void dwInit(dwDevice_t* dev, dwOps_t* ops) { dev->ops = ops; dev->userdata = NULL; /* Device default state */ dev->extendedFrameLength = FRAME_LENGTH_NORMAL; dev->pacSize = PAC_SIZE_8; dev->pulseFrequency = TX_PULSE_FREQ_16MHZ; dev->dataRate = TRX_RATE_6800KBPS; dev->preambleLength = TX_PREAMBLE_LEN_128; dev->preambleCode = PREAMBLE_CODE_16MHZ_4; dev->channel = CHANNEL_5; dev->smartPower = false; dev->frameCheck = true; dev->permanentReceive = false; dev->deviceMode = IDLE_MODE; writeValueToBytes(dev->antennaDelay.raw, 16384, LEN_STAMP); // Dummy callback handlers dev->handleSent = dummy; dev->handleReceived = dummy; dev->handleReceiveFailed = dummy; }
void DW1000Class::begin(int irq, int rst) { // generous initial init/wake-up-idle delay delay(5); // start SPI SPI.begin(); SPI.usingInterrupt(irq); // pin and basic member setup _rst = rst; _irq = irq; _deviceMode = IDLE_MODE; pinMode(_rst, OUTPUT); digitalWrite(_rst, HIGH); // reset chip (either soft or hard) if(_rst <= 0) { softReset(); } else { reset(); } // try locking clock at PLL speed (should be done already, // but just to be sure) enableClock(AUTO_CLOCK); delay(5); // default network and node id writeValueToBytes(_networkAndAddress, 0xFF, LEN_PANADR); writeNetworkIdAndDeviceAddress(); // default system configuration memset(_syscfg, 0, LEN_SYS_CFG); setDoubleBuffering(false); setInterruptPolarity(true); writeSystemConfigurationRegister(); // default interrupt mask, i.e. no interrupts clearInterrupts(); writeSystemEventMaskRegister(); // attach interrupt attachInterrupt(_irq, DW1000Class::handleInterrupt, RISING); }
void DW1000Class::tune() { // these registers are going to be tuned/configured byte agctune1[LEN_AGC_TUNE1]; byte agctune2[LEN_AGC_TUNE2]; byte agctune3[LEN_AGC_TUNE3]; byte drxtune0b[LEN_DRX_TUNE0b]; byte drxtune1a[LEN_DRX_TUNE1a]; byte drxtune1b[LEN_DRX_TUNE1b]; byte drxtune2[LEN_DRX_TUNE2]; byte drxtune4H[LEN_DRX_TUNE4H]; byte ldecfg1[LEN_LDE_CFG1]; byte ldecfg2[LEN_LDE_CFG2]; byte lderepc[LEN_LDE_REPC]; byte txpower[LEN_TX_POWER]; byte rfrxctrlh[LEN_RF_RXCTRLH]; byte rftxctrl[LEN_RF_TXCTRL]; byte tcpgdelay[LEN_TC_PGDELAY]; byte fspllcfg[LEN_FS_PLLCFG]; byte fsplltune[LEN_FS_PLLTUNE]; // AGC_TUNE1 if(_pulseFrequency == TX_PULSE_FREQ_16MHZ) { writeValueToBytes(agctune1, 0x8870, LEN_AGC_TUNE1); } else if(_pulseFrequency == TX_PULSE_FREQ_64MHZ) { writeValueToBytes(agctune1, 0x889B, LEN_AGC_TUNE1); } else { // TODO proper error/warning handling } // AGC_TUNE2 writeValueToBytes(agctune2, 0x2502A907L, LEN_AGC_TUNE2); // AGC_TUNE3 writeValueToBytes(agctune3, 0x0035, LEN_AGC_TUNE3); // DRX_TUNE0b (already optimized according to Table 20 of user manual) if(_dataRate == TRX_RATE_110KBPS) { writeValueToBytes(drxtune0b, 0x0016, LEN_DRX_TUNE0b); } else if(_dataRate == TRX_RATE_850KBPS) { writeValueToBytes(drxtune0b, 0x0006, LEN_DRX_TUNE0b); } else if(_dataRate == TRX_RATE_6800KBPS) { writeValueToBytes(drxtune0b, 0x0001, LEN_DRX_TUNE0b); } else { // TODO proper error/warning handling } // DRX_TUNE1a if(_pulseFrequency == TX_PULSE_FREQ_16MHZ) { writeValueToBytes(drxtune1a, 0x0087, LEN_DRX_TUNE1a); } else if(_pulseFrequency == TX_PULSE_FREQ_64MHZ) { writeValueToBytes(drxtune1a, 0x008D, LEN_DRX_TUNE1a); } else { // TODO proper error/warning handling } // DRX_TUNE1b if(_preambleLength == TX_PREAMBLE_LEN_1536 || _preambleLength == TX_PREAMBLE_LEN_2048 || _preambleLength == TX_PREAMBLE_LEN_4096) { if(_dataRate == TRX_RATE_110KBPS) { writeValueToBytes(drxtune1b, 0x0064, LEN_DRX_TUNE1b); } else { // TODO proper error/warning handling } } else if(_preambleLength != TX_PREAMBLE_LEN_64) { if(_dataRate == TRX_RATE_850KBPS || _dataRate == TRX_RATE_6800KBPS) { writeValueToBytes(drxtune1b, 0x0020, LEN_DRX_TUNE1b); } else { // TODO proper error/warning handling } } else { if(_dataRate == TRX_RATE_6800KBPS) { writeValueToBytes(drxtune1b, 0x0010, LEN_DRX_TUNE1b); } else { // TODO proper error/warning handling } } // DRX_TUNE2 if(_pacSize == PAC_SIZE_8) { if(_pulseFrequency == TX_PULSE_FREQ_16MHZ) { writeValueToBytes(drxtune2, 0x311A002DL, LEN_DRX_TUNE2); } else if(_pulseFrequency == TX_PULSE_FREQ_64MHZ) { writeValueToBytes(drxtune2, 0x313B006BL, LEN_DRX_TUNE2); } else { // TODO proper error/warning handling } } else if(_pacSize == PAC_SIZE_16) { if(_pulseFrequency == TX_PULSE_FREQ_16MHZ) { writeValueToBytes(drxtune2, 0x331A0052L, LEN_DRX_TUNE2); } else if(_pulseFrequency == TX_PULSE_FREQ_64MHZ) { writeValueToBytes(drxtune2, 0x333B00BEL, LEN_DRX_TUNE2); } else { // TODO proper error/warning handling } } else if(_pacSize == PAC_SIZE_32) { if(_pulseFrequency == TX_PULSE_FREQ_16MHZ) { writeValueToBytes(drxtune2, 0x351A009AL, LEN_DRX_TUNE2); } else if(_pulseFrequency == TX_PULSE_FREQ_64MHZ) { writeValueToBytes(drxtune2, 0x353B015EL, LEN_DRX_TUNE2); } else { // TODO proper error/warning handling } } else if(_pacSize == PAC_SIZE_64) { if(_pulseFrequency == TX_PULSE_FREQ_16MHZ) { writeValueToBytes(drxtune2, 0x371A011DL, LEN_DRX_TUNE2); } else if(_pulseFrequency == TX_PULSE_FREQ_64MHZ) { writeValueToBytes(drxtune2, 0x373B0296L, LEN_DRX_TUNE2); } else { // TODO proper error/warning handling } } else { // TODO proper error/warning handling } // DRX_TUNE4H if(_preambleLength == TX_PREAMBLE_LEN_64) { writeValueToBytes(drxtune4H, 0x0010, LEN_DRX_TUNE4H); } else { writeValueToBytes(drxtune4H, 0x0028, LEN_DRX_TUNE4H); } // RF_RXCTRLH if(_channel != CHANNEL_4 && _channel != CHANNEL_7) { writeValueToBytes(rfrxctrlh, 0xD8, LEN_RF_RXCTRLH); } else { writeValueToBytes(rfrxctrlh, 0xBC, LEN_RF_RXCTRLH); } // RX_TXCTRL if(_channel == CHANNEL_1) { writeValueToBytes(rftxctrl, 0x00005C40L, LEN_RF_TXCTRL); } else if(_channel == CHANNEL_2) { writeValueToBytes(rftxctrl, 0x00045CA0L, LEN_RF_TXCTRL); } else if(_channel == CHANNEL_3) { writeValueToBytes(rftxctrl, 0x00086CC0L, LEN_RF_TXCTRL); } else if(_channel == CHANNEL_4) { writeValueToBytes(rftxctrl, 0x00045C80L, LEN_RF_TXCTRL); } else if(_channel == CHANNEL_5) { writeValueToBytes(rftxctrl, 0x001E3FE0L, LEN_RF_TXCTRL); } else if(_channel == CHANNEL_7) { writeValueToBytes(rftxctrl, 0x001E7DE0L, LEN_RF_TXCTRL); } else { // TODO proper error/warning handling } // TC_PGDELAY if(_channel == CHANNEL_1) { writeValueToBytes(tcpgdelay, 0xC9, LEN_TC_PGDELAY); } else if(_channel == CHANNEL_2) { writeValueToBytes(tcpgdelay, 0xC2, LEN_TC_PGDELAY); } else if(_channel == CHANNEL_3) { writeValueToBytes(tcpgdelay, 0xC5, LEN_TC_PGDELAY); } else if(_channel == CHANNEL_4) { writeValueToBytes(tcpgdelay, 0x95, LEN_TC_PGDELAY); } else if(_channel == CHANNEL_5) { writeValueToBytes(tcpgdelay, 0xC0, LEN_TC_PGDELAY); } else if(_channel == CHANNEL_7) { writeValueToBytes(tcpgdelay, 0x93, LEN_TC_PGDELAY); } else { // TODO proper error/warning handling } // FS_PLLCFG and FS_PLLTUNE if(_channel == CHANNEL_1) { writeValueToBytes(fspllcfg, 0x09000407L, LEN_FS_PLLCFG); writeValueToBytes(fsplltune, 0x1E, LEN_FS_PLLTUNE); } else if(_channel == CHANNEL_2 || _channel == CHANNEL_4) { writeValueToBytes(fspllcfg, 0x08400508L, LEN_FS_PLLCFG); writeValueToBytes(fsplltune, 0x26, LEN_FS_PLLTUNE); } else if(_channel == CHANNEL_3) { writeValueToBytes(fspllcfg, 0x08401009L, LEN_FS_PLLCFG); writeValueToBytes(fsplltune, 0x5E, LEN_FS_PLLTUNE); } else if(_channel == CHANNEL_5 || _channel == CHANNEL_7) { writeValueToBytes(fspllcfg, 0x0800041DL, LEN_FS_PLLCFG); writeValueToBytes(fsplltune, 0xA6, LEN_FS_PLLTUNE); } else { // TODO proper error/warning handling } // LDE_CFG1 writeValueToBytes(ldecfg1, 0xD, LEN_LDE_CFG1); // LDE_CFG2 if(_pulseFrequency == TX_PULSE_FREQ_16MHZ) { writeValueToBytes(ldecfg2, 0x1607, LEN_LDE_CFG2); } else if(_pulseFrequency == TX_PULSE_FREQ_64MHZ) { writeValueToBytes(ldecfg2, 0x0607, LEN_LDE_CFG2); } else { // TODO proper error/warning handling } // LDE_REPC if(_preambleCode == PREAMBLE_CODE_16MHZ_1 || _preambleCode == PREAMBLE_CODE_16MHZ_2) { if(_dataRate == TRX_RATE_110KBPS) { writeValueToBytes(lderepc, ((0x5998 >> 3) & 0xFFFF), LEN_LDE_REPC); } else {