Tobi's ubw test branch

Dependencies:   mavlink_bridge mbed

Fork of AIT_UWB_Range by Benjamin Hepp

Committer:
naegelit
Date:
Mon Jan 04 12:45:37 2016 +0000
Revision:
53:79a72d752ec4
Parent:
52:94688f414dcd
Child:
54:a59803fcce58
i hope not commiting into bennis branch ;-)

Who changed what in which revision?

UserRevisionLine numberNew contents of line
manumaet 24:6f25ba679490 1 // by Matthias Grob & Manuel Stalder - ETH Zürich - 2015
manumaet 0:f50e671ffff7 2 #include "mbed.h"
manumaet 26:a65c6f26c458 3 #include "PC.h" // Serial Port via USB for debugging with Terminal
manumaet 27:71178fdb78e1 4 #include "DW1000.h" // our DW1000 device driver
manumaet 44:2e0045042a59 5 #include "MM2WayRanging.h" // our self developed ranging application
bhepp 48:5999e510f154 6 #include "InterruptMultiplexer.h"
manumaet 44:2e0045042a59 7
bhepp 48:5999e510f154 8 #include "mavlink_bridge/mavlink_bridge.h"
bhepp 48:5999e510f154 9
bhepp 48:5999e510f154 10 #define ANCHOR false
bhepp 48:5999e510f154 11
bhepp 48:5999e510f154 12 using namespace ait;
manumaet 44:2e0045042a59 13
bhepp 50:50b8aea54a51 14 const int SPI_FREQUENCY = 1000000;
bhepp 52:94688f414dcd 15 const int NUM_OF_ANCHORS = 1;
bhepp 52:94688f414dcd 16 const int ANCHOR_ADDRESS_OFFSET = 10;
naegelit 53:79a72d752ec4 17 const bool USE_NLOS_SETTINGS = false;
bhepp 48:5999e510f154 18 const PinName DW_RESET_PIN = D15;
bhepp 48:5999e510f154 19 const PinName DW_IRQ_PIN = D14;
bhepp 48:5999e510f154 20 const PinName DW_MOSI_PIN = D11;
bhepp 48:5999e510f154 21 const PinName DW_MISO_PIN = D12;
bhepp 48:5999e510f154 22 const PinName DW_SCLK_PIN = D13;
bhepp 48:5999e510f154 23 #if ANCHOR
naegelit 53:79a72d752ec4 24 const bool MAVLINK_COMM = false;
naegelit 53:79a72d752ec4 25 const int NUM_OF_DW_UNITS = 1;
naegelit 53:79a72d752ec4 26 const PinName DW_CS_PINS[NUM_OF_DW_UNITS] = {D10};
bhepp 48:5999e510f154 27 #else
bhepp 52:94688f414dcd 28 // const bool MAVLINK_COMM = true;
naegelit 53:79a72d752ec4 29 const bool MAVLINK_COMM = false;
naegelit 53:79a72d752ec4 30 const int NUM_OF_DW_UNITS = 2;
naegelit 53:79a72d752ec4 31 //const PinName DW_CS_PINS[NUM_OF_DW_UNITS] = {D9, D8,D10};
naegelit 53:79a72d752ec4 32 //const PinName DW_CS_PINS[NUM_OF_DW_UNITS] = {D10,D9,D8};
naegelit 53:79a72d752ec4 33 //const PinName DW_CS_PINS[NUM_OF_DW_UNITS] = {D10,D9,D8,D7};
naegelit 53:79a72d752ec4 34 const PinName DW_CS_PINS[NUM_OF_DW_UNITS] = {D9,D10};
naegelit 53:79a72d752ec4 35 //const PinName DW_CS_PINS[NUM_OF_DW_UNITS] = {D10};
bhepp 48:5999e510f154 36 #endif
bhepp 48:5999e510f154 37
bhepp 48:5999e510f154 38 PC pc(USBTX, USBRX, 115200); // USB UART Terminal
bhepp 48:5999e510f154 39
naegelit 53:79a72d752ec4 40 void rangeAndDisplayAll(MM2WayRanging& node, MAVLinkBridge& mb, Timer& timer)
naegelit 53:79a72d752ec4 41 {
bhepp 52:94688f414dcd 42 for (int i = 0; i < NUM_OF_ANCHORS; i++) {
bhepp 52:94688f414dcd 43 uint8_t remote_address = ANCHOR_ADDRESS_OFFSET + i;
bhepp 52:94688f414dcd 44 node.requestRanging(remote_address);
bhepp 52:94688f414dcd 45
manumaet 0:f50e671ffff7 46
naegelit 53:79a72d752ec4 47 pc.printf("%d - %d> dist = %.4f\r\n", node.address, remote_address, node.distances[remote_address]);
bhepp 48:5999e510f154 48
manumaet 44:2e0045042a59 49 }
manumaet 44:2e0045042a59 50 }
naegelit 53:79a72d752ec4 51 //continue;
manumaet 45:01a33363bc21 52
manumaet 45:01a33363bc21 53
manumaet 46:6398237672a0 54 struct __attribute__((packed, aligned(1))) DistancesFrame {
bhepp 48:5999e510f154 55 uint8_t source;
bhepp 48:5999e510f154 56 uint8_t destination;
bhepp 48:5999e510f154 57 uint8_t type;
bhepp 48:5999e510f154 58 float dist[4];
bhepp 48:5999e510f154 59 };
manumaet 45:01a33363bc21 60
bhepp 48:5999e510f154 61
bhepp 48:5999e510f154 62 // -----------------------------------------------------------------------------------------------
manumaet 46:6398237672a0 63 void altCallbackRX();
manumaet 45:01a33363bc21 64
naegelit 53:79a72d752ec4 65 int main()
naegelit 53:79a72d752ec4 66 {
naegelit 53:79a72d752ec4 67 //first set the CS to high
naegelit 53:79a72d752ec4 68 DigitalOut test1(D9);
naegelit 53:79a72d752ec4 69 DigitalOut test2(D10);
naegelit 53:79a72d752ec4 70 test1=1;
naegelit 53:79a72d752ec4 71 test2=1;
naegelit 53:79a72d752ec4 72
naegelit 53:79a72d752ec4 73 wait(0.1);
bhepp 50:50b8aea54a51 74 UART_Mbed uart(USBTX, USBRX, 115200);
bhepp 50:50b8aea54a51 75 MAVLinkBridge mb(&uart);
bhepp 50:50b8aea54a51 76
bhepp 50:50b8aea54a51 77 if (!MAVLINK_COMM) {
bhepp 50:50b8aea54a51 78 pc.printf("==== AIT UWB Range ====\r\n");
bhepp 50:50b8aea54a51 79 }
bhepp 48:5999e510f154 80
bhepp 48:5999e510f154 81 SPI spi(DW_MOSI_PIN, DW_MISO_PIN, DW_SCLK_PIN);
bhepp 50:50b8aea54a51 82 spi.format(8, 0); // Setup the spi for standard 8 bit data and SPI-Mode 0 (GPIO5, GPIO6 open circuit or ground on DW1000)
bhepp 48:5999e510f154 83 // NOTE: Minimum Frequency 1MHz. Below it is now working. Could be something with the activation and deactivation of interrupts.
bhepp 50:50b8aea54a51 84 spi.frequency(SPI_FREQUENCY); // with a 1MHz clock rate (worked up to 49MHz in our Test)
bhepp 50:50b8aea54a51 85
bhepp 50:50b8aea54a51 86 // Setup interrupt pin
bhepp 50:50b8aea54a51 87 InterruptMultiplexer irq_mp(DW_IRQ_PIN);
bhepp 50:50b8aea54a51 88 irq_mp.getIRQ().rise(&irq_mp, &InterruptMultiplexer::trigger); // attach interrupt handler to rising edge of interrupt pin from DW1000
bhepp 50:50b8aea54a51 89
bhepp 50:50b8aea54a51 90 Timer timer;
bhepp 50:50b8aea54a51 91 timer.start();
bhepp 50:50b8aea54a51 92
naegelit 53:79a72d752ec4 93
bhepp 48:5999e510f154 94
naegelit 53:79a72d752ec4 95 DW1000* dw_array[NUM_OF_DW_UNITS + 0];
naegelit 53:79a72d752ec4 96 MM2WayRanging* node_array[NUM_OF_DW_UNITS + 0]; // Instance of the two way ranging algorithm
bhepp 48:5999e510f154 97
bhepp 50:50b8aea54a51 98 if (!MAVLINK_COMM) {
bhepp 50:50b8aea54a51 99 pc.printf("Performing hardware reset of UWB modules\r\n");
bhepp 50:50b8aea54a51 100 }
bhepp 48:5999e510f154 101 // == IMPORTANT == Create all DW objects first (this will cause a reset of the DW module)
bhepp 48:5999e510f154 102 DW1000::hardwareReset(DW_RESET_PIN);
naegelit 53:79a72d752ec4 103 for (int i = 0; i < 2; ++i) {
naegelit 53:79a72d752ec4 104
bhepp 48:5999e510f154 105 dw_array[i] = new DW1000(spi, irq_mp, DW_CS_PINS[i]); // Device driver instanceSPI pins: (MOSI, MISO, SCLK, CS, IRQ, RESET)
naegelit 53:79a72d752ec4 106
naegelit 53:79a72d752ec4 107 // dw_array[1] = new DW1000(spi, irq_mp, DW_CS_PINS[1]); // Device driver instanceSPI pins: (MOSI, MISO, SCLK, CS, IRQ, RESET)
bhepp 48:5999e510f154 108
bhepp 48:5999e510f154 109 DW1000& dw = *dw_array[i];
naegelit 53:79a72d752ec4 110
naegelit 53:79a72d752ec4 111 wait(0.1) ;
naegelit 53:79a72d752ec4 112
naegelit 53:79a72d752ec4 113 dw.setEUI(0xFAEDCD01FAEDCD01 + i);
naegelit 53:79a72d752ec4 114 wait(0.1) ;
naegelit 53:79a72d752ec4 115 // basic methods called to check if we have a working SPI connection
bhepp 48:5999e510f154 116 node_array[i] = new MM2WayRanging(*dw_array[i]);
bhepp 48:5999e510f154 117
naegelit 53:79a72d752ec4 118 pc.printf("\r\nUnit %d\r\n", i);
naegelit 53:79a72d752ec4 119 pc.printf("\r\nDecaWave 1.0 up and running!\r\n"); // Splashscreen
naegelit 53:79a72d752ec4 120 pc.printf("DEVICE_ID register: 0x%X\r\n", dw.getDeviceID());
naegelit 53:79a72d752ec4 121 pc.printf("EUI register: %016llX\r\n", dw.getEUI());
naegelit 53:79a72d752ec4 122 pc.printf("Voltage: %.2fV\r\n", dw.getVoltage());
naegelit 53:79a72d752ec4 123
naegelit 53:79a72d752ec4 124
bhepp 48:5999e510f154 125 MM2WayRanging& node = *node_array[i];
bhepp 48:5999e510f154 126 node.isAnchor = ANCHOR; // declare as anchor or beacon
bhepp 48:5999e510f154 127 if (ANCHOR) {
bhepp 48:5999e510f154 128 node.address = ANCHOR_ADDRESS_OFFSET + i;
bhepp 48:5999e510f154 129 if (!MAVLINK_COMM)
bhepp 48:5999e510f154 130 pc.printf("This node is Anchor node %d\r\n", node.address);
bhepp 48:5999e510f154 131 } else {
bhepp 48:5999e510f154 132 node.address = i;
bhepp 48:5999e510f154 133 if (!MAVLINK_COMM)
bhepp 50:50b8aea54a51 134 pc.printf("This node is a Beacon\r\n");
bhepp 48:5999e510f154 135 }
naegelit 53:79a72d752ec4 136
naegelit 53:79a72d752ec4 137 uint8_t remote_address = ANCHOR_ADDRESS_OFFSET + 0;
naegelit 53:79a72d752ec4 138 node.requestRanging(remote_address);
naegelit 53:79a72d752ec4 139 rangeAndDisplayAll(node, mb, timer);
naegelit 53:79a72d752ec4 140 irq_mp.clear();
naegelit 53:79a72d752ec4 141 wait(2);
manumaet 47:b6120c152ad1 142 }
bhepp 48:5999e510f154 143
naegelit 53:79a72d752ec4 144 // wait(1);
naegelit 53:79a72d752ec4 145 // MM2WayRanging& node = *node_array[1];
naegelit 53:79a72d752ec4 146 // uint8_t remote_address = ANCHOR_ADDRESS_OFFSET + 0;
naegelit 53:79a72d752ec4 147 // node.requestRanging(remote_address);
naegelit 53:79a72d752ec4 148 // rangeAndDisplayAll(node, mb, timer);
bhepp 50:50b8aea54a51 149 if (!MAVLINK_COMM)
bhepp 50:50b8aea54a51 150 pc.printf("Entering main loop\r\n");
bhepp 51:e9391d04af00 151
naegelit 53:79a72d752ec4 152 //for (int i = 0; i < 2; ++i) {
naegelit 53:79a72d752ec4 153 //
naegelit 53:79a72d752ec4 154 // if (ANCHOR) {
naegelit 53:79a72d752ec4 155 // pc.printf("."); // to see if the core and output is working
naegelit 53:79a72d752ec4 156 // wait_ms(1);
naegelit 53:79a72d752ec4 157 // } else {
naegelit 53:79a72d752ec4 158 // for (int j = 0; j < NUM_OF_DW_UNITS; ++j) {
naegelit 53:79a72d752ec4 159 // MM2WayRanging& node = *node_array[j];
naegelit 53:79a72d752ec4 160 // rangeAndDisplayAll(node, mb, timer);
naegelit 53:79a72d752ec4 161 // wait(0.1);
naegelit 53:79a72d752ec4 162 // }
naegelit 53:79a72d752ec4 163 // }
naegelit 53:79a72d752ec4 164 // }
bhepp 50:50b8aea54a51 165
manumaet 46:6398237672a0 166 }