cc1101.h 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634
  1. /****************************************************************************
  2. * include/nuttx/wireless/cc1101.h
  3. *
  4. * Copyright (C) 2011 Uros Platise. All rights reserved.
  5. * Authors: Uros Platise <uros.platise@isotel.eu>
  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_WIRELESS_CC1101_H
  36. #define __INCLUDE_NUTTX_WIRELESS_CC1101_H
  37. /****************************************************************************
  38. * Included Files
  39. ****************************************************************************/
  40. #include <nuttx/config.h>
  41. #include <stdint.h>
  42. #include <stdbool.h>
  43. #include <poll.h>
  44. #include <nuttx/wqueue.h>
  45. #include <nuttx/semaphore.h>
  46. #include <nuttx/spi/spi.h>
  47. /****************************************************************************
  48. * Pre-Processor Declarations
  49. ****************************************************************************/
  50. /* Present maximum packet length */
  51. #define CC1101_FIFO_SIZE 64
  52. #define CC1101_PACKET_MAXTOTALLEN 63
  53. #define CC1101_PACKET_MAXDATALEN 61
  54. /* General Purpose, Test Output Pin Options */
  55. /* CC1101 General Purpose Pins */
  56. #define CC1101_PIN_GDO0 2
  57. #define CC1101_PIN_GDO1 1
  58. #define CC1101_PIN_GDO2 0
  59. /* Associated to the RX FIFO: Asserts when RX FIFO is filled at or above
  60. * the RX FIFO threshold. De-asserts when RX FIFO is drained below the
  61. * same threshold.
  62. */
  63. #define CC1101_GDO_RXFIFO_THR 0x00
  64. /* Associated to the RX FIFO: Asserts when RX FIFO is filled at or above
  65. * the RX FIFO threshold or the end of packet is reached. De-asserts when
  66. * the RX FIFO is empty.
  67. */
  68. #define CC1101_GDO_RXFIFO_THREND 0x01
  69. /* Associated to the TX FIFO: Asserts when the TX FIFO is filled at or
  70. * above the TX FIFO threshold. De-asserts when the TX FIFO is below the
  71. * same threshold.
  72. */
  73. #define CC1101_GDO_TXFIFO_THR 0x02
  74. /* Associated to the TX FIFO: Asserts when TX FIFO is full. De-asserts
  75. * when the TX FIFO is drained below theTX FIFO threshold.
  76. */
  77. #define CC1101_GDO_TXFIFO_FULL 0x03
  78. /* Asserts when the RX FIFO has overflowed. De-asserts when the FIFO has
  79. * been flushed.
  80. */
  81. #define CC1101_GDO_RXFIFO_OVR 0x04
  82. /* Asserts when the TX FIFO has underflowed. De-asserts when the FIFO is
  83. * flushed.
  84. */
  85. #define CC1101_GDO_TXFIFO_UNR 0x05
  86. /* Asserts when sync word has been sent / received, and de-asserts at the
  87. * end of the packet. In RX, the pin will de-assert when the optional
  88. * address check fails or the RX FIFO overflows. In TX the pin will
  89. * de-assert if the TX FIFO underflows.
  90. */
  91. #define CC1101_GDO_SYNC 0x06
  92. /* Asserts when a packet has been received with CRC OK. De-asserts when
  93. * the first byte is read from the RX FIFO.
  94. */
  95. #define CC1101_GDO_PKTRCV_CRCOK 0x07
  96. /* Preamble Quality Reached. Asserts when the PQI is above the programmed
  97. * PQT value.
  98. */
  99. #define CC1101_GDO_PREAMBLE 0x08
  100. /* Clear channel assessment. High when RSSI level is below threshold
  101. * (dependent on the current CCA_MODE setting).
  102. */
  103. #define CC1101_GDO_CHCLEAR 0x09
  104. /* Lock detector output. The PLL is in lock if the lock detector output
  105. * has a positive transition or is constantly logic high. To check for
  106. * PLL lock the lock detector output should be used as an interrupt for
  107. * the MCU.
  108. */
  109. #define CC1101_GDO_LOCK 0x0A
  110. /* Serial Clock. Synchronous to the data in synchronous serial mode.
  111. * In RX mode, data is set up on the falling edge by CC1101 when GDOx_INV=0.
  112. * In TX mode, data is sampled by CC1101 on the rising edge of the serial
  113. * clock when GDOx_INV=0.
  114. */
  115. #define CC1101_GDO_SSCLK 0x0B
  116. /* Serial Synchronous Data Output. Used for synchronous serial mode. */
  117. #define CC1101_GDO_SSDO 0x0C
  118. /* Serial Data Output. Used for asynchronous serial mode. */
  119. #define CC1101_GDO_ASDO 0x0D
  120. /* Carrier sense. High if RSSI level is above threshold. */
  121. #define CC1101_GDO_CARRIER 0x0E
  122. /* CRC_OK. The last CRC comparison matched. Cleared when entering or
  123. * restarting RX mode.
  124. */
  125. #define CC1101_GDO_CRCOK 0x0F
  126. /* RX_HARD_DATA[1]. Can be used together with RX_SYMBOL_TICK for
  127. * alternative serial RX output.
  128. */
  129. #define CC1101_GDO_RXOUT1 0x16
  130. /* RX_HARD_DATA[0]. Can be used together with RX_SYMBOL_TICK for
  131. * alternative serial RX output.
  132. */
  133. #define CC1101_GDO_RXOUT0 0x17
  134. /* PA_PD. Note: PA_PD will have the same signal level in SLEEP and TX
  135. * states. To control an external PA or RX/TX switch in applications
  136. * where the SLEEP state is used it is recommended to use GDOx_CFGx=0x2F
  137. * instead.
  138. */
  139. #define CC1101_GDO_PA_PD 0x1b
  140. /* LNA_PD. Note: LNA_PD will have the same signal level in SLEEP and RX
  141. * states. To control an external LNA or RX/TX switch in applications
  142. * where the SLEEP state is used it is recommended to use GDOx_CFGx=0x2F
  143. * instead.
  144. */
  145. #define CC1101_GDO_LNA_PD 0x1c
  146. /* RX_SYMBOL_TICK. Can be used together with RX_HARD_DATA for alternative
  147. * serial RX output.
  148. */
  149. #define CC1101_GDO_RXSYMTICK 0x1d
  150. #define CC1101_GDO_WOR_EVNT0 0x24
  151. #define CC1101_GDO_WOR_EVNT1 0x25
  152. #define CC1101_GDO_CLK32K 0x27
  153. #define CC1101_GDO_CHIP_RDYn 0x29
  154. #define CC1101_GDO_XOSC_STABLE 0x2B
  155. /* GDO0_Z_EN_N. When this output is 0, GDO0 is configured as input
  156. * (for serial TX data).
  157. */
  158. #define CC1101_GDO_GDO0_Z_EN_N 0x2D
  159. /* High impedance (3-state). */
  160. #define CC1101_GDO_HIZ 0x2e
  161. /* HW to 0 (HW1 achieved by setting GDOx_INV=1). Can be used to control
  162. * an external LNA/PA or RX/TX switch.
  163. */
  164. #define CC1101_GDO_HW 0x2f
  165. /* There are 3 GDO pins, but only one CLK_XOSC/n can be selected as an
  166. * output at any time. If CLK_XOSC/n is to be monitored on one of the
  167. * GDO pins, the other two GDO pins must be configured to values less
  168. * than 0x30. The GDO0 default value is CLK_XOSC/192. To optimize RF
  169. * performance, these signals should not be used while the radio is
  170. * in RX or TX mode.
  171. */
  172. #define CC1101_GDO_CLK_XOSC1 0x30
  173. #define CC1101_GDO_CLK_XOSC1_5 0x31
  174. #define CC1101_GDO_CLK_XOSC2 0x32
  175. #define CC1101_GDO_CLK_XOSC3 0x33
  176. #define CC1101_GDO_CLK_XOSC4 0x34
  177. #define CC1101_GDO_CLK_XOSC6 0x35
  178. #define CC1101_GDO_CLK_XOSC8 0x36
  179. #define CC1101_GDO_CLK_XOSC12 0x37
  180. #define CC1101_GDO_CLK_XOSC16 0x38
  181. #define CC1101_GDO_CLK_XOSC24 0x39
  182. #define CC1101_GDO_CLK_XOSC32 0x3a
  183. #define CC1101_GDO_CLK_XOSC48 0x3b
  184. #define CC1101_GDO_CLK_XOSC64 0x3c
  185. #define CC1101_GDO_CLK_XOSC96 0x3d
  186. #define CC1101_GDO_CLK_XOSC128 0x3e
  187. #define CC1101_GDO_CLK_XOSC192 0x3f
  188. /****************************************************************************
  189. * Public Data Types
  190. ****************************************************************************/
  191. #ifndef __ASSEMBLY__
  192. #undef EXTERN
  193. #if defined(__cplusplus)
  194. # define EXTERN extern "C"
  195. extern "C"
  196. {
  197. #else
  198. # define EXTERN extern
  199. #endif
  200. typedef CODE int (*wait_cc1101_ready)(FAR struct cc1101_dev_s *dev, uint32_t);
  201. struct cc1101_dev_s;
  202. struct cc1101_ops_s
  203. {
  204. CODE void (*wait)(FAR struct cc1101_dev_s *dev, uint32_t);
  205. CODE void (*irq)(FAR struct cc1101_dev_s *dev, bool enable);
  206. CODE void (*pwr)(FAR struct cc1101_dev_s *dev, bool enable);
  207. };
  208. enum cc1101_status
  209. {
  210. CC1101_INIT,
  211. CC1101_IDLE,
  212. CC1101_SEND,
  213. CC1101_RECV,
  214. CC1101_SLEEP,
  215. CC1101_SXOFF
  216. };
  217. struct cc1101_dev_s
  218. {
  219. const struct c1101_rfsettings_s *rfsettings;
  220. struct spi_dev_s *spi;
  221. struct cc1101_ops_s ops;
  222. enum cc1101_status status;
  223. uint8_t flags;
  224. uint8_t channel;
  225. uint8_t power;
  226. uint32_t dev_id; /*SPI device Id*/
  227. uint32_t gdo; /*GDO for interrupt*/
  228. uint32_t isr_pin; /*ISR Pin*/
  229. uint32_t miso_pin; /*MISO Pin*/
  230. struct work_s irq_work; /* Interrupt handling "bottom half" */
  231. uint8_t nopens; /* The number of times the device has been opened */
  232. sem_t devsem; /* Ensures exclusive access to this structure */
  233. uint8_t *rx_buffer; /* Circular RX buffer. [pipe# / pkt_len] [packet data...] */
  234. uint16_t fifo_len; /* Number of bytes stored in fifo */
  235. uint16_t nxt_read; /* Next read index */
  236. uint16_t nxt_write; /* Next write index */
  237. sem_t sem_rx_buffer; /* Protect access to rx fifo */
  238. sem_t sem_rx; /* Wait for availability of received data */
  239. sem_t sem_tx; /* Wait for availability of send data */
  240. FAR struct pollfd *pfd; /* Polled file descr (or NULL if any) */
  241. };
  242. /* The RF Settings includes only those fields required to configure
  243. * the RF radio. Other configuration fields depended on this driver
  244. * are configured by the cc1101_init().
  245. *
  246. * REVISIT: Upper case field names violates the NuttX coding standard.
  247. */
  248. struct c1101_rfsettings_s
  249. {
  250. uint8_t FIFOTHR; /* FIFOTHR */
  251. uint8_t SYNC1; /* SYNC1 */
  252. uint8_t SYNC0; /* SYNC0 */
  253. uint8_t PKTLEN; /* PKTLEN */
  254. uint8_t PKTCTRL0; /* Packet Automation Control */
  255. uint8_t PKTCTRL1; /* Packet Automation Control */
  256. uint8_t ADDR; /* ADDR */
  257. uint8_t CHANNR; /* CHANNR */
  258. uint8_t FSCTRL1; /* Frequency synthesizer control. */
  259. uint8_t FSCTRL0; /* Frequency synthesizer control. */
  260. uint8_t FREQ2; /* Frequency control word, high byte. */
  261. uint8_t FREQ1; /* Frequency control word, middle byte. */
  262. uint8_t FREQ0; /* Frequency control word, low byte. */
  263. uint8_t MDMCFG4; /* Modem configuration. */
  264. uint8_t MDMCFG3; /* Modem configuration. */
  265. uint8_t MDMCFG2; /* Modem configuration. */
  266. uint8_t MDMCFG1; /* Modem configuration. */
  267. uint8_t MDMCFG0; /* Modem configuration. */
  268. uint8_t DEVIATN; /* Modem deviation setting (when FSK modulation is enabled). */
  269. /* GAP */
  270. uint8_t FOCCFG; /* Frequency Offset Compensation Configuration. */
  271. uint8_t BSCFG; /* Bit synchronization Configuration. */
  272. uint8_t AGCCTRL2; /* AGC control. */
  273. uint8_t AGCCTRL1; /* AGC control. */
  274. uint8_t AGCCTRL0; /* AGC control. */
  275. /* GAP */
  276. uint8_t FREND1; /* Front end RX configuration. */
  277. uint8_t FREND0; /* Front end RX configuration. */
  278. uint8_t FSCAL3; /* Frequency synthesizer calibration. */
  279. uint8_t FSCAL2; /* Frequency synthesizer calibration. */
  280. uint8_t FSCAL1; /* Frequency synthesizer calibration. */
  281. uint8_t FSCAL0; /* Frequency synthesizer calibration. */
  282. /* REGULATORY LIMITS */
  283. uint8_t CHMIN; /* Channel Range definition MIN .. */
  284. uint8_t CHMAX; /* .. and MAX */
  285. uint8_t PAMAX; /* at given maximum output power */
  286. /* Power Table, for ramp-up/down and ASK modulation defined for
  287. * output power values as:
  288. * PA = {-30, -20, -15, -10, -5, 0, 5, 10} [dBm]
  289. */
  290. uint8_t PA[8];
  291. };
  292. /****************************************************************************
  293. * RF Configuration Database
  294. ****************************************************************************/
  295. /* TODO Recalculate ERP in maximum power level */
  296. /* 868 MHz, GFSK, 100 kbps, ISM Region 1 (Europe only)
  297. *
  298. * ISM Region 1 (Europe) only, Band 868–870 MHz
  299. *
  300. * Frequency bands for non-specific short range devices in Europe:
  301. *
  302. * Frequency ERP Duty Cycle Bandwidth Remarks
  303. * 868 – 868.6 MHz +14 dBm < 1% No limits
  304. * 868.7 – 869.2 MHz +14 dBm < 0.1% No limits
  305. * 869.3 – 869.4 MHz +10 dBm No limits < 25 kHz Appropriate access
  306. * protocol required 869.4 – 869.65 MHz +27 dBm < 10% < 25 kHz
  307. * Channels may be combined to one high speed channel 869.7 -870 MHz +7
  308. * dBm No limits No limits
  309. *
  310. * Frequency Band For License-Free Specific Applications in Europe
  311. *
  312. * Frequency Application ERP Duty Cycle Bandwidth
  313. * 868.6 – 868.7 MHz Alarms +10 dBm < 0.1% 25 kHz(1)
  314. * 869.2 – 869.25 MHz Social Alarms +10 dBm < 0.1% 25 kHz
  315. * 869.25 – 869.3 MHz Alarms +10 dBm < 0.1% 25 kHz
  316. * 869.65 -869.7 MHz Alarms +14 dBm < 10% 25 kHz
  317. * 863 – 865 MHz Radio Microphones +10 dBm No limits 200 kHz
  318. * 863 -865 MHz Wireless Audio Applications +10 dBm No limits 300 kHz
  319. *
  320. * Duty Cycle Limit Total On Time Maximum On Time of Minimum
  321. * Off Time of Within One Hour One Transmission Two Transmission <
  322. * 0.1% 3.6 seconds 0.72 seconds 0.72 seconds < 1% 36
  323. * seconds 3.6 seconds 1.8 seconds < 10% 360
  324. * seconds 36 seconds 3.6 seconds
  325. *
  326. * Reference: TI Application Report: swra048.pdf, May 2005
  327. * ISM-Band and Short Range Device Regulatory Compliance Overview
  328. */
  329. EXTERN const struct c1101_rfsettings_s
  330. cc1101_rfsettings_ISM1_868MHzGFSK100kbps;
  331. /* 905 MHz, GFSK, 250 kbps, ISM Region 2 (America only)
  332. *
  333. * ISM Region 2 (America) only, Band 902–928 MHz
  334. *
  335. * Cordless phones 1 W
  336. * Microwave ovens 750 W
  337. * Industrial heaters 100 kW
  338. * Military radar 1000 kW
  339. */
  340. EXTERN const struct c1101_rfsettings_s
  341. cc1101_rfsettings_ISM2_905MHzGFSK250kbps;
  342. EXTERN const struct c1101_rfsettings_s
  343. cc1101_rfsettings_ISM2_433MHzMSK500kbps;
  344. /****************************************************************************
  345. * Public Function Prototypes
  346. ****************************************************************************/
  347. FAR int cc1101_init2(FAR struct cc1101_dev_s *dev);
  348. /****************************************************************************
  349. * Initialize Chipcon CC1101 Chip.
  350. * After initialization CC1101 is ready to listen, receive and transmit
  351. * messages on the default channel 0 at given RF configuration.
  352. *
  353. * Input Parameters:
  354. * spi SPI Device Structure
  355. * isrpin Select the CC1101_PIN_GDOx used to signal interrupts
  356. * rfsettings Pointer to default RF Settings loaded at boot time.
  357. *
  358. * Returned Value:
  359. * Pointer to newly allocated CC1101 structure or NULL on error with errno
  360. * set.
  361. *
  362. * Possible errno as set by this function on error:
  363. * - ENODEV: When device addressed is not compatible or it is not a CC1101
  364. * - EFAULT: When there is no device
  365. * - ENOMEM: Out of kernel memory to allocate the device
  366. * - EBUSY: When device is already addressed by other device driver (not yet
  367. * supported by low-level driver)
  368. *
  369. ****************************************************************************/
  370. struct cc1101_dev_s *cc1101_init(
  371. FAR struct spi_dev_s *spi, uint32_t isr_pin, uint32_t miso_pin,
  372. FAR const struct c1101_rfsettings_s *rfsettings, wait_cc1101_ready wait);
  373. /****************************************************************************
  374. ** Deinitialize Chipcon CC1101 Chip
  375. *
  376. * Input Parameters:
  377. * dev Device to CC1101 device structure, as returned by the cc1101_init()
  378. *
  379. * Returned Value:
  380. * OK On success
  381. *
  382. ****************************************************************************/
  383. int cc1101_deinit(FAR struct cc1101_dev_s *dev);
  384. /****************************************************************************
  385. * Power up device, start conversion. Returns zero on success.
  386. ****************************************************************************/
  387. int cc1101_powerup(FAR struct cc1101_dev_s *dev);
  388. /****************************************************************************
  389. * Power down device, stop conversion. Returns zero on success.
  390. ****************************************************************************/
  391. int cc1101_powerdown(FAR struct cc1101_dev_s *dev);
  392. /****************************************************************************
  393. * Set Multi Purpose Output Function. Returns zero on success.
  394. ****************************************************************************/
  395. int cc1101_setgdo(FAR struct cc1101_dev_s *dev, uint8_t pin, uint8_t function);
  396. /****************************************************************************
  397. * Set RF settings. Use one from the database above.
  398. ****************************************************************************/
  399. int cc1101_setrf(FAR struct cc1101_dev_s *dev,
  400. FAR const struct c1101_rfsettings_s *settings);
  401. /****************************************************************************
  402. * Set Channel.
  403. * Note that regulatory check is made and sending may be prohibited.
  404. *
  405. * Returned Value:
  406. * 0 On success, sending and receiving is allowed.
  407. * 1 Only receive mode is allowed.
  408. * <0 On error.
  409. *
  410. ****************************************************************************/
  411. int cc1101_setchannel(FAR struct cc1101_dev_s *dev, uint8_t channel);
  412. /****************************************************************************
  413. * Set Output Power
  414. *
  415. * Input Parameters:
  416. * power Value from 0 - 8, where 0 means power off, and values
  417. * from 1 .. 8 denote the following output power in dBm:
  418. * {-30, -20, -15, -10, -5, 0, 5, 10} [dBm]
  419. *
  420. * If power is above the regulatory limit (defined by the RF settings)
  421. * it is limited.
  422. *
  423. * Returned Value:
  424. * Actual output power in range from 0..8.
  425. *
  426. ****************************************************************************/
  427. uint8_t cc1101_setpower(FAR struct cc1101_dev_s *dev, uint8_t power);
  428. /****************************************************************************
  429. * Convert RSSI as obtained from CC1101 to [dBm]
  430. *
  431. ****************************************************************************/
  432. int cc1101_calcRSSIdBm(int rssi);
  433. /****************************************************************************
  434. * Enter receive mode and wait for a packet.
  435. * If transmission is in progress, receive mode is entered upon its
  436. * completion. As long cc1101_idle() is not called, each transmission
  437. * returns to receive mode.
  438. *
  439. * Input Parameters:
  440. * dev Device to CC1101 structure
  441. *
  442. * Returned Value:
  443. * Zero on success.
  444. *
  445. ****************************************************************************/
  446. int cc1101_receive(FAR struct cc1101_dev_s *dev);
  447. /****************************************************************************
  448. * Read received packet
  449. *
  450. * If size of buffer is too small then the remaining part of data can
  451. * be discarded by the driver.
  452. *
  453. * Packet contains raw data, including the two bytes:
  454. * - RSSI and
  455. * - LQI
  456. * appended at the end of the message.
  457. *
  458. * To inquery about the data pending size you the following:
  459. * - pass buf=NULL and size > 0, returns pending data packet size
  460. * - pass buf=NULL and size = 0, returns maximum data packet size
  461. *
  462. * NOTE: messages length are typically defined by the MAC, transmit/
  463. * receive windows at some rate.
  464. *
  465. ****************************************************************************/
  466. int cc1101_read(FAR struct cc1101_dev_s *dev, FAR uint8_t *buf, size_t size);
  467. /****************************************************************************
  468. * Write data to be send, using the cc1101_send()
  469. *
  470. * Input Parameters:
  471. * dev Device to CC1101 structure
  472. * buf Pointer to data.
  473. * size Size must be within limits, otherwise data is truncated.
  474. * Present driver limitation supports a single cc1101_write()
  475. * prioer cc1101_send() is called.
  476. *
  477. ****************************************************************************/
  478. int cc1101_write(FAR struct cc1101_dev_s *dev, FAR const uint8_t *buf,
  479. size_t size);
  480. /****************************************************************************
  481. * Send data previously written using cc1101_write()
  482. *
  483. * Input Parameters:
  484. * dev Device to CC1101 structure
  485. *
  486. * Returned Value:
  487. * Zero on success.
  488. *
  489. ****************************************************************************/
  490. int cc1101_send(FAR struct cc1101_dev_s *dev);
  491. /****************************************************************************
  492. * Enter idle state (after reception and transmission completes).
  493. *
  494. * Returned Value:
  495. * Zero on success.
  496. *
  497. ****************************************************************************/
  498. int cc1101_idle(FAR struct cc1101_dev_s *dev);
  499. int cc1101_register(FAR const char *path, FAR struct cc1101_dev_s *dev);
  500. void cc1101_isr_process(FAR void *arg);
  501. int cc1101_isr(int irq, FAR void *context, FAR void *arg);
  502. #undef EXTERN
  503. #if defined(__cplusplus)
  504. }
  505. #endif
  506. #endif /* __ASSEMBLY__ */
  507. #endif /* __INCLUDE_NUTTX_WIRELESS_CC1101_H */