Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • garlichs/dw1000_driver_freertos
  • cwulf/dw1000_driver_freertos
  • cm-projects/dw1000_driver_freertos
3 results
Show changes
Commits on Source (17)
......@@ -98,7 +98,7 @@ extern "C" {
**/
#define SYS_TIME_ID 0x06 /* System Time Counter (40-bit) */
#define SYS_TIME_LEN (5) /* Note 40 bit register */
#define SYS_TIME_MASK 0x000000FFFFFFFFFFULL
/****************************************************************************//**
* @brief Bit definitions for register 0x07
......
......@@ -4,26 +4,16 @@
#include <stdint.h>
#include "cmsis_os.h"
#include "dw1000_util.h"
//DECA:DW1000 SLEEP and WAKEUP configuration parameters
#define DWT_LOADLDO 0x1000 // ONW_LLDO - on wakeup load the LDO tune value
#define DWT_LOADUCODE 0x0800 // ONW_LLDE - on wakeup load the LDE ucode
#define DWT_PRESRV_SLEEP 0x0100 // PRES_SLEEP - on wakeup preserve sleep bit
#define DWT_LOADOPSET 0x0080 // ONW_L64P - on wakeup load operating parameter set for 64 PSR
#define DWT_CONFIG 0x0040 // ONW_LDC - on wakeup restore (load) the saved configurations (from AON array into HIF)
#define DWT_TANDV 0x0001 // ONW_RADC - on wakeup run ADC to sample temperature and voltage sensor values
#define DWT_XTAL_EN 0x10 // keep XTAL running during sleep
#define DWT_WAKE_SLPCNT 0x8 // wake up after sleep count
#define DWT_WAKE_CS 0x4 // wake up on chip select
#define DWT_WAKE_WK 0x2 // wake up on WAKEUP PIN
#define DWT_SLP_EN 0x1 // enable sleep/deep sleep functionality
#define MAXIMUM_FRAME_LENGTH 127
#define FRAME_OVERHEAD sizeof(dw1000_frame_t) - MAXIMUM_FRAME_LENGTH
/**
* Defines for channel and prf selection and Preamble Code.
* Refer to Page 204 in the dw1000 User Manual 2.04
*/
#define PRF_SHIFT 0
#define CHANNEL_SHIFT 1
#define PREAMBLE_SHIFT 4
......@@ -73,22 +63,19 @@
#define CH7_64MHZ_19 (1 << PRF_SHIFT) | (7 << CHANNEL_SHIFT) | (19 << PREAMBLE_SHIFT)
#define CH7_64MHZ_20 (1 << PRF_SHIFT) | (7 << CHANNEL_SHIFT) | (20 << PREAMBLE_SHIFT)
//DECA:DW1000 INIT configuration parameters
#define DWT_LOADLDOTUNE 0x8
#define DWT_LOADTXCONFIG 0x4
#define DWT_LOADANTDLY 0x2
#define DWT_LOADXTALTRIM 0x1
#define DWT_LOADNONE 0x0
//DECA:DW1000 OTP operating parameter set selection
#define DWT_OPSET_64LEN 0x0
#define DWT_OPSET_TIGHT 0x1
#define DWT_OPSET_DEFLT 0x2
/**
* Defines various return codes for driver functions
*/
#define DW1000_RET_OK 0
#define DW1000_RET_MSG_TO_LONG -1
#define DW1000_RET_TX_BUFFER_OVERFLOW -2
#define DWT_SFDTOC_DEF 0x1041 // default SFD timeout value
/**
* The following defines are taken from the original driver
*/
#define DWT_LOADUCODE 0x0800 // ONW_LLDE - on wakeup load the LDE ucode
#define DWT_PHRMODE_STD 0x0 // standard PHR mode
#define DWT_PHRMODE_EXT 0x3 // DW proprietary extended frames PHR mode
#define DWT_SFDTOC_DEF 0x1041 // default SFD timeout value
//! constants for selecting the bit rate for data TX (and RX)
//! These are defined for write (with just a shift) the TX_FCTRL register
......@@ -119,43 +106,118 @@
#define DWT_PLEN_256 0x24 //! Non-standard preamble length 256 symbols
#define DWT_PLEN_128 0x14 //! Non-standard preamble length 128 symbols
#define DWT_PLEN_64 0x04 //! Standard preamble length 64 symbols
typedef struct {
uint8_t chan; //!< channel number {1, 2, 3, 4, 5, 7 }
uint8_t prf; //!< Pulse Repetition Frequency {DWT_PRF_16M or DWT_PRF_64M}
uint8_t txPreambLength; //!< DWT_PLEN_64..DWT_PLEN_4096
uint8_t rxPAC; //!< Acquisition Chunk Size (Relates to RX preamble length)
/**
* This structure describes a configuration,
* which is used in the configure function.
*/
typedef struct __attribute__((packed)){
uint8_t channel;
uint8_t pulse_repetition_frequency;
uint8_t preamble_length;
uint8_t preamble_acquisition_chunk_size;
uint8_t tx_preamble_code;
uint8_t rx_preamble_code;
uint8_t data_rate;
uint16_t sfd_timeout;
} dw1000_config_t;
uint8_t txCode; //!< TX preamble code
uint8_t rxCode; //!< RX preamble code
/**
* This structure describes a received frame
* rx_timestamp contains the time stamp counter as specified in the manual,
* if the timestamp_valid is non-zero.
* length specifies the actual length of the buffer, containing the received bytes
*/
typedef struct __attribute__((packed)){
uint8_t timestamp_valid;
uint8_t rx_timestamp[5];
uint16_t length;
uint8_t buffer[MAXIMUM_FRAME_LENGTH];
uint8_t nsSFD; //!< Boolean should we use non-standard SFD for better performance
uint8_t dataRate; //!< Data Rate {DWT_BR_110K, DWT_BR_850K or DWT_BR_6M8}
} dw1000_frame_t;
uint8_t phrMode; //!< PHR mode {0x0 - standard DWT_PHRMODE_STD, 0x3 - extended frames DWT_PHRMODE_EXT}
/**
* This function initializes the UWB module and sets the corresponding callbacks
* Parameters:
* send_callback: called after a frame has been transmitted
* receive_callback: called on frame reception
* task_handle: handle of a task which should be notified
* Either a task_handle or receive_callback can be used.
* If both is specified, the callback is used.
* The callbacks must return pdTrue, in case a higher priority task has to be scheduled
*/
void dw1000_init(BaseType_t (*send_callback)(), BaseType_t (*receive_callback)(), TaskHandle_t task_handle);
/**
* This function transfers the given configuration to the transceiver.
* The configuration can either be generated by dw1000_generateConfig, or written by onselfs
*/
void dw1000_configure(dw1000_config_t *config);
uint8_t smartPowerEn; //!< Smart Power enable / disable
/**
* This function is a convenience function for writeFrameIntoBuffer and transmitFrame.
* However, it ignores any offset or written frames and writes the frame with no offset
* to the the buffer.
* Parameters:
* frame: a pointer to a uint8_t array with the bytes which should be send
* frame_length: amount of bytes to be send
* Return value:
* DW1000_RET_OK on success
* DW1000_RET_MSG_TO_LONG if the message is too long
* DW1000_RET_TX_BUFFER_OVERFLOW if there is an buffer overflow
*/
int dw1000_sendFrame(uint8_t *frame, uint16_t frame_length);
uint16_t sfdTO; //!< SFD timeout value (in symbols)
/**
* This function writes a frame into the transmission buffer
* using the given offset
* Parameters:
* tx_buffer_offset: offset inside the transmission buffer
* frame: a pointer to a uint8_t array with the bytes which should be send
* frame_length: amount of bytes to be send
* Return value:
* DW1000_RET_OK on success
* DW1000_RET_MSG_TO_LONG if the message is too long
* DW1000_RET_TX_BUFFER_OVERFLOW if there is an buffer overflow
*/
int dw1000_writeFrameIntoBuffer(uint16_t tx_buffer_offset, uint8_t *frame, uint16_t frame_length);
} dwt_config_t;
/**
* This function transmits a frame already stored in the transmission buffer
* using the given offset
* Parameters:
* tx_buffer_offset: offset inside the transmission buffer
* frame_length: amount of bytes to be send
* Return value:
* DW1000_RET_OK on success
*/
int dw1000_transmitFrame(uint16_t txBufferOffset, uint16_t frame_length);
int dw1000_init(uint16_t config, BaseType_t (*sendCallback)(),
BaseType_t (*receiveCallback)(uint32_t bufferLength, uint8_t ts_valid));
int dw1000_configure(dwt_config_t *config, uint8_t use_otpconfigvalues);
int dw1000_sendFrame(uint8_t *payload, uint16_t len);
int dw1000_writeFrameIntoBuffer(uint16_t txBufferOffset, uint8_t *payload, uint16_t len);
int dw1000_transmitFrame(uint16_t txBufferOffset, uint16_t len);
int dw_1000_receiveFrameFromIsr(uint8_t * buffer, uint32_t length);
void dw1000_extiCallback(void);
void vTaskGlobalTimeIncrement(void *pvParameters);
/**
* This function gets a frame stored in the reception buffer.
* Parameters:
* frame: a dw1000_t frame in which the received frame
* inside the receive buffer is written
* length and time stamp information is set
* accordingly
*/
void dw1000_receiveFrameFromIsr(dw1000_frame_t *frame);
void dw1000_generateConfig(uint16_t mode, dwt_config_t *config);
/**
* This functions generates a configuration out of the given defines
* data_rate is always 6.8 MHz, sfd timeout 129 symbols,
* pac size 8 and preamble length 128
*
* See DW1000 User Manual 2.04 page 195 for further information
*
*/
void dw1000_generateConfig(uint16_t mode, dw1000_config_t *config, uint8_t fast);
#endif /*__ dw1000_H */
/**
* Defines various return codes for driver functions
* Callback for the external interrupt from the UWB.
* Triggered by the os.
*/
#define DW1000_RET_OK 0
#define DW1000_RET_MSG_TO_LONG -1
#define DW1000_RET_TX_BUFFER_OVERFLOW -2
void dw1000_extiCallback();
#endif /*__ dw1000_H */
/**
* DW1000 FreeRTOS Driver
*
* This header file and the corresponding c file take care of all ISR related execution,
* such as handling interrupts and invoking callback
*/
#ifndef __dw1000_isr_H
#define __dw1000_isr_H
#include "FreeRTOS.h"
#include <stdint.h>
/**
* This function handles interrupts from the UWB-module.
* It reschedules higher priority task, in case they have been notified within the interrupt
*/
void dw1000Isr_handleInterrupt(void);
#endif /*__ dw1000_isr_H */
/**
* DW1000 FreeRTOS Driver
*
* This header file and the corresponding c file
* provide functions and constants used internally by the driver.
* They should not be used outside of it.
*/
#ifndef __dw1000_util_H
#define __dw1000_util_H
#include "FreeRTOS.h"
#include <stdint.h>
#include <string.h>
#include "deca_regs.h"
//#define DOUBLE_BUFFER
#include "task.h"
#define DOUBLE_BUFFER
//DECA:Defines for enable_clocks function
#define FORCE_SYS_XTI 0
......@@ -33,71 +41,53 @@
#define PCODES 25 //supported preamble codes
#define ever ;;
#define GLOBAL_TIME_TICK_MS 17592
typedef struct {
uint64_t ms;
uint64_t subms;
} dw1000_global_time_t;
typedef struct {//DECA
uint32_t txFCTRL; // keep TX_FCTRL register config
uint16_t rfrxDly; // rf delay (delay though the RF blocks before the signal comes out of the antenna i.e. "antenna delay")
uint16_t rftxDly; // rf delay (delay though the RF blocks before the signal comes out of the antenna i.e. "antenna delay")
uint32_t antennaDly; // antenna delay read from OTP 64 PRF value is in high 16 bits and 16M PRF in low 16 bits
uint8_t xtrim; // xtrim value read from OTP
uint8_t dblbuffon; // double rx buffer mode flag
uint32_t sysCFGreg; // local copy of system config register
uint32_t txPowCfg[12]; // stores the Tx power configuration read from OTP (6 channels consecutively with PRF16 then 64, e.g. Ch 1 PRF16 is index 0 and 64 index 1)
BaseType_t (*sendCB)();
BaseType_t (*receiveCB)(uint32_t bufferLength, uint8_t ts_valid);
TaskHandle_t taskHandle;
int prfIndex;
uint8_t longFrames ; // flag in non-standard long frame mode
uint32_t ldoTune; //low 32 bits of LDO tune value
uint8_t chan; // added chan here - used in the reading of acc
dw1000_global_time_t last_rx_time;
typedef struct { //DECA
BaseType_t (*send_callback)();
BaseType_t (*receive_callback)();
uint16_t frame_length;
uint8_t timestamp_valid;
TaskHandle_t task_handle;
} dw1000_local_data_t;
extern dw1000_local_data_t dw1000local; // Static local device data
extern const uint8_t pll2calcfg;
// SFD Threshold
/**
* The following constants are taken from the original driver
*/
extern const uint8_t pll2calcfg;
extern const uint16_t sftsh[NUM_BR][NUM_SFD];
extern const uint16_t dtune1[NUM_PRF];
//-----------------------------------------
// map the channel number to the index in the configuration arrays below
// 0th element is chan 1, 1st is chan 2, 2nd is chan 3, 3rd is chan 4, 4th is chan 5, 5th is chan 7
extern const uint32_t digital_bb_config[NUM_PRF][NUM_PACS];
extern const uint8_t chan_idx[NUM_CH_SUPPORTED];
extern const uint32_t tx_config[NUM_CH] ;
extern const uint32_t tx_config[NUM_CH];
extern const uint8_t pll2_config[NUM_CH][5];
//bandwidth configuration
extern const uint8_t rx_config[NUM_BW];
extern const uint8_t dwnsSFDlen[NUM_BR]; //DW non-standard SFD length for 110k, 850k and 6.81M
extern const uint32_t digital_bb_config[NUM_PRF][NUM_PACS];
extern const uint16_t lde_replicaCoeff[PCODES];
#define DEBUG
void dw1000Util_enableclocks(int clocks);
/**
* This function enables the receiver
*/
void dw1000Util_enableRX();
/**
* This function reads the time stamp from is corresponding register
*/
void dw1000Util_getRxTimestamp(uint8_t *rx_time);
/**
* This function read the system time from is corresponding register
*/
void dw1000Util_getSysTime(uint8_t *nt);
/**
* The following functions were taken and adapted from the original driver
*/
void dw1000Util_enableclocks(int clocks);
uint32_t dw1000Util_otpread(uint32_t address);
void dw1000Util_forceTrxOff(void);
void dw1000Util_reset(void);
void dw1000Util_resetRxOnly(void);
void dw1000Util_getRxTimestamp(dw1000_global_time_t *timeBuffer);
void dw1000Util_printGlobalTimestamp(dw1000_global_time_t *time);
#ifdef DEBUG
void lltoa(int64_t val, char *dest_buf, uint8_t base);
void hexdump(uint8_t * buffer, uint8_t len);
#endif
......
This diff is collapsed.
......@@ -192,6 +192,7 @@ int dw1000Hal_readRegister(uint8_t regID, uint8_t *dest, uint16_t len) {
while (hspi->State != HAL_SPI_STATE_READY) {
}
xSemaphoreGive(spiSema);
} else {
ret = HAL_LOCKED;
//trace_printf("nb");
......
#include "dw1000_hal.h"
#include "deca_regs.h"
#include "dw1000_util.h"
#ifdef DEBUG
#include "Trace.h"
#endif
BaseType_t dw1000Hal_handleTx(uint64_t * event, uint64_t * event_clear) {
/**
* This function handles the end of the transmission of a frame.
* It just triggers the provided callback and re-enables the receiver.
* Return Value:
* pdTrue, if the callback or the notify has woken a task with a higher priority.
* This information is used to invoke a reschedule, when the ISR is done, if necessary.
*/
BaseType_t _handleTx(uint64_t * event, uint64_t * event_clear) {
// Ignore unused parameters, may be needed for later purposes
(void) event;
(void) event_clear;
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
BaseType_t higher_priority_task_woken = pdFALSE;
dw1000Util_enableRX();
if (dw1000local.sendCB != NULL) {
xHigherPriorityTaskWoken |= dw1000local.sendCB();
if (dw1000local.send_callback != NULL) {
higher_priority_task_woken |= dw1000local.send_callback();
}
return xHigherPriorityTaskWoken;
return higher_priority_task_woken;
}
BaseType_t dw1000Hal_handleRx(uint64_t * event, uint64_t * event_clear) {
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
/**
* This function handles the reception of a frame.
* It either triggers the provided callback, or notifies a task if provided.
* Return Value:
* pdTrue, if the callback or the notify has woken a task with a higher priority.
* This information is used to invoke a reschedule, when the ISR is done, if necessary.
*/
BaseType_t _handleRx(uint64_t * event, uint64_t * event_clear) {
BaseType_t higher_priority_task_woken = pdFALSE;
//Fixme: Wann kann ein Overrun auftreten?
//Get get length
// Get get length
uint32_t rx_frame_info;
dw1000Hal_readRegisterFromIsr(RX_FINFO_ID, (uint8_t *) &rx_frame_info,
RX_FINFO_LEN);
uint32_t rx_buffer_len;
rx_buffer_len = rx_frame_info & RX_FINFO_RXFLEN_MASK; // No shifting required
// Check if the time stamp is valid, i.e. lde_done bit is set
uint8_t lde_done = (*event & SYS_STATUS_LDEDONE) ? 1 : 0;
//Trigger Callback
if (dw1000local.receiveCB != NULL) {
xHigherPriorityTaskWoken = dw1000local.receiveCB(rx_buffer_len,
lde_done);
} else if (dw1000local.taskHandle != NULL) {
//TODO Notify taskHandle
// Store validity of the time stamp and the buffer length locally,
// so it can be used by the dw1000_receiveFrameFromISR function.
dw1000local.timestamp_valid = lde_done;
dw1000local.frame_length = rx_buffer_len;
// Trigger callback or notify task
if (dw1000local.receive_callback != NULL) {
higher_priority_task_woken = dw1000local.receive_callback();
}
if (dw1000local.task_handle != NULL) {
vTaskNotifyGiveFromISR(dw1000local.task_handle, &higher_priority_task_woken);
}
#ifdef DOUBLE_BUFFER
if((*event & SYS_STATUS_HSRBP) != (*event & SYS_STATUS_ICRBP)){
*event_clear |= *event & CLEAR_DBLBUFF_EVENTS ;
// Set clear bits for double buffer
if((*event & SYS_STATUS_HSRBP) != (*event & SYS_STATUS_ICRBP)) {
*event_clear |= *event & CLEAR_DBLBUFF_EVENTS;
}
#endif
......@@ -47,25 +72,31 @@ BaseType_t dw1000Hal_handleRx(uint64_t * event, uint64_t * event_clear) {
*event_clear |= CLEAR_ALLRXGOOD_EVENTS;
*event_clear |= CLEAR_ALLRXERROR_EVENTS;
// Re-enable the receiver
dw1000Util_enableRX();
return xHigherPriorityTaskWoken;
return higher_priority_task_woken;
}
/**
* See header file dw1000_isr.h
*/
void dw1000Isr_handleInterrupt(void) {
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
BaseType_t higher_priority_task_woken = pdFALSE;
uint64_t event = 0;
uint64_t event_clear = 0;
dw1000Hal_readRegisterFromIsr(SYS_STATUS_ID, (uint8_t*) &event,
SYS_STATUS_LEN);
// Handle weird somehow random occuring losing lock events
// Handle weird somehow random occurring losing lock events
if (event & SYS_STATUS_CLKPLL_LL) { // Clock PLL Losing Lock
event_clear |= SYS_STATUS_CLKPLL_LL;
if (event & SYS_STATUS_CPLOCK) {
event_clear |= SYS_STATUS_CPLOCK;
#ifdef DEBUG
trace_printf("dw1000Hal_extiCallback:Clock PLL Losing Lock\n");
#endif
event &= ~(SYS_STATUS_CPLOCK);
}
event &= ~(SYS_STATUS_CLKPLL_LL);
......@@ -73,30 +104,35 @@ void dw1000Isr_handleInterrupt(void) {
if (event & SYS_STATUS_TXFRS) {
// Frame sent
dw1000Hal_handleTx(&event, &event_clear);
} else if ((event
& ( SYS_STATUS_RXFCG | SYS_STATUS_RXPHD | SYS_STATUS_RXSFDD))
!= (SYS_STATUS_RXFCG | SYS_STATUS_RXPHD | SYS_STATUS_RXSFDD)) {
#ifdef DOUBLE_BUFFER
dw1000Hal_handleRx(&event, &event_clear);
#else
//Error Case
trace_printf("Error!\n");
hexdump(&event, 5);
_handleTx(&event, &event_clear);
#ifndef DOUBLE_BUFFER
}else if ((event
& ( SYS_STATUS_LDEDONE | SYS_STATUS_RXPHD | SYS_STATUS_RXSFDD))
!= (SYS_STATUS_LDEDONE | SYS_STATUS_RXPHD | SYS_STATUS_RXSFDD)) {
// LDE done flag gets latched on a bad frame
trace_printf("Special Error!\n");
hexdump((uint8_t*) &event, 5);
event_clear |= CLEAR_ALLRXERROR_EVENTS;
event_clear |= CLEAR_ALLRXGOOD_EVENTS;
dw1000Util_enableRX();
#endif
} else {
dw1000Hal_handleRx(&event, &event_clear);
} else if(event & (SYS_STATUS_LDEDONE | SYS_STATUS_RXFCG)){
_handleRx(&event, &event_clear);
}else{
// Error Case
trace_printf("Error!\n");
hexdump((uint8_t*) &event, 5);
event_clear |= CLEAR_ALLRXERROR_EVENTS;
event_clear |= CLEAR_ALLRXGOOD_EVENTS;
dw1000Util_enableRX();
}
//Clear the status register
// Clear the status register
dw1000Hal_writeRegisterFromIsr(SYS_STATUS_ID, (uint8_t*) &event_clear,
SYS_STATUS_LEN);
//Schedule higher priority task ASAP
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
// Schedule higher priority task ASAP
portYIELD_FROM_ISR(higher_priority_task_woken);
}
......@@ -3,10 +3,13 @@
#include "dw1000_util.h"
#include <stdio.h>
#include "Trace.h"
extern volatile uint32_t global_time;
#include "string.h"
dw1000_local_data_t dw1000local; // Static local device data
/**
* The following constants are taken from the original driver.
*/
//-----------------------------------------
// map the channel number to the index in the configuration arrays below
// 0th element is chan 1, 1st is chan 2, 2nd is chan 3, 3rd is chan 4, 4th is chan 5, 5th is chan 7
......@@ -49,13 +52,6 @@ const uint8_t rx_config[NUM_BW] =
0xBC //WBW
};
//FIXME
//const agc_cfg_struct agc_config =
//{
// AGC_TUNE2_VAL,
//
// { AGC_TUNE1_16M , AGC_TUNE1_64M } //adc target
//}
const uint8_t dwnsSFDlen[NUM_BR] = { 0x40, 0x10, 0x08 }; //DW non-standard SFD length for 110k, 850k and 6.81M
// SFD Threshold
......@@ -163,8 +159,54 @@ const uint16_t lde_replicaCoeff[PCODES] = {
// 24
(int)(0.22 * 65536)
};
void dw1000Util_enableclocks(int clocks)
{
/**
* See header file dw1000_util.h
*/
void dw1000Util_enableRX(){
#ifdef DOUBLE_BUFFER
//Align HSRBP and ICRBP if needed (see page 37 in the Usermanual)
uint64_t event = 0;
dw1000Hal_readRegisterFromIsr(SYS_STATUS_ID, (uint8_t*) &event,
SYS_STATUS_LEN);
if((event & SYS_STATUS_HSRBP) != (event & SYS_STATUS_ICRBP)){
uint32_t reg;
dw1000Hal_readRegisterFromIsr(SYS_CTRL_ID, (uint8_t *)&reg, SYS_CTRL_LEN);
reg |= SYS_CTRL_HSRBTOGGLE;
dw1000Hal_writeRegisterFromIsr(SYS_CTRL_ID, (uint8_t *)&reg, SYS_CTRL_LEN);
}
#endif
uint32_t sys_ctrl = 0;
dw1000Hal_readRegisterFromIsr(SYS_CTRL_ID, (uint8_t*) &sys_ctrl,
SYS_CTRL_LEN); // switch to rx mode
sys_ctrl |= SYS_CTRL_RXENAB;
dw1000Hal_writeRegisterFromIsr(SYS_CTRL_ID, (uint8_t*) &sys_ctrl,
SYS_CTRL_LEN);
}
/**
* See header file dw1000_util.h
*/
void dw1000Util_getRxTimestamp(uint8_t *radio_rx_time){
// Read rx timestamp from radio
dw1000Hal_readSubRegisterFromIsr(RX_TIME_ID, RX_TIME_RX_STAMP_OFFSET, radio_rx_time, RX_TIME_RX_STAMP_LEN);
}
/**
* See header file dw1000_util.h
*/
void dw1000Util_getSysTime(uint8_t *nt) {
uint8_t rev_buf[SYS_TIME_LEN];
dw1000Hal_readRegister(SYS_TIME_ID, rev_buf, SYS_TIME_LEN);
for(uint8_t i = 0; i < SYS_TIME_LEN; i++) {
nt[i] = rev_buf[i];
//nt[i] = rev_buf[(SYS_TIME_LEN -1) - i];
}
}
/**
* The following functions were taken and adapted from the original driver
*/
void dw1000Util_enableclocks(int clocks){
uint8_t reg[2];
dw1000Hal_readSubRegister(PMSC_ID,PMSC_CTRL0_OFFSET, reg, 2);
switch(clocks)
......@@ -224,42 +266,16 @@ void dw1000Util_enableclocks(int clocks)
dw1000Hal_writeSubRegister(PMSC_ID, PMSC_CTRL0_OFFSET + 1, &reg[0], 1);
}
void dw1000Util_enableRX(){
#ifdef DOUBLE_BUFFER
//Align HSRBP and ICRBP if needed (see page 37 in the Usermanual)
uint64_t event = 0;
dw1000Hal_readRegisterFromIsr(SYS_STATUS_ID, (uint8_t*) &event,
SYS_STATUS_LEN);
if((event & SYS_STATUS_HSRBP) != (event & SYS_STATUS_ICRBP)){
uint32_t reg;
dw1000Hal_readRegisterFromIsr(SYS_CTRL_ID, (uint8_t *)&reg, SYS_CTRL_LEN);
reg |= SYS_CTRL_HSRBTOGGLE;
dw1000Hal_writeRegisterFromIsr(SYS_CTRL_ID, (uint8_t *)&reg, SYS_CTRL_LEN);
}
#endif
uint32_t sys_ctrl = 0;
dw1000Hal_readRegisterFromIsr(SYS_CTRL_ID, (uint8_t*) &sys_ctrl,
SYS_CTRL_LEN); // switch to rx mode
sys_ctrl |= SYS_CTRL_RXENAB;
dw1000Hal_writeRegisterFromIsr(SYS_CTRL_ID, (uint8_t*) &sys_ctrl,
SYS_CTRL_LEN);
}
uint32_t dw1000Util_otpread(uint32_t address)
{
uint8_t buf[4];
uint32_t ret_data;
//TODO Wieso buf? Und nicht gleich von address?
buf[1] = (address>>8) & 0xff;
buf[0] = address & 0xff;
// Write the address
dw1000Hal_writeSubRegister(OTP_IF_ID, OTP_ADDR, buf, OTP_ADDR_LEN);
// Assert OTP Read (self clearing)
buf[0] = 0x03; // 0x03 for manual drive of OTP_READ and OTP_READ
dw1000Hal_writeSubRegister(OTP_IF_ID, OTP_CTRL, buf, 1);
......@@ -273,96 +289,23 @@ uint32_t dw1000Util_otpread(uint32_t address)
return (ret_data);
}
void dw1000Util_getRxTimestamp(dw1000_global_time_t *time_buffer){
uint8_t buf[5] = {0};
uint64_t radio_rx_time = 0;
// Read rx timestamp from radio
dw1000Hal_readSubRegisterFromIsr(RX_TIME_ID, RX_TIME_RX_STAMP_OFFSET, buf, RX_TIME_RX_STAMP_LEN);
radio_rx_time = ((uint64_t) buf[4]) << 32 |
((uint64_t) buf[3]) << 24 |
((uint64_t) buf[2]) << 16 |
((uint64_t) buf[1]) << 8 |
((uint64_t) buf[0]) << 0;
// multiply by 16 to get picoseconds (actually ~15.65 is right)
radio_rx_time <<= 4;
// Calculate timestamp in milliseconds and sub-milliseconds parts separately
uint64_t ms_buf = global_time * GLOBAL_TIME_TICK_MS + radio_rx_time / 1000000000llu;
uint64_t subms_buf = radio_rx_time - (global_time * 1000000000llu);
if(ms_buf < dw1000local.last_rx_time.ms) {
// The radio timer had an overflow, but the global timer didn't, yet
ms_buf += GLOBAL_TIME_TICK_MS;
}
// Write calculated timestamp to provided structure
time_buffer->ms = ms_buf;
time_buffer->subms = subms_buf;
// Store new timestamp to be able to detect asynchronous overflows
dw1000local.last_rx_time.ms = ms_buf;
}
void lltoa(uint64_t val, char *dest_buf, uint8_t base) {
char buf[64] = {0};
uint32_t i = 62;
for(; val && i ; --i, val /= base) {
buf[i] = "0123456789abcdef"[val % base];
}
memcpy(dest_buf, &buf[i + 1], 64);
}
void dw1000Util_printGlobalTimestamp(dw1000_global_time_t *time) {
char ms_buf[64] = {0};
char subms_buf[64] = {0};
// Convert uint64_t timestamp to strings, because printf can't handle 64-bit integers
lltoa(time->ms, ms_buf, 10);
lltoa(time->subms, subms_buf, 10);
printf("RX time = %s.%sms\n", ms_buf, subms_buf);
}
void dw1000Util_forceTrxOff(void) {
uint32_t sys_ctrl = 0;
//DECA: decaIrqStatus_t stat ; ???
uint32_t sys_mask;
dw1000Hal_readRegisterFromIsr(SYS_MASK_ID, (uint8_t *) &sys_mask, SYS_MASK_LEN);
// need to beware of interrupts occurring in the middle of following read modify write cycle
// we can disable the radio, but before the status is cleared an interrupt can be set (e.g. the
// event has just happened before the radio was disabled)
// thus we need to disable interrupt during this operation
/// stat = decamutexon() ; DECA: ???:" -->
portDISABLE_INTERRUPTS(); //FIXME Eigentlich eher EXTI
portDISABLE_INTERRUPTS();
uint32_t tmp_mask = 0;
// No interrupts
dw1000Hal_writeRegisterFromIsr(SYS_MASK_ID, (uint8_t *) &tmp_mask, SYS_MASK_LEN);
//Disable radio
// Disable radio
dw1000Hal_readRegisterFromIsr(SYS_CTRL_ID, (uint8_t *) &sys_ctrl, 4);
sys_ctrl |= SYS_CTRL_TRXOFF;// Immediately cancel all RX and TX operations, bring radio to IDLE state
// Immediately cancel all RX and TX operations, bring radio to IDLE state
sys_ctrl |= SYS_CTRL_TRXOFF;
dw1000Hal_writeRegisterFromIsr(SYS_CTRL_ID, (uint8_t *) &sys_ctrl, 4);
uint32_t tmp = (CLEAR_ALLTX_EVENTS | CLEAR_ALLRXERROR_EVENTS | CLEAR_ALLRXGOOD_EVENTS);
dw1000Hal_writeRegisterFromIsr(SYS_STATUS_ID,(uint8_t *) &tmp, 4) ;
//TODO dwt_syncrxbufptrs();
dw1000Hal_writeRegisterFromIsr(SYS_MASK_ID, (uint8_t *) &sys_mask, SYS_MASK_LEN);
portENABLE_INTERRUPTS();
}
void dw1000Util_reset(void) {
......@@ -396,16 +339,12 @@ void dw1000Util_resetRxOnly(void) {
subreg |= (0xe << 28);
dw1000Hal_writeSubRegisterFromIsr(PMSC_ID, PMSC_CTRL0_OFFSET,
(uint8_t*) &subreg, PMSC_CTRL0_LEN);
// dw1000Hal_readSubRegisterFromIsr(PMSC_ID, PMSC_CTRL0_OFFSET,
// (uint8_t*) &subreg, PMSC_CTRL0_LEN);
subreg |= (0xf << 28);
dw1000Hal_writeSubRegisterFromIsr(PMSC_ID, PMSC_CTRL0_OFFSET,
(uint8_t*) &subreg, PMSC_CTRL0_LEN);
}
#ifdef DEBUG
void hexdump(uint8_t * buffer, uint8_t len){
char string [2*len +1];
char * string_ptr = string;
......@@ -416,6 +355,28 @@ void hexdump(uint8_t * buffer, uint8_t len){
string[2*len] = '\0';
trace_printf("Ev: %s\n", string);
}
void lltoa(int64_t val, char *dest_buf, uint8_t base) {
uint8_t sign = 0;
char buf[64] = {0};
uint32_t i = 0;
if(val == 0) {
dest_buf[0] = '0';
dest_buf[1] = '\0';
return;
}
else if(val < 0) {
sign = 1;
val = -val;
}
for(i = 62; val && i ; --i, val /= base) {
buf[i] = "0123456789abcdef"[val % base];
}
if(sign) {
buf[i--] = '-';
}
memcpy(dest_buf, &buf[i + 1], 64);
}
#endif