Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Beacon/AP_Beacon_Marvelmind.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15Original C Code by Marvelmind (https://github.com/MarvelmindRobotics/marvelmind.c)16Adapted into Ardupilot by Karthik Desai, Amilcar Lucas17April 201718*/1920#include "AP_Beacon_Marvelmind.h"2122#if AP_BEACON_MARVELMIND_ENABLED2324#include <AP_HAL/AP_HAL.h>25#include <AP_Math/crc.h>2627#define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID 0x000128#define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID 0x000229#define AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID 0x000430#define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID 0x001131#define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID 0x00123233extern const AP_HAL::HAL& hal;3435#define MM_DEBUG_LEVEL 03637#if MM_DEBUG_LEVEL38#include <GCS_MAVLink/GCS.h>39#define Debug(level, fmt, args ...) do { if (level <= MM_DEBUG_LEVEL) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ## args); } } while (0)40#else41#define Debug(level, fmt, args ...)42#endif4344void AP_Beacon_Marvelmind::process_position_datagram()45{46hedge.cur_position.address = input_buffer[16];47hedge.cur_position.timestamp = input_buffer[5]48| (((uint32_t) input_buffer[6]) << 8)49| (((uint32_t) input_buffer[7]) << 16)50| (((uint32_t) input_buffer[8]) << 24);51const int16_t vx = input_buffer[9] | (((uint16_t) input_buffer[10]) << 8);52hedge.cur_position.x__mm = vx * 10; // centimeters -> millimeters53const int16_t vy = input_buffer[11] | (((uint16_t) input_buffer[12]) << 8);54hedge.cur_position.y__mm = vy * 10; // centimeters -> millimeters55const int16_t vz = input_buffer[13] | (((uint16_t) input_buffer[14]) << 8);56hedge.cur_position.z__mm = vz * 10; // centimeters -> millimeters57hedge.cur_position.high_resolution = false;58hedge._have_new_values = true;59}6061void AP_Beacon_Marvelmind::process_position_highres_datagram()62{63hedge.cur_position.address = input_buffer[22];64hedge.cur_position.timestamp = input_buffer[5]65| (((uint32_t) input_buffer[6]) << 8)66| (((uint32_t) input_buffer[7]) << 16)67| (((uint32_t) input_buffer[8]) << 24);68hedge.cur_position.x__mm = input_buffer[9] | (((uint32_t) input_buffer[10]) << 8)69| (((uint32_t) input_buffer[11]) << 16)70| (((uint32_t) input_buffer[12]) << 24);71hedge.cur_position.y__mm = input_buffer[13] | (((uint32_t) input_buffer[14]) << 8)72| (((uint32_t) input_buffer[15]) << 16)73| (((uint32_t) input_buffer[16]) << 24);74hedge.cur_position.z__mm = input_buffer[17] | (((uint32_t) input_buffer[18]) << 8)75| (((uint32_t) input_buffer[19]) << 16)76| (((uint32_t) input_buffer[20]) << 24);77hedge.cur_position.high_resolution = true;78hedge._have_new_values = true;79}8081AP_Beacon_Marvelmind::StationaryBeaconPosition* AP_Beacon_Marvelmind::get_or_alloc_beacon(uint8_t address)82{83const uint8_t n_used = hedge.positions_beacons.num_beacons;84for (uint8_t i = 0; i < n_used; i++) {85if (hedge.positions_beacons.beacons[i].address == address) {86return &hedge.positions_beacons.beacons[i];87}88}89if (n_used >= AP_BEACON_MAX_BEACONS) {90return nullptr;91}92hedge.positions_beacons.num_beacons = (n_used + 1);93return &hedge.positions_beacons.beacons[n_used];94}9596void AP_Beacon_Marvelmind::process_beacons_positions_datagram()97{98const uint8_t n = input_buffer[5]; // number of beacons in packet99StationaryBeaconPosition *stationary_beacon;100if ((1 + n * 8) != input_buffer[4]) {101Debug(1, "beacon pos lo pkt size %d != %d", input_buffer[4], (1 + n * 8));102return; // incorrect size103}104for (uint8_t i = 0; i < n; i++) {105const uint8_t ofs = 6 + i * 8;106const uint8_t address = input_buffer[ofs];107const int16_t x = input_buffer[ofs + 1]108| (((uint16_t) input_buffer[ofs + 2]) << 8);109const int16_t y = input_buffer[ofs + 3]110| (((uint16_t) input_buffer[ofs + 4]) << 8);111const int16_t z = input_buffer[ofs + 5]112| (((uint16_t) input_buffer[ofs + 6]) << 8);113stationary_beacon = get_or_alloc_beacon(address);114if (stationary_beacon != nullptr) {115stationary_beacon->address = address; //The instance and the address are the same116stationary_beacon->x__mm = x * 10; // centimeters -> millimeters117stationary_beacon->y__mm = y * 10; // centimeters -> millimeters118stationary_beacon->z__mm = z * 10; // centimeters -> millimeters119stationary_beacon->high_resolution = false;120hedge.positions_beacons.updated = true;121}122}123order_stationary_beacons();124}125126void AP_Beacon_Marvelmind::process_beacons_positions_highres_datagram()127{128const uint8_t n = input_buffer[5]; // number of beacons in packet129StationaryBeaconPosition *stationary_beacon;130if ((1 + n * 14) != input_buffer[4]) {131Debug(1, "beacon pos hi pkt size %d != %d", input_buffer[4], (1 + n * 14));132return; // incorrect size133}134for (uint8_t i = 0; i < n; i++) {135const uint8_t ofs = 6 + i * 14;136const uint8_t address = input_buffer[ofs];137const int32_t x = input_buffer[ofs + 1]138| (((uint32_t) input_buffer[ofs + 2]) << 8)139| (((uint32_t) input_buffer[ofs + 3]) << 16)140| (((uint32_t) input_buffer[ofs + 4]) << 24);141const int32_t y = input_buffer[ofs + 5]142| (((uint32_t) input_buffer[ofs + 6]) << 8)143| (((uint32_t) input_buffer[ofs + 7]) << 16)144| (((uint32_t) input_buffer[ofs + 8]) << 24);145const int32_t z = input_buffer[ofs + 9]146| (((uint32_t) input_buffer[ofs + 10]) << 8)147| (((uint32_t) input_buffer[ofs + 11]) << 16)148| (((uint32_t) input_buffer[ofs + 12]) << 24);149stationary_beacon = get_or_alloc_beacon(address);150if (stationary_beacon != nullptr) {151stationary_beacon->address = address; //The instance and the address are the same152stationary_beacon->x__mm = x; // millimeters153stationary_beacon->y__mm = y; // millimeters154stationary_beacon->z__mm = z; // millimeters155stationary_beacon->high_resolution = true;156hedge.positions_beacons.updated = true;157}158}159order_stationary_beacons();160}161162void AP_Beacon_Marvelmind::process_beacons_distances_datagram()163{164if (32 != input_buffer[4]) {165Debug(1, "beacon dist pkt size %d != 32", input_buffer[4]);166return; // incorrect size167}168bool set = false;169for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; i++) {170const uint8_t ofs = 6 + i * 6;171const uint8_t address = input_buffer[ofs];172const int8_t instance = find_beacon_instance(address);173if (instance != -1) {174const uint32_t distance = input_buffer[ofs + 1]175| (((uint32_t) input_buffer[ofs + 2]) << 8)176| (((uint32_t) input_buffer[ofs + 3]) << 16)177| (((uint32_t) input_buffer[ofs + 4]) << 24);178hedge.positions_beacons.beacons[instance].distance__m = distance * 0.001f; // millimeters -> meters179set_beacon_distance(instance, hedge.positions_beacons.beacons[instance].distance__m);180set = true;181Debug(2, "Beacon %d is %.2fm", instance, hedge.positions_beacons.beacons[instance].distance__m);182}183}184if (set) {185last_update_ms = AP_HAL::millis();186}187}188189int8_t AP_Beacon_Marvelmind::find_beacon_instance(uint8_t address) const190{191for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; i++) {192if (hedge.positions_beacons.beacons[i].address == address) {193return i;194}195}196return -1;197}198199void AP_Beacon_Marvelmind::update(void)200{201if (uart == nullptr) {202return;203}204// read any available characters205uint16_t num_bytes_read = MIN(uart->available(), 16384U);206while (num_bytes_read-- > 0) {207bool good_byte = false;208if (!uart->read(input_buffer[num_bytes_in_block_received])) {209break;210}211const uint8_t received_char = input_buffer[num_bytes_in_block_received];212switch (parse_state) {213case RECV_HDR:214switch (num_bytes_in_block_received) {215case 0:216good_byte = (received_char == 0xff);217break;218case 1:219good_byte = (received_char == 0x47);220break;221case 2:222good_byte = true;223break;224case 3:225data_id = (((uint16_t)received_char) << 8) + input_buffer[2];226good_byte = (data_id == AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID)227|| (data_id == AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID)228|| (data_id == AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID)229|| (data_id == AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID)230|| (data_id == AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID);231break;232case 4: {233switch (data_id) {234case AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID: {235good_byte = (received_char == 0x10);236break;237}238case AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID:239case AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID:240case AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID:241good_byte = true;242break;243case AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID: {244good_byte = (received_char == 0x16);245break;246}247}248if (good_byte) {249parse_state = RECV_DGRAM;250}251break;252}253}254if (good_byte) {255// correct header byte256num_bytes_in_block_received++;257} else {258// ...or incorrect259parse_state = RECV_HDR;260num_bytes_in_block_received = 0;261}262break;263264case RECV_DGRAM:265num_bytes_in_block_received++;266if (num_bytes_in_block_received >= 7 + input_buffer[4]) {267// parse dgram268uint16_t block_crc = calc_crc_modbus(input_buffer, num_bytes_in_block_received);269if (block_crc == 0) {270switch (data_id) {271case AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID:272{273// add to position_buffer274process_position_datagram();275vehicle_position_initialized = true;276set_stationary_beacons_positions();277break;278}279280case AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID:281{282process_beacons_positions_datagram();283beacon_position_initialized = true;284set_stationary_beacons_positions();285break;286}287288case AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID:289{290process_beacons_distances_datagram();291break;292}293294case AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID:295{296process_position_highres_datagram();297vehicle_position_initialized = true;298set_stationary_beacons_positions();299break;300}301302case AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID:303{304process_beacons_positions_highres_datagram();305beacon_position_initialized = true;306set_stationary_beacons_positions();307break;308}309}310}311// and repeat312parse_state = RECV_HDR;313num_bytes_in_block_received = 0;314}315break;316}317}318}319320bool AP_Beacon_Marvelmind::healthy()321{322// healthy if we have parsed a message within the past 300ms323return ((AP_HAL::millis() - last_update_ms) < AP_BEACON_TIMEOUT_MS);324}325326void AP_Beacon_Marvelmind::set_stationary_beacons_positions()327{328bool set = false;329if (vehicle_position_initialized && beacon_position_initialized) {330if (hedge._have_new_values) {331vehicle_position_NED__m = Vector3f(hedge.cur_position.y__mm * 0.001f,332hedge.cur_position.x__mm * 0.001f,333-hedge.cur_position.z__mm * 0.001f); //Transform Marvelmind ENU to Ardupilot NED334//TODO: Calculate Accuracy of the received signal. Marvelmind *advertises* +/- 2cms335// But we are conservative here and use 20cm instead (until MM provides us with a proper accuracy value)336set_vehicle_position(vehicle_position_NED__m, 0.2f);337set = true;338Debug(2,339"Hedge is at N%.2f, E%.2f, D%.2f",340vehicle_position_NED__m[0],341vehicle_position_NED__m[1],342vehicle_position_NED__m[2]);343}344hedge._have_new_values = false;345for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; ++i) {346if (hedge.positions_beacons.updated) {347beacon_position_NED__m[i] = Vector3f(hedge.positions_beacons.beacons[i].y__mm * 0.001f,348hedge.positions_beacons.beacons[i].x__mm * 0.001f,349-hedge.positions_beacons.beacons[i].z__mm * 0.001f); //Transform Marvelmind ENU to Ardupilot NED350set_beacon_position(i, beacon_position_NED__m[i]);351set = true;352Debug(2,353"Beacon %d is at N%.2f, E%.2f, D%.2f",354i,355beacon_position_NED__m[i][0],356beacon_position_NED__m[i][1],357beacon_position_NED__m[i][2]);358}359}360hedge.positions_beacons.updated = false;361362}363if (set) {364last_update_ms = AP_HAL::millis();365}366}367368void AP_Beacon_Marvelmind::order_stationary_beacons()369{370if (hedge.positions_beacons.updated) {371bool swapped = false;372uint8_t j = hedge.positions_beacons.num_beacons;373do374{375swapped = false;376StationaryBeaconPosition beacon_to_swap;377for (uint8_t i = 1; i < j; i++) {378if (hedge.positions_beacons.beacons[i-1].address > hedge.positions_beacons.beacons[i].address) {379beacon_to_swap = hedge.positions_beacons.beacons[i];380hedge.positions_beacons.beacons[i] = hedge.positions_beacons.beacons[i-1];381hedge.positions_beacons.beacons[i-1] = beacon_to_swap;382swapped = true;383}384}385j--;386} while(swapped);387}388}389390#endif // AP_BEACON_MARVELMIND_ENABLED391392393