ioctl.h 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561
  1. /****************************************************************************
  2. * include/nuttx/fs/ioctl.h
  3. *
  4. * Copyright (C) 2008, 2009, 2011-2014, 2017-2019 Gregory Nutt. All rights
  5. * reserved.
  6. * Author: Gregory Nutt <gnutt@nuttx.org>
  7. *
  8. * Redistribution and use in source and binary forms, with or without
  9. * modification, are permitted provided that the following conditions
  10. * are met:
  11. *
  12. * 1. Redistributions of source code must retain the above copyright
  13. * notice, this list of conditions and the following disclaimer.
  14. * 2. Redistributions in binary form must reproduce the above copyright
  15. * notice, this list of conditions and the following disclaimer in
  16. * the documentation and/or other materials provided with the
  17. * distribution.
  18. * 3. Neither the name NuttX nor the names of its contributors may be
  19. * used to endorse or promote products derived from this software
  20. * without specific prior written permission.
  21. *
  22. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  23. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  24. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  25. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  26. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  27. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  28. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  29. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  30. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  31. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  32. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  33. * POSSIBILITY OF SUCH DAMAGE.
  34. *
  35. ****************************************************************************/
  36. #ifndef __INCLUDE_NUTTX_FS_IOCTL_H
  37. #define __INCLUDE_NUTTX_FS_IOCTL_H
  38. /****************************************************************************
  39. * Included Files
  40. ****************************************************************************/
  41. #include <nuttx/config.h>
  42. /****************************************************************************
  43. * Pre-processor Definitions
  44. ****************************************************************************/
  45. /* General ioctl definitions ************************************************/
  46. /* Each NuttX ioctl commands are uint16_t's consisting of an 8-bit type
  47. * identifier and an 8-bit command number. All command type identifiers are
  48. * defined below:
  49. */
  50. #define _TIOCBASE (0x0100) /* Terminal I/O ioctl commands */
  51. #define _WDIOCBASE (0x0200) /* Watchdog driver ioctl commands */
  52. #define _FIOCBASE (0x0300) /* File system ioctl commands */
  53. #define _DIOCBASE (0x0400) /* Character driver ioctl commands */
  54. #define _BIOCBASE (0x0500) /* Block driver ioctl commands */
  55. #define _MTDIOCBASE (0x0600) /* MTD ioctl commands */
  56. #define _SIOCBASE (0x0700) /* Socket ioctl commands */
  57. #define _ARPIOCBASE (0x0800) /* ARP ioctl commands */
  58. #define _TSIOCBASE (0x0900) /* Touchscreen ioctl commands */
  59. #define _SNIOCBASE (0x0a00) /* Sensor ioctl commands */
  60. #define _ANIOCBASE (0x0b00) /* Analog (DAC/ADC) ioctl commands */
  61. #define _PWMIOCBASE (0x0c00) /* PWM ioctl commands */
  62. #define _CAIOCBASE (0x0d00) /* CDC/ACM ioctl commands */
  63. #define _BATIOCBASE (0x0e00) /* Battery driver ioctl commands */
  64. #define _QEIOCBASE (0x0f00) /* Quadrature encoder ioctl commands */
  65. #define _AUDIOIOCBASE (0x1000) /* Audio ioctl commands */
  66. #define _LCDIOCBASE (0x1100) /* LCD character driver ioctl commands */
  67. #define _SLCDIOCBASE (0x1200) /* Segment LCD ioctl commands */
  68. /* 0x1300: Not used */
  69. #define _WLCIOCBASE (0x1400) /* Wireless modules ioctl character driver commands */
  70. #define _CFGDIOCBASE (0x1500) /* Config Data device (app config) ioctl commands */
  71. #define _TCIOCBASE (0x1600) /* Timer ioctl commands */
  72. #define _JOYBASE (0x1700) /* Joystick ioctl commands */
  73. #define _PIPEBASE (0x1800) /* FIFO/pipe ioctl commands */
  74. #define _RTCBASE (0x1900) /* RTC ioctl commands */
  75. #define _RELAYBASE (0x1a00) /* Relay devices ioctl commands */
  76. #define _CANBASE (0x1b00) /* CAN ioctl commands */
  77. #define _BTNBASE (0x1c00) /* Button ioctl commands */
  78. #define _ULEDBASE (0x1d00) /* User LED ioctl commands */
  79. #define _ZCBASE (0x1e00) /* Zero Cross ioctl commands */
  80. #define _LOOPBASE (0x1f00) /* Loop device commands */
  81. #define _MODEMBASE (0x2000) /* Modem ioctl commands */
  82. #define _I2CBASE (0x2100) /* I2C driver commands */
  83. #define _SPIBASE (0x2200) /* SPI driver commands */
  84. #define _GPIOBASE (0x2300) /* GPIO driver commands */
  85. #define _CLIOCBASE (0x2400) /* Contactless modules ioctl commands */
  86. #define _USBCBASE (0x2500) /* USB-C controller ioctl commands */
  87. #define _MAC802154BASE (0x2600) /* 802.15.4 MAC ioctl commands */
  88. #define _PWRBASE (0x2700) /* Power-related ioctl commands */
  89. #define _FBIOCBASE (0x2800) /* Frame buffer character driver ioctl commands */
  90. #define _NXTERMBASE (0x2900) /* NxTerm character driver ioctl commands */
  91. #define _RFIOCBASE (0x2a00) /* RF devices ioctl commands */
  92. #define _RPTUNBASE (0x2b00) /* Remote processor tunnel ioctl commands */
  93. #define _WLIOCBASE (0x8b00) /* Wireless modules ioctl network commands */
  94. /* boardctl() commands share the same number space */
  95. #define _BOARDBASE (0xff00) /* boardctl commands */
  96. /* Macros used to manage ioctl commands. IOCTL commands are divided into
  97. * groups of 256 commands for major, broad functional areas. That makes
  98. * them a limited resource.
  99. */
  100. #define _IOC_MASK (0x00ff)
  101. #define _IOC_TYPE(cmd) ((cmd) & ~_IOC_MASK)
  102. #define _IOC_NR(cmd) ((cmd) & _IOC_MASK)
  103. #define _IOC(type,nr) ((type)|(nr))
  104. /* Terminal I/O ioctl commands **********************************************/
  105. #define _TIOCVALID(c) (_IOC_TYPE(c)==_TIOCBASE)
  106. #define _TIOC(nr) _IOC(_TIOCBASE,nr)
  107. /* Terminal I/O IOCTL definitions are retained in tioctl.h */
  108. /****************************************************************************
  109. * Included Files
  110. ****************************************************************************/
  111. #include <nuttx/serial/tioctl.h>
  112. /* Watchdog driver ioctl commands *******************************************/
  113. #define _WDIOCVALID(c) (_IOC_TYPE(c)==_WDIOCBASE)
  114. #define _WDIOC(nr) _IOC(_WDIOCBASE,nr)
  115. /* NuttX file system ioctl definitions **************************************/
  116. #define _FIOCVALID(c) (_IOC_TYPE(c)==_FIOCBASE)
  117. #define _FIOC(nr) _IOC(_FIOCBASE,nr)
  118. #define FIOC_MMAP _FIOC(0x0001) /* IN: Location to return address (void **)
  119. * OUT: If media is directly accessible,
  120. * return (void*) base address
  121. * of file
  122. */
  123. #define FIOC_REFORMAT _FIOC(0x0002) /* IN: None
  124. * OUT: None
  125. */
  126. #define FIOC_OPTIMIZE _FIOC(0x0003) /* IN: The number of bytes to recover
  127. * (ignored on most file systems)
  128. * OUT: None
  129. */
  130. #define FIOC_FILENAME _FIOC(0x0004) /* IN: FAR const char ** pointer
  131. * OUT: Pointer to a persistent file name
  132. * (Guaranteed to persist while the
  133. * file is open).
  134. */
  135. #define FIOC_INTEGRITY _FIOC(0x0005) /* Run a consistency check on the
  136. * file system media.
  137. * IN: None
  138. * OUT: None */
  139. #define FIOC_DUMP _FIOC(0x0006) /* Dump logical content of media.
  140. * IN: None
  141. * OUT: None */
  142. #define FIONREAD _FIOC(0x0007) /* IN: Location to return value (int *)
  143. * OUT: Bytes readable from this fd
  144. */
  145. #define FIONWRITE _FIOC(0x0008) /* IN: Location to return value (int *)
  146. * OUT: Number bytes in send queue
  147. */
  148. #define FIONSPACE _FIOC(0x0009) /* IN: Location to return value (int *)
  149. * OUT: Free space in send queue.
  150. */
  151. #define FIONUSERFS _FIOC(0x000a) /* IN: Pointer to struct usefs_config_s
  152. * holding userfs configuration.
  153. * OUT: Instance number is returned on
  154. * success.
  155. */
  156. #define FIONBIO _FIOC(0x000b) /* IN: Boolean option takes an
  157. * int value.
  158. * OUT: Origin option.
  159. */
  160. #define FIOC_MINOR _FIOC(0x000c) /* IN: None
  161. * OUT: Integer that contains device
  162. * minor number
  163. */
  164. /* NuttX file system ioctl definitions **************************************/
  165. #define _DIOCVALID(c) (_IOC_TYPE(c)==_DIOCBASE)
  166. #define _DIOC(nr) _IOC(_DIOCBASE,nr)
  167. #define DIOC_GETPRIV _DIOC(0x0001) /* IN: Location to return handle (void **)
  168. * OUT: Reference to internal data
  169. * structure. May have a reference
  170. * incremented.
  171. */
  172. #define DIOC_RELPRIV _DIOC(0x0003) /* IN: None
  173. * OUT: None, reference obtained by
  174. * FIOC_GETPRIV released.
  175. */
  176. #define DIOC_SETKEY _DIOC(0X0004) /* IN: Encryption key
  177. * OUT: None
  178. */
  179. /* NuttX block driver ioctl definitions *************************************/
  180. #define _BIOCVALID(c) (_IOC_TYPE(c)==_BIOCBASE)
  181. #define _BIOC(nr) _IOC(_BIOCBASE,nr)
  182. #define BIOC_XIPBASE _BIOC(0x0001) /* Perform mapping to random access memory.
  183. * IN: Pointer to pointer to void in
  184. * which to received the XIP base.
  185. * OUT: If media is directly accessible,
  186. * return (void *) base address
  187. * of device memory */
  188. #define BIOC_PROBE _BIOC(0x0002) /* Re-probe and interface; check for media
  189. * in the slot
  190. * IN: None
  191. * OUT: None (ioctl return value provides
  192. * success/failure indication). */
  193. #define BIOC_EJECT _BIOC(0x0003) /* Eject/disable media in the slot
  194. * IN: None
  195. * OUT: None (ioctl return value provides
  196. * success/failure indication). */
  197. #define BIOC_LLFORMAT _BIOC(0x0004) /* Low-Level Format on SMART flash devices
  198. * IN: None
  199. * OUT: None (ioctl return value provides
  200. * success/failure indication). */
  201. #define BIOC_GETFORMAT _BIOC(0x0005) /* Returns SMART flash format information
  202. * such as format status, logical sector
  203. * size, total sectors, free sectors, etc.
  204. * IN: None
  205. * OUT: Pointer to the format information. */
  206. #define BIOC_ALLOCSECT _BIOC(0x0006) /* Allocate a logical sector from the block
  207. * device.
  208. * IN: None
  209. * OUT: Logical sector number allocated. */
  210. #define BIOC_FREESECT _BIOC(0x0007) /* Allocate a logical sector from the block
  211. * device.
  212. * IN: None
  213. * OUT: Logical sector number allocated. */
  214. #define BIOC_READSECT _BIOC(0x0008) /* Read a logical sector from the block
  215. * device.
  216. * IN: Pointer to sector read data (the
  217. * logical sector number, count and
  218. * read buffer address
  219. * OUT: Number of bytes read or error */
  220. #define BIOC_WRITESECT _BIOC(0x0009) /* Write to data to a logical sector
  221. * IN: Pointer to sector write data (the
  222. * logical sector number and write
  223. * buffer address
  224. * OUT: None (ioctl return value provides
  225. * success/failure indication). */
  226. #define BIOC_GETPROCFSD _BIOC(0x000a) /* Get ProcFS data specific to the
  227. * block device.
  228. * IN: Pointer to a struct defined for
  229. * the block to load with it's
  230. * ProcFS data.
  231. * OUT: None (ioctl return value provides
  232. * success/failure indication). */
  233. #define BIOC_DEBUGCMD _BIOC(0x000b) /* Send driver specific debug command /
  234. * data to the block device.
  235. * IN: Pointer to a struct defined for
  236. * the block with specific debug
  237. * command and data.
  238. * OUT: None. */
  239. #define BIOC_GEOMETRY _BIOC(0x000c) /* Used only by BCH to return the
  240. * geometry of the contained block
  241. * driver.
  242. * IN: Pointer to writable instance
  243. * of struct geometry in which
  244. * to return geometry.
  245. * OUT: Data return in user-provided
  246. * buffer. */
  247. #define BIOC_FLUSH _BIOC(0x000d) /* Flush the block device write buffer
  248. * IN: None
  249. * OUT: None (ioctl return value provides
  250. * success/failure indication). */
  251. /* NuttX MTD driver ioctl definitions ***************************************/
  252. #define _MTDIOCVALID(c) (_IOC_TYPE(c)==_MTDIOCBASE)
  253. #define _MTDIOC(nr) _IOC(_MTDIOCBASE,nr)
  254. /* Socket IOCTLs ************************************************************/
  255. /* See include/nuttx/net/ioctl.h */
  256. #define _SIOCVALID(c) (_IOC_TYPE(c)==_SIOCBASE)
  257. #define _SIOC(nr) _IOC(_SIOCBASE,nr)
  258. /* NuttX ARP driver ioctl definitions (see netinet/arp.h) *******************/
  259. #define _ARPIOCVALID(c) (_IOC_TYPE(c)==_ARPIOCBASE)
  260. #define _ARPIOC(nr) _IOC(_ARPIOCBASE,nr)
  261. /* NuttX touchscreen ioctl definitions (see nuttx/input/touchscreen.h) ******/
  262. #define _TSIOCVALID(c) (_IOC_TYPE(c)==_TSIOCBASE)
  263. #define _TSIOC(nr) _IOC(_TSIOCBASE,nr)
  264. /* NuttX sensor ioctl definitions (see nuttx/sensor/ioctl.h) ****************/
  265. #define _SNIOCVALID(c) (_IOC_TYPE(c)==_SNIOCBASE)
  266. #define _SNIOC(nr) _IOC(_SNIOCBASE,nr)
  267. /* Nuttx Analog (DAC/ADC) ioctl commands (see nuttx/analog/ioctl.h **********/
  268. #define _ANIOCVALID(c) (_IOC_TYPE(c)==_ANIOCBASE)
  269. #define _ANIOC(nr) _IOC(_ANIOCBASE,nr)
  270. /* NuttX PWM ioctl definitions (see nuttx/timers/pwm.h) *********************/
  271. #define _PWMIOCVALID(c) (_IOC_TYPE(c)==_PWMIOCBASE)
  272. #define _PWMIOC(nr) _IOC(_PWMIOCBASE,nr)
  273. /* NuttX USB CDC/ACM serial driver ioctl definitions ************************/
  274. /* (see nuttx/usb/cdcacm.h) */
  275. #define _CAIOCVALID(c) (_IOC_TYPE(c)==_CAIOCBASE)
  276. #define _CAIOC(nr) _IOC(_CAIOCBASE,nr)
  277. /* NuttX battery driver ioctl definitions ***********************************/
  278. /* (see nuttx/power/battery.h) */
  279. #define _BATIOCVALID(c) (_IOC_TYPE(c)==_BATIOCBASE)
  280. #define _BATIOC(nr) _IOC(_BATIOCBASE,nr)
  281. /* NuttX Quadrature Encoder driver ioctl definitions ************************/
  282. /* (see nuttx/power/battery.h) */
  283. #define _QEIOCVALID(c) (_IOC_TYPE(c)==_QEIOCBASE)
  284. #define _QEIOC(nr) _IOC(_QEIOCBASE,nr)
  285. /* NuttX Audio driver ioctl definitions *************************************/
  286. /* (see nuttx/audio/audio.h) */
  287. #define _AUDIOIOCVALID(c) (_IOC_TYPE(c)==_AUDIOIOCBASE)
  288. #define _AUDIOIOC(nr) _IOC(_AUDIOIOCBASE,nr)
  289. /* LCD character driver ioctl definitions ***********************************/
  290. /* (see nuttx/include/lcd/slcd_codec.h */
  291. #define _LCDIOCVALID(c) (_IOC_TYPE(c)==_LCDIOCBASE)
  292. #define _LCDIOC(nr) _IOC(_LCDIOCBASE,nr)
  293. /* Segment LCD driver ioctl definitions *************************************/
  294. /* (see nuttx/include/lcd/slcd_codec.h */
  295. #define _SLCDIOCVALID(c) (_IOC_TYPE(c)==_SLCDIOCBASE)
  296. #define _SLCDIOC(nr) _IOC(_SLCDIOCBASE,nr)
  297. /* Wireless driver character driver ioctl definitions ***********************/
  298. /* (see nuttx/include/wireless/ioctl.h */
  299. #define _WLCIOCVALID(c) (_IOC_TYPE(c)==_WLCIOCBASE)
  300. #define _WLCIOC(nr) _IOC(_WLCIOCBASE,nr)
  301. /* Application Config Data driver ioctl definitions *************************/
  302. /* (see nuttx/include/configdata.h */
  303. #define _CFGDIOCVALID(c) (_IOC_TYPE(c)==_CFGDIOCBASE)
  304. #define _CFGDIOC(nr) _IOC(_CFGDIOCBASE,nr)
  305. /* Timer driver ioctl commands **********************************************/
  306. /* (see nuttx/include/timer.h */
  307. #define _TCIOCVALID(c) (_IOC_TYPE(c)==_TCIOCBASE)
  308. #define _TCIOC(nr) _IOC(_TCIOCBASE,nr)
  309. /* Joystick driver ioctl definitions ****************************************/
  310. /* Discrete Joystick (see nuttx/include/input/djoystick.h */
  311. #define _JOYIOCVALID(c) (_IOC_TYPE(c)==_JOYBASE)
  312. #define _JOYIOC(nr) _IOC(_JOYBASE,nr)
  313. /* FIFOs and pipe driver ioctl definitions **********************************/
  314. #define _PIPEIOCVALID(c) (_IOC_TYPE(c)==_PIPEBASE)
  315. #define _PIPEIOC(nr) _IOC(_PIPEBASE,nr)
  316. #define PIPEIOC_POLICY _PIPEIOC(0x0001) /* Set buffer policy
  317. * IN: unsigned long integer
  318. * 0=free on last close
  319. * (default)
  320. * 1=fre when empty
  321. * OUT: None */
  322. /* RTC driver ioctl definitions *********************************************/
  323. /* (see nuttx/include/rtc.h */
  324. #define _RTCIOCVALID(c) (_IOC_TYPE(c)==_RTCBASE)
  325. #define _RTCIOC(nr) _IOC(_RTCBASE,nr)
  326. /* Relay driver ioctl definitions *******************************************/
  327. /* (see nuttx/power/relay.h */
  328. #define _RELAYIOCVALID(c) (_IOC_TYPE(c)==_RELAYBASE)
  329. #define _RELAYIOC(nr) _IOC(_RELAYBASE,nr)
  330. /* CAN driver ioctl definitions *********************************************/
  331. /* (see nuttx/can/can.h */
  332. #define _CANIOCVALID(c) (_IOC_TYPE(c)==_CANBASE)
  333. #define _CANIOC(nr) _IOC(_CANBASE,nr)
  334. /* Button driver ioctl definitions ******************************************/
  335. /* (see nuttx/input/buttons.h */
  336. #define _BTNIOCVALID(c) (_IOC_TYPE(c)==_BTNBASE)
  337. #define _BTNIOC(nr) _IOC(_BTNBASE,nr)
  338. /* User LED driver ioctl definitions ****************************************/
  339. /* (see nuttx/leds/usersled.h */
  340. #define _ULEDIOCVALID(c) (_IOC_TYPE(c)==_ULEDBASE)
  341. #define _ULEDIOC(nr) _IOC(_ULEDBASE,nr)
  342. /* Zero Cross driver ioctl definitions **************************************/
  343. /* (see nuttx/include/sensor/zerocross.h */
  344. #define _ZCIOCVALID(c) (_IOC_TYPE(c)==_ZCBASE)
  345. #define _ZCIOC(nr) _IOC(_ZCBASE,nr)
  346. /* Loop driver ioctl definitions ********************************************/
  347. /* (see nuttx/include/fs/loop.h */
  348. #define _LOOPIOCVALID(c) (_IOC_TYPE(c)==_LOOPBASE)
  349. #define _LOOPIOC(nr) _IOC(_LOOPBASE,nr)
  350. /* Modem driver ioctl definitions *******************************************/
  351. /* see nuttx/include/modem/ioctl.h */
  352. #define _MODEMIOCVALID(c) (_IOC_TYPE(c)==_MODEMBASE)
  353. #define _MODEMIOC(nr) _IOC(_MODEMBASE,nr)
  354. /* I2C driver ioctl definitions *********************************************/
  355. /* see nuttx/include/i2c/i2c_master.h */
  356. #define _I2CIOCVALID(c) (_IOC_TYPE(c)==_I2CBASE)
  357. #define _I2CIOC(nr) _IOC(_I2CBASE,nr)
  358. /* SPI driver ioctl definitions *********************************************/
  359. /* see nuttx/include/spi/spi_transfer.h */
  360. #define _SPIIOCVALID(c) (_IOC_TYPE(c)==_SPIBASE)
  361. #define _SPIIOC(nr) _IOC(_SPIBASE,nr)
  362. /* GPIO driver command definitions ******************************************/
  363. /* see nuttx/include/ioexpander/gpio.h */
  364. #define _GPIOCVALID(c) (_IOC_TYPE(c)==_GPIOBASE)
  365. #define _GPIOC(nr) _IOC(_GPIOBASE,nr)
  366. /* Contactless driver ioctl definitions *************************************/
  367. /* (see nuttx/include/contactless/ioctl.h */
  368. #define _CLIOCVALID(c) (_IOC_TYPE(c)==_CLIOCBASE)
  369. #define _CLIOC(nr) _IOC(_CLIOCBASE,nr)
  370. /* USB-C controller driver ioctl definitions ********************************/
  371. /* (see nuttx/include/usb/xxx.h */
  372. #define _USBCIOCVALID(c) (_IOC_TYPE(c)==_USBCBASE)
  373. #define _USBCIOC(nr) _IOC(_USBCBASE,nr)
  374. /* 802.15.4 MAC driver ioctl definitions ************************************/
  375. /* (see nuttx/include/wireless/ieee802154/ieee802154_mac.h */
  376. #define _MAC802154IOCVALID(c) (_IOC_TYPE(c)==_MAC802154BASE)
  377. #define _MAC802154IOC(nr) _IOC(_MAC802154BASE,nr)
  378. /* Power-Related IOCTLs *****************************************************/
  379. #define _PWRIOCVALID(c) (_IOC_TYPE(c)==_PWRBASE)
  380. #define _PWRIOC(nr) _IOC(_PWRBASE,nr)
  381. /* Frame buffer character drivers *******************************************/
  382. #define _FBIOCVALID(c) (_IOC_TYPE(c)==_FBIOCBASE)
  383. #define _FBIOC(nr) _IOC(_FBIOCBASE,nr)
  384. /* NxTerm character drivers *************************************************/
  385. #define _NXTERMVALID(c) (_IOC_TYPE(c)==_NXTERMBASE)
  386. #define _NXTERMIOC(nr) _IOC(_NXTERMBASE,nr)
  387. /* NuttX RF ioctl definitions (see nuttx/rf/ioctl.h) ************************/
  388. #define _RFIOCVALID(c) (_IOC_TYPE(c)==_RFIOCBASE)
  389. #define _RFIOC(nr) _IOC(_RFIOCBASE,nr)
  390. /* Rptun drivers ************************************************************/
  391. #define _RPTUNIOCVALID(c) (_IOC_TYPE(c)==_RPTUNBASE)
  392. #define _RPTUNIOC(nr) _IOC(_RPTUNBASE,nr)
  393. /* Wireless driver network ioctl definitions ********************************/
  394. /* (see nuttx/include/wireless/wireless.h */
  395. #define _WLIOCVALID(c) (_IOC_TYPE(c)==_WLIOCBASE)
  396. #define _WLIOC(nr) _IOC(_WLIOCBASE,nr)
  397. /* boardctl() command definitions *******************************************/
  398. #define _BOARDIOCVALID(c) (_IOC_TYPE(c)==_BOARDBASE)
  399. #define _BOARDIOC(nr) _IOC(_BOARDBASE,nr)
  400. /****************************************************************************
  401. * Public Type Definitions
  402. ****************************************************************************/
  403. /****************************************************************************
  404. * Public Data
  405. ****************************************************************************/
  406. #ifdef __cplusplus
  407. #define EXTERN extern "C"
  408. extern "C"
  409. {
  410. #else
  411. #define EXTERN extern
  412. #endif
  413. /****************************************************************************
  414. * Public Function Prototypes
  415. ****************************************************************************/
  416. #undef EXTERN
  417. #ifdef __cplusplus
  418. }
  419. #endif
  420. #endif /* __INCLUDE_NUTTX_FS_IOCTL_H */