Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: DW1000 ait_link BufferedSerial mbed
main_multi_range.cpp@12:152a51255a28, 2016-04-13 (annotated)
- Committer:
- bhepp
- Date:
- Wed Apr 13 12:23:53 2016 +0000
- Revision:
- 12:152a51255a28
- Parent:
- 10:6e95128c2efa
Removed test-code for UWBLink
Who changed what in which revision?
| User | Revision | Line number | New contents of line |
|---|---|---|---|
| bhepp | 1:c070ca30da80 | 1 | #include "settings.h" |
| bhepp | 1:c070ca30da80 | 2 | |
| bhepp | 1:c070ca30da80 | 3 | #if not BUILD_SLAVE |
| bhepp | 1:c070ca30da80 | 4 | |
| bhepp | 2:5af0f0006f40 | 5 | #include <stdarg.h> |
| bhepp | 1:c070ca30da80 | 6 | #include <mbed.h> |
| bhepp | 1:c070ca30da80 | 7 | #include <DW1000.h> |
| bhepp | 1:c070ca30da80 | 8 | #include <DW1000Utils.h> |
| bhepp | 10:6e95128c2efa | 9 | #include <ait_link/uwb_link/uwb_link_mbed.h> |
| bhepp | 1:c070ca30da80 | 10 | |
| bhepp | 10:6e95128c2efa | 11 | #include <BufferedSerial/BufferedSerial.h> |
| bhepp | 2:5af0f0006f40 | 12 | #include "UWB2WayMultiRange.h" |
| bhepp | 1:c070ca30da80 | 13 | |
| bhepp | 6:9055fcc2f0cb | 14 | enum CommMode { |
| bhepp | 6:9055fcc2f0cb | 15 | ASCII, |
| bhepp | 6:9055fcc2f0cb | 16 | UWBLINK |
| bhepp | 6:9055fcc2f0cb | 17 | }; |
| bhepp | 6:9055fcc2f0cb | 18 | |
| bhepp | 2:5af0f0006f40 | 19 | using ait::UWB2WayMultiRange; |
| bhepp | 1:c070ca30da80 | 20 | |
| bhepp | 1:c070ca30da80 | 21 | //#define MEASURE_UWB_RANGING_RATE 1 |
| bhepp | 1:c070ca30da80 | 22 | |
| bhepp | 6:9055fcc2f0cb | 23 | using ait::UWBLink; |
| bhepp | 6:9055fcc2f0cb | 24 | using ait::UWBLinkMbed; |
| bhepp | 6:9055fcc2f0cb | 25 | using ait::UWBMessageString; |
| bhepp | 6:9055fcc2f0cb | 26 | using ait::UWBMessageMultiRange; |
| bhepp | 6:9055fcc2f0cb | 27 | using ait::UWBMessage; |
| bhepp | 1:c070ca30da80 | 28 | |
| bhepp | 5:1928eb8c417a | 29 | // Overall reset rate (if no ranging is performed within the timeout) |
| bhepp | 5:1928eb8c417a | 30 | const float WATCHDOG_TIMEOUT = 1.0f; |
| bhepp | 5:1928eb8c417a | 31 | |
| bhepp | 5:1928eb8c417a | 32 | const int SPI_FREQUENCY = 5000000; |
| bhepp | 6:9055fcc2f0cb | 33 | const float MIN_DW_VOLTAGE = 2.0f; |
| bhepp | 1:c070ca30da80 | 34 | |
| bhepp | 2:5af0f0006f40 | 35 | const int TRACKER_ADDRESS = 0; |
| bhepp | 1:c070ca30da80 | 36 | const int NUM_OF_SLAVES = 1; |
| bhepp | 4:1a2c1e5e5516 | 37 | const int SLAVE_ADDRESS_OFFSET = 20; |
| bhepp | 1:c070ca30da80 | 38 | |
| bhepp | 1:c070ca30da80 | 39 | const bool USE_NLOS_SETTINGS = true; |
| bhepp | 1:c070ca30da80 | 40 | |
| bhepp | 5:1928eb8c417a | 41 | //const PinName DW_RESET_PIN = D15; |
| bhepp | 5:1928eb8c417a | 42 | const PinName DW_RESET_PIN = NC; |
| bhepp | 1:c070ca30da80 | 43 | const PinName DW_MOSI_PIN = D11; |
| bhepp | 1:c070ca30da80 | 44 | const PinName DW_MISO_PIN = D12; |
| bhepp | 1:c070ca30da80 | 45 | const PinName DW_SCLK_PIN = D13; |
| bhepp | 1:c070ca30da80 | 46 | |
| bhepp | 5:1928eb8c417a | 47 | const int NUM_OF_DW_UNITS = 4; |
| bhepp | 9:3844cf7e5c00 | 48 | // These CS pins are used on the Solo |
| bhepp | 9:3844cf7e5c00 | 49 | const PinName DW_CS_PINS[NUM_OF_DW_UNITS] = {D8, D9, D15, D14}; |
| bhepp | 9:3844cf7e5c00 | 50 | // These CS pins are used on the pyramid |
| bhepp | 5:1928eb8c417a | 51 | //const PinName DW_CS_PINS[NUM_OF_DW_UNITS] = {D7, D8, D9, D10}; |
| bhepp | 6:9055fcc2f0cb | 52 | |
| bhepp | 6:9055fcc2f0cb | 53 | const int MAX_UWB_LINK_FRAME_LENGTH = 1024; |
| bhepp | 1:c070ca30da80 | 54 | #if _DEBUG |
| bhepp | 9:3844cf7e5c00 | 55 | CommMode comm_mode = ASCII; |
| bhepp | 1:c070ca30da80 | 56 | #else |
| bhepp | 6:9055fcc2f0cb | 57 | CommMode comm_mode = UWBLINK; |
| bhepp | 1:c070ca30da80 | 58 | #endif |
| bhepp | 1:c070ca30da80 | 59 | |
| bhepp | 1:c070ca30da80 | 60 | |
| bhepp | 2:5af0f0006f40 | 61 | BufferedSerial pc(USBTX, USBRX, 115200, 8 * 1024); // USB UART Terminal |
| bhepp | 1:c070ca30da80 | 62 | |
| bhepp | 10:6e95128c2efa | 63 | void send_status_message(UWBLink& ul, char* str, ...) |
| bhepp | 1:c070ca30da80 | 64 | { |
| bhepp | 2:5af0f0006f40 | 65 | va_list args; |
| bhepp | 2:5af0f0006f40 | 66 | va_start(args, str); |
| bhepp | 10:6e95128c2efa | 67 | if (comm_mode == UWBLINK) { |
| bhepp | 6:9055fcc2f0cb | 68 | char buffer[MAX_UWB_LINK_FRAME_LENGTH]; |
| bhepp | 6:9055fcc2f0cb | 69 | int n = vsnprintf(buffer, sizeof(buffer), str, args); |
| bhepp | 6:9055fcc2f0cb | 70 | if(n > sizeof(buffer)) { |
| bhepp | 6:9055fcc2f0cb | 71 | // Dangerous: Could lead to infinite recursion |
| bhepp | 10:6e95128c2efa | 72 | send_status_message(ul, "%s %d buffer to small (buf_size: %d, required: %d)!\r\n", __FILE__, __LINE__, sizeof(buffer), n); |
| bhepp | 6:9055fcc2f0cb | 73 | } else { |
| bhepp | 6:9055fcc2f0cb | 74 | UWBMessageString msg_str(buffer); |
| bhepp | 6:9055fcc2f0cb | 75 | UWBMessage msg(UWBMessage::UWB_MESSAGE_TYPE_STATUS, &msg_str); |
| bhepp | 6:9055fcc2f0cb | 76 | if (!ul.sendMessage(msg)) { |
| bhepp | 6:9055fcc2f0cb | 77 | DEBUG_PRINTF("\r\nSending UWBLink message failed\r\n"); |
| bhepp | 6:9055fcc2f0cb | 78 | } |
| bhepp | 6:9055fcc2f0cb | 79 | } |
| bhepp | 2:5af0f0006f40 | 80 | } else { |
| bhepp | 2:5af0f0006f40 | 81 | pc.printf(str, args); |
| bhepp | 2:5af0f0006f40 | 82 | pc.printf("\r\n"); |
| bhepp | 2:5af0f0006f40 | 83 | } |
| bhepp | 2:5af0f0006f40 | 84 | va_end(args); |
| bhepp | 2:5af0f0006f40 | 85 | } |
| bhepp | 2:5af0f0006f40 | 86 | |
| bhepp | 10:6e95128c2efa | 87 | bool measureTimesOfFlight(UWB2WayMultiRange& tracker, UWBLink& ul, Timer& timer, float ranging_timeout = 0.1f) |
| bhepp | 2:5af0f0006f40 | 88 | { |
| bhepp | 2:5af0f0006f40 | 89 | #if _DEBUG |
| bhepp | 2:5af0f0006f40 | 90 | int time_begin_us = timer.read_us(); |
| bhepp | 2:5af0f0006f40 | 91 | #endif |
| bhepp | 2:5af0f0006f40 | 92 | |
| bhepp | 1:c070ca30da80 | 93 | #if MEASURE_UWB_RANGING_RATE |
| bhepp | 1:c070ca30da80 | 94 | static int32_t range_counter = 0; |
| bhepp | 1:c070ca30da80 | 95 | static uint32_t last_stamp_us = timer.read_us(); |
| bhepp | 1:c070ca30da80 | 96 | #endif |
| bhepp | 1:c070ca30da80 | 97 | |
| bhepp | 5:1928eb8c417a | 98 | bool any_success = false; |
| bhepp | 6:9055fcc2f0cb | 99 | for (int i = 0; i < NUM_OF_SLAVES; i++) { |
| bhepp | 1:c070ca30da80 | 100 | uint8_t remote_address = SLAVE_ADDRESS_OFFSET + i; |
| bhepp | 2:5af0f0006f40 | 101 | const UWB2WayMultiRange::RawRangingResult& raw_result = tracker.measureTimesOfFlight(remote_address, ranging_timeout); |
| bhepp | 6:9055fcc2f0cb | 102 | if (raw_result.status == UWB2WayMultiRange::SUCCESS) { |
| bhepp | 5:1928eb8c417a | 103 | any_success = true; |
| bhepp | 10:6e95128c2efa | 104 | if (comm_mode == UWBLINK) { |
| bhepp | 6:9055fcc2f0cb | 105 | UWBMessageMultiRange msg_multi_range( |
| bhepp | 6:9055fcc2f0cb | 106 | tracker.getAddress(), |
| bhepp | 6:9055fcc2f0cb | 107 | remote_address |
| bhepp | 6:9055fcc2f0cb | 108 | ); |
| bhepp | 6:9055fcc2f0cb | 109 | for (int j = 0; j < tracker.getNumOfModules(); ++j) { |
| bhepp | 6:9055fcc2f0cb | 110 | msg_multi_range.addModuleMeasurement(raw_result.timestamp_master_request_1[j], raw_result.timestamp_slave_reply[j], raw_result.timestamp_master_request_2[j]); |
| bhepp | 6:9055fcc2f0cb | 111 | } |
| bhepp | 6:9055fcc2f0cb | 112 | msg_multi_range.setSlaveMeasurement(raw_result.timestamp_master_request_1_recv, raw_result.timestamp_slave_reply_send, raw_result.timestamp_master_request_2_recv); |
| bhepp | 6:9055fcc2f0cb | 113 | UWBMessage msg(UWBMessage::UWB_MESSAGE_TYPE_MULTI_RANGE, &msg_multi_range); |
| bhepp | 6:9055fcc2f0cb | 114 | if (!ul.sendMessage(msg)) { |
| bhepp | 6:9055fcc2f0cb | 115 | ERROR_PRINTF("\r\nSending UWBLink message failed\r\n"); |
| bhepp | 6:9055fcc2f0cb | 116 | } |
| bhepp | 6:9055fcc2f0cb | 117 | } else { |
| bhepp | 6:9055fcc2f0cb | 118 | for (int j = 0; j < tracker.getNumOfModules(); ++j) { |
| bhepp | 1:c070ca30da80 | 119 | int64_t timediff_slave = raw_result.timestamp_master_request_1_recv + raw_result.timestamp_master_request_2_recv - 2 * raw_result.timestamp_slave_reply_send; |
| bhepp | 1:c070ca30da80 | 120 | // Calculation of the summand on the sending node/beacon |
| bhepp | 1:c070ca30da80 | 121 | int64_t timediff_master = 2 * raw_result.timestamp_slave_reply[j] - raw_result.timestamp_master_request_1[j] - raw_result.timestamp_master_request_2[j]; |
| bhepp | 1:c070ca30da80 | 122 | // Calculation of the resulting sum of all four ToFs. |
| bhepp | 1:c070ca30da80 | 123 | int64_t timediff = timediff_master + timediff_slave; |
| bhepp | 1:c070ca30da80 | 124 | float tof = tracker.convertDWTimeunitsToMicroseconds(timediff) / 4.0f; |
| bhepp | 1:c070ca30da80 | 125 | float range = tracker.convertTimeOfFlightToDistance(tof); |
| bhepp | 1:c070ca30da80 | 126 | |
| bhepp | 10:6e95128c2efa | 127 | send_status_message(ul, "%d.%d - %d> range = %.2f, tof = %.2e", tracker.getAddress(), j, remote_address, range, tof); |
| bhepp | 1:c070ca30da80 | 128 | } |
| bhepp | 1:c070ca30da80 | 129 | } |
| bhepp | 6:9055fcc2f0cb | 130 | } else { |
| bhepp | 10:6e95128c2efa | 131 | send_status_message(ul, "Ranging failed: %s - %s", UWB2WayMultiRange::RANGING_STATUS_MESSAGES[raw_result.status], raw_result.status_description); |
| bhepp | 1:c070ca30da80 | 132 | } |
| bhepp | 1:c070ca30da80 | 133 | #if MEASURE_UWB_RANGING_RATE |
| bhepp | 1:c070ca30da80 | 134 | ++range_counter; |
| bhepp | 1:c070ca30da80 | 135 | #endif |
| bhepp | 1:c070ca30da80 | 136 | } |
| bhepp | 1:c070ca30da80 | 137 | |
| bhepp | 1:c070ca30da80 | 138 | #if MEASURE_UWB_RANGING_RATE |
| bhepp | 1:c070ca30da80 | 139 | uint32_t now_stamp_us = timer.read_us(); |
| bhepp | 1:c070ca30da80 | 140 | uint32_t dt_us = now_stamp_us - last_stamp_us; |
| bhepp | 1:c070ca30da80 | 141 | if (dt_us > 2 * 1000 * 1000) |
| bhepp | 1:c070ca30da80 | 142 | { |
| bhepp | 1:c070ca30da80 | 143 | float rate = 1000 * 1000 * range_counter / ((float)dt_us); |
| bhepp | 10:6e95128c2efa | 144 | send_status_message(ul, "Rate = %f.2Hz", rate); |
| bhepp | 10:6e95128c2efa | 145 | send_status_message(ul, "range_counter = %d, stamp_us = %u, last_stamp_us = %u", range_counter, now_stamp_us, last_stamp_us); |
| bhepp | 1:c070ca30da80 | 146 | range_counter = 0; |
| bhepp | 1:c070ca30da80 | 147 | last_stamp_us = now_stamp_us; |
| bhepp | 1:c070ca30da80 | 148 | } |
| bhepp | 1:c070ca30da80 | 149 | #endif |
| bhepp | 2:5af0f0006f40 | 150 | |
| bhepp | 2:5af0f0006f40 | 151 | #if _DEBUG |
| bhepp | 2:5af0f0006f40 | 152 | int time_end_us = timer.read_us(); |
| bhepp | 2:5af0f0006f40 | 153 | int time_elapsed_us = time_end_us - time_begin_us; |
| bhepp | 2:5af0f0006f40 | 154 | int time_elapsed_ms = time_elapsed_us / 1000; |
| bhepp | 2:5af0f0006f40 | 155 | DEBUG_PRINTF_VA("Time elapsed for ranging and output: %d ms (%d microseconds)\r\n", time_elapsed_ms, time_elapsed_us); |
| bhepp | 2:5af0f0006f40 | 156 | DEBUG_PRINTF("\r\n\r\n"); |
| bhepp | 2:5af0f0006f40 | 157 | #endif |
| bhepp | 2:5af0f0006f40 | 158 | |
| bhepp | 2:5af0f0006f40 | 159 | #if _DEBUG |
| bhepp | 6:9055fcc2f0cb | 160 | ////wait_ms(500); |
| bhepp | 2:5af0f0006f40 | 161 | #endif |
| bhepp | 5:1928eb8c417a | 162 | |
| bhepp | 5:1928eb8c417a | 163 | return any_success; |
| bhepp | 1:c070ca30da80 | 164 | } |
| bhepp | 1:c070ca30da80 | 165 | |
| bhepp | 1:c070ca30da80 | 166 | int main() |
| bhepp | 1:c070ca30da80 | 167 | { |
| bhepp | 5:1928eb8c417a | 168 | while (true) { |
| bhepp | 12:152a51255a28 | 169 | // Ensure that all DW units are deactiviated at the beginning |
| bhepp | 12:152a51255a28 | 170 | for (int i = 0; i < NUM_OF_DW_UNITS; ++i) { |
| bhepp | 12:152a51255a28 | 171 | DigitalOut out(DW_CS_PINS[i]); |
| bhepp | 5:1928eb8c417a | 172 | out = 1; |
| bhepp | 5:1928eb8c417a | 173 | } |
| bhepp | 5:1928eb8c417a | 174 | |
| bhepp | 6:9055fcc2f0cb | 175 | UWBLinkMbed ul(&pc, MAX_UWB_LINK_FRAME_LENGTH); |
| bhepp | 6:9055fcc2f0cb | 176 | |
| bhepp | 5:1928eb8c417a | 177 | SPI spi(DW_MOSI_PIN, DW_MISO_PIN, DW_SCLK_PIN); |
| bhepp | 5:1928eb8c417a | 178 | 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 | 5:1928eb8c417a | 179 | // NOTE: Minimum Frequency 1MHz. Below it is now working. Could be something with the activation and deactivation of interrupts. |
| bhepp | 5:1928eb8c417a | 180 | spi.frequency(SPI_FREQUENCY); // with a 1MHz clock rate (worked up to 49MHz in our Test) |
| bhepp | 5:1928eb8c417a | 181 | |
| bhepp | 5:1928eb8c417a | 182 | Timer timer; |
| bhepp | 5:1928eb8c417a | 183 | timer.start(); |
| bhepp | 5:1928eb8c417a | 184 | |
| bhepp | 5:1928eb8c417a | 185 | DW1000* dw_array[NUM_OF_DW_UNITS]; |
| bhepp | 6:9055fcc2f0cb | 186 | bool dw_init_success[NUM_OF_DW_UNITS]; |
| bhepp | 5:1928eb8c417a | 187 | InterruptIn* irq = NULL; |
| bhepp | 5:1928eb8c417a | 188 | |
| bhepp | 10:6e95128c2efa | 189 | send_status_message(ul, "Performing hardware reset of UWB modules\r\n"); |
| bhepp | 5:1928eb8c417a | 190 | // == IMPORTANT == Create all DW objects first (this will cause a reset of the DW module) |
| bhepp | 5:1928eb8c417a | 191 | DW1000::hardwareReset(DW_RESET_PIN); |
| bhepp | 6:9055fcc2f0cb | 192 | |
| bhepp | 5:1928eb8c417a | 193 | // Now we can initialize the DW modules |
| bhepp | 6:9055fcc2f0cb | 194 | for (int i = 0; i < NUM_OF_DW_UNITS; ++i) { |
| bhepp | 6:9055fcc2f0cb | 195 | dw_init_success[i] = true; |
| bhepp | 5:1928eb8c417a | 196 | dw_array[i] = new DW1000(spi, irq, DW_CS_PINS[i]); // Device driver instanceSPI pins: (MOSI, MISO, SCLK, CS, IRQ, RESET) |
| bhepp | 5:1928eb8c417a | 197 | |
| bhepp | 5:1928eb8c417a | 198 | DW1000& dw = *dw_array[i]; |
| bhepp | 6:9055fcc2f0cb | 199 | uint64_t eui = 0xFAEDCD01FAEDCD01 + i; |
| bhepp | 6:9055fcc2f0cb | 200 | dw.setEUI(eui); // basic methods called to check if we have a working SPI connection |
| bhepp | 6:9055fcc2f0cb | 201 | uint64_t query_eui = dw.getEUI(); |
| bhepp | 6:9055fcc2f0cb | 202 | float query_voltage = dw.getVoltage(); |
| bhepp | 6:9055fcc2f0cb | 203 | uint32_t query_device_id = dw.getDeviceID(); |
| bhepp | 5:1928eb8c417a | 204 | |
| bhepp | 10:6e95128c2efa | 205 | send_status_message(ul, "\r\nUnit %d", i); |
| bhepp | 10:6e95128c2efa | 206 | send_status_message(ul, "\r\nDecaWave 1.0 up and running!"); // Splashscreen |
| bhepp | 10:6e95128c2efa | 207 | send_status_message(ul, "DEVICE_ID register: 0x%X", query_device_id); |
| bhepp | 10:6e95128c2efa | 208 | send_status_message(ul, "EUI register: %016llX", query_eui); |
| bhepp | 10:6e95128c2efa | 209 | send_status_message(ul, "Voltage: %.2fV", query_voltage); |
| bhepp | 6:9055fcc2f0cb | 210 | |
| bhepp | 6:9055fcc2f0cb | 211 | if (query_eui != eui) { |
| bhepp | 10:6e95128c2efa | 212 | send_status_message(ul, "ERROR: Queried EUI is not equal to the configured EUI"); |
| bhepp | 6:9055fcc2f0cb | 213 | dw_init_success[i] = false; |
| bhepp | 6:9055fcc2f0cb | 214 | continue; |
| bhepp | 6:9055fcc2f0cb | 215 | } |
| bhepp | 6:9055fcc2f0cb | 216 | |
| bhepp | 6:9055fcc2f0cb | 217 | if (query_voltage < MIN_DW_VOLTAGE) { |
| bhepp | 10:6e95128c2efa | 218 | send_status_message(ul, "ERROR: Queried voltage is below minimum value"); |
| bhepp | 6:9055fcc2f0cb | 219 | dw_init_success[i] = false; |
| bhepp | 6:9055fcc2f0cb | 220 | continue; |
| bhepp | 6:9055fcc2f0cb | 221 | } |
| bhepp | 5:1928eb8c417a | 222 | |
| bhepp | 5:1928eb8c417a | 223 | // Set NLOS settings (According to DecaWave Application Note APS006) |
| bhepp | 6:9055fcc2f0cb | 224 | if (USE_NLOS_SETTINGS) { |
| bhepp | 10:6e95128c2efa | 225 | send_status_message(ul, "Setting NLOS configuration for Unit %d", i); |
| bhepp | 5:1928eb8c417a | 226 | DW1000Utils::setNLOSSettings(&dw, DATA_RATE_SETTING, PRF_SETTING, PREAMBLE_SETTING); |
| bhepp | 5:1928eb8c417a | 227 | } |
| bhepp | 5:1928eb8c417a | 228 | } |
| bhepp | 6:9055fcc2f0cb | 229 | |
| bhepp | 6:9055fcc2f0cb | 230 | bool all_dw_initialized = true; |
| bhepp | 6:9055fcc2f0cb | 231 | for (int i = 0; i < NUM_OF_DW_UNITS; ++i) { |
| bhepp | 6:9055fcc2f0cb | 232 | if (!dw_init_success[i]) { |
| bhepp | 6:9055fcc2f0cb | 233 | all_dw_initialized = false; |
| bhepp | 6:9055fcc2f0cb | 234 | break; |
| bhepp | 6:9055fcc2f0cb | 235 | } |
| bhepp | 5:1928eb8c417a | 236 | } |
| bhepp | 6:9055fcc2f0cb | 237 | |
| bhepp | 6:9055fcc2f0cb | 238 | if (all_dw_initialized) { |
| bhepp | 10:6e95128c2efa | 239 | send_status_message(ul, "Initializing tracker with address %d", TRACKER_ADDRESS); |
| bhepp | 6:9055fcc2f0cb | 240 | UWB2WayMultiRange tracker(TRACKER_ADDRESS); |
| bhepp | 6:9055fcc2f0cb | 241 | |
| bhepp | 6:9055fcc2f0cb | 242 | for (int i = 0; i < NUM_OF_DW_UNITS; ++i) { |
| bhepp | 6:9055fcc2f0cb | 243 | tracker.addModule(dw_array[i]); |
| bhepp | 6:9055fcc2f0cb | 244 | } |
| bhepp | 6:9055fcc2f0cb | 245 | |
| bhepp | 10:6e95128c2efa | 246 | send_status_message(ul, "Resetting all modules and waiting 100ms"); |
| bhepp | 6:9055fcc2f0cb | 247 | for (int i = 0; i < tracker.getNumOfModules(); ++i) { |
| bhepp | 6:9055fcc2f0cb | 248 | tracker.getModule(i)->softwareReset(); |
| bhepp | 6:9055fcc2f0cb | 249 | } |
| bhepp | 6:9055fcc2f0cb | 250 | wait_us(100); // This helps sometimes |
| bhepp | 6:9055fcc2f0cb | 251 | |
| bhepp | 6:9055fcc2f0cb | 252 | Timer watchdog_timer; |
| bhepp | 6:9055fcc2f0cb | 253 | watchdog_timer.start(); |
| bhepp | 6:9055fcc2f0cb | 254 | float watchdog_last_time = watchdog_timer.read(); |
| bhepp | 6:9055fcc2f0cb | 255 | bool watchdog_timeout_flag = false; |
| bhepp | 5:1928eb8c417a | 256 | |
| bhepp | 10:6e95128c2efa | 257 | send_status_message(ul, "Entering main loop"); |
| bhepp | 6:9055fcc2f0cb | 258 | while (!watchdog_timeout_flag) { |
| bhepp | 10:6e95128c2efa | 259 | bool success = measureTimesOfFlight(tracker, ul, timer); |
| bhepp | 6:9055fcc2f0cb | 260 | float current_time = watchdog_timer.read(); |
| bhepp | 6:9055fcc2f0cb | 261 | if (success) { |
| bhepp | 6:9055fcc2f0cb | 262 | watchdog_last_time = current_time; |
| bhepp | 6:9055fcc2f0cb | 263 | } else { |
| bhepp | 6:9055fcc2f0cb | 264 | float watchdog_time = current_time - watchdog_last_time; |
| bhepp | 6:9055fcc2f0cb | 265 | if (watchdog_time > WATCHDOG_TIMEOUT) { |
| bhepp | 6:9055fcc2f0cb | 266 | watchdog_timeout_flag = true; |
| bhepp | 6:9055fcc2f0cb | 267 | } |
| bhepp | 5:1928eb8c417a | 268 | } |
| bhepp | 5:1928eb8c417a | 269 | } |
| bhepp | 10:6e95128c2efa | 270 | send_status_message(ul, ""); |
| bhepp | 10:6e95128c2efa | 271 | send_status_message(ul, "Watchdog timed out ..."); |
| bhepp | 10:6e95128c2efa | 272 | send_status_message(ul, "Restarting ..."); |
| bhepp | 10:6e95128c2efa | 273 | send_status_message(ul, ""); |
| bhepp | 6:9055fcc2f0cb | 274 | } else { |
| bhepp | 10:6e95128c2efa | 275 | send_status_message(ul, "\r\nNot all DW units could be initialized."); |
| bhepp | 6:9055fcc2f0cb | 276 | for (int i = 0; i < NUM_OF_DW_UNITS; ++i) { |
| bhepp | 6:9055fcc2f0cb | 277 | if (!dw_init_success[i]) { |
| bhepp | 10:6e95128c2efa | 278 | send_status_message(ul, "Failed to initialize DW unit %d", i); |
| bhepp | 6:9055fcc2f0cb | 279 | } |
| bhepp | 6:9055fcc2f0cb | 280 | } |
| bhepp | 10:6e95128c2efa | 281 | send_status_message(ul, "Trying again ..."); |
| bhepp | 6:9055fcc2f0cb | 282 | wait_ms(1000); |
| bhepp | 5:1928eb8c417a | 283 | } |
| bhepp | 1:c070ca30da80 | 284 | |
| bhepp | 6:9055fcc2f0cb | 285 | for (int i = 0; i < NUM_OF_DW_UNITS; ++i) { |
| bhepp | 5:1928eb8c417a | 286 | delete dw_array[i]; |
| bhepp | 1:c070ca30da80 | 287 | } |
| bhepp | 1:c070ca30da80 | 288 | } |
| bhepp | 1:c070ca30da80 | 289 | } |
| bhepp | 1:c070ca30da80 | 290 | #endif |