This is the DW1000 driver and our self developed distance measurement application based on it. We do this as a semester thesis at ETH Zürich under the Automatic Control Laboratory in the Department of electrical engineering.

Dependencies:   mbed

main.cpp

Committer:
manumaet
Date:
2015-03-10
Revision:
46:6398237672a0
Parent:
45:01a33363bc21
Child:
47:b6120c152ad1

File content as of revision 46:6398237672a0:

// by Matthias Grob & Manuel Stalder - ETH Zürich - 2015
#include "mbed.h"
#include "PC.h"                                     // Serial Port via USB for debugging with Terminal
#include "DW1000.h"                                 // our DW1000 device driver
#include "MM2WayRanging.h"                          // our self developed ranging application

#define myprintf    pc.printf                       // to make the code adaptable to other outputs that support printf

PC              pc(USBTX, USBRX, 921600);           // USB UART Terminal
DW1000          dw(PA_7, PA_6, PA_5, PB_6, PB_9);   // Device driver instanceSPI pins: (MOSI, MISO, SCLK, CS, IRQ)
MM2WayRanging   node(dw);                           // Instance of the two way ranging algorithm

void rangeAndDisplayAll(){
    node.requestRangingAll();                       // Request ranging to all anchors
    for (int i = 1; i <= 5; i++) {                  // Output Results
        myprintf("%f, ", node.distances[i]);
        //myprintf("T:%f", node.roundtriptimes[i]);
        //myprintf("\r\n");
    }
    myprintf("\r\n");
}

void calibrationRanging(int destination){

    const int numberOfRangings = 100;
    float rangings[numberOfRangings];
    int index = 0;
    float mean = 0;
    float start, stop;

    Timer localTimer;
    localTimer.start();

    start = localTimer.read();

    while (1) {

        node.requestRanging(destination);
        if(node.overflow){
            myprintf("Overflow! Measured: %f\r\n", node.distances[destination]);
        }

        if (node.distances[destination] == -1) {
            myprintf("Measurement timed out\r\n");
            wait(0.001);
            continue;
        }

        if (node.distances[destination] < 100) {
            rangings[index] = node.distances[destination];
            //myprintf("%f\r\n", node.distances[destination]);
            index++;

            if (index == numberOfRangings) {
            stop = localTimer.read();

                for (int i = 0; i < numberOfRangings - 1; i++)
                    rangings[numberOfRangings - 1] += rangings[i];

                mean = rangings[numberOfRangings - 1] / numberOfRangings;
                myprintf("\r\n\r\nMean %i: %f\r\n", destination, mean);
                myprintf("Elapsed Time for %i: %f\r\n", numberOfRangings, stop - start);

                mean = 0;
                index = 0;

                //wait(2);

                start = localTimer.read();
            }
        }

        else myprintf("%f\r\n", node.distances[destination]);

    }  
    
}    

struct __attribute__((packed, aligned(1))) DistancesFrame {
        uint8_t source;
        uint8_t destination;
        uint8_t type;
        float dist[4];
    };
    

    
void altCallbackRX();
// -----------------------------------------------------------------------------------------------

int main() {
    pc.printf("\r\nDecaWave 1.0   up and running!\r\n");            // Splashscreen
    dw.setEUI(0xFAEDCD01FAEDCD01);                                  // basic methods called to check if we have a working SPI connection
    pc.printf("DEVICE_ID register: 0x%X\r\n", dw.getDeviceID());
    pc.printf("EUI register: %016llX\r\n", dw.getEUI());
    pc.printf("Voltage: %fV\r\n", dw.getVoltage());
    
    node.isAnchor = true;
                                               // declare as anchor or beacon
    if (node.isAnchor) {
        node.address = 5;
        myprintf("This node is Anchor node %d \r\n", node.address);
    } else {
        node.address = 0;
        myprintf("This node is a Beacon. ");
    }
    
    if (node.address == 5){
            dw.setCallbacks(&altCallbackRX, NULL);   
        }
             
    while(1) {
        if (!node.isAnchor){
            rangeAndDisplayAll();
            //calibrationRanging(4);


            

        
        }else
            //myprintf(".\r");
            
            wait(0.5);
    }
}


void altCallbackRX(){

   DistancesFrame distFrame;
   float distances[4];
   dw.readRegister(DW1000_RX_BUFFER, 0, (uint8_t*)&distFrame, dw.getFramelength());
       
    if (distFrame.destination == 5){
        for (int i = 0; i<4; i++){
        distances[i] = distFrame.dist[i];  
        } 
        
        for (int i = 0; i < 4; i++) {                  // Output Results
        myprintf("%f, ", distances[i]);
        
        }
        
        myprintf("\r\n");
    }
    dw.startRX();
}