Skip to content

Commit

Permalink
device mode printing + some progress on ranging
Browse files Browse the repository at this point in the history
  • Loading branch information
thotro committed Jul 3, 2015
1 parent 7be3030 commit 649e675
Show file tree
Hide file tree
Showing 10 changed files with 151 additions and 97 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@
#define SENDER true
#define RECEIVER false
// toggle and message RX/TX
// NOTE: the other Arduino needs to be configured with RECEIVER
// NOTE: the other Arduino needs to be configured with RECEIVER
// (or SENDER respectively)
volatile boolean trxToggle = RECEIVER;
volatile boolean trxAck = false;
volatile boolean rxError = false;
Expand Down Expand Up @@ -54,6 +55,8 @@ void setup() {
Serial.print("Unique ID: "); Serial.println(msgInfo);
DW1000.getPrintableNetworkIdAndShortAddress(msgInfo);
Serial.print("Network ID & Device Address: "); Serial.println(msgInfo);
DW1000.getPrintableDeviceMode(msg);
Serial.print("Device mode: "); Serial.println(msg);
// attach callback for (successfully) sent and received messages
DW1000.attachSentHandler(handleSent);
DW1000.attachReceivedHandler(handleReceived);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@ DW1000Time timePollAckSent;
DW1000Time timePollAckReceived;
DW1000Time timeRangeSent;
DW1000Time timeRangeReceived;
// last computed range/time
DW1000Time timeComputedRange;
// data buffer
#define LEN_DATA 16
byte data[LEN_DATA];
Expand All @@ -62,13 +64,15 @@ void setup() {
DW1000.commitConfiguration();
Serial.println("Committed configuration ...");
// DEBUG chip info and registers pretty printed
char msg[1024];
char msg[256];
DW1000.getPrintableDeviceIdentifier(msg);
Serial.print("Device ID: "); Serial.println(msg);
DW1000.getPrintableExtendedUniqueIdentifier(msg);
Serial.print("Unique ID: "); Serial.println(msg);
DW1000.getPrintableNetworkIdAndShortAddress(msg);
Serial.print("Network ID & Device Address: "); Serial.println(msg);
DW1000.getPrintableDeviceMode(msg);
Serial.print("Device mode: "); Serial.println(msg);
// attach callback for (successfully) sent and received messages
DW1000.attachSentHandler(handleSent);
DW1000.attachReceivedHandler(handleReceived);
Expand All @@ -92,7 +96,6 @@ void transmitPollAck() {
data[0] = POLL_ACK;
DW1000.setData(data, LEN_DATA);
DW1000.startTransmit();
receiver();
}

void transmitRangeReport(float curRange) {
Expand All @@ -103,7 +106,6 @@ void transmitRangeReport(float curRange) {
memcpy(data+1, &curRange, 4);
DW1000.setData(data, LEN_DATA);
DW1000.startTransmit();
receiver();
}

void transmitRangeFailed() {
Expand All @@ -112,7 +114,6 @@ void transmitRangeFailed() {
data[0] = RANGE_FAILED;
DW1000.setData(data, LEN_DATA);
DW1000.startTransmit();
receiver();
}

void receiver() {
Expand All @@ -123,12 +124,16 @@ void receiver() {
DW1000.startReceive();
}

DW1000Time getRange() {
void computeRange() {
// correct timestamps (in case system time counter wrap-arounds occured)
// TODO
/*if(timePollAckReceived < timePollSent) {
timePollAckReceived += ...
}*/
// two roundtrip times - each minus message preparation times / 4
return ((timePollAckReceived-timePollSent)-(timePollAckSent-timePollReceived) +
(timeRangeReceived-timePollAckSent)-(timeRangeSent-timePollAckReceived)) / 4;
DW1000Time tof = ((timePollAckReceived-timePollSent)-(timePollAckSent-timePollReceived) +
(timeRangeReceived-timePollAckSent)-(timeRangeSent-timePollAckReceived)) * 0.25f;
timeComputedRange.setTimestamp(tof);
}

void loop() {
Expand All @@ -141,9 +146,10 @@ void loop() {
byte msgId = data[0];
if(msgId == POLL_ACK) {
DW1000.getTransmitTimestamp(timePollAckSent);
Serial.print("Sent POLL ACK @ "); Serial.println(timePollAckSent.getAsFloat());
//Serial.print("Sent POLL ACK @ "); Serial.println(timePollAckSent.getAsFloat());
}
} else if(receivedAck) {
}
if(receivedAck) {
receivedAck = false;
// get message and parse
DW1000.getData(data, LEN_DATA);
Expand All @@ -157,23 +163,24 @@ void loop() {
protocolFailed = false;
DW1000.getReceiveTimestamp(timePollReceived);
expectedMsgId = RANGE;
Serial.print("Received POLL @ "); Serial.println(timePollReceived.getAsFloat());
transmitPollAck();
//Serial.print("Received POLL @ "); Serial.println(timePollReceived.getAsFloat());
} else if(msgId == RANGE) {
DW1000.getReceiveTimestamp(timeRangeReceived);
expectedMsgId = POLL;
if(!protocolFailed) {
timePollSent.setTimestamp(data+1);
timePollAckReceived.setTimestamp(data+6);
timeRangeSent.setTimestamp(data+11);
Serial.print("Received RANGE @ "); Serial.println(timeRangeReceived.getAsFloat());
// (re-)compute range as two-way ranging is done
computeRange();
transmitRangeReport(timeComputedRange.getAsFloat());
/*Serial.print("Received RANGE @ "); Serial.println(timeRangeReceived.getAsFloat());
Serial.print("POLL sent @ "); Serial.println(timePollSent.getAsFloat());
Serial.print("POLL ACK received @ "); Serial.println(timePollAckReceived.getAsFloat());
Serial.print("RANGE sent @ "); Serial.println(timeRangeSent.getAsFloat());
DW1000Time curRange = getRange();
Serial.print("Range time is "); Serial.println(curRange.getAsFloat(), 4);
Serial.print("Range is "); Serial.println(curRange.getAsMeters());
transmitRangeReport(curRange.getAsFloat());
Serial.print("Range time is "); Serial.println(timeComputedRange.getAsFloat(), 4);*/
Serial.print("Range is [m] "); Serial.println(timeComputedRange.getAsMeters());
} else {
transmitRangeFailed();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,13 +58,15 @@ void setup() {
DW1000.commitConfiguration();
Serial.println("Committed configuration ...");
// DEBUG chip info and registers pretty printed
char msg[1024];
char msg[256];
DW1000.getPrintableDeviceIdentifier(msg);
Serial.print("Device ID: "); Serial.println(msg);
DW1000.getPrintableExtendedUniqueIdentifier(msg);
Serial.print("Unique ID: "); Serial.println(msg);
DW1000.getPrintableNetworkIdAndShortAddress(msg);
Serial.print("Network ID & Device Address: "); Serial.println(msg);
DW1000.getPrintableDeviceMode(msg);
Serial.print("Device mode: "); Serial.println(msg);
// attach callback for (successfully) sent and received messages
DW1000.attachSentHandler(handleSent);
DW1000.attachReceivedHandler(handleReceived);
Expand Down Expand Up @@ -103,7 +105,7 @@ void transmitRange() {
timeRangeSent.getTimestamp(data+11);
DW1000.setData(data, LEN_DATA);
DW1000.startTransmit();
Serial.print("Expect RANGE to be sent @ "); Serial.println(timeRangeSent.getAsFloat());
//Serial.print("Expect RANGE to be sent @ "); Serial.println(timeRangeSent.getAsFloat());
}

void receiver() {
Expand All @@ -124,40 +126,41 @@ void loop() {
byte msgId = data[0];
if(msgId == POLL) {
DW1000.getTransmitTimestamp(timePollSent);
Serial.print("Sent POLL @ "); Serial.println(timePollSent.getAsFloat());
//Serial.print("Sent POLL @ "); Serial.println(timePollSent.getAsFloat());
} else if(msgId == RANGE) {
DW1000.getTransmitTimestamp(timeRangeSent);
Serial.print("Sent RANGE @ "); Serial.println(timeRangeSent.getAsFloat());
//Serial.print("Sent RANGE @ "); Serial.println(timeRangeSent.getAsFloat());
}
} else if(receivedAck) {
}
if(receivedAck) {
receivedAck = false;
// get message and parse
DW1000.getData(data, LEN_DATA);
byte msgId = data[0];
if(msgId != expectedMsgId) {
// unexpected message, start over again
Serial.print("Received wrong message # "); Serial.println(msgId);
delay(2000);
delay(100);
expectedMsgId = POLL_ACK;
transmitPoll();
return;
}
if(msgId == POLL_ACK) {
DW1000.getReceiveTimestamp(timePollAckReceived);
expectedMsgId = RANGE_REPORT;
Serial.print("Received POLL ACK @ "); Serial.println(timePollAckReceived.getAsFloat());
transmitRange();
//Serial.print("Received POLL ACK @ "); Serial.println(timePollAckReceived.getAsFloat());
} else if(msgId == RANGE_REPORT) {
expectedMsgId = POLL_ACK;
float curRange;
memcpy(&curRange, data+1, 4);
Serial.print("Received RANGE REPORT = "); Serial.println(curRange);
delay(2000);
//Serial.print("Received RANGE REPORT = "); Serial.println(curRange);
delay(100);
transmitPoll();
} else if(msgId == RANGE_FAILED) {
expectedMsgId = POLL_ACK;
Serial.println("Received RANGE FAILED");
delay(2000);
delay(100);
transmitPoll();
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@ void setup() {
Serial.print("Unique ID: "); Serial.println(msg);
DW1000.getPrintableNetworkIdAndShortAddress(msg);
Serial.print("Network ID & Device Address: "); Serial.println(msg);
DW1000.getPrintableDeviceMode(msg);
Serial.print("Device mode: "); Serial.println(msg);
// attach callback for (successfully) received messages
DW1000.attachReceivedHandler(handleReceived);
DW1000.attachReceiveErrorHandler(handleReceiveError);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ void setup() {
Serial.print("Unique ID: "); Serial.println(msg);
DW1000.getPrintableNetworkIdAndShortAddress(msg);
Serial.print("Network ID & Device Address: "); Serial.println(msg);
DW1000.getPrintableDeviceMode(msg);
Serial.print("Device mode: "); Serial.println(msg);
// attach callback for (successfully) sent messages
DW1000.attachSentHandler(handleSent);
// start a transmission
Expand All @@ -65,7 +67,6 @@ void transmitter() {
String msg = "Hello DW1000, it's #"; msg += sentNum;
DW1000.setData(msg);
// delay sending the message for the given amount
//DW1000Time deltaTime = DW1000Time(500, DW1000Time::MILLISECONDS);
DW1000Time deltaTime = DW1000Time(10, DW1000Time::MILLISECONDS);
DW1000.setDelay(deltaTime);
DW1000.startTransmit();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ void loop() {
// variables for the test
DW1000Time time;
DW1000Time time2;
DW1000Time time3;
byte stamp[LEN_STAMP];
// unit test
Serial.print("Time is [us] ... "); Serial.println(time.getAsFloat(), 4);
Expand All @@ -40,6 +41,10 @@ void loop() {
time2 = DW1000Time(stamp);
Serial.print("Time2 is [us] ... "); Serial.println(time2.getAsFloat(), 4);
Serial.print("Time2 range is [m] ... "); Serial.println(time2.getAsMeters(), 4);
time3 = DW1000Time(10, DW1000Time::SECONDS);
time3.getTimestamp(stamp);
time3.setTimestamp(stamp);
Serial.print("Time3 is [s] ... "); Serial.println(time3.getAsFloat() * 1.0e-6, 4);
// keep calm
delay(1000);
}
Expand Down
Loading

0 comments on commit 649e675

Please sign in to comment.