cdc_acm_mavlink_template.c 6.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254
  1. /*
  2. * Copyright (c) 2025, sakumisu
  3. *
  4. * SPDX-License-Identifier: Apache-2.0
  5. */
  6. #include "usbd_core.h"
  7. #include "usbd_cdc_acm.h"
  8. #include "chry_ringbuffer.h"
  9. #include <mavlink.h>
  10. /*!< endpoint address */
  11. #define CDC_IN_EP 0x81
  12. #define CDC_OUT_EP 0x02
  13. #define CDC_INT_EP 0x83
  14. #define USBD_VID 0xFFFF
  15. #define USBD_PID 0xFFFF
  16. #define USBD_MAX_POWER 100
  17. #define USBD_LANGID_STRING 1033
  18. /*!< config descriptor size */
  19. #define USB_CONFIG_SIZE (9 + CDC_ACM_DESCRIPTOR_LEN)
  20. #ifdef CONFIG_USB_HS
  21. #define CDC_MAX_MPS 512
  22. #else
  23. #define CDC_MAX_MPS 64
  24. #endif
  25. static const uint8_t device_descriptor[] = {
  26. USB_DEVICE_DESCRIPTOR_INIT(USB_2_0, 0xEF, 0x02, 0x01, USBD_VID, USBD_PID, 0x0100, 0x01)
  27. };
  28. static const uint8_t config_descriptor[] = {
  29. USB_CONFIG_DESCRIPTOR_INIT(USB_CONFIG_SIZE, 0x02, 0x01, USB_CONFIG_BUS_POWERED, USBD_MAX_POWER),
  30. CDC_ACM_DESCRIPTOR_INIT(0x00, CDC_INT_EP, CDC_OUT_EP, CDC_IN_EP, CDC_MAX_MPS, 0x02)
  31. };
  32. static const uint8_t device_quality_descriptor[] = {
  33. ///////////////////////////////////////
  34. /// device qualifier descriptor
  35. ///////////////////////////////////////
  36. 0x0a,
  37. USB_DESCRIPTOR_TYPE_DEVICE_QUALIFIER,
  38. 0x00,
  39. 0x02,
  40. 0x00,
  41. 0x00,
  42. 0x00,
  43. 0x40,
  44. 0x00,
  45. 0x00,
  46. };
  47. static const char *string_descriptors[] = {
  48. (const char[]){ 0x09, 0x04 }, /* Langid */
  49. "CherryUSB", /* Manufacturer */
  50. "CherryUSB CDC DEMO", /* Product */
  51. "2022123456", /* Serial Number */
  52. };
  53. static const uint8_t *device_descriptor_callback(uint8_t speed)
  54. {
  55. return device_descriptor;
  56. }
  57. static const uint8_t *config_descriptor_callback(uint8_t speed)
  58. {
  59. return config_descriptor;
  60. }
  61. static const uint8_t *device_quality_descriptor_callback(uint8_t speed)
  62. {
  63. return device_quality_descriptor;
  64. }
  65. static const char *string_descriptor_callback(uint8_t speed, uint8_t index)
  66. {
  67. if (index > 3) {
  68. return NULL;
  69. }
  70. return string_descriptors[index];
  71. }
  72. const struct usb_descriptor cdc_descriptor = {
  73. .device_descriptor_callback = device_descriptor_callback,
  74. .config_descriptor_callback = config_descriptor_callback,
  75. .device_quality_descriptor_callback = device_quality_descriptor_callback,
  76. .string_descriptor_callback = string_descriptor_callback
  77. };
  78. chry_ringbuffer_t usb_rx_rb;
  79. uint8_t usb_rx_buffer[2048];
  80. USB_NOCACHE_RAM_SECTION USB_MEM_ALIGNX uint8_t temp_rx_buffer[512];
  81. USB_NOCACHE_RAM_SECTION USB_MEM_ALIGNX uint8_t usb_tx_buffer[MAVLINK_MAX_PACKET_LEN];
  82. volatile bool ep_tx_busy_flag = false;
  83. static void usbd_event_handler(uint8_t busid, uint8_t event)
  84. {
  85. switch (event) {
  86. case USBD_EVENT_RESET:
  87. break;
  88. case USBD_EVENT_CONNECTED:
  89. break;
  90. case USBD_EVENT_DISCONNECTED:
  91. break;
  92. case USBD_EVENT_RESUME:
  93. break;
  94. case USBD_EVENT_SUSPEND:
  95. break;
  96. case USBD_EVENT_CONFIGURED:
  97. ep_tx_busy_flag = false;
  98. /* setup first out ep read transfer */
  99. usbd_ep_start_read(busid, CDC_OUT_EP, temp_rx_buffer, usbd_get_ep_mps(busid, CDC_OUT_EP));
  100. break;
  101. case USBD_EVENT_SET_REMOTE_WAKEUP:
  102. break;
  103. case USBD_EVENT_CLR_REMOTE_WAKEUP:
  104. break;
  105. default:
  106. break;
  107. }
  108. }
  109. void usbd_cdc_acm_bulk_out(uint8_t busid, uint8_t ep, uint32_t nbytes)
  110. {
  111. USB_LOG_RAW("actual out len:%d\r\n", (unsigned int)nbytes);
  112. chry_ringbuffer_write(&usb_rx_rb, temp_rx_buffer, nbytes);
  113. usbd_ep_start_read(busid, CDC_OUT_EP, temp_rx_buffer, usbd_get_ep_mps(busid, CDC_OUT_EP));
  114. }
  115. void usbd_cdc_acm_bulk_in(uint8_t busid, uint8_t ep, uint32_t nbytes)
  116. {
  117. USB_LOG_RAW("actual in len:%d\r\n", (unsigned int)nbytes);
  118. if ((nbytes % usbd_get_ep_mps(busid, ep)) == 0 && nbytes) {
  119. /* send zlp */
  120. usbd_ep_start_write(busid, CDC_IN_EP, NULL, 0);
  121. } else {
  122. ep_tx_busy_flag = false;
  123. }
  124. }
  125. /*!< endpoint call back */
  126. struct usbd_endpoint cdc_out_ep = {
  127. .ep_addr = CDC_OUT_EP,
  128. .ep_cb = usbd_cdc_acm_bulk_out
  129. };
  130. struct usbd_endpoint cdc_in_ep = {
  131. .ep_addr = CDC_IN_EP,
  132. .ep_cb = usbd_cdc_acm_bulk_in
  133. };
  134. static struct usbd_interface intf0;
  135. static struct usbd_interface intf1;
  136. void cdc_acm_mavlink_init(uint8_t busid, uintptr_t reg_base)
  137. {
  138. chry_ringbuffer_init(&usb_rx_rb, usb_rx_buffer, sizeof(usb_rx_buffer));
  139. usbd_desc_register(busid, &cdc_descriptor);
  140. usbd_add_interface(busid, usbd_cdc_acm_init_intf(busid, &intf0));
  141. usbd_add_interface(busid, usbd_cdc_acm_init_intf(busid, &intf1));
  142. usbd_add_endpoint(busid, &cdc_out_ep);
  143. usbd_add_endpoint(busid, &cdc_in_ep);
  144. usbd_initialize(busid, reg_base, usbd_event_handler);
  145. }
  146. void cdc_acm_mavlink_write(uint8_t *data, uint32_t len)
  147. {
  148. if (!usb_device_is_configured(0)) {
  149. return;
  150. }
  151. ep_tx_busy_flag = true;
  152. usbd_ep_start_write(0, CDC_IN_EP, data, len);
  153. while (ep_tx_busy_flag) {
  154. }
  155. }
  156. void send_heartbeat(void)
  157. {
  158. mavlink_message_t message;
  159. const uint8_t system_id = 42;
  160. const uint8_t base_mode = 0;
  161. const uint8_t custom_mode = 0;
  162. mavlink_msg_heartbeat_pack_chan(
  163. system_id,
  164. MAV_COMP_ID_PERIPHERAL,
  165. MAVLINK_COMM_0,
  166. &message,
  167. MAV_TYPE_GENERIC,
  168. MAV_AUTOPILOT_GENERIC,
  169. base_mode,
  170. custom_mode,
  171. MAV_STATE_STANDBY);
  172. const int len = mavlink_msg_to_send_buffer(usb_tx_buffer, &message);
  173. cdc_acm_mavlink_write(usb_tx_buffer, len);
  174. }
  175. void handle_heartbeat(const mavlink_message_t *message)
  176. {
  177. mavlink_heartbeat_t heartbeat;
  178. mavlink_msg_heartbeat_decode(message, &heartbeat);
  179. USB_LOG_RAW("Got heartbeat from ");
  180. switch (heartbeat.autopilot) {
  181. case MAV_AUTOPILOT_GENERIC:
  182. USB_LOG_RAW("generic");
  183. break;
  184. case MAV_AUTOPILOT_ARDUPILOTMEGA:
  185. USB_LOG_RAW("ArduPilot");
  186. break;
  187. case MAV_AUTOPILOT_PX4:
  188. USB_LOG_RAW("PX4");
  189. break;
  190. default:
  191. USB_LOG_RAW("other");
  192. break;
  193. }
  194. USB_LOG_RAW(" autopilot\n");
  195. send_heartbeat();
  196. }
  197. void mavlink_polling(void)
  198. {
  199. uint8_t ch;
  200. bool ret;
  201. mavlink_message_t message;
  202. mavlink_status_t status;
  203. ret = chry_ringbuffer_read_byte(&usb_rx_rb, &ch);
  204. if (ret) {
  205. if (mavlink_parse_char(MAVLINK_COMM_0, ch, &message, &status) == 1) {
  206. USB_LOG_INFO(
  207. "Received message %d from %d/%d\n",
  208. message.msgid, message.sysid, message.compid);
  209. switch (message.msgid) {
  210. case MAVLINK_MSG_ID_HEARTBEAT:
  211. handle_heartbeat(&message);
  212. break;
  213. }
  214. }
  215. }
  216. }