Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 4 additions & 2 deletions DW1000_library_pizzo00/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,18 +14,20 @@ Project state

**Development:**

Currently (2024) **under development**.
Currently (2026) **under development**.

**Improvements:**

- Added informations about the known anchors on blink message so only the unkown will respond
- After a poll an anchor that is not on the poll can respond with a ranging_init on some free time slots (to avoid waiting until a blink)
- I have increased (by reducing the transmitted data) the maximum number of anchor per tag to 6, the tag can still "know" more than 6 anchor and query only the 6 with the best signal
- I have increased (by reducing the transmitted data) the maximum number of anchor per tag to 6
- The system is working with multiple tags, the limit is the occupation of the channel so the number of tags supported depends on the update frequency
- Tag would not wait for the last poll ack to arrive before sending the range anymore (so if the last anchor is offline you had to wait for it to be remove for inactivity). Now it wait for the last one or use a timeout, so the range is always sent.
- Range report to the tag can be opt-out using a flag
- Removed long address
- Add a minimal log library instead of Serial.print
- Send frames of correct length (Thanks to danielkucera)
- Randomly select anchors for poll (if more anchors in sight than needed)

**TODOs:**
* Create a attachCustomPackageHandler for maintenance operation throught uwb (like changing the esp ip remotely)
Expand Down
153 changes: 82 additions & 71 deletions DW1000_library_pizzo00/src/DW1000.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,25 +166,35 @@ void DW1000Class::reselect(uint8_t ss)
digitalWrite(_ss, HIGH);
}

TaskHandle_t DW1000Class::xHandleUwbInterrupt;
SemaphoreHandle_t DW1000Class::interruptSemaphore = NULL;

void DW1000Class::begin(uint8_t irq, uint8_t rst)
{
// generous initial init/wake-up-idle delay
delay(5);
// Configure the IRQ pin as INPUT. Required for correct interrupt setting for ESP8266
// Generous initial init/wake-up-idle delay
vTaskDelay(pdMS_TO_TICKS(5));

// Configure the IRQ pin as INPUT
pinMode(irq, INPUT);
// start SPI

// Start SPI
SPI.begin();
// #ifndef ESP8266
// SPI.usingInterrupt(digitalPinToInterrupt(irq)); // not every board support this, e.g. ESP8266
// #endif
// pin and basic member setup

// Pin and basic member setup
_rst = rst;
_irq = irq;
_deviceMode = IDLE_MODE;
// attach interrupt
// attachInterrupt(_irq, DW1000Class::handleInterrupt, CHANGE); // todo interrupt for ESP8266
// TODO throw error if pin is not a interrupt pin
attachInterrupt(digitalPinToInterrupt(_irq), DW1000Class::handleInterrupt, RISING); // todo interrupt for ESP8266

// Attach interrupt for ESP32
interruptSemaphore = xSemaphoreCreateCounting(100, 0);
attachInterrupt(digitalPinToInterrupt(_irq), DW1000Class::handleInterrupt, RISING);
vTaskDelay(pdMS_TO_TICKS(5));
if (xHandleUwbInterrupt != NULL)
{
vTaskDelete(xHandleUwbInterrupt);
xHandleUwbInterrupt = NULL;
}
xTaskCreate(&processInterrupt, "UWB-Interrupt", 4 * 1024, NULL, 2, &xHandleUwbInterrupt);
}

void DW1000Class::manageLDE()
Expand Down Expand Up @@ -971,57 +981,69 @@ void DW1000Class::tune()
/* ###########################################################################
* #### Interrupt handling ###################################################
* ######################################################################### */
void IRAM_ATTR DW1000Class::handleInterrupt() {
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
xSemaphoreGiveFromISR(interruptSemaphore, &xHigherPriorityTaskWoken);
if (xHigherPriorityTaskWoken == pdTRUE)
portYIELD_FROM_ISR();
}

void DW1000Class::handleInterrupt()
void DW1000Class::processInterrupt(void *pvParameter)
{
// read current status and handle via callbacks
readSystemEventStatusRegister();
if (isClockProblem() /* TODO and others */ && _handleError != 0)
{
(*_handleError)();
}
if (isTransmitDone() && _handleSent != 0)
for(;;)
{
(*_handleSent)();
clearTransmitStatus();
}
if (isReceiveTimestampAvailable() && _handleReceiveTimestampAvailable != 0)
{
(*_handleReceiveTimestampAvailable)();
clearReceiveTimestampAvailableStatus();
}
if (isReceiveFailed() && _handleReceiveFailed != 0)
{
(*_handleReceiveFailed)();
clearReceiveStatus();
if (_permanentReceive)
xSemaphoreTake(interruptSemaphore, portMAX_DELAY);

// read current status and handle via callbacks
readSystemEventStatusRegister();
if (isClockProblem() /* TODO and others */ && _handleError != 0)
{
newReceive();
startReceive();
(*_handleError)();
}
}
else if (isReceiveTimeout() && _handleReceiveTimeout != 0)
{
(*_handleReceiveTimeout)();
clearReceiveStatus();
if (_permanentReceive)
if (isTransmitDone() && _handleSent != 0)
{
newReceive();
startReceive();
(*_handleSent)();
clearTransmitStatus();
}
}
else if (isReceiveDone() && _handleReceived != 0)
{
(*_handleReceived)();
clearReceiveStatus();
if (_permanentReceive)
if (isReceiveTimestampAvailable() && _handleReceiveTimestampAvailable != 0)
{
(*_handleReceiveTimestampAvailable)();
clearReceiveTimestampAvailableStatus();
}
if (isReceiveFailed() && _handleReceiveFailed != 0)
{
(*_handleReceiveFailed)();
clearReceiveStatus();
if (_permanentReceive)
{
newReceive();
startReceive();
}
}
else if (isReceiveTimeout() && _handleReceiveTimeout != 0)
{
newReceive();
startReceive();
(*_handleReceiveTimeout)();
clearReceiveStatus();
if (_permanentReceive)
{
newReceive();
startReceive();
}
}
else if (isReceiveDone() && _handleReceived != 0)
{
(*_handleReceived)();
clearReceiveStatus();
if (_permanentReceive)
{
newReceive();
startReceive();
}
}
// clear all status that is left unhandled
clearAllStatus();
}
// clear all status that is left unhandled
clearAllStatus();
vTaskDelete(NULL);
}

/* ###########################################################################
Expand Down Expand Up @@ -1783,25 +1805,14 @@ void DW1000Class::getData(byte data[], uint16_t n)
readBytes(RX_BUFFER, NO_SUB, data, n);
}

void DW1000Class::getData(String &data)
bool DW1000Class::getData(byte data[], uint16_t maxLength, uint16_t &dataLength)
{
uint16_t i;
uint16_t n = getDataLength(); // number of bytes w/o the two FCS ones
if (n <= 0)
{ // TODO
return;
}
byte *dataBytes = (byte *)malloc(n);
getData(dataBytes, n);
// clear string
data.remove(0);
data = "";
// append to string
for (i = 0; i < n; i++)
{
data += (char)dataBytes[i];
}
free(dataBytes);
dataLength = getDataLength(); // number of bytes w/o the two FCS ones
if (dataLength <= 0 || maxLength < dataLength)
return false;

getData(data, dataLength);
return true;
}

void DW1000Class::getTransmitTimestamp(DW1000Time &time)
Expand Down
8 changes: 6 additions & 2 deletions DW1000_library_pizzo00/src/DW1000.h
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,7 @@ class DW1000Class {
static void setData(byte data[], uint16_t n);
static void setData(const String& data);
static void getData(byte data[], uint16_t n);
static void getData(String& data);
static bool getData(byte data[], uint16_t maxLength, uint16_t& dataLength);
static uint16_t getDataLength();
static void getTransmitTimestamp(DW1000Time& time);
static void getReceiveTimestamp(DW1000Time& time);
Expand Down Expand Up @@ -472,7 +472,11 @@ class DW1000Class {
static boolean _debounceClockEnabled;

/* Arduino interrupt handler */
static void handleInterrupt();
static TaskHandle_t xHandleUwbInterrupt;
static SemaphoreHandle_t interruptSemaphore;
static void processInterrupt(void *pvParameter);

static IRAM_ATTR void handleInterrupt();

/* Allow MAC frame filtering . */
// TODO auto-acknowledge
Expand Down
2 changes: 1 addition & 1 deletion DW1000_library_pizzo00/src/DW1000Device.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class DW1000Device
DW1000Time timeRangeSent;
DW1000Time timeRangeReceived;

bool hasSentPoolAck;
bool hasSentPollAck;

DW1000Time timePollAckReceivedMinusPollSent;
DW1000Time timeRangeSentMinusPollAckReceived;
Expand Down
Loading