This commit is contained in:
Laureηt 2023-06-20 20:50:12 +02:00
commit dd8ea38ff2
Signed by: Laurent
SSH key fingerprint: SHA256:kZEpW8cMJ54PDeCvOhzreNr4FSh6R13CMGH/POoO8DI
16 changed files with 3300 additions and 0 deletions

1300
DecaDuino-master/DecaDuino.cpp Executable file

File diff suppressed because it is too large Load diff

966
DecaDuino-master/DecaDuino.h Executable file
View file

@ -0,0 +1,966 @@
// DecaDuino.h
//
// Another DecaWave DW1000 driver for Arduino
// See the README file in this directory for documentation
//
/// \mainpage DecaDuino library for Arduino
///
/// Get the latest version of this documentation here: https://www.irit.fr/~Adrien.Van-Den-Bossche/decaduino/
///
/// DecaDuino is an Arduino library which provides a driver for the DecaWave DW1000 transceiver and modules based on this transceiver, such as DecaWave DWM1000. Since the DW1000 is based on a Ultra Wide Band (UWB) Physical layer, in addition to wireless communication, DecaDuino supports Time-of-Flight (ToF) ranging and can be used as an open framework for protocol evaluation.
///
/// DecaDuino supports the PJRC Teensy 3.2/3.1/3.0. Others Arduino boards have not been tested yet. User feedback on the topic will be greatly appreciated. For this purpose, please use the contact address indicated in the "Contact, feedback and users forum" section of this documentation.
///
/// DecaDuino is a <i>Physical-layer Service Access Point (PHY-SAP)</i>. It provides the two conventional <i>Physical-Data</i> (PD) and <i>Physical Layer Management Entity</i> (PLME) SAPs which enable MAC-level protocols to send/receive data and configure the transceiver (channel, transmission rate, preamble parameters...). Since this framework was designed to aid in the implementation of Time-of-Flight based ranging protocols, DecaDuino also provides access to the DW1000's Physical-level high precision timer (64GHz/40bit) which enables precise message timestamping at both transmission (t_TX) and reception (t_RX). Finally, DecaDuino implements DW1000's advanced synchronization/timestamping functionalities such as delayed transmission and receiver skew evaluation, which are required for efficient centimetre-level ranging protocols using Time-of-Flight.
///
/// DecaDuino comes with several Arduino examples implementing the most popular ranging protocols such as <i>Two-Way Ranging</i> (TWR) and <i>Symetrical Double-Sided Two-Way Ranging</i> (SDS-TWR).
///
/// \image html DecaDuinoStack.png
///
/// DecaDuino has been written by Adrien van den Bossche and Réjane Dalcé at the <a href='http://www.irit.fr'>Institut de Recherche en Informatique de Toulouse</a> (IRIT), France. Thanks to Thierry Val, François Despaux, Laurent Guerby, Ibrahim Fofana and Robert Try for their contributions to DecaDuino.
///
/// \par Download
///
/// Get the <a href='https://github.com/irit-irt/DecaDuino'>current release of the library on github.com</a>. Previous versions (before github.com hosting) are also available in the "Revision History" section of this documentation.
///
/// \par Installation
///
/// To use DecaDuino on a PJRC Teensy 3.2/3.1/3.0, install the <a href='http://www.pjrc.com/teensy/teensyduino.html'>Teensyduino add-on</a> first. Then, download DecaDuino, unzip the files into the libraries sub-directory and relaunch the Arduino environment; you should see the library in the Sketch->Import Library menu, and example sketches in File->Examples->DecaDuino.
///
/// \par Usage
///
/// Remember to import the SPI and Decaduino libraries in your sketches:
/// \code
/// #include <SPI.h>
/// #include <DecaDuino.h>
/// \endcode
/// For more details, please checkout the examples in the File->Examples->DecaDuino menu in the Arduino IDE. The sketches include both frame send/receive examples and ranging protocols implementation examples.
///
/// \par Contact, feedback and users forum
///
/// Please contact <a href='mailto:vandenbo_nospam@irit.fr?subject=[DecaDuino] '>Adrien van den Bossche</a> (remove _nospam) for any question concerning DecaDuino.
///
/// \par Demonstrations
///
/// <a href='https://www.irit.fr/~Adrien.Van-Den-Bossche/DecaWiNo/20150914-DecaWiNo-SDS-TWR-RGB-strip-low_res.mp4'>In this video</a>, a fixed node running DecaDuino executes a ranging session every 100ms with another node, using the TWR protocol. Once the distance to the other node is estimated, the fixed node represents the distance by driving an RGB LED strip: the LED corresponding to the estimated distance is powered up in blue. Note that the strip used in the video is 1m-long and the leds are spaced by 1.65cm. Using a LED strip gives a direct and real-time feedback of the ranging precision and accuracy using DecaDuino.
/// \htmlonly <a href='https://www.irit.fr/~Adrien.Van-Den-Bossche/DecaWiNo/20150914-DecaWiNo-SDS-TWR-RGB-strip-low_res.mp4'> \endhtmlonly
/// \image html TWR_led_strip.jpg
/// \htmlonly </a> \endhtmlonly
///
/// \par Revision History
///
/// - <a href='https://github.com/irit-irt/DecaDuino'>Current release on github.com</a>
///
/// - <a href='https://www.irit.fr/~Adrien.Van-Den-Bossche/decaduino/download/decaduino-1.0.zip'>1.0 (19/03/2016) Initial release</a>
///
/// \par Academic Publications
///
/// DecaDuino has been presented in this academic publication: <a target='_blank' href='https://www.irit.fr/~Adrien.Van-Den-Bossche/papers/WD2016_AVDB_RD_IF_TV_OpenWiNo.pdf'>Adrien Van den Bossche, Rejane Dalce, Nezo Ibrahim Fofana, Thierry Val, <i>DecaDuino: An Open Framework for Wireless Time-of-Flight Ranging Systems</i></a>, IFIP Wireless Days (WD 2016) conference, Toulouse, 23/03/2016-25/03/2016.
///
/// Academic Publications that references DecaDuino <a href='https://www.irit.fr/~Adrien.Van-Den-Bossche/projets_decaduino.php'>are listed here</a>. Please contact <a href='mailto:vandenbo_nospam@irit.fr?subject=[DecaDuino] '>Adrien van den Bossche</a> (remove _nospam) if you want to add your work to this list.
///
/// \par Licence
///
/// DecaDuino's use is subject to licensing, GPL_V3 (http://www.gnu.org/copyleft/gpl.html) or Commercial. Please contact <a href='mailto:vandenbo_nospam@irit.fr?subject=[DecaDuino] '>Adrien van den Bossche</a> (remove _nospam) for Commercial Licensing.
///
/// \page Hardware
///
/// \par Supported Hardware
///
/// DecaDuino supports PJRC Teensy 3.2/3.1/3.0 MCU and DecaWave DM1000 chip and DWM1000 module.
///
/// Please report any successfull operation on others Arduino boards by using the contact address indicated in the "Contact, feedback and users forum" section of this documentation.
///
/// \par Wiring
///
/// A wiring example between Teensy 3.2 and DWM1000 module is given here.
///
/// \image html Wiring.png
///
/// Notes:
/// - In the reception state, the DWM1000 consumes 110mA+ which is more than the Teensy 3.1 can provide. You may add a DC-DC converter on the board to supply VDD 3.3V to the DWM1000. The Teensy 3.2 solves this issue as it embeds an DC-DC converter that can provide 250mA+ on the 3.3V pin.
/// - On the Teensy 3.2/3.1, the default SPI clock pin (SCK) is the pin 13, which the same pin than the onboard LED. We recommend using an alternative SPI clock pin (SCK_, pin 14) on the Teensy. This configuration can be achieved using the following instruction:
/// \code
/// SPI.setSCK(14);
/// \endcode
///
/// \par Hardware examples
///
/// - <a target='_blank' href='http://wino.cc/decawino'>DecaWiNo: <i>Deca-Wireless Node</i></a>. The <a target='_blank' href='http://wino.cc/decawino'>DecaWiNo</a> is the first DecaDuino-compliant hardware built in our facility (IRIT). It includes a PJRC Teensy 3.1, a DecaWave DWM1000 module, a MCP1825 3.3V DC-DC converter and a 5mm RGB LED.
///
/// \image html DecaWiNo.jpg
#ifndef DecaDuino_h
#define DecaDuino_h
#include "Arduino.h"
//#define DECADUINO_DEBUG
#define DW1000_IRQ0_PIN 9
#define DW1000_IRQ1_PIN 0
#define DW1000_IRQ2_PIN 1
#define DW1000_CS0_PIN 10
#define DW1000_CS1_PIN 10 ///@todo Check Teensy3.1 other SlaveSelect pins
#define DW1000_CS2_PIN 10 ///@todo Check Teensy3.1 other SlaveSelect pins
#define MAX_NB_DW1000_FOR_INTERRUPTS 32
#define DEBUG_STR_LEN 256
#define RANGING_ERROR 0x00
#define DW1000_TIMEBASE 15.65E-12
#define AIR_SPEED_OF_LIGHT 282622876.092008 // @brief Unofficial celerity value, prototype based, by Adrien van den Bossche <vandenbo at univ-tlse2.fr>
#define RANGING_UNIT AIR_SPEED_OF_LIGHT*DW1000_TIMEBASE
#define DWM1000_DEFAULT_ANTENNA_DELAY_VALUE 32847 //@brief Calibration value for DWM1000 on IRIT's DecaWiNo, by Adrien van den Bossche <vandenbo at univ-tlse2.fr>
#define DW1000_TRX_STATUS_IDLE 0
#define DW1000_TRX_STATUS_TX 1
#define DW1000_TRX_STATUS_RX 2
#define DW1000_TRX_STATUS_SLEEP 3
// DW1000 register map
#define DW1000_REGISTER_DEV_ID 0x00
#define DW1000_REGISTER_EUI 0x01
#define DW1000_REGISTER_PANADR 0x03
#define DW1000_REGISTER_PANADR_SHORT_ADDRESS_OFFSET 0x00
#define DW1000_REGISTER_PANADR_PANID_OFFSET 0x02
#define DW1000_REGISTER_SYS_CFG 0x04
#define DW1000_REGISTER_SYS_CFG_RXAUTR_MASK 0x20000000
#define DW1000_REGISTER_SYS_CFG_PHR_MODE_MASK 0x00030000
#define DW1000_REGISTER_SYS_CFG_PHR_MODE_SHIFT 16
#define DW1000_REGISTER_SYS_TIME 0x06
#define DW1000_REGISTER_TX_FCTRL 0x08
#define DW1000_REGISTER_TX_FCTRL_FRAME_LENGTH_MASK 0x000003FF
#define DW1000_REGISTER_TX_BUFFER 0x09
#define DW1000_REGISTER_DX_TIME 0x0A
#define DW1000_REGISTER_SYS_CTRL 0x0D
#define DW1000_REGISTER_SYS_CTRL_TXSTRT_MASK 0x00000002
#define DW1000_REGISTER_SYS_CTRL_TXDLYS_MASK 0x00000004
#define DW1000_REGISTER_SYS_CTRL_TRXOFF_MASK 0x00000040
#define DW1000_REGISTER_SYS_CTRL_RXENAB_MASK 0x00000100
#define DW1000_REGISTER_SYS_MASK 0x0E
#define DW1000_REGISTER_SYS_MASK_MTXFRS_MASK 0x00000080
#define DW1000_REGISTER_SYS_MASK_MRXDFR_MASK 0x00002000
#define DW1000_REGISTER_SYS_MASK_MRXFCG_MASK 0x00004000
#define DW1000_REGISTER_SYS_STATUS 0x0F
#define DW1000_REGISTER_SYS_STATUS_IRQS_MASK 0x00000001
#define DW1000_REGISTER_SYS_STATUS_TXFRS_MASK 0x00000080
#define DW1000_REGISTER_SYS_STATUS_LDEDONE_MASK 0x00000400
#define DW1000_REGISTER_SYS_STATUS_RXDFR_MASK 0x00002000
#define DW1000_REGISTER_SYS_STATUS_RXFCG_MASK 0x00004000
#define DW1000_REGISTER_SYS_STATUS_RXFCE_MASK 0x00008000
#define DW1000_REGISTER_RX_FINFO 0x10
#define DW1000_REGISTER_RX_FINFO_RXFLEN_MASK 0x000003FF
#define DW1000_REGISTER_RX_BUFFER 0x11
#define DW1000_REGISTER_RX_RFQUAL 0x12
#define DW1000_REGISTER_RX_TTCKI 0x13
#define DW1000_REGISTER_RX_TTCKO 0x14
#define DW1000_REGISTER_RX_TIME 0x15
#define DW1000_REGISTER_TX_TIME 0x17
#define DW1000_REGISTER_TX_ANTD 0x18
#define DW1000_REGISTER_CHAN_CTRL 0x1F
#define DW1000_REGISTER_CHAN_CTRL_TX_CHAN_MASK 0x0000000F
#define DW1000_REGISTER_CHAN_CTRL_RX_CHAN_MASK 0x000000F0
#define DW1000_REGISTER_CHAN_CTRL_RXPRF_MASK 0x000C0000
#define DW1000_REGISTER_CHAN_CTRL_TX_PCODE_MASK 0x07C00000
#define DW1000_REGISTER_CHAN_CTRL_RX_PCODE_MASK 0xF8000000
#define DW1000_REGISTER_AON_CTRL 0x2C
#define DW1000_REGISTER_OFFSET_AON_CTRL 0x02
#define DW1000_REGISTER_AON_CTRL_UPL_CFG_MASK 0x04
#define DW1000_REGISTER_AON_CFG0 0x2C
#define DW1000_REGISTER_OFFSET_AON_CFG0 0x06
#define DW1000_REGISTER_AON_CFG0_SLEEP_EN_MASK 0x01
#define DW1000_REGISTER_AON_CFG0_WAKE_PIN_MASK 0x02
#define DW1000_REGISTER_AON_CFG0_WAKE_SPI_MASK 0x04
#define DW1000_REGISTER_AON_CFG0_WAKE_CNT_MASK 0x08
#define DW1000_REGISTER_AON_CFG0_LPDIV_EN_MASK 0x10
#define DW1000_REGISTER_PMSC_CTRL0 0x36
#define DW1000_REGISTER_OFFSET_PMSC_CTRL0 0x00
#define DW1000_REGISTER_PMSC_CTRL1 0x36
#define DW1000_REGISTER_OFFSET_PMSC_CTRL1 0x04
class DecaDuino {
public:
/**
* @brief DecaDuino Constructor
* @param slaveSelectPin The slaveSelect pin number
* @param interruptPin The interrupt pin number
* @author Adrien van den Bossche
* @date 20140701
*/
DecaDuino(uint8_t slaveSelectPin = DW1000_CS0_PIN, uint8_t interruptPin = DW1000_IRQ0_PIN);
/**
* @brief Initializes DecaDuino and DWM1000 without addressing fields filtering (Promiscuous mode)
* @return true if both DecaDuino and DWM1000 have been successfully initialized
* @author Adrien van den Bossche
* @date 20140701
*/
boolean init();
/**
* @brief Initializes DecaDuino and DWM1000 with given Short Address and Pan Id
* @param shortAddrAndPanId The 16-bit short address and 16-bit Pan Id as a 32-bit integer where short address in on the LSB.
* @return true if both DecaDuino and DWM1000 have been successfully initialized
* @author Adrien van den Bossche
* @date 20150905
*/
boolean init(uint32_t shortAddrAndPanId);
/**
* @brief Reset the DW1000 chip
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void resetDW1000();
/**
* @brief Set PHR Mode
* @param mode 0 for standard 127 bytes frame, 3 for extended 1023 bytes frame
* @return No return
* @author Laurent GUERBY
* @date 20170329
*/
void setPHRMode(uint8_t mode);
/**
* @brief Returns the PHR Mode
* @return PHR Mode
* @author Laurent GUERBY
* @date 20170329
*/
uint8_t getPHRMode(void);
/**
* @brief Stores the System Time Counter value in the variable referenced by the pointer passed as an input parameter
* @param p The address of the uint64_t variable
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void getSystemTimeCounter(uint64_t *p);
/**
* @brief Returns the System Time Counter value
* @return The System Time Counter value as a uint64_t
* @author Adrien van den Bossche
* @date 20141115
*/
uint64_t getSystemTimeCounter(void);
/**
* @brief Gets the PanId (Personnal Area Network Identifier) stored in the DW1000's RAM
* @return The PanId as an uint16_t value
* @author Adrien van den Bossche
* @date 20141115
*/
uint16_t getPanId();
/**
* @brief Gets the ShortAddress (16-bit network address, aka IEEE short address) stored in the DW1000's RAM
* @return The Short Address as an uint16_t value
* @author Adrien van den Bossche
* @date 20141115
*/
uint16_t getShortAddress();
/**
* @brief Gets the Euid (Extended Unique IDentifier) stored in the DW1000's ROM
* @return The Identifier as an uint64_t value
* @author Adrien van den Bossche
* @date 20141115
*/
uint64_t getEuid();
/**
* @brief Sets the PanId (Personnal Area Network Identifier) in the DW1000's RAM
* @param panId The 16-bit PANID (PAN Identifier)
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void setPanId(uint16_t panId);
/**
* @brief Sets the ShortAddress (16-bit network address, aka IEEE short address) in the DW1000's RAM
* @param shortAddress The 16-bit short address
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void setShortAddress(uint16_t shortAddress);
/**
* @brief Sets both the ShortAddress and the PanId in the DW1000's RAM
* @param shortAddress The 16-bit short address
* @param panId The 16-bit PANID (PAN Identifier)
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void setShortAddressAndPanId(uint16_t shortAddress, uint16_t panId);
/**
* @brief Sets both the ShortAddress and the PanId in the DW1000's RAM
* @param shortAddressPanId The 16-bit short address and 16-bit Pan Id as a 32-bit integer where short address in on the LSB.
* @return true if success, false otherwise
* @author Adrien van den Bossche
* @date 20141115
*/
int setShortAddressAndPanId(uint32_t shortAddressPanId);
/**
* @brief Returns the currently configured radio channels
* @return A byte which MSB is the X channel and the LSB is the X channel
* @author Réjane Dalce
* @date 20160109
*/
uint8_t getChannelRaw(void);
/**
* @brief Returns the currently configured radio channel
* @return The channel value as an unsigned byte
* @author Réjane Dalce
* @date 20160109
*/
uint8_t getChannel(void);
/**
* @brief Returns the currently configured Pulse Repetition Frequency
* @return The PRF value as an unsigned byte
* @author Réjane Dalce
* @date 20161003
*/
uint8_t getRxPrf(void);
/**
* @brief Returns the currently configured Tx Preamble Code
* @return The Preamble Code value as an unsigned byte
* @author Réjane Dalce
* @date 20161003
*/
uint8_t getTxPcode(void);
/**
* @brief Returns the currently configured Rx Preamble Code
* @return The Preamble Code value as an unsigned byte
* @author Réjane Dalce
* @date 20161003
*/
uint8_t getRxPcode(void);
/**
* @brief Sets the radio channels for TX and RX
* @param channel The channel number to set. Valid values are: 1, 2, 3, 4, 5, 7.
* @return Indicates whether configuration went well or not
* @author Réjane Dalce
* @date 20160109
*/
bool setChannel(uint8_t channel);
/**
* @brief Sets the Pulse Repetition Frequency
* @param prf The PRF value to set. Valid values are: 1, 2.
* @return Indicates whether configuration went well or not
* @author Réjane Dalce
* @date 20160310
*/
bool setRxPrf(uint8_t prf);
/**
* @brief Sets the Tx Preamble Code
* @param pcode The Preamble Code to set. Valid values are: 1-20.
* @return Indicates whether configuration went well or not
* @author Réjane Dalce
* @date 20160310
*/
bool setTxPcode(uint8_t pcode);
/**
* @brief Sets the Rx Preamble Code
* @param pcode The Preamble Code to set. Valid values are: 1-20.
* @return Indicates whether configuration went well or not
* @author Réjane Dalce
* @date 20160310
*/
bool setRxPcode(uint8_t pcode);
/**
* @brief Returns the preamble length
* @return A byte representing the preamble length
* @author François Despaux
* @date 20160217
*/
int getPreambleLength(void);
/**
* @brief Sets the preamble length
* @param plength The preamble length to set. Valid values are: 64, 128, 256, 512, 1024, 1536, 2048, 4096.
* @return Indicates whether configuration went well or not
* @author François Despaux
* @date 20160217
*/
bool setPreambleLength(int plength);
/**
* @brief Returns an aligned timestamp to use with pdDataRequest() in case of delayed transmissions
* @param wantedDelay The required delay to align the delayed transmission
* @return the aligned timestamp
* @author Adrien van den Bossche
* @date 20151028
*/
uint64_t alignDelayedTransmission ( uint64_t wantedDelay );
/**
* @brief Sends a len-byte frame from buf
* @param buf The address of the buffer
* @param len The message length
* @return true if success, false otherwise
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t pdDataRequest(uint8_t* buf, uint16_t len);
/**
* @brief Sends a len-byte frame from buf with an optionnal delay
* @param buf The address of the buffer
* @param len The message length
* @param delayed The delayed flag (true or false)
* @param time The time to send, based on the DWM1000 System Time Counter at 64GHz
* @return true if success, false otherwise
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t pdDataRequest(uint8_t* buf, uint16_t len, uint8_t delayed, uint64_t time);
/**
* @brief Sends a len-byte frame from buf
* @param buf The address of the buffer
* @param len The message length
* @return true if success, false otherwise
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t send(uint8_t* buf, uint16_t len);
/**
* @brief Sends a len-byte frame from buf with an optionnal delay
* @param buf The address of the buffer
* @param len The message length
* @param delayed The delayed flag (true or false)
* @param time The time to send, based on the DWM1000 System Time Counter at 64GHz
* @return true if success, false otherwise
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t send(uint8_t* buf, uint16_t len, uint8_t delayed, uint64_t time);
/**
* @brief Sets the RX buffer for future frame reception. Received bytes will be stored at the beginning of the buffer.
* @param buf The address of the buffer
* @param len The address of the message length
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void setRxBuffer(uint8_t* buf, uint16_t *len);
/**
* @brief Sets the RX buffer for future frame reception. Received bytes will be stored at the end of the buffer of max size.
* @param buf The address of the buffer
* @param len The address of the message length
* @param max The buffer size
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void setRxBuffer(uint8_t* buf, uint16_t *len, uint16_t max);
/**
* @brief Sets transceiver mode to receive mode
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void plmeRxEnableRequest(void);
/**
* @brief Sets transceiver mode to receive mode. Received bytes will be stored at the end of the buffer of max size.
* @param max The buffer size
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void plmeRxEnableRequest(uint16_t max);
/**
* @brief Sets transceiver mode to receive mode and set the RX buffer for future frame reception.
* @param buf The address of the buffer
* @param len The address of the message length
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void plmeRxEnableRequest(uint8_t* buf, uint16_t *len);
/**
* @brief Sets transceiver mode to receive mode and set the RX buffer for future frame reception. Received bytes will be stored at the end of the buffer of max size.
* @param buf The address of the buffer
* @param len The address of the message length
* @param max The buffer size
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void plmeRxEnableRequest(uint8_t* buf, uint16_t *len, uint16_t max);
/**
* @brief Sets transceiver mode to idle mode.
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void plmeRxDisableRequest(void);
/**
* @brief Sets transceiver mode to sleep mode.
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void sleepRequest(void);
/**
* @brief Returns true if a frame has been received.
* @return true if a frame has been received, false otherwise.
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t rxFrameAvailable(void);
/**
* @brief Returns true if a frame has been received, copy received bytes in buf and store message length in len.
* @param buf The address of the buffer
* @param len The address of the message length
* @return true if a frame has been received, false otherwise.
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t rxFrameAvailable(uint8_t* buf, uint16_t *len);
/**
* @brief Returns true if a frame has been received, copy received bytes in buf and store message length in len. The received bytes shall be copied toward the end of the buffer of size max.
* @param buf The address of the buffer
* @param len The address of the message length
* @param max The buffer size
* @return true if a frame has been received, false otherwise.
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t rxFrameAvailable(uint8_t* buf, uint16_t *len, uint16_t max);
/**
* @brief Returns true if the last transmission request has been succefully completed
* @return true if the last transmission request has been succefully completed
* @author Adrien van den Bossche
* @date 20141115
*/
bool hasTxSucceeded(void);
/**
* @brief Gets the DecaDuino transceiver status
* @return the DecaDuino transceiver status
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t getTrxStatus(void);
/**
* @brief Gets the raw value from the DW1000's embedded temperature sensor
* @return The temperature raw value
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t getTemperatureRaw(void);
/**
* @brief Gets the temperature value in celsius degrees from the DW1000's embedded temperature sensor
* @return The temperature value in celsius degrees
* @author Adrien van den Bossche
* @date 20141115
* @todo To be implemented
*/
float getTemperature(void);
/**
* @brief Gets the raw value from the DW1000's embedded voltage sensor
* @return The voltage raw value
* @author Adrien van den Bossche
* @date 20141115
*/
uint8_t getVoltageRaw(void);
/**
* @brief Gets the voltage value in volts from the DW1000's embedded voltage sensor
* @return The voltage value in volts
* @author Adrien van den Bossche
* @date 20141115
* @todo To be implemented
*/
float getVoltage(void);
/**
* @brief Builds an uint16 value from two uint8 values
* @param data The address of the uint8_t buffer
* @return The decoded uint16_t
* @author Adrien van den Bossche
* @date 20111123
*/
uint16_t decodeUint16 ( uint8_t *data );
/**
* @brief Formats an uint16 value as a list of uint8 values
* @param from The uint16_t value
* @param to The address of the uint8_t buffer
* @return No return
* @author Adrien van den Bossche
* @date 20111011
*/
void encodeUint16 ( uint16_t from, uint8_t *to );
/**
* @brief Builds an uint32 value from four uint8 values
* @param data The address of the uint8_t buffer
* @return The decoded uint32_t
* @author Adrien van den Bossche
* @date 20111123
*/
uint32_t decodeUint32 ( uint8_t *data );
/**
* @brief Formats an uint32 value as a list of uint8 values
* @param from The uint32_t value
* @param to The address of the uint8_t buffer
* @return No return
* @author Adrien van den Bossche
* @date 20111011
*/
void encodeUint32 ( uint32_t from, uint8_t *to );
/**
* @brief Builds an uint64 value from five uint8 values
* @param data The address of the uint8_t buffer
* @return The decoded uint64_t
*/
uint64_t decodeUint40 ( uint8_t *data );
/**
* @brief Formats an uint64 value with only 5 LSbytes as a list of uint8 values
* @param from The uint64_t value
* @param to The address of the uint8_t buffer
*/
void encodeUint40 ( uint64_t from, uint8_t *to );
/**
* @brief Builds an uint64 value from eight uint8 values
* @param data The address of the uint8_t buffer
* @return The decoded uint64_t
* @author Adrien van den Bossche
* @date 20140804
*/
uint64_t decodeUint64 ( uint8_t *data );
/**
* @brief Formats an uint64 value as a list of uint8 values
* @param from The uint64_t value
* @param to The address of the uint8_t buffer
* @return No return
* @author Adrien van den Bossche
* @date 20111011
*/
void encodeUint64 ( uint64_t from, uint8_t *to );
/**
* @brief Builds a float value from four uint8 values
* @param data The address of the uint8_t buffer
* @return The decoded float
* @author Adrien van den Bossche
* @date 20171020
*/
float decodeFloat ( uint8_t *data );
/**
* @brief Formats an float value as a list of uint8 values
* @param from The float value
* @param to The address of the uint8_t buffer
* @return No return
* @author Adrien van den Bossche
* @date 20171020
*/
void encodeFloat ( float from, uint8_t *to );
/**
* @brief Prints an uint64_t value on console
* @param ui64 The uint64_t value
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void printUint64 ( uint64_t ui64 );
/**
* @brief Returns last transmitted frame timestamp based on the DWM1000 System Time Counter at 64GHz
* @return Last transmitted frame timestamp
* @author Adrien van den Bossche
* @date 20140905
*/
uint64_t getLastTxTimestamp();
/**
* @brief Returns last received frame timestamp based on the DWM1000 System Time Counter at 64GHz
* @return Last received frame timestamp
* @author Adrien van den Bossche
* @date 20140905
*/
uint64_t getLastRxTimestamp();
/**
* @brief Returns last received frame's clock skew, also designated as clock offset in the Decawave documentation
* @return Last received frame's clock skew
* @author Adrien van den Bossche
* @date 20150905
*/
double getLastRxSkew();
/**
* @brief Returns current antenna delay value
* @return The current antenna delay value
* @author Adrien van den Bossche
* @date 20160915
*/
uint16_t getAntennaDelay();
/**
* @brief Sets the current antenna delay value
* @param antennaDelay The antenna delay value
* @return No return
* @author Adrien van den Bossche
* @date 20160915
*/
void setAntennaDelay(uint16_t newAntennaDelay);
private:
/**
* @brief Reads len bytes on SPI at given address, and store data in buf
* @param address The source address
* @param buf The address of the buffer
* @param len The message length
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void readSpi(uint8_t address, uint8_t* buf, uint16_t len);
/**
* @brief Reads len bytes on SPI at given address/subaddress, and store data in buf
* @param address The source address
* @param subAddress The source subAddress
* @param buf The address of the buffer
* @param len The message length
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void readSpiSubAddress(uint8_t address, uint16_t subAddress, uint8_t* buf, uint16_t len);
/**
* @brief Reads a 4-byte word on SPI at given address
* @param address The source address
* @return The 4 bytes
* @author Adrien van den Bossche
* @date 20141115
*/
uint32_t readSpiUint32(uint8_t address);
/**
* @brief Writes len bytes on SPI at given address from buf
* @param address The destination address
* @param buf The address of the buffer
* @param len The message length
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void writeSpi(uint8_t address, uint8_t* buf, uint16_t len);
/**
* @brief Writes len bytes on SPI at given address/subaddress from buf
* @param address The destination address
* @param address The destination sub-address
* @param buf The address of the buffer
* @param len The message length
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void writeSpiSubAddress(uint8_t address, uint16_t subAddress, uint8_t* buf, uint16_t len);
/**
* @brief Writes a 4-byte word on SPI at given address
* @param address The destination address
* @param ui32t The 4-byte word to write on SPI
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void writeSpiUint32(uint8_t address, uint32_t ui32t);
/**
* @brief Returns the antenna delay value in the DW1000 register
* @return The antenna delay value in the register
* @author Adrien van den Bossche
* @date 20160915
*/
uint16_t getAntennaDelayReg();
/**
* @brief Sets the antenna delay value in the DW1000 register
* @param antennaDelay The antenna delay value
* @return No return
* @author Adrien van den Bossche
* @date 20160915
*/
void setAntennaDelayReg(uint16_t newAntennaDelay);
uint8_t debugStr[DEBUG_STR_LEN];
void spi_send ( uint8_t u8 );
void spi_send ( uint16_t u16 );
void spi_send ( uint8_t* buf, uint16_t len );
void spi_receive ( uint8_t* buf, uint16_t len );
uint16_t antennaDelay;
protected:
/**
* @brief The first interrupt function
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
static void isr0();
/**
* @brief The second interrupt function
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
static void isr1();
/**
* @brief The third interrupt function
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
static void isr2();
/**
* @brief The global interrupt function
* @return No return
* @author Adrien van den Bossche
* @date 20141115
*/
void handleInterrupt();
/**
* @brief Current SPI-bus settings
*/
SPISettings currentSPISettings;
/**
* @brief Current EUID (Extended Unique IDentifier)
*/
uint64_t euid;
/**
* @brief The current (or last) PPDU
*/
uint8_t *rxData;
/**
* @brief The current PPDU length
*/
uint16_t *rxDataLen;
/**
* @brief The max PPDU length
*/
uint16_t rxDataLenMax;
/**
* @brief Flag indicating if last reception has data
*/
uint8_t rxDataAvailable;
/**
* @brief Transceiver status
*/
uint8_t trxStatus;
/**
* @brief Flag indicating if last transmission is done
*/
bool lastTxOK;
/**
* @brief Timestamp of last transmitted frame
*/
uint64_t lastTxTimestamp;
/**
* @brief Timestamp of last received frame
*/
uint64_t lastRxTimestamp;
/**
* @brief Last clock offset (aka clock skew)
*/
double clkOffset;
uint8_t _slaveSelectPin;
uint8_t _interruptPin;
static DecaDuino* _DecaDuinoInterrupt[];
};
#endif

5
DecaDuino-master/LICENSE Executable file
View file

@ -0,0 +1,5 @@
Using DecaDuino is subject to licensing:
- GPL_V3: See http://www.gnu.org/copyleft/gpl.html
- Commercial: Please contact Adrien van den Bossche <vandenbo@irit.fr> for Commercial Licensing

73
DecaDuino-master/README.md Executable file
View file

@ -0,0 +1,73 @@
# DecaDuino
Ranging/synchronisation over UWB - DecaDuino library for Arduino
## Brief
DecaDuino is an Arduino library which provides a driver for the DecaWave DW1000
transceiver, and modules based on this transceiver, such as DecaWave DWM1000.
Since the DecaWave DW1000/DWM1000 is based on a Ultra Wide Band (UWB) Physical
layer, DecaDuino can be used as an open framework for wireless Time-of-Flight
(ToF) ranging systems.
For more details on the DecaDuino library, get the latest version of the
documentation here: https://www.irit.fr/~Adrien.Van-Den-Bossche/decaduino/)
## Installation
You have to put this library in your Arduino libraries directory.
## Hardware
An example hardware is DecaWiNo: https://wino.cc/decawino/
## Start using DecaDuino with simple example sketchs
All example sketches are available as usual in the Arduino IDE menu:
```
File > Examples > DecaDuino
```
### DecaDuinoSender
This sketch shows how to use the DecaDuino library to send messages over the UWB
radio.
### DecaDuinoReceiverSniffer
This sketch shows how to use the DecaDuino library to receive messages over the
UWB radio. The received bytes are printed in HEX; this sketch can be used as a
frame sniffer to dump received messages.
### DecaDuinoChat
This sketch shows how to use the DecaDuino library to send and receive ascii
messages via the Serial port over the UWB radio.
## Use DecaDuino to implement ranging protocols
DecaDuino can be used to implement Time-of-Flight (ToF) ranging protocols
by timestamping frames at transmission and reception. The DecaDuino library
comes with a set of sketches that implement popular ranging protocols.
### Two-Way Ranging (TWR) protocol
The two example sketchs DecaDuinoTWR_client and DecaDuinoTWR_server propose a
simple implementation of the TWR protocol without addressing fields.
Flash each example sketch on two nodes (client and server) and get the distance
between the two nodes. The documentation directory contains the client and
server state machine diagram.
### Symmetric Double-Sided Two-Way Ranging (SDS-TWR) protocol
The two example sketchs DecaDuinoSDSTWR_client and DecaDuinoSDSTWR_server
propose a simple implementation of the SDS-TWR protocol without addressing
fields. The SDS-TWR protocol implies more messages but is theorically better
than the TWR protocol since the clock skew effect is compensated by the
symetry of the exchanges.
Flash each example sketch on two nodes (client and server) and get the distance
between the two nodes.
## Licensing
Using DecaDuino is subject to licensing:
* GPL_V3: See http://www.gnu.org/copyleft/gpl.html
* Commercial: Please contact Adrien van den Bossche <vandenbo@irit.fr> for Commercial Licensing

Binary file not shown.

After

Width:  |  Height:  |  Size: 152 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 149 KiB

View file

@ -0,0 +1,83 @@
// DecaDuinoChat
// This sketch shows how to use the DecaDuino library to send and receive ascii messages via the Serial port over
// the UWB radio
// by Adrien van den Bossche <vandenbo@univ-tlse2.fr>
// This sketch is a part of the DecaDuino Project - please refer to the DecaDuino LICENCE file for licensing details
#include <SPI.h>
#include <DecaDuino.h>
#define MAX_FRAME_LEN 120
uint8_t txData[MAX_FRAME_LEN];
uint8_t rxData[MAX_FRAME_LEN];
uint16_t rxLen;
uint16_t txLen;
DecaDuino decaduino;
int rxFrames;
void setup()
{
pinMode(13, OUTPUT); // Internal LED (pin 13 on DecaWiNo board)
Serial.begin(115200); // Init Serial port
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Init DecaDuino and blink if initialisation fails
if ( !decaduino.init() ) {
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
// Set RX buffer and enable RX
decaduino.setRxBuffer(rxData, &rxLen);
decaduino.plmeRxEnableRequest();
rxFrames = 0;
txLen = 0;
Serial.println("DecaDuino chat ready!");
}
void loop()
{
int i, let_s_send = false;
// This is the sender part ****************************************************************
// Get chars on Serial and prepare buffer
while ( ( Serial.available() > 0 ) && ( txLen < MAX_FRAME_LEN ) ) {
char c = Serial.read();
txData[txLen++] = c;
if ( (c=='\n')||(c=='\r')||(txLen==MAX_FRAME_LEN) ) {
// Send if NL or CR char is detected, or if buffer is full
let_s_send = true;
}
}
// Send the buffered chars
if ( let_s_send == true ) {
// LED ON, disable RX, send, wait sent complete, re-enable RX and LED OFF
digitalWrite(13, HIGH);
decaduino.plmeRxDisableRequest(); // Always disable RX before request frame sending
decaduino.pdDataRequest(txData, txLen);
txData[txLen]= 0;
Serial.print("Sending ["); Serial.print((char*)txData); Serial.print("]... ");
while ( !decaduino.hasTxSucceeded() );
Serial.println("done!");
txLen = 0;
decaduino.plmeRxEnableRequest();
digitalWrite(13, LOW);
}
// This is the receiver part **************************************************************
if ( decaduino.rxFrameAvailable() ) {
// LED ON, print received chars, re-enable RX and LED OFF
digitalWrite(13, HIGH);
Serial.print("["); Serial.print(++rxFrames); Serial.print("] ");
Serial.print(rxLen);
Serial.print("bytes received: ");
rxData[rxLen] = 0;
Serial.println((char*)rxData);
decaduino.plmeRxEnableRequest(); // Always renable RX after a frame reception
digitalWrite(13, LOW);
}
}

View file

@ -0,0 +1,54 @@
// DecaDuinoReceiver
// This sketch shows how to use the DecaDuino library to receive messages over the UWB radio.
// The sketch prints the received bytes in HEX; it can be used as a frame sniffer.
// by Adrien van den Bossche <vandenbo@univ-tlse2.fr>
// This sketch is a part of the DecaDuino Project - please refer to the DecaDuino LICENCE file for licensing details
#include <SPI.h>
#include <DecaDuino.h>
#define MAX_FRAME_LEN 120
uint8_t rxData[MAX_FRAME_LEN];
uint16_t rxLen;
DecaDuino decaduino;
int rxFrames;
void setup()
{
pinMode(13, OUTPUT); // Internal LED (pin 13 on DecaWiNo board)
Serial.begin(115200); // Init Serial port
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Init DecaDuino and blink if initialisation fails
if ( !decaduino.init() ) {
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
// Set RX buffer and enable RX
decaduino.setRxBuffer(rxData, &rxLen);
decaduino.plmeRxEnableRequest();
rxFrames = 0;
}
void loop()
{
// If a message has been received, print it and re-enable receiver
if ( decaduino.rxFrameAvailable() ) {
digitalWrite(13, HIGH);
Serial.print("#"); Serial.print(++rxFrames); Serial.print(" ");
Serial.print(rxLen);
Serial.print("bytes received: |");
for (int i=0; i<rxLen; i++) {
Serial.print(rxData[i], HEX);
Serial.print("|");
}
Serial.println();
decaduino.plmeRxEnableRequest(); // Always renable RX after a frame reception
digitalWrite(13, LOW);
}
}

View file

@ -0,0 +1,175 @@
// DecaDuinoSDSTWR_client
// A simple implementation of the SDS-TWR protocol, client side
// Contributors: Adrien van den Bossche, Réjane Dalcé, Ibrahim Fofana, Robert Try, Thierry Val
// This sketch is a part of the DecaDuino Project - please refer to the DecaDuino LICENCE file for licensing details
// https://arxiv.org/pdf/1603.06736.pdf
#include <SPI.h>
#include <DecaDuino.h>
// Timeout parameters
#define TIMEOUT_WAIT_START_SENT 5 //ms
#define TIMEOUT_WAIT_ACK_REQ 10 //ms
#define TIMEOUT_WAIT_ACK_SENT 5 //ms
#define TIMEOUT_WAIT_DATA_REPLY 10 //ms
// Ranging period parameter
#define RANGING_PERIOD 500 //ms
// SDS-TWR client states state machine enumeration
enum { SDSTWR_ENGINE_STATE_INIT, SDSTWR_ENGINE_STATE_WAIT_START_SENT, SDSTWR_ENGINE_STATE_MEMORISE_T1,
SDSTWR_ENGINE_STATE_WAIT_ACK_REQ, SDSTWR_ENGINE_STATE_MEMORISE_T4, SDSTWR_ENGINE_STATE_SEND_ACK,
SDSTWR_ENGINE_STATE_WAIT_ACK_SENT, SDSTWR_ENGINE_STATE_MEMORISE_T5, SDSTWR_ENGINE_STATE_WAIT_DATA_REPLY,
SDSTWR_ENGINE_STATE_EXTRACT_T2_T3_T6 };
// Message types of the SDS-TWR protocol
#define SDSTWR_MSG_TYPE_UNKNOWN 10
#define SDSTWR_MSG_TYPE_START 11
#define SDSTWR_MSG_TYPE_ACK_REQ 12
#define SDSTWR_MSG_TYPE_ACK 13
#define SDSTWR_MSG_TYPE_DATA_REPLY 14
uint64_t t1, t2, t3, t4, t5, t6;
uint64_t mask = 0xFFFFFFFFFF;
int32_t tof;
DecaDuino decaduino;
uint8_t txData[128];
uint8_t rxData[128];
uint16_t rxLen;
int state;
uint32_t timeout;
void setup()
{
pinMode(13, OUTPUT); // Internal LED (pin 13 on DecaWiNo board)
Serial.begin(115200); // Init Serial port
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Init DecaDuino and blink if initialisation fails
if ( !decaduino.init() ) {
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
// Set RX buffer
decaduino.setRxBuffer(rxData, &rxLen);
state = SDSTWR_ENGINE_STATE_INIT;
// Print top table colomns
Serial.println("ToF\td");
}
void loop()
{
float distance;
switch (state) {
case SDSTWR_ENGINE_STATE_INIT:
delay(RANGING_PERIOD); // Wait to avoid medium flooding between two rangings or if a ranging fails
decaduino.plmeRxDisableRequest();
Serial.println("New SDS-TWR");
txData[0] = SDSTWR_MSG_TYPE_START;
decaduino.pdDataRequest(txData, 1);
timeout = millis() + TIMEOUT_WAIT_START_SENT;
state = SDSTWR_ENGINE_STATE_WAIT_START_SENT;
break;
case SDSTWR_ENGINE_STATE_WAIT_START_SENT:
if ( millis() > timeout ) {
state = SDSTWR_ENGINE_STATE_INIT;
} else {
if (decaduino.hasTxSucceeded()) {
state = SDSTWR_ENGINE_STATE_MEMORISE_T1;
}
}
break;
case SDSTWR_ENGINE_STATE_MEMORISE_T1 :
t1 = decaduino.getLastTxTimestamp();
timeout = millis() + TIMEOUT_WAIT_ACK_REQ;
decaduino.plmeRxEnableRequest();
state = SDSTWR_ENGINE_STATE_WAIT_ACK_REQ;
break;
case SDSTWR_ENGINE_STATE_WAIT_ACK_REQ :
if ( millis() > timeout) {
state = SDSTWR_ENGINE_STATE_INIT;
}
else {
if (decaduino.rxFrameAvailable()){
if (rxData[0] == SDSTWR_MSG_TYPE_ACK_REQ) {
state = SDSTWR_ENGINE_STATE_MEMORISE_T4;
} else {
decaduino.plmeRxEnableRequest();
state = SDSTWR_ENGINE_STATE_WAIT_ACK_REQ;
}
}
}
break;
case SDSTWR_ENGINE_STATE_MEMORISE_T4 :
t4 = decaduino.getLastRxTimestamp();
state = SDSTWR_ENGINE_STATE_SEND_ACK;
break;
case SDSTWR_ENGINE_STATE_SEND_ACK :
txData[0]= SDSTWR_MSG_TYPE_ACK;
decaduino.pdDataRequest(txData, 1);
timeout = millis() + TIMEOUT_WAIT_ACK_SENT;
state = SDSTWR_ENGINE_STATE_WAIT_ACK_SENT;
break;
case SDSTWR_ENGINE_STATE_WAIT_ACK_SENT :
if ( millis() > timeout ) {
state = SDSTWR_ENGINE_STATE_INIT;
} else {
if (decaduino.hasTxSucceeded()){
state = SDSTWR_ENGINE_STATE_MEMORISE_T5;
}
}
break;
case SDSTWR_ENGINE_STATE_MEMORISE_T5 :
t5 = decaduino.getLastTxTimestamp();
timeout = millis() + TIMEOUT_WAIT_DATA_REPLY;
decaduino.plmeRxEnableRequest();
state = SDSTWR_ENGINE_STATE_WAIT_DATA_REPLY;
break;
case SDSTWR_ENGINE_STATE_WAIT_DATA_REPLY :
if ( millis() > timeout) {
state = SDSTWR_ENGINE_STATE_INIT;
}
else {
if (decaduino.rxFrameAvailable()){
if (rxData[0] == SDSTWR_MSG_TYPE_DATA_REPLY) {
state = SDSTWR_ENGINE_STATE_EXTRACT_T2_T3_T6;
} else {
decaduino.plmeRxEnableRequest();
state = SDSTWR_ENGINE_STATE_WAIT_DATA_REPLY;
}
}
}
break;
case SDSTWR_ENGINE_STATE_EXTRACT_T2_T3_T6 :
t2 = decaduino.decodeUint40(&rxData[1]);
t3 = decaduino.decodeUint40(&rxData[6]);
t6 = decaduino.decodeUint40(&rxData[11]);
tof = (((((t4 - t1) & mask) - ((t3 - t2) & mask)) & mask) + ((((t6 - t3) & mask) - ((t5 - t4) & mask)) & mask))/4;
distance = tof*RANGING_UNIT;
Serial.print(tof);
Serial.print("\t");
Serial.println(distance);
state = SDSTWR_ENGINE_STATE_INIT;
break;
default:
state = SDSTWR_ENGINE_STATE_INIT;
break;
}
}

View file

@ -0,0 +1,145 @@
// DecaDuinoSDSTWR_server
// A simple implementation of the TWR protocol, server side
// Contributors: Adrien van den Bossche, Réjane Dalcé, Ibrahim Fofana, Robert Try, Thierry Val
// This sketch is a part of the DecaDuino Project - please refer to the DecaDuino LICENCE file for licensing details
#include <SPI.h>
#include <DecaDuino.h>
// Timeout parameters
#define TIMEOUT_WAIT_ACK_REQ_SENT 5 //ms
#define TIMEOUT_WAIT_ACK 10 //ms
#define TIMEOUT_WAIT_DATA_REPLY_SENT 5 //ms
// SDS-TWR server states state machine enumeration: see state diagram on documentation for more details
enum { SDSTWR_ENGINE_STATE_INIT, SDSTWR_ENGINE_STATE_WAIT_START, SDSTWR_ENGINE_STATE_MEMORISE_T2,
SDSTWR_ENGINE_STATE_SEND_ACK_REQ, SDSTWR_ENGINE_STATE_WAIT_ACK_REQ_SENT, SDSTWR_ENGINE_STATE_MEMORISE_T3,
SDSTWR_ENGINE_STATE_WAIT_ACK, SDSTWR_ENGINE_STATE_MEMORISE_T6, SDSTWR_ENGINE_STATE_SEND_DATA_REPLY,
SDSTWR_ENGINE_STATE_WAIT_DATA_REPLY_SENT};
// Message types of the SDS-TWR protocol
#define SDSTWR_MSG_TYPE_UNKNOWN 10
#define SDSTWR_MSG_TYPE_START 11
#define SDSTWR_MSG_TYPE_ACK_REQ 12
#define SDSTWR_MSG_TYPE_ACK 13
#define SDSTWR_MSG_TYPE_DATA_REPLY 14
uint64_t t2, t3, t6;
DecaDuino decaduino;
uint8_t txData[128];
uint8_t rxData[128];
uint16_t rxLen;
int state;
uint32_t timeout;
void setup()
{
pinMode(13, OUTPUT); // Internal LED (pin 13 on DecaWiNo board)
Serial.begin(115200); // Init Serial port
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Init DecaDuino and blink if initialisation fails
if ( !decaduino.init() ) {
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
// Set RX buffer
decaduino.setRxBuffer(rxData, &rxLen);
state = SDSTWR_ENGINE_STATE_INIT;
}
void loop()
{
switch (state) {
case SDSTWR_ENGINE_STATE_INIT :
decaduino.plmeRxEnableRequest();
state = SDSTWR_ENGINE_STATE_WAIT_START;
break;
case SDSTWR_ENGINE_STATE_WAIT_START :
if (decaduino.rxFrameAvailable()){
if ( rxData[0] == SDSTWR_MSG_TYPE_START){
state = SDSTWR_ENGINE_STATE_MEMORISE_T2;
} else {
decaduino.plmeRxEnableRequest();
state = SDSTWR_ENGINE_STATE_WAIT_START;
}
}
break;
case SDSTWR_ENGINE_STATE_MEMORISE_T2 :
t2 = decaduino.getLastRxTimestamp();
state = SDSTWR_ENGINE_STATE_SEND_ACK_REQ;
break;
case SDSTWR_ENGINE_STATE_SEND_ACK_REQ :
txData[0]= SDSTWR_MSG_TYPE_ACK_REQ;
decaduino.pdDataRequest(txData, 1);
timeout = millis() + TIMEOUT_WAIT_ACK_REQ_SENT;
state = SDSTWR_ENGINE_STATE_WAIT_ACK_REQ_SENT;
break;
case SDSTWR_ENGINE_STATE_WAIT_ACK_REQ_SENT:
if ( millis() > timeout ) {
state = SDSTWR_ENGINE_STATE_INIT;
} else {
if ( decaduino.hasTxSucceeded() ) {
state = SDSTWR_ENGINE_STATE_MEMORISE_T3;
}
}
break;
case SDSTWR_ENGINE_STATE_MEMORISE_T3 :
t3 = decaduino.getLastTxTimestamp();
timeout = millis() + TIMEOUT_WAIT_ACK;
decaduino.plmeRxEnableRequest();
state = SDSTWR_ENGINE_STATE_WAIT_ACK;
break;
case SDSTWR_ENGINE_STATE_WAIT_ACK :
if ( millis() > timeout) {
state = SDSTWR_ENGINE_STATE_INIT;
}
else {
if (decaduino.rxFrameAvailable()){
if (rxData[0] == SDSTWR_MSG_TYPE_ACK) {
state = SDSTWR_ENGINE_STATE_MEMORISE_T6;
} else {
decaduino.plmeRxEnableRequest();
state = SDSTWR_ENGINE_STATE_WAIT_ACK;
}
}
}
break;
case SDSTWR_ENGINE_STATE_MEMORISE_T6 :
t6 = decaduino.getLastRxTimestamp();
state = SDSTWR_ENGINE_STATE_SEND_DATA_REPLY;
break;
case SDSTWR_ENGINE_STATE_SEND_DATA_REPLY :
txData[0] = SDSTWR_MSG_TYPE_DATA_REPLY;
decaduino.encodeUint40(t2, &txData[1]);
decaduino.encodeUint40(t3, &txData[6]);
decaduino.encodeUint40(t6, &txData[11]);
decaduino.pdDataRequest(txData, 16);
timeout = millis() + TIMEOUT_WAIT_DATA_REPLY_SENT;
state = SDSTWR_ENGINE_STATE_WAIT_DATA_REPLY_SENT;
break;
case SDSTWR_ENGINE_STATE_WAIT_DATA_REPLY_SENT:
if ( (millis()>timeout) || (decaduino.hasTxSucceeded()) ) {
state = SDSTWR_ENGINE_STATE_INIT;
}
break;
default :
state = SDSTWR_ENGINE_STATE_INIT;
break;
}
}

View file

@ -0,0 +1,45 @@
// DecaDuinoSender
// This sketch shows how to use the DecaDuino library to send messages over the UWB radio
// by Adrien van den Bossche <vandenbo@univ-tlse2.fr>
// This sketch is a part of the DecaDuino Project - please refer to the DecaDuino LICENCE file for licensing details
#include <SPI.h>
#include <DecaDuino.h>
#define MAX_FRAME_LEN 120
uint8_t txData[MAX_FRAME_LEN];
uint16_t txLen;
DecaDuino decaduino;
int rxFrames;
void setup()
{
pinMode(13, OUTPUT); // Internal LED (pin 13 on DecaWiNo board)
Serial.begin(115200); // Init Serial port
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Init DecaDuino and blink if initialisation fails
if ( !decaduino.init() ) {
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
}
void loop()
{
// make dummy data, send it and wait the end of the transmission.
digitalWrite(13, HIGH);
for (int i=0; i<MAX_FRAME_LEN; i++) {
txData[i] = i;
}
decaduino.pdDataRequest(txData, MAX_FRAME_LEN);
while ( !decaduino.hasTxSucceeded() );
digitalWrite(13, LOW);
// wait 1 second
delay(1000);
}

View file

@ -0,0 +1,156 @@
// DecaDuinoTWR_client
// A simple implementation of the TWR protocol, client side
// Contributors: Adrien van den Bossche, Réjane Dalcé, Ibrahim Fofana, Robert Try, Thierry Val
// This sketch is a part of the DecaDuino Project - please refer to the DecaDuino LICENCE file for licensing details
// This sketch implements the skew correction published in "Nezo Ibrahim Fofana, Adrien van den Bossche, Réjane
// Dalcé, Thierry Val, "An Original Correction Method for Indoor Ultra Wide Band Ranging-based Localisation System"
// https://arxiv.org/pdf/1603.06736.pdf
#include <SPI.h>
#include <DecaDuino.h>
// Timeout parameters
#define TIMEOUT_WAIT_START_SENT 5 //ms
#define TIMEOUT_WAIT_ACK 10 //ms
#define TIMEOUT_WAIT_DATA_REPLY 20 //ms
// Ranging period parameter
#define RANGING_PERIOD 500 //ms
// TWR client states state machine enumeration: see state diagram on documentation for more details
enum { TWR_ENGINE_STATE_INIT, TWR_ENGINE_STATE_WAIT_START_SENT, TWR_ENGINE_STATE_MEMORISE_T1,
TWR_ENGINE_STATE_WAIT_ACK, TWR_ENGINE_STATE_MEMORISE_T4, TWR_ENGINE_STATE_WAIT_DATA_REPLY,
TWR_ENGINE_STATE_EXTRACT_T2_T3 };
// Message types of the TWR protocol
#define TWR_MSG_TYPE_UNKNOWN 0
#define TWR_MSG_TYPE_START 1
#define TWR_MSG_TYPE_ACK 2
#define TWR_MSG_TYPE_DATA_REPLY 3
uint64_t t1, t2, t3, t4;
uint64_t mask = 0xFFFFFFFFFF;
int32_t tof;
DecaDuino decaduino;
uint8_t txData[128];
uint8_t rxData[128];
uint16_t rxLen;
int state;
uint32_t timeout;
void setup()
{
pinMode(13, OUTPUT); // Internal LED (pin 13 on DecaWiNo board)
Serial.begin(115200); // Init Serial port
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Init DecaDuino and blink if initialisation fails
if ( !decaduino.init() ) {
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
// Set RX buffer
decaduino.setRxBuffer(rxData, &rxLen);
state = TWR_ENGINE_STATE_INIT;
// Print top table colomns
Serial.println("ToF\td\tToF_sk\td_sk");
}
void loop()
{
float distance;
switch (state) {
case TWR_ENGINE_STATE_INIT:
delay(RANGING_PERIOD); // Wait to avoid medium flooding between two rangings or if a ranging fails
decaduino.plmeRxDisableRequest();
Serial.println("New TWR");
txData[0] = TWR_MSG_TYPE_START;
decaduino.pdDataRequest(txData, 1);
timeout = millis() + TIMEOUT_WAIT_START_SENT;
state = TWR_ENGINE_STATE_WAIT_START_SENT;
break;
case TWR_ENGINE_STATE_WAIT_START_SENT:
if ( millis() > timeout ) {
state = TWR_ENGINE_STATE_INIT;
} else {
if ( decaduino.hasTxSucceeded() ) {
state = TWR_ENGINE_STATE_MEMORISE_T1;
}
}
break;
case TWR_ENGINE_STATE_MEMORISE_T1:
t1 = decaduino.getLastTxTimestamp();
timeout = millis() + TIMEOUT_WAIT_ACK;
decaduino.plmeRxEnableRequest();
state = TWR_ENGINE_STATE_WAIT_ACK;
break;
case TWR_ENGINE_STATE_WAIT_ACK:
if ( millis() > timeout ) {
state = TWR_ENGINE_STATE_INIT;
} else {
if ( decaduino.rxFrameAvailable() ) {
if ( rxData[0] == TWR_MSG_TYPE_ACK ) {
state = TWR_ENGINE_STATE_MEMORISE_T4;
} else {
decaduino.plmeRxEnableRequest();
state = TWR_ENGINE_STATE_WAIT_ACK;
}
}
}
break;
case TWR_ENGINE_STATE_MEMORISE_T4:
t4 = decaduino.getLastRxTimestamp();
timeout = millis() + TIMEOUT_WAIT_DATA_REPLY;
decaduino.plmeRxEnableRequest();
state = TWR_ENGINE_STATE_WAIT_DATA_REPLY;
break;
case TWR_ENGINE_STATE_WAIT_DATA_REPLY:
if ( millis() > timeout ) {
state = TWR_ENGINE_STATE_INIT;
} else {
if ( decaduino.rxFrameAvailable() ) {
if ( rxData[0] == TWR_MSG_TYPE_DATA_REPLY ) {
state = TWR_ENGINE_STATE_EXTRACT_T2_T3;
} else {
decaduino.plmeRxEnableRequest();
state = TWR_ENGINE_STATE_WAIT_DATA_REPLY;
}
}
}
break;
case TWR_ENGINE_STATE_EXTRACT_T2_T3:
t2 = decaduino.decodeUint40(&rxData[1]);
t3 = decaduino.decodeUint40(&rxData[6]);
tof = (((t4 - t1) & mask) - ((t3 - t2) & mask))/2;
distance = tof*RANGING_UNIT;
Serial.print(tof);
Serial.print("\t");
Serial.print(distance);
tof = (((t4 - t1) & mask) - (1+1.0E-6*decaduino.getLastRxSkew())*((t3 - t2) & mask))/2;
distance = tof*RANGING_UNIT;
Serial.print("\t");
Serial.print(tof);
Serial.print("\t");
Serial.println(distance);
state = TWR_ENGINE_STATE_INIT;
break;
default:
state = TWR_ENGINE_STATE_INIT;
break;
}
}

View file

@ -0,0 +1,121 @@
// DecaDuinoTWR_server
// A simple implementation of the TWR protocol, server side
// Contributors: Adrien van den Bossche, Réjane Dalcé, Ibrahim Fofana, Robert Try, Thierry Val
// This sketch is a part of the DecaDuino Project - please refer to the DecaDuino LICENCE file for licensing details
#include <SPI.h>
#include <DecaDuino.h>
// Timeout parameters
#define TIMEOUT_WAIT_ACK_SENT 5 //ms
#define TIMEOUT_WAIT_DATA_REPLY_SENT 5 //ms
#define ACK_DATA_REPLY_INTERFRAME 10 //ms
// TWR server states state machine enumeration: see state diagram on documentation for more details
enum { TWR_ENGINE_STATE_INIT, TWR_ENGINE_STATE_WAIT_START, TWR_ENGINE_STATE_MEMORISE_T2,
TWR_ENGINE_STATE_SEND_ACK, TWR_ENGINE_STATE_WAIT_ACK_SENT, TWR_ENGINE_STATE_MEMORISE_T3,
TWR_ENGINE_STATE_SEND_DATA_REPLY, TWR_ENGINE_STATE_WAIT_DATA_REPLY_SENT };
// Message types of the TWR protocol
#define TWR_MSG_TYPE_UNKNOWN 0
#define TWR_MSG_TYPE_START 1
#define TWR_MSG_TYPE_ACK 2
#define TWR_MSG_TYPE_DATA_REPLY 3
uint64_t t2, t3;
DecaDuino decaduino;
uint8_t txData[128];
uint8_t rxData[128];
uint16_t rxLen;
int state;
uint32_t timeout;
void setup()
{
pinMode(13, OUTPUT); // Internal LED (pin 13 on DecaWiNo board)
Serial.begin(115200); // Init Serial port
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Init DecaDuino and blink if initialisation fails
if ( !decaduino.init() ) {
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
// Set RX buffer
decaduino.setRxBuffer(rxData, &rxLen);
state = TWR_ENGINE_STATE_INIT;
}
void loop()
{
switch (state) {
case TWR_ENGINE_STATE_INIT:
decaduino.plmeRxEnableRequest();
state = TWR_ENGINE_STATE_WAIT_START;
break;
case TWR_ENGINE_STATE_WAIT_START:
if ( decaduino.rxFrameAvailable() ) {
if ( rxData[0] == TWR_MSG_TYPE_START ) {
state = TWR_ENGINE_STATE_MEMORISE_T2;
} else {
state = TWR_ENGINE_STATE_INIT;
}
}
break;
case TWR_ENGINE_STATE_MEMORISE_T2:
t2 = decaduino.getLastRxTimestamp();
state = TWR_ENGINE_STATE_SEND_ACK;
break;
case TWR_ENGINE_STATE_SEND_ACK:
txData[0] = TWR_MSG_TYPE_ACK;
decaduino.pdDataRequest(txData, 1);
timeout = millis() + TIMEOUT_WAIT_ACK_SENT;
state = TWR_ENGINE_STATE_WAIT_ACK_SENT;
break;
case TWR_ENGINE_STATE_WAIT_ACK_SENT:
if ( millis() > timeout ) {
state = TWR_ENGINE_STATE_INIT;
} else {
if ( decaduino.hasTxSucceeded() ) {
state = TWR_ENGINE_STATE_MEMORISE_T3;
}
}
break;
case TWR_ENGINE_STATE_MEMORISE_T3:
t3 = decaduino.getLastTxTimestamp();
state = TWR_ENGINE_STATE_SEND_DATA_REPLY;
break;
case TWR_ENGINE_STATE_SEND_DATA_REPLY:
delay(ACK_DATA_REPLY_INTERFRAME);
txData[0] = TWR_MSG_TYPE_DATA_REPLY;
decaduino.encodeUint40(t2, &txData[1]);
decaduino.encodeUint40(t3, &txData[6]);
decaduino.pdDataRequest(txData, 11);
timeout = millis() + TIMEOUT_WAIT_DATA_REPLY_SENT;
state = TWR_ENGINE_STATE_WAIT_DATA_REPLY_SENT;
break;
case TWR_ENGINE_STATE_WAIT_DATA_REPLY_SENT:
if ( (millis()>timeout) || (decaduino.hasTxSucceeded()) ) {
state = TWR_ENGINE_STATE_INIT;
}
break;
default:
state = TWR_ENGINE_STATE_INIT;
break;
}
}

View file

@ -0,0 +1,76 @@
// DecaDuinoReceiver
// Ce croquis est un exemple d'utilisation de la librairie DecaDuino
// Il permet de recevoir un message quelconque envoyé par UWB.
// Il écrit le contenu des octets reçus en HEX
// Il peut-être utilisé comme un sniffer de trames.
// by Adrien van den Bossche <vandenbo@univ-tlse2.fr>
// Ce croquis fait partir du projet DecaDuino (cf. fichier DecaDuino LICENCE)
#include <SPI.h>
#include <DecaDuino.h>
#define MAX_FRAME_LEN 120
//#define MY_ADDR 32 // Mon adresse
DecaDuino decaduino; //Interface radio UWB
uint8_t rxData[MAX_FRAME_LEN]; //buffer des données reçues (tableau d'octets)
uint16_t rxLen; // nombre d'octets reçus, <= MAX_FRAME_LEN
uint8_t rxNb; // nombre de trames modulo 255
void setup()
{
//Sélection de la LED interne connectée au pin 13 de la carte
pinMode(13, OUTPUT);
Serial.begin(115200); // Init Serial port speed
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Initialisation de DecaDuino
if ( !decaduino.init() ) {
// LED 13 clignotte si init échoue
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
// Initialisation du buffer de reception avec rxData,
// et de la variable où sera enregistré le nombre d'octets reçus.
decaduino.setRxBuffer(rxData, &rxLen);
// Lancement de l'écoute pour la réception d'une trame.
decaduino.plmeRxEnableRequest();
// On met a zéro le nombre de trames reçues
rxNb = 0;
}
void loop()
{
// Si un message a été reçu, l'afficher sur le port série
// et repasser en écoute
if ( decaduino.rxFrameAvailable() ) {
digitalWrite(13, HIGH);
Serial.print(" rxNb |");
Serial.print(++rxNb);
Serial.print("| ");
Serial.print(" rxLen |");
Serial.print(rxLen);
Serial.print("| ");
Serial.print(" DATA: |");
for (int i=0; i<rxLen; i++) {
Serial.print(rxData[i], HEX);
}
if (rxData[0] == 22) {
Serial.print(' OK');
}
Serial.print("|");
Serial.println();
// on repasse en écoute
decaduino.plmeRxEnableRequest();
digitalWrite(13, LOW);
}
}

View file

@ -0,0 +1,101 @@
// DecaDuinoSender
// Ce croquis est un exemple d'utilisation de la librairie DecaDuino
// Il permet d'envoyer des messages avec l'interface UWB
// by Adrien van den Bossche <vandenbo@univ-tlse2.fr>
// Ce croquis fait partir du projet DecaDuino (cf. fichier DecaDuino LICENCE)
#include <SPI.h>
#include <DecaDuino.h>
#define MAX_FRAME_LEN 120
#//define MY_ADDR 34
DecaDuino decaduino; //Interface radio UWB
uint8_t txData[MAX_FRAME_LEN]; // buffer des données émises (tableau d'octets)
uint16_t txLen; // nombre d'octets émis <= MAC_FRAME_LEN
uint8_t txFrames; // nb de trames émises module 255
uint8_t T_trame; // durée emission trame
uint8_t W; // taille de la fenêtre
uint8_t k; // aléatoire
void setup()
{
//Sélection de la LED interne connectée au pin 13 de la carte
pinMode(13, OUTPUT);
Serial.begin(115200); // Init Serial port speed
SPI.setSCK(14); // Set SPI clock pin (pin 14 on DecaWiNo board)
// Initialisation de DecaDuino
if ( !decaduino.init() ) {
// LED 13 clignotte si init échoue
Serial.println("decaduino init failed");
while(1) { digitalWrite(13, HIGH); delay(50); digitalWrite(13, LOW); delay(50); }
}
txFrames = 1;
//On attend 5s avant d'emettre
delay(5000);
T_trame = 100; // ms
W = 8; // taille
}
void loop()
{
// On allume la LED interne sur le port 13
digitalWrite(13, HIGH);
// Taille des données
txLen = 10;
// sélection du canal
txData[0] = 22;
// envoie du numéro de trame
txData[1] = txFrames;
// Creation de donnees fictives dans txData
for (int i=2; i<txLen; i++) {
txData[i] = 0;
}
// Envoi de la trame
decaduino.pdDataRequest(txData, txLen);
// On attend que la trame soit émise
while ( !decaduino.hasTxSucceeded() );
// Log du nb de trames émises
digitalWrite(13, LOW);
Serial.print(" txFrames |");
Serial.print(txFrames++);
Serial.print("| ");
Serial.print(" txLen |");
Serial.print(txLen);
Serial.print("| ");
Serial.print(" txData: |");
for (int i=0; i<txLen; i++) {
Serial.print(txData[i], HEX);
if (i != txLen - 1) {
Serial.print("-");
}
}
Serial.print("| ");
//k = random(W);
//Serial.print(" k |");
//Serial.print(k);
//Serial.print("| ");
Serial.println();
// Attente de T_trame * k secondes
//delay(k*T_trame);
delay(100);
}

BIN
TP-MACArduino-Sujet.pdf Executable file

Binary file not shown.