Revision 33f54213
include/DW1000/alld_DW1000.h | ||
---|---|---|
32 | 32 |
|
33 | 33 |
#if (AMIROLLD_CFG_DW1000 == 1) |
34 | 34 |
#include "v1/alld_dw1000_v1.h" |
35 |
#include "v1/alld_dw1000_regs_v1.h" |
|
36 |
#include "v1/deca_instance_v1.h" |
|
37 | 35 |
#elif (AMIROLLD_CFG_DW1000 == 0) |
38 | 36 |
#error "DW1000 LLD implementation for v0 is not ready yet." |
39 | 37 |
#else |
include/DW1000/v1/alld_dw1000_v1.h | ||
---|---|---|
477 | 477 |
* |
478 | 478 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error |
479 | 479 |
*/ |
480 |
int dwt_initialise(uint16_t config) ; // TODO |
|
481 |
//int dwt_initialise(uint16_t config, DW1000Driver* drv) ;
|
|
480 |
//int dwt_initialise(uint16_t config) ; // TODO
|
|
481 |
int dwt_initialise(uint16_t config, DW1000Driver* drv) ; |
|
482 | 482 |
|
483 | 483 |
/*! ------------------------------------------------------------------------------------------------------------------ |
484 | 484 |
* @fn dwt_configure() |
... | ... | |
1728 | 1728 |
****************************************************************************************************************************************************/ |
1729 | 1729 |
|
1730 | 1730 |
|
1731 |
/*! ------------------------------------------------------------------------------------------------------------------ |
|
1732 |
* @fn writetospi() |
|
1733 |
* |
|
1734 |
* @brief |
|
1735 |
* NB: In porting this to a particular microprocessor, the implementer needs to define the two low |
|
1736 |
* level abstract functions to write to and read from the SPI. |
|
1737 |
* Low level abstract function to write to the SPI |
|
1738 |
* Takes two separate byte buffers for write header and write data |
|
1739 |
* returns 0 for success, or -1 for error |
|
1740 |
* |
|
1741 |
* Note: The body of this function is platform specific |
|
1742 |
* |
|
1743 |
* input parameters: |
|
1744 |
* @param headerLength - number of bytes header being written |
|
1745 |
* @param headerBuffer - pointer to buffer containing the 'headerLength' bytes of header to be written |
|
1746 |
* @param bodylength - number of bytes data being written |
|
1747 |
* @param bodyBuffer - pointer to buffer containing the 'bodylength' bytes od data to be written |
|
1748 |
* |
|
1749 |
* output parameters |
|
1750 |
* |
|
1751 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error |
|
1752 |
*/ |
|
1753 |
extern int writetospi(uint16_t headerLength, const uint8_t *headerBuffer, uint32_t bodylength, const uint8_t *bodyBuffer); |
|
1754 |
|
|
1755 |
/*! ------------------------------------------------------------------------------------------------------------------ |
|
1756 |
* @fn readfromspi() |
|
1757 |
* |
|
1758 |
* @brief |
|
1759 |
* NB: In porting this to a particular microprocessor, the implementer needs to define the two low |
|
1760 |
* level abstract functions to write to and read from the SPI. |
|
1761 |
* Low level abstract function to write to the SPI |
|
1762 |
* Takes two separate byte buffers for write header and write data |
|
1763 |
* returns 0 for success, or -1 for error |
|
1764 |
* |
|
1765 |
* Note: The body of this function is platform specific |
|
1766 |
* |
|
1767 |
* input parameters: |
|
1768 |
* @param headerLength - number of bytes header to write |
|
1769 |
* @param headerBuffer - pointer to buffer containing the 'headerLength' bytes of header to write |
|
1770 |
* @param readlength - number of bytes data being read |
|
1771 |
* @param readBuffer - pointer to buffer containing to return the data (NB: size required = headerLength + readlength) |
|
1772 |
* |
|
1773 |
* output parameters |
|
1774 |
* |
|
1775 |
* returns DWT_SUCCESS for success (and the position in the buffer at which data begins), or DWT_ERROR for error |
|
1776 |
*/ |
|
1777 |
extern int readfromspi(uint16_t headerLength, const uint8_t *headerBuffer, uint32_t readlength, uint8_t *readBuffer); |
|
1778 |
|
|
1779 | 1731 |
// --------------------------------------------------------------------------- |
1780 | 1732 |
// |
1781 | 1733 |
// NB: The purpose of the deca_mutex.c file is to provide for microprocessor interrupt enable/disable, this is used for |
... | ... | |
1845 | 1797 |
|
1846 | 1798 |
void port_EnableEXT_IRQ(void); |
1847 | 1799 |
void port_DisableEXT_IRQ(void); |
1848 |
ITStatus port_GetEXT_IRQStatus(void); |
|
1800 |
decaIrqStatus_t port_GetEXT_IRQStatus(void); |
|
1801 |
//ITStatus port_GetEXT_IRQStatus(void); |
|
1849 | 1802 |
|
1850 | 1803 |
void port_set_dw1000_slowrate(void); |
1851 | 1804 |
void port_set_dw1000_fastrate(void); |
... | ... | |
1859 | 1812 |
#define DW1000_EXTI_IRQn EXTI15_10_IRQn |
1860 | 1813 |
|
1861 | 1814 |
|
1862 |
/** |
|
1863 |
* @brief Flag to switch between two SPI speeds on the fly |
|
1864 |
*/ |
|
1865 |
extern bool isHighSpeedSpi; |
|
1866 |
|
|
1867 |
|
|
1868 |
/** |
|
1869 |
* @brief Configuration for the Low Speed SPI interface driver to communicate with DW1000 |
|
1870 |
*/ |
|
1871 |
//extern SPIConfig moduleHalSpiUwbLsConfig; |
|
1872 |
|
|
1873 |
|
|
1874 |
/** |
|
1875 |
* @brief Configuration for the High Speed SPI interface driver to communicate with DW1000 |
|
1876 |
*/ |
|
1877 |
//extern SPIConfig moduleHalSpiUwbHsConfig; |
|
1878 |
|
|
1879 | 1815 |
#endif /* defined(AMIROLLD_CFG_DW1000) && (AMIROLLD_CFG_DW1000 == 1) */ |
1880 | 1816 |
|
1881 | 1817 |
#endif //AMIROLLD_DW1000_V1_H |
include/DW1000/v1/deca_instance_v1.h | ||
---|---|---|
470 | 470 |
void instance_close(void); |
471 | 471 |
// Call init, then call config, then call run. call close when finished |
472 | 472 |
// initialise the instance (application) structures and DW1000 device |
473 |
int instance_init(void); |
|
473 |
// int instance_init(void); |
|
474 |
int instance_init(DW1000Driver* drv); //TODO |
|
475 |
|
|
474 | 476 |
// configure the instance and DW1000 device |
475 | 477 |
void instance_config(instanceConfig_t *config, sfConfig_t *sfconfig) ; |
476 | 478 |
|
... | ... | |
528 | 530 |
uint64_t convertmicrosectodevicetimeu (double microsecu); |
529 | 531 |
double convertdevicetimetosec(int32_t dt); |
530 | 532 |
|
531 |
#define DWT_PRF_64M_RFDLY (514.462f) |
|
532 |
#define DWT_PRF_16M_RFDLY (513.9067f) |
|
533 | 533 |
|
534 |
/* Extern declaration while defining the data in .c file */ |
|
534 |
// ------------------------------------------------------------------------------------------------------------------- |
|
535 |
// Deca Calibration Values |
|
536 |
// ------------------------------------------------------------------------------------------------------------------- |
|
537 |
|
|
538 |
#define DWT_PRF_64M_RFDLY (514.462f) |
|
539 |
#define DWT_PRF_16M_RFDLY (513.9067f) |
|
540 |
|
|
541 |
/* Extern declaration while defining them in .c file */ |
|
535 | 542 |
extern const uint16_t rfDelays[2]; |
536 | 543 |
extern const uint16_t rfDelaysTREK[2]; |
537 | 544 |
extern const tx_struct txSpectrumConfig[8]; |
538 | 545 |
extern instance_data_t instance_data[NUM_INST] ; |
539 | 546 |
|
547 |
extern sfConfig_t sfConfig[4]; |
|
548 |
extern instanceConfig_t chConfig[4]; |
|
549 |
|
|
540 | 550 |
|
541 | 551 |
int instance_peekevent(void); |
542 | 552 |
|
... | ... | |
579 | 589 |
|
580 | 590 |
int instance_starttxtest(int framePeriod); |
581 | 591 |
|
592 |
|
|
593 |
|
|
582 | 594 |
#endif /* defined(AMIROLLD_CFG_DW1000) && (AMIROLLD_CFG_DW1000 == 1) */ |
583 | 595 |
|
584 | 596 |
#ifdef __cplusplus |
source/DW1000/v1/alld_dw1000_v1.c | ||
---|---|---|
28 | 28 |
* |
29 | 29 |
*/ |
30 | 30 |
|
31 |
|
|
32 | 31 |
#include <alld_DW1000.h> |
33 | 32 |
|
34 | 33 |
#if (defined(AMIROLLD_CFG_DW1000) && (AMIROLLD_CFG_DW1000 == 1)) || defined(__DOXYGEN__) |
35 | 34 |
|
35 |
#include <v1/alld_dw1000_regs_v1.h> |
|
36 |
|
|
36 | 37 |
#include <aos_thread.h> |
37 | 38 |
#include <assert.h> |
38 | 39 |
#include <string.h> |
... | ... | |
40 | 41 |
#include <math.h> |
41 | 42 |
|
42 | 43 |
|
44 |
// HW dependent implementation (see bottom of file) |
|
45 |
static int writetospi(uint16_t headerLength, |
|
46 |
const uint8_t *headerBuffer, |
|
47 |
uint32_t bodyLength, |
|
48 |
const uint8_t *bodyBuffer); |
|
49 |
|
|
50 |
static int readfromspi(uint16_t headerLength, |
|
51 |
const uint8_t *headerBuffer, |
|
52 |
uint32_t readlength, |
|
53 |
uint8_t *readBuffer); |
|
54 |
|
|
55 |
|
|
43 | 56 |
// Defines for enable_clocks function |
44 | 57 |
#define FORCE_SYS_XTI 0 |
45 | 58 |
#define ENABLE_ALL_SEQ 1 |
... | ... | |
57 | 70 |
#define FCTRL_LEN_MAX 2 |
58 | 71 |
|
59 | 72 |
|
60 |
/** |
|
61 |
* Move to the header file <alld_dw1000_v1.h> |
|
62 |
*/ |
|
63 |
//#define NUM_BR 3 |
|
64 |
//#define NUM_PRF 2 |
|
65 |
//#define NUM_PACS 4 |
|
66 |
//#define NUM_BW 2 //2 bandwidths are supported |
|
67 |
//#define NUM_SFD 2 //supported number of SFDs - standard = 0, non-standard = 1 |
|
68 |
//#define NUM_CH 6 //supported channels are 1, 2, 3, 4, 5, 7 |
|
69 |
//#define NUM_CH_SUPPORTED 8 //supported channels are '0', 1, 2, 3, 4, 5, '6', 7 |
|
70 |
//#define PCODES 25 //supported preamble codes |
|
71 |
|
|
72 |
|
|
73 | 73 |
typedef struct { |
74 | 74 |
uint32_t lo32; |
75 | 75 |
uint16_t target[NUM_PRF]; |
... | ... | |
1013 | 1013 |
#define VTEMP_ADDRESS (0x09) |
1014 | 1014 |
#define XTRIM_ADDRESS (0x1E) |
1015 | 1015 |
|
1016 |
//int dwt_initialise(const uint16_t config, DW1000Driver* drv)
|
|
1017 |
int dwt_initialise(const uint16_t config) // TODO: |
|
1016 |
int dwt_initialise(const uint16_t config, DW1000Driver* drv) |
|
1017 |
//int dwt_initialise(const uint16_t config) // TODO:
|
|
1018 | 1018 |
{ |
1019 | 1019 |
uint16_t otp_addr = 0; |
1020 | 1020 |
uint32_t ldo_tune = 0; |
... | ... | |
1028 | 1028 |
pdw1000local->cbRxTo = NULL; |
1029 | 1029 |
pdw1000local->cbRxErr = NULL; |
1030 | 1030 |
|
1031 |
// pdw1000local->driver = drv; // TODO:
|
|
1031 |
pdw1000local->driver = drv; // TODO: |
|
1032 | 1032 |
|
1033 | 1033 |
// Read and validate device ID return -1 if not recognised |
1034 | 1034 |
if (DWT_DEVICE_ID != dwt_readdevid()) // MP IC ONLY (i.e. DW1000) FOR THIS CODE |
... | ... | |
1813 | 1813 |
} |
1814 | 1814 |
|
1815 | 1815 |
// Write it to the SPI |
1816 |
// _alld_dw1000_writespi(cnt,header,length,buffer); |
|
1817 |
writetospi(cnt,header,length,buffer); // TODO |
|
1816 |
writetospi(cnt,header,length,buffer); |
|
1818 | 1817 |
} // end dwt_writetodevice() |
1819 | 1818 |
|
1820 | 1819 |
/*! ------------------------------------------------------------------------------------------------------------------ |
... | ... | |
1878 | 1877 |
} |
1879 | 1878 |
|
1880 | 1879 |
// Do the read from the SPI |
1881 |
// _alld_dw1000_readspi(cnt, header, length, buffer); // result is stored in the buffer |
|
1882 |
readfromspi(cnt, header, length, buffer); // TODO: |
|
1880 |
readfromspi(cnt, header, length, buffer); |
|
1883 | 1881 |
} // end dwt_readfromdevice() |
1884 | 1882 |
|
1885 | 1883 |
|
... | ... | |
4419 | 4417 |
* |
4420 | 4418 |
****************************************************************************************************************************************************/ |
4421 | 4419 |
|
4422 |
/* |
|
4423 |
* DW1000 Hardware dependent functions: SPI, EXTI |
|
4424 |
*/ |
|
4420 |
/****************************************************************************//** |
|
4421 |
* |
|
4422 |
* alld_dw1000.c SPI Section |
|
4423 |
* |
|
4424 |
*******************************************************************************/ |
|
4425 | 4425 |
|
4426 | 4426 |
/*! ------------------------------------------------------------------------------------------------------------------ |
4427 | 4427 |
* Function: writetospi() |
... | ... | |
4431 | 4431 |
* returns 0 for success, or -1 for error |
4432 | 4432 |
*/ |
4433 | 4433 |
#pragma GCC optimize ("O3") |
4434 |
int writetospi(uint16_t headerLength, |
|
4434 |
static int writetospi(uint16_t headerLength,
|
|
4435 | 4435 |
const uint8_t *headerBuffer, |
4436 | 4436 |
uint32_t bodyLength, |
4437 | 4437 |
const uint8_t *bodyBuffer) |
4438 | 4438 |
{ |
4439 | 4439 |
|
4440 |
port_SPIx_clear_chip_select(); |
|
4441 |
|
|
4442 | 4440 |
uint8_t buffer[bodyLength + 3]; |
4443 | 4441 |
memcpy(buffer, headerBuffer, headerLength); //copy data to buffer |
4444 | 4442 |
memcpy(&buffer[headerLength], bodyBuffer, bodyLength); //copy data to buffer |
... | ... | |
4447 | 4445 |
buffer, |
4448 | 4446 |
bodyLength + headerLength); // send header and data |
4449 | 4447 |
|
4450 |
port_SPIx_set_chip_select(); |
|
4451 |
|
|
4452 | 4448 |
return 0; |
4453 | 4449 |
} // end writetospi() |
4454 | 4450 |
|
4455 | 4451 |
|
4456 |
|
|
4457 | 4452 |
/*! ------------------------------------------------------------------------------------------------------------------ |
4458 | 4453 |
* Function: readfromspi() |
4459 | 4454 |
* |
... | ... | |
4463 | 4458 |
* or returns -1 if there was an error |
4464 | 4459 |
*/ |
4465 | 4460 |
#pragma GCC optimize ("O3") |
4466 |
int readfromspi(uint16_t headerLength, |
|
4461 |
static int readfromspi(uint16_t headerLength,
|
|
4467 | 4462 |
const uint8_t *headerBuffer, |
4468 | 4463 |
uint32_t readlength, |
4469 | 4464 |
uint8_t *readBuffer) |
4470 | 4465 |
{ |
4471 | 4466 |
|
4472 |
apalSPITransmitAndReceive(&MODULE_HAL_SPI_UWB, |
|
4467 |
apalSPITransmitAndReceive(&MODULE_HAL_SPI_UWB, // TODO: "pdw1000local->driver->spid" fails two spi configs
|
|
4473 | 4468 |
headerBuffer, |
4474 | 4469 |
readBuffer, |
4475 | 4470 |
headerLength, |
... | ... | |
4499 | 4494 |
* |
4500 | 4495 |
* returns the state of the DW1000 interrupt |
4501 | 4496 |
*/ |
4502 |
decaIrqStatus_t decamutexon(void)
|
|
4497 |
decaIrqStatus_t decamutexon(void) |
|
4503 | 4498 |
{ |
4504 |
decaIrqStatus_t s = port_GetEXT_IRQStatus(); |
|
4505 | 4499 |
|
4506 |
if(s) { |
|
4507 |
port_DisableEXT_IRQ(); //disable the external interrupt line |
|
4508 |
} |
|
4509 |
return s ; // return state before disable, value is used to re-enable in decamutexoff call |
|
4500 |
decaIrqStatus_t s = port_GetEXT_IRQStatus(); |
|
4501 |
if(s) { |
|
4502 |
port_DisableEXT_IRQ(); //disable the external interrupt line |
|
4503 |
} |
|
4504 |
return s ; // return state before disable, value is used to re-enable in decamutexoff call |
|
4510 | 4505 |
} |
4511 | 4506 |
|
4512 | 4507 |
/*! ------------------------------------------------------------------------------------------------------------------ |
... | ... | |
4526 | 4521 |
*/ |
4527 | 4522 |
void decamutexoff(decaIrqStatus_t s) |
4528 | 4523 |
{ |
4529 |
// (void) s;
|
|
4530 |
if(s) { //need to check the port state as we can't use level sensitive interrupt on the STM ARM
|
|
4531 |
port_EnableEXT_IRQ();
|
|
4532 |
}
|
|
4533 |
// return;
|
|
4524 |
// (void) s; |
|
4525 |
if(s) { //need to check the port state as we can't use level sensitive interrupt on the STM ARM |
|
4526 |
port_EnableEXT_IRQ(); |
|
4527 |
} |
|
4528 |
return; |
|
4534 | 4529 |
} |
4535 | 4530 |
|
4536 | 4531 |
|
... | ... | |
4540 | 4535 |
|
4541 | 4536 |
void deca_sleep(unsigned int time_ms) |
4542 | 4537 |
{ |
4543 |
aosThdMSleep(time_ms);
|
|
4538 |
aosThdMSleep(time_ms); |
|
4544 | 4539 |
} |
4545 | 4540 |
|
4546 | 4541 |
void Sleep(unsigned int time_ms) |
4547 | 4542 |
{ |
4548 |
aosThdMSleep(time_ms);
|
|
4543 |
aosThdMSleep(time_ms); |
|
4549 | 4544 |
} |
4550 | 4545 |
|
4551 | 4546 |
|
4552 |
void port_set_dw1000_slowrate(){ // replaced with setHighSpeed_SPI(bool speedValue) implemented in module.c |
|
4553 |
return; |
|
4554 |
} |
|
4555 |
|
|
4556 |
void port_set_dw1000_fastrate(){ // replaced with setHighSpeed_SPI(bool speedValue) implemented in module.c |
|
4557 |
return; |
|
4558 |
} |
|
4559 |
|
|
4560 | 4547 |
void port_wakeup_dw1000_fast(){ // NOT SUPPORTED |
4561 |
return;
|
|
4548 |
return; |
|
4562 | 4549 |
} |
4563 | 4550 |
|
4564 | 4551 |
uint32_t portGetTickCnt(){ |
4565 |
return chVTGetSystemTimeX();
|
|
4552 |
return chVTGetSystemTimeX(); |
|
4566 | 4553 |
} |
4567 | 4554 |
|
4568 | 4555 |
//inline uint32_t portGetTickCnt(){ |
... | ... | |
4571 | 4558 |
|
4572 | 4559 |
|
4573 | 4560 |
void port_DisableEXT_IRQ(void){ |
4574 |
nvicDisableVector(DW1000_EXTI_IRQn);
|
|
4561 |
nvicDisableVector(DW1000_EXTI_IRQn); |
|
4575 | 4562 |
|
4576 | 4563 |
} |
4577 | 4564 |
|
4578 | 4565 |
void port_EnableEXT_IRQ(void){ |
4579 |
nvicEnableVector(DW1000_EXTI_IRQn, STM32_IRQ_EXTI10_15_PRIORITY);
|
|
4566 |
nvicEnableVector(DW1000_EXTI_IRQn, STM32_IRQ_EXTI10_15_PRIORITY); |
|
4580 | 4567 |
} |
4581 | 4568 |
|
4582 | 4569 |
|
4583 |
ITStatus port_GetEXT_IRQStatus(void){ |
|
4584 |
ITStatus bitstatus = RESET; |
|
4585 |
// uint32_t enablestatus = 0; |
|
4570 |
decaIrqStatus_t port_GetEXT_IRQStatus(void){ |
|
4571 |
decaIrqStatus_t bitstatus = RESET; |
|
4586 | 4572 |
|
4587 | 4573 |
if(NVIC_GetActive(DW1000_EXTI_IRQn)|| NVIC_GetPendingIRQ(DW1000_EXTI_IRQn)){ |
4588 | 4574 |
// if(NVIC_GetPendingIRQ(EXTI15_10_IRQn)){ //if the interrupt is pending (background ) |
4589 | 4575 |
bitstatus = SET; //Interrupt is active or panding |
4590 | 4576 |
} |
4591 | 4577 |
else { |
4592 |
bitstatus = RESET; //Currently there is no interrupt IRQ
|
|
4578 |
bitstatus = RESET; //No interrupt IRQ at the moment
|
|
4593 | 4579 |
} |
4594 | 4580 |
|
4595 | 4581 |
return bitstatus; |
4596 | 4582 |
} |
4597 | 4583 |
|
4598 |
|
|
4599 |
|
|
4600 | 4584 |
#endif /* defined(AMIROLLD_CFG_DW1000) && (AMIROLLD_CFG_DW1000 == 1) */ |
source/DW1000/v1/deca_instance_common_v1.c | ||
---|---|---|
18 | 18 |
#include "module.h" |
19 | 19 |
#include <string.h> |
20 | 20 |
#include <math.h> |
21 |
#include <v1/deca_instance_v1.h> |
|
22 |
|
|
23 |
|
|
24 |
/*! @brief Software defined configuration settings for RTLS applications */ |
|
25 |
/*! Configuration for DecaRangeRTLS TREK Modes (4 default use cases selected by the switch S1 [2,3] on EVB1000, indexed 0 to 3 )*/ |
|
26 |
instanceConfig_t chConfig[4] ={ |
|
27 |
//mode 1 - S1: 2 off, 3 off |
|
28 |
{ |
|
29 |
.channelNumber = 2, // channel |
|
30 |
.preambleCode = 4, // preambleCode |
|
31 |
.pulseRepFreq = DWT_PRF_16M, // prf |
|
32 |
.dataRate = DWT_BR_110K, // datarate |
|
33 |
.preambleLen = DWT_PLEN_1024, // preambleLength |
|
34 |
.pacSize = DWT_PAC32, // pacSize |
|
35 |
.nsSFD = 1, // non-standard SFD |
|
36 |
.sfdTO = (1025 + 64 - 32) // SFD timeout |
|
37 |
}, |
|
38 |
//mode 2 - S1: 2 on, 3 off |
|
39 |
{ |
|
40 |
.channelNumber = 2, // channel |
|
41 |
.preambleCode = 4, // preambleCode |
|
42 |
.pulseRepFreq = DWT_PRF_16M, // prf |
|
43 |
.dataRate = DWT_BR_6M8, // datarate |
|
44 |
.preambleLen = DWT_PLEN_128, // preambleLength |
|
45 |
.pacSize = DWT_PAC8, // pacSize |
|
46 |
.nsSFD = 0, // non-standard SFD |
|
47 |
.sfdTO = (129 + 8 - 8) // SFD timeout |
|
48 |
}, |
|
49 |
//mode 3 - S1: 2 off, 3 on |
|
50 |
{ |
|
51 |
.channelNumber = 5, // channel |
|
52 |
.preambleCode = 3, // preambleCode |
|
53 |
.pulseRepFreq = DWT_PRF_16M, // prf |
|
54 |
.dataRate = DWT_BR_110K, // datarate |
|
55 |
.preambleLen = DWT_PLEN_1024, // preambleLength |
|
56 |
.pacSize = DWT_PAC32, // pacSize |
|
57 |
.nsSFD = 1, // non-standard SFD |
|
58 |
.sfdTO = (1025 + 64 - 32) // SFD timeout |
|
59 |
}, |
|
60 |
//mode 4 - S1: 2 on, 3 on |
|
61 |
{ |
|
62 |
.channelNumber = 5, // channel |
|
63 |
.preambleCode = 3, // preambleCode |
|
64 |
.pulseRepFreq = DWT_PRF_16M, // prf |
|
65 |
.dataRate = DWT_BR_6M8, // datarate |
|
66 |
.preambleLen = DWT_PLEN_128, // preambleLength |
|
67 |
.pacSize = DWT_PAC8, // pacSize |
|
68 |
.nsSFD = 0, // non-standard SFD |
|
69 |
.sfdTO = (129 + 8 - 8) // SFD timeout |
|
70 |
} |
|
71 |
}; |
|
21 | 72 |
|
22 | 73 |
|
23 |
extern double dwt_getrangebias(uint8_t chan, float range, uint8_t prf); |
|
24 |
|
|
25 |
extern const uint16_t rfDelays[2]; |
|
26 |
extern const uint16_t rfDelaysTREK[2]; |
|
27 |
extern const tx_struct txSpectrumConfig[8]; |
|
28 |
|
|
29 |
|
|
30 |
|
|
31 |
// ------------------------------------------------------------------------------------------------------------------- |
|
32 |
// Deca Calibration Values |
|
33 |
// ------------------------------------------------------------------------------------------------------------------- |
|
74 |
/*! Slot and Superframe Configuration for DecaRangeRTLS TREK Modes (4 default use cases selected by the switch S1 [2,3] on EVB1000, indexed 0 to 3 )*/ |
|
75 |
sfConfig_t sfConfig[4] ={ |
|
76 |
//mode 1 - S1: 2 off, 3 off |
|
77 |
{ |
|
78 |
.slotPeriod = (28), //slot duration in milliseconds (NOTE: the ranging exchange must be able to complete in this time |
|
79 |
//e.g. tag sends a poll, 4 anchors send responses and tag sends the final + processing time |
|
80 |
.numSlots = (10), //number of slots in the superframe (8 tag slots and 2 used for anchor to anchor ranging), |
|
81 |
.sfPeriod = (10*28), //in ms => 280ms frame means 3.57 Hz location rate |
|
82 |
.pollSleepDly = (10*28), //tag period in ms (sleep time + ranging time) |
|
83 |
.replyDly = (25000) //poll to final delay in microseconds (needs to be adjusted according to lengths of ranging frames) |
|
84 |
}, |
|
85 |
#if (DISCOVERY == 1) |
|
86 |
//mode 2 - S1: 2 on, 3 off |
|
87 |
{ |
|
88 |
.slotPeriod = (10), //slot duration in milliseconds (NOTE: the ranging exchange must be able to complete in this time |
|
89 |
//e.g. tag sends a poll, 4 anchors send responses and tag sends the final + processing time |
|
90 |
.numSlots = (100), //number of slots in the superframe (98 tag slots and 2 used for anchor to anchor ranging), |
|
91 |
.sfPeriod = (10*100), //in ms => 1000 ms frame means 1 Hz location rate |
|
92 |
.pollSleepDly = (10*100), //tag period in ms (sleep time + ranging time) |
|
93 |
.replyDly = (2500) //poll to final delay in microseconds (needs to be adjusted according to lengths of ranging frames) |
|
94 |
|
|
95 |
}, |
|
96 |
#else |
|
97 |
//mode 2 - S1: 2 on, 3 off |
|
98 |
{ |
|
99 |
.slotPeriod = (10), //slot duration in milliseconds (NOTE: the ranging exchange must be able to complete in this time |
|
100 |
//e.g. tag sends a poll, 4 anchors send responses and tag sends the final + processing time |
|
101 |
.numSlots = (10), //number of slots in the superframe (8 tag slots and 2 used for anchor to anchor ranging), |
|
102 |
.sfPeriod = (10*10), //in ms => 100 ms frame means 10 Hz location rate |
|
103 |
.pollSleepDly = (10*10), //tag period in ms (sleep time + ranging time) |
|
104 |
.replyDly = (2500) //poll to final delay in microseconds (needs to be adjusted according to lengths of ranging frames) |
|
105 |
}, |
|
106 |
#endif |
|
107 |
//mode 3 - S1: 2 off, 3 on |
|
108 |
{ |
|
109 |
.slotPeriod = (28), //slot duration in milliseconds (NOTE: the ranging exchange must be able to complete in this time |
|
110 |
//e.g. tag sends a poll, 4 anchors send responses and tag sends the final + processing time |
|
111 |
.numSlots = (10), //number of slots in the superframe (8 tag slots and 2 used for anchor to anchor ranging), |
|
112 |
.sfPeriod = (10*28), //in ms => 280ms frame means 3.57 Hz location rate |
|
113 |
.pollSleepDly = (10*28), //tag period in ms (sleep time + ranging time) |
|
114 |
.replyDly = (20000) //poll to final delay in microseconds (needs to be adjusted according to lengths of ranging frames) |
|
115 |
|
|
116 |
}, |
|
117 |
//mode 4 - S1: 2 on, 3 on |
|
118 |
{ |
|
119 |
.slotPeriod = (10), //slot duration in milliseconds (NOTE: the ranging exchange must be able to complete in this time |
|
120 |
//e.g. tag sends a poll, 4 anchors send responses and tag sends the final + processing time |
|
121 |
.numSlots = (10), //number of slots in the superframe (8 tag slots and 2 used for anchor to anchor ranging), |
|
122 |
.sfPeriod = (10*10), //in ms => 100 ms frame means 10 Hz location rate |
|
123 |
.pollSleepDly = (10*10), //tag period in ms (sleep time + ranging time) |
|
124 |
.replyDly = (2500) //poll to final delay in microseconds (needs to be adjusted according to lengths of ranging frames) |
|
125 |
} |
|
126 |
}; |
|
34 | 127 |
|
35 |
#define DWT_PRF_64M_RFDLY (514.462f) |
|
36 |
#define DWT_PRF_16M_RFDLY (513.9067f) |
|
37 | 128 |
|
38 | 129 |
// ------------------------------------------------------------------------------------------------------------------- |
39 | 130 |
|
... | ... | |
341 | 432 |
// function to initialise instance structures |
342 | 433 |
// |
343 | 434 |
// Returns 0 on success and -1 on error |
344 |
int instance_init(void){ |
|
435 |
//int instance_init(void){ // TODO |
|
436 |
int instance_init(DW1000Driver* drv){ |
|
345 | 437 |
int instance = 0 ; |
346 | 438 |
int i; |
347 | 439 |
int result; |
... | ... | |
356 | 448 |
//dwt_softreset(); |
357 | 449 |
|
358 | 450 |
//this initialises DW1000 and uses specified configurations from OTP/ROM |
359 |
result = dwt_initialise(DWT_LOADUCODE) ; |
|
451 |
result = dwt_initialise(DWT_LOADUCODE, drv) ; // TODO |
|
452 |
// result = dwt_initialise(DWT_LOADUCODE) ; |
|
360 | 453 |
|
361 | 454 |
//this is platform dependent - only program if DW EVK/EVB |
362 | 455 |
dwt_setleds(3) ; //configure the GPIOs which control the leds on EVBs |
source/DW1000/v1/deca_instance_tag_anchor_v1.c | ||
---|---|---|
15 | 15 |
|
16 | 16 |
#if (defined(AMIROLLD_CFG_DW1000) && (AMIROLLD_CFG_DW1000 == 1)) || defined(__DOXYGEN__) |
17 | 17 |
|
18 |
#include <v1/deca_instance_v1.h> |
|
18 | 19 |
#include <string.h> |
19 | 20 |
#include<math.h> |
20 | 21 |
#include "module.h" |
Also available in: Unified diff