cdcacm.h 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435
  1. /****************************************************************************
  2. * include/nuttx/usb/cdcacm.h
  3. *
  4. * Copyright (C) 2011-2012, 2015, 2017 Gregory Nutt. All rights reserved.
  5. * Author: Gregory Nutt <gnutt@nuttx.org>
  6. *
  7. * Redistribution and use in source and binary forms, with or without
  8. * modification, are permitted provided that the following conditions
  9. * are met:
  10. *
  11. * 1. Redistributions of source code must retain the above copyright
  12. * notice, this list of conditions and the following disclaimer.
  13. * 2. Redistributions in binary form must reproduce the above copyright
  14. * notice, this list of conditions and the following disclaimer in
  15. * the documentation and/or other materials provided with the
  16. * distribution.
  17. * 3. Neither the name NuttX nor the names of its contributors may be
  18. * used to endorse or promote products derived from this software
  19. * without specific prior written permission.
  20. *
  21. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  22. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  23. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  24. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  25. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  26. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  27. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  28. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  29. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  30. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  31. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  32. * POSSIBILITY OF SUCH DAMAGE.
  33. *
  34. ****************************************************************************/
  35. #ifndef __INCLUDE_NUTTX_USB_CDCACM_H
  36. #define __INCLUDE_NUTTX_USB_CDCACM_H
  37. /****************************************************************************
  38. * Included Files
  39. ****************************************************************************/
  40. #include <nuttx/config.h>
  41. #include <nuttx/fs/ioctl.h>
  42. #include <nuttx/usb/usb.h>
  43. /****************************************************************************
  44. * Preprocessor definitions
  45. ****************************************************************************/
  46. /* Configuration ************************************************************/
  47. /* CONFIG_CDCACM
  48. * Enable compilation of the USB serial driver
  49. * CONFIG_CDCACM_EP0MAXPACKET
  50. * Endpoint 0 max packet size. Default 64.
  51. * CONFIG_CDCACM_EPINTIN
  52. * The logical 7-bit address of a hardware endpoint that supports
  53. * interrupt IN operation. Default 1.
  54. * CONFIG_CDCACM_EPINTIN_FSSIZE
  55. * Max package size for the interrupt IN endpoint if full speed mode.
  56. * Default 64.
  57. * CONFIG_CDCACM_EPINTIN_HSSIZE
  58. * Max package size for the interrupt IN endpoint if high speed mode.
  59. * Default 64.
  60. * CONFIG_CDCACM_EPBULKOUT
  61. * The logical 7-bit address of a hardware endpoint that supports
  62. * bulk OUT operation. Default: 3
  63. * CONFIG_CDCACM_EPBULKOUT_FSSIZE
  64. * Max package size for the bulk OUT endpoint if full speed mode.
  65. * Default 64.
  66. * CONFIG_CDCACM_EPBULKOUT_HSSIZE
  67. * Max package size for the bulk OUT endpoint if high speed mode.
  68. * Default 512.
  69. * CONFIG_CDCACM_EPBULKIN
  70. * The logical 7-bit address of a hardware endpoint that supports
  71. * bulk IN operation. Default: 2
  72. * CONFIG_CDCACM_EPBULKIN_FSSIZE
  73. * Max package size for the bulk IN endpoint if full speed mode.
  74. * Default 64.
  75. * CONFIG_CDCACM_EPBULKIN_HSSIZE
  76. * Max package size for the bulk IN endpoint if high speed mode.
  77. * Default 512.
  78. * CONFIG_CDCACM_NWRREQS and CONFIG_CDCACM_NRDREQS
  79. * The number of write/read requests that can be in flight.
  80. * CONFIG_CDCACM_NWRREQS includes write requests used for both the
  81. * interrupt and bulk IN endpoints. Default 4.
  82. * CONFIG_CDCACM_VENDORID and CONFIG_CDCACM_VENDORSTR
  83. * The vendor ID code/string. Default 0x0525 and "NuttX"
  84. * 0x0525 is the Netchip vendor and should not be used in any
  85. * products. This default VID was selected for compatibility with
  86. * the Linux CDC ACM default VID.
  87. * CONFIG_CDCACM_PRODUCTID and CONFIG_CDCACM_PRODUCTSTR
  88. * The product ID code/string. Default 0xa4a7 and "CDC/ACM Serial"
  89. * 0xa4a7 was selected for compatibility with the Linux CDC ACM
  90. * default PID.
  91. * CONFIG_CDCACM_RXBUFSIZE and CONFIG_CDCACM_TXBUFSIZE
  92. * Size of the serial receive/transmit buffers. Default 256.
  93. */
  94. /* Information needed in usbdev_devinfo_s */
  95. #define CDCACM_NUM_EPS (3)
  96. #define CDCACM_EP_INTIN_IDX (0)
  97. #define CDCACM_EP_BULKIN_IDX (1)
  98. #define CDCACM_EP_BULKOUT_IDX (2)
  99. #define CDCACM_NCONFIGS (1) /* Number of configurations supported */
  100. /* Configuration descriptor values */
  101. #define CDCACM_CONFIGID (1) /* The only supported configuration ID */
  102. #define CDCACM_NINTERFACES (2) /* Number of interfaces in the configuration */
  103. /* EP0 max packet size */
  104. #ifndef CONFIG_CDCACM_EP0MAXPACKET
  105. # define CONFIG_CDCACM_EP0MAXPACKET 64
  106. #endif
  107. /* Endpoint number and size (in bytes) of the CDC serial device-to-host (IN)
  108. * notification interrupt endpoint.
  109. */
  110. #ifndef CONFIG_CDCACM_COMPOSITE
  111. # ifndef CONFIG_CDCACM_EPINTIN
  112. # define CONFIG_CDCACM_EPINTIN 1
  113. # endif
  114. #endif
  115. #ifndef CONFIG_CDCACM_EPINTIN_FSSIZE
  116. # define CONFIG_CDCACM_EPINTIN_FSSIZE 64
  117. #endif
  118. #ifndef CONFIG_CDCACM_EPINTIN_HSSIZE
  119. # define CONFIG_CDCACM_EPINTIN_HSSIZE 64
  120. #endif
  121. /* Endpoint number and size (in bytes) of the CDC device-to-host (IN) data
  122. * bulk endpoint. NOTE that difference sizes may be selected for full (FS)
  123. * or high speed (HS) modes.
  124. *
  125. * Ideally, the BULKOUT request size should *not* be the same size as the
  126. * maxpacket size. That is because IN transfers of exactly the maxpacket
  127. * size will be followed by a NULL packet.
  128. */
  129. #ifndef CONFIG_CDCACM_COMPOSITE
  130. # ifndef CONFIG_CDCACM_EPBULKIN
  131. # define CONFIG_CDCACM_EPBULKIN 2
  132. # endif
  133. #endif
  134. #ifndef CONFIG_CDCACM_EPBULKIN_FSSIZE
  135. # define CONFIG_CDCACM_EPBULKIN_FSSIZE 64
  136. #endif
  137. #ifndef CONFIG_CDCACM_EPBULKIN_HSSIZE
  138. # define CONFIG_CDCACM_EPBULKIN_HSSIZE 512
  139. #endif
  140. #ifndef CONFIG_CDCACM_BULKIN_REQLEN
  141. # ifdef CONFIG_USBDEV_DUALSPEED
  142. # define CONFIG_CDCACM_BULKIN_REQLEN (3 * CONFIG_CDCACM_EPBULKIN_FSSIZE / 2)
  143. # else
  144. # define CONFIG_CDCACM_BULKIN_REQLEN (3 * CONFIG_CDCACM_EPBULKIN_FSSIZE / 2)
  145. # endif
  146. #endif
  147. /* Endpoint number and size (in bytes) of the CDC host-to-device (OUT) data
  148. * bulk endpoint. NOTE that difference sizes may be selected for full (FS)
  149. * or high speed (HS) modes.
  150. *
  151. * NOTE: The BULKOUT request buffer size is always the same as the
  152. * maxpacket size.
  153. */
  154. #ifndef CONFIG_CDCACM_COMPOSITE
  155. # ifndef CONFIG_CDCACM_EPBULKOUT
  156. # define CONFIG_CDCACM_EPBULKOUT 3
  157. # endif
  158. #endif
  159. #ifndef CONFIG_CDCACM_EPBULKOUT_FSSIZE
  160. # define CONFIG_CDCACM_EPBULKOUT_FSSIZE 64
  161. #endif
  162. #ifndef CONFIG_CDCACM_EPBULKOUT_HSSIZE
  163. # define CONFIG_CDCACM_EPBULKOUT_HSSIZE 512
  164. #endif
  165. /* Number of requests in the write queue. This includes write requests used
  166. * for both the interrupt and bulk IN endpoints.
  167. */
  168. #ifndef CONFIG_CDCACM_NWRREQS
  169. # define CONFIG_CDCACM_NWRREQS 4
  170. #endif
  171. /* Number of requests in the read queue */
  172. #ifndef CONFIG_CDCACM_NRDREQS
  173. # define CONFIG_CDCACM_NRDREQS 4
  174. #endif
  175. /* TX/RX buffer sizes */
  176. #ifndef CONFIG_CDCACM_RXBUFSIZE
  177. # define CONFIG_CDCACM_RXBUFSIZE 256
  178. #endif
  179. #ifndef CONFIG_CDCACM_TXBUFSIZE
  180. # define CONFIG_CDCACM_TXBUFSIZE 256
  181. #endif
  182. /* Vendor and product IDs and strings. The default is the Linux Netchip
  183. * CDC ACM VID and PID.
  184. */
  185. #ifndef CONFIG_CDCACM_VENDORID
  186. # define CONFIG_CDCACM_VENDORID 0x0525
  187. #endif
  188. #ifndef CONFIG_CDCACM_PRODUCTID
  189. # define CONFIG_CDCACM_PRODUCTID 0xa4a7
  190. #endif
  191. #ifndef CONFIG_CDCACM_VENDORSTR
  192. # define CONFIG_CDCACM_VENDORSTR "NuttX"
  193. #endif
  194. #ifndef CONFIG_CDCACM_PRODUCTSTR
  195. # define CONFIG_CDCACM_PRODUCTSTR "CDC ACM Serial"
  196. #endif
  197. #undef CONFIG_CDCACM_SERIALSTR
  198. #define CONFIG_CDCACM_SERIALSTR "0"
  199. #undef CONFIG_CDCACM_CONFIGSTR
  200. #define CONFIG_CDCACM_CONFIGSTR "Bulk"
  201. /* USB Controller */
  202. #ifdef CONFIG_USBDEV_SELFPOWERED
  203. # define CDCACM_SELFPOWERED USB_CONFIG_ATTR_SELFPOWER
  204. #else
  205. # define CDCACM_SELFPOWERED (0)
  206. #endif
  207. #ifdef CONFIG_USBDEV_REMOTEWAKEUP
  208. # define CDCACM_REMOTEWAKEUP USB_CONFIG_ATTR_WAKEUP
  209. #else
  210. # define CDCACM_REMOTEWAKEUP (0)
  211. #endif
  212. #ifndef CONFIG_USBDEV_MAXPOWER
  213. # define CONFIG_USBDEV_MAXPOWER 100
  214. #endif
  215. /* IOCTL Commands ***********************************************************/
  216. /* The USB serial driver will support a subset of the TIOC IOCTL commands
  217. * defined in include/nuttx/serial/tioctl.h. This subset includes:
  218. *
  219. * CAICO_REGISTERCB
  220. * Register a callback for serial event notification. Argument:
  221. * cdcacm_callback_t. See cdcacm_callback_t type definition below.
  222. * NOTE: The callback will most likely invoked at the interrupt level.
  223. * The called back function should, therefore, limit its operations to
  224. * invoking some kind of IPC to handle the serial event in some normal
  225. * task environment.
  226. * CAIOC_GETLINECODING
  227. * Get current line coding. Argument: struct cdc_linecoding_s*.
  228. * See include/nuttx/usb/cdc.h for structure definition. This IOCTL
  229. * should be called to get the data associated with the
  230. * CDCACM_EVENT_LINECODING event (see devent definition below).
  231. * CAIOC_GETCTRLLINE
  232. * Get control line status bits. Argument FAR int*. See
  233. * include/nuttx/usb/cdc.h for bit definitions. This IOCTL should be
  234. * called to get the data associated CDCACM_EVENT_CTRLLINE event (see event
  235. * definition below).
  236. * CAIOC_NOTIFY
  237. * Send a serial state to the host via the Interrupt IN endpoint.
  238. * Argument: int. This includes the current state of the carrier detect,
  239. * DSR, break, and ring signal. See "Table 69: UART State Bitmap Values"
  240. * and CDC_UART_definitions in include/nuttx/usb/cdc.h.
  241. */
  242. #define CAIOC_REGISTERCB _CAIOC(0x0001)
  243. #define CAIOC_GETLINECODING _CAIOC(0x0002)
  244. #define CAIOC_GETCTRLLINE _CAIOC(0x0003)
  245. #define CAIOC_NOTIFY _CAIOC(0x0004)
  246. /****************************************************************************
  247. * Public Types
  248. ****************************************************************************/
  249. #undef EXTERN
  250. #if defined(__cplusplus)
  251. # define EXTERN extern "C"
  252. extern "C"
  253. {
  254. #else
  255. # define EXTERN extern
  256. #endif
  257. /* Reported serial events. Data is associated with CDCACM_EVENT_LINECODING
  258. * and CDCACM_EVENT_CTRLLINE. The data may be obtained using CDCACM IOCTL
  259. * commands described above.
  260. *
  261. * CDCACM_EVENT_LINECODING - See "Table 50: Line Coding Structure" and struct
  262. * cdc_linecoding_s in include/nuttx/usb/cdc.h.
  263. * CDCACM_EVENT_CTRLLINE - See "Table 51: Control Signal Bitmap Values for
  264. * SetControlLineState" and definitions in include/nutt/usb/cdc.h
  265. * CDCACM_EVENT_SENDBREAK - See Paragraph "6.2.15 SendBreak." This request
  266. * sends special carrier modulation that generates an RS-232 style break.
  267. */
  268. enum cdcacm_event_e
  269. {
  270. CDCACM_EVENT_LINECODING = 0, /* New line coding received from host */
  271. CDCACM_EVENT_CTRLLINE, /* New control line status received from host */
  272. CDCACM_EVENT_SENDBREAK /* Send break request received */
  273. };
  274. typedef CODE void (*cdcacm_callback_t)(enum cdcacm_event_e event);
  275. /****************************************************************************
  276. * Public Function Prototypes
  277. ****************************************************************************/
  278. /****************************************************************************
  279. * Name: cdcacm_classobject
  280. *
  281. * Description:
  282. * Register USB serial port (and USB serial console if so configured) and
  283. * return the class object.
  284. *
  285. * Input Parameters:
  286. * minor - Device minor number. E.g., minor 0 would correspond to
  287. * /dev/ttyACM0.
  288. * classdev - The location to return the CDC serial class' device
  289. * instance.
  290. *
  291. * Returned Value:
  292. * A pointer to the allocated class object (NULL on failure).
  293. *
  294. ****************************************************************************/
  295. #if defined(CONFIG_USBDEV_COMPOSITE) && defined(CONFIG_CDCACM_COMPOSITE)
  296. struct usbdev_devinfo_s;
  297. struct usbdevclass_driver_s;
  298. int cdcacm_classobject(int minor, FAR struct usbdev_devinfo_s *devinfo,
  299. FAR struct usbdevclass_driver_s **classdev);
  300. #endif
  301. /****************************************************************************
  302. * Name: cdcacm_initialize
  303. *
  304. * Description:
  305. * Register USB serial port (and USB serial console if so configured).
  306. *
  307. * Input Parameters:
  308. * minor - Device minor number. E.g., minor 0 would correspond to
  309. * /dev/ttyACM0.
  310. * handle - An optional opaque reference to the CDC/ACM class object that
  311. * may subsequently be used with cdcacm_uninitialize().
  312. *
  313. * Returned Value:
  314. * Zero (OK) means that the driver was successfully registered. On any
  315. * failure, a negated errno value is returned.
  316. *
  317. ****************************************************************************/
  318. #if !defined(CONFIG_USBDEV_COMPOSITE) || !defined(CONFIG_CDCACM_COMPOSITE)
  319. int cdcacm_initialize(int minor, FAR void **handle);
  320. #endif
  321. /****************************************************************************
  322. * Name: cdcacm_uninitialize
  323. *
  324. * Description:
  325. * Un-initialize the USB storage class driver. This function is used
  326. * internally by the USB composite driver to uninitialize the CDC/ACM
  327. * driver. This same interface is available (with an untyped input
  328. * parameter) when the CDC/ACM driver is used standalone.
  329. *
  330. * Input Parameters:
  331. * There is one parameter, it differs in typing depending upon whether the
  332. * CDC/ACM driver is an internal part of a composite device, or a
  333. * standalone USB driver:
  334. *
  335. * classdev - The class object returned by cdcacm_classobject()
  336. * handle - The opaque handle representing the class object returned by
  337. * a previous call to cdcacm_initialize().
  338. *
  339. * Returned Value:
  340. * None
  341. *
  342. ****************************************************************************/
  343. #if defined(CONFIG_USBDEV_COMPOSITE) && defined(CONFIG_CDCACM_COMPOSITE)
  344. void cdcacm_uninitialize(FAR struct usbdevclass_driver_s *classdev);
  345. #else
  346. void cdcacm_uninitialize(FAR void *handle);
  347. #endif
  348. /****************************************************************************
  349. * Name: cdcacm_get_composite_devdesc
  350. *
  351. * Description:
  352. * Helper function to fill in some constants into the composite
  353. * configuration struct.
  354. *
  355. * Input Parameters:
  356. * dev - Pointer to the configuration struct we should fill
  357. *
  358. * Returned Value:
  359. * None
  360. *
  361. ****************************************************************************/
  362. #if defined(CONFIG_USBDEV_COMPOSITE) && defined(CONFIG_CDCACM_COMPOSITE)
  363. struct composite_devdesc_s;
  364. void cdcacm_get_composite_devdesc(struct composite_devdesc_s *dev);
  365. #endif
  366. #undef EXTERN
  367. #if defined(__cplusplus)
  368. }
  369. #endif
  370. #endif /* __INCLUDE_NUTTX_USB_CDCACM_H */