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_GPS/AP_GPS_DroneCAN.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*/1415//16// UAVCAN GPS driver17//18#include "AP_GPS_config.h"1920#if AP_GPS_DRONECAN_ENABLED2122#include <AP_HAL/AP_HAL.h>2324#include "AP_GPS_DroneCAN.h"2526#include <AP_CANManager/AP_CANManager.h>27#include <AP_DroneCAN/AP_DroneCAN.h>28#include <GCS_MAVLink/GCS.h>2930#include <AP_Logger/AP_Logger.h>3132#include <stdio.h>33#include <AP_BoardConfig/AP_BoardConfig.h>3435#define GPS_PPS_EMULATION 03637extern const AP_HAL::HAL& hal;3839#define GPS_UAVCAN_DEBUGGING 04041#if GPS_UAVCAN_DEBUGGING42#if defined(HAL_BUILD_AP_PERIPH)43extern "C" {44void can_printf(const char *fmt, ...);45}46# define Debug(fmt, args ...) do {can_printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args);} while(0)47#else48# define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)49#endif50#else51# define Debug(fmt, args ...)52#endif5354#define LOG_TAG "GPS"5556#if CONFIG_HAL_BOARD == HAL_BOARD_SITL57#define NATIVE_TIME_OFFSET (AP_HAL::micros64() - AP_HAL::micros64())58#else59#define NATIVE_TIME_OFFSET 060#endif61AP_GPS_DroneCAN::DetectedModules AP_GPS_DroneCAN::_detected_modules[];62HAL_Semaphore AP_GPS_DroneCAN::_sem_registry;6364// Member Methods65AP_GPS_DroneCAN::AP_GPS_DroneCAN(AP_GPS &_gps,66AP_GPS::Params &_params,67AP_GPS::GPS_State &_state,68AP_GPS::GPS_Role _role) :69AP_GPS_Backend(_gps, _params, _state, nullptr),70interim_state(_state),71role(_role)72{73param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_get_set_response_int, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &);74param_float_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_get_set_response_float, bool, AP_DroneCAN*, const uint8_t, const char*, float &);75param_save_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_save_response, void, AP_DroneCAN*, const uint8_t, bool);76}7778AP_GPS_DroneCAN::~AP_GPS_DroneCAN()79{80WITH_SEMAPHORE(_sem_registry);8182_detected_modules[_detected_module].driver = nullptr;8384#if GPS_MOVING_BASELINE85if (rtcm3_parser != nullptr) {86delete rtcm3_parser;87}88#endif89}9091bool AP_GPS_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)92{93const auto driver_index = ap_dronecan->get_driver_index();9495return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_fix2_msg_trampoline, driver_index) != nullptr)96&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_aux_msg_trampoline, driver_index) != nullptr)97&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_heading_msg_trampoline, driver_index) != nullptr)98&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_status_msg_trampoline, driver_index) != nullptr)99#if GPS_MOVING_BASELINE100&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_moving_baseline_msg_trampoline, driver_index) != nullptr)101&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_relposheading_msg_trampoline, driver_index) != nullptr)102#endif103;104}105106AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state)107{108WITH_SEMAPHORE(_sem_registry);109int8_t found_match = -1, last_match = -1;110AP_GPS_DroneCAN* backend = nullptr;111bool bad_override_config = false;112for (int8_t i = GPS_MAX_RECEIVERS - 1; i >= 0; i--) {113if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) {114if (_gps.params[_state.instance].override_node_id != 0 &&115_gps.params[_state.instance].override_node_id != _detected_modules[i].node_id) {116continue; // This device doesn't match the correct node117}118last_match = found_match;119for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) {120if (_detected_modules[i].node_id == _gps.params[j].override_node_id &&121(j != _state.instance)) {122//wrong instance123found_match = -1;124break;125}126found_match = i;127}128129// Handle Duplicate overrides130for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) {131if (_gps.params[i].override_node_id != 0 && (i != j) &&132_gps.params[i].override_node_id == _gps.params[j].override_node_id) {133bad_override_config = true;134}135}136if (bad_override_config) {137GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Same Node Id %lu set for multiple GPS", (unsigned long int)_gps.params[i].override_node_id.get());138last_match = i;139}140141if (found_match == -1) {142found_match = last_match;143continue;144}145break;146}147}148149if (found_match == -1) {150return NULL;151}152// initialise the backend based on the UAVCAN Moving baseline selection153switch (_gps.get_type(_state.instance)) {154case AP_GPS::GPS_TYPE_UAVCAN:155backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_NORMAL);156break;157#if GPS_MOVING_BASELINE158case AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE:159backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_BASE);160break;161case AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER:162backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_ROVER);163break;164#endif165default:166return NULL;167}168if (backend == nullptr) {169AP::can().log_text(AP_CANManager::LOG_ERROR,170LOG_TAG,171"Failed to register DroneCAN GPS Node %d on Bus %d\n",172_detected_modules[found_match].node_id,173_detected_modules[found_match].ap_dronecan->get_driver_index());174} else {175_detected_modules[found_match].driver = backend;176backend->_detected_module = found_match;177AP::can().log_text(AP_CANManager::LOG_INFO,178LOG_TAG,179"Registered DroneCAN GPS Node %d on Bus %d as instance %d\n",180_detected_modules[found_match].node_id,181_detected_modules[found_match].ap_dronecan->get_driver_index(),182_state.instance);183snprintf(backend->_name, ARRAY_SIZE(backend->_name), "DroneCAN%u-%u", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id);184_detected_modules[found_match].instance = _state.instance;185for (uint8_t i=0; i < GPS_MAX_RECEIVERS; i++) {186if (_detected_modules[found_match].node_id == AP::gps().params[i].node_id) {187if (i == _state.instance) {188// Nothing to do here189break;190}191// else swap192uint8_t tmp = AP::gps().params[_state.instance].node_id.get();193AP::gps().params[_state.instance].node_id.set_and_notify(_detected_modules[found_match].node_id);194AP::gps().params[i].node_id.set_and_notify(tmp);195}196}197#if GPS_MOVING_BASELINE198if (backend->role == AP_GPS::GPS_ROLE_MB_BASE) {199backend->rtcm3_parser = NEW_NOTHROW RTCM3_Parser;200if (backend->rtcm3_parser == nullptr) {201GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DroneCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id);202}203}204#endif // GPS_MOVING_BASELINE205}206207return backend;208}209210bool AP_GPS_DroneCAN::inter_instance_pre_arm_checks(char failure_msg[], uint16_t failure_msg_len)211{212// lint parameters and detected node IDs:213for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {214const auto ¶ms_i = AP::gps().params[i];215// we are only interested in parameters for DroneCAN GPSs:216if (!is_dronecan_gps_type(params_i.type)) {217continue;218}219bool overriden_node_found = false;220bool bad_override_config = false;221if (params_i.override_node_id == 0) {222//anything goes223continue;224}225for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) {226const auto ¶ms_j = AP::gps().params[j];227// we are only interested in parameters for DroneCAN GPSs:228if (!is_dronecan_gps_type(params_j.type)) {229continue;230}231if (params_i.override_node_id == params_j.override_node_id && (i != j)) {232bad_override_config = true;233break;234}235if (i == _detected_modules[j].instance && _detected_modules[j].driver) {236if (params_i.override_node_id == _detected_modules[j].node_id) {237overriden_node_found = true;238break;239}240}241}242if (bad_override_config) {243snprintf(failure_msg, failure_msg_len, "Same Node Id %lu set for multiple GPS", (unsigned long int)params_i.override_node_id.get());244return false;245}246247if (!overriden_node_found) {248snprintf(failure_msg, failure_msg_len, "Selected GPS Node %lu not set as instance %d", (unsigned long int)params_i.override_node_id.get(), i + 1);249return false;250}251}252253return true;254}255256AP_GPS_DroneCAN* AP_GPS_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id)257{258if (ap_dronecan == nullptr) {259return nullptr;260}261262for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {263if (_detected_modules[i].driver != nullptr &&264_detected_modules[i].ap_dronecan == ap_dronecan &&265_detected_modules[i].node_id == node_id) {266return _detected_modules[i].driver;267}268}269270bool already_detected = false;271// Check if there's an empty spot for possible registeration272for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {273if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) {274// Already Detected275already_detected = true;276break;277}278}279if (!already_detected) {280for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {281if (_detected_modules[i].ap_dronecan == nullptr) {282_detected_modules[i].ap_dronecan = ap_dronecan;283_detected_modules[i].node_id = node_id;284// Just set the Node ID in order of appearance285// This will be used to set select ids286AP::gps().params[i].node_id.set_and_notify(node_id);287break;288}289}290}291struct DetectedModules tempslot;292// Sort based on the node_id, larger values first293// we do this, so that we have repeatable GPS294// registration295for (uint8_t i = 1; i < GPS_MAX_RECEIVERS; i++) {296for (uint8_t j = i; j > 0; j--) {297if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) {298tempslot = _detected_modules[j];299_detected_modules[j] = _detected_modules[j-1];300_detected_modules[j-1] = tempslot;301// also fix the _detected_module in the driver so that RTCM injection302// can determine if it has the bus to itself303if (_detected_modules[j].driver) {304_detected_modules[j].driver->_detected_module = j;305}306if (_detected_modules[j-1].driver) {307_detected_modules[j-1].driver->_detected_module = j-1;308}309}310}311}312return nullptr;313}314315/*316handle velocity element of message317*/318void AP_GPS_DroneCAN::handle_velocity(const float vx, const float vy, const float vz)319{320if (!isnan(vx)) {321const Vector3f vel(vx, vy, vz);322interim_state.velocity = vel;323velocity_to_speed_course(interim_state);324// assume we have vertical velocity if we ever get a non-zero Z velocity325if (!isnan(vel.z) && !is_zero(vel.z)) {326interim_state.have_vertical_velocity = true;327} else {328interim_state.have_vertical_velocity = state.have_vertical_velocity;329}330} else {331interim_state.have_vertical_velocity = false;332}333}334335void AP_GPS_DroneCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec)336{337bool process = false;338seen_fix2 = true;339340WITH_SEMAPHORE(sem);341342if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX) {343interim_state.status = AP_GPS::GPS_Status::NO_FIX;344} else {345if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_TIME_ONLY) {346interim_state.status = AP_GPS::GPS_Status::NO_FIX;347} else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX) {348interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_2D;349process = true;350} else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX) {351interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D;352process = true;353}354355if (msg.gnss_time_standard == UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_UTC) {356uint64_t epoch_ms = msg.gnss_timestamp.usec;357if (epoch_ms != 0) {358epoch_ms /= 1000;359uint64_t gps_ms = epoch_ms - UNIX_OFFSET_MSEC;360interim_state.time_week = (uint16_t)(gps_ms / AP_MSEC_PER_WEEK);361interim_state.time_week_ms = (uint32_t)(gps_ms - (interim_state.time_week) * AP_MSEC_PER_WEEK);362}363}364365if (interim_state.status == AP_GPS::GPS_Status::GPS_OK_FIX_3D) {366if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS) {367interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS;368} else if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK) {369if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT) {370interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT;371} else if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED) {372interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED;373}374}375}376}377378if (process) {379Location loc = { };380loc.lat = msg.latitude_deg_1e8 / 10;381loc.lng = msg.longitude_deg_1e8 / 10;382const int32_t alt_amsl_cm = msg.height_msl_mm / 10;383interim_state.have_undulation = true;384interim_state.undulation = (msg.height_msl_mm - msg.height_ellipsoid_mm) * 0.001;385interim_state.location = loc;386set_alt_amsl_cm(interim_state, alt_amsl_cm);387388handle_velocity(msg.ned_velocity[0], msg.ned_velocity[1], msg.ned_velocity[2]);389390if (msg.covariance.len == 6) {391if (!isnan(msg.covariance.data[0])) {392interim_state.horizontal_accuracy = sqrtf(msg.covariance.data[0]);393interim_state.have_horizontal_accuracy = true;394} else {395interim_state.have_horizontal_accuracy = false;396}397if (!isnan(msg.covariance.data[2])) {398interim_state.vertical_accuracy = sqrtf(msg.covariance.data[2]);399interim_state.have_vertical_accuracy = true;400} else {401interim_state.have_vertical_accuracy = false;402}403if (!isnan(msg.covariance.data[3]) &&404!isnan(msg.covariance.data[4]) &&405!isnan(msg.covariance.data[5])) {406interim_state.speed_accuracy = sqrtf((msg.covariance.data[3] + msg.covariance.data[4] + msg.covariance.data[5])/3);407interim_state.have_speed_accuracy = true;408} else {409interim_state.have_speed_accuracy = false;410}411}412413interim_state.num_sats = msg.sats_used;414} else {415interim_state.have_vertical_velocity = false;416interim_state.have_vertical_accuracy = false;417interim_state.have_horizontal_accuracy = false;418interim_state.have_speed_accuracy = false;419interim_state.num_sats = 0;420}421422if (!seen_aux) {423// if we haven't seen an Aux message then populate vdop and424// hdop from pdop. Some GPS modules don't provide the Aux message425interim_state.hdop = interim_state.vdop = msg.pdop * 100.0;426}427428if ((msg.timestamp.usec > msg.gnss_timestamp.usec) && (msg.gnss_timestamp.usec > 0)) {429// we have a valid timestamp based on gnss_timestamp timescale, we can use that to correct our gps message time430interim_state.last_corrected_gps_time_us = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, (timestamp_usec + NATIVE_TIME_OFFSET));431interim_state.last_gps_time_ms = interim_state.last_corrected_gps_time_us/1000U;432interim_state.last_corrected_gps_time_us -= msg.timestamp.usec - msg.gnss_timestamp.usec;433// this is also the time the message was received on the UART on other end.434interim_state.corrected_timestamp_updated = true;435} else {436interim_state.last_gps_time_ms = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, timestamp_usec + NATIVE_TIME_OFFSET)/1000U;437}438439#if GPS_PPS_EMULATION440// Emulates a PPS signal, can be used to check how close are we to real GPS time441static virtual_timer_t timeout_vt;442hal.gpio->pinMode(51, 1);443auto handle_timeout = [](void *arg)444{445(void)arg;446//we are called from ISR context447chSysLockFromISR();448hal.gpio->toggle(51);449chSysUnlockFromISR();450};451452static uint64_t next_toggle, last_toggle;453454next_toggle = (msg.timestamp.usec) + (1000000ULL - ((msg.timestamp.usec) % 1000000ULL));455456next_toggle += jitter_correction.get_link_offset_usec();457if (next_toggle != last_toggle) {458chVTSet(&timeout_vt, chTimeUS2I(next_toggle - AP_HAL::micros64()), handle_timeout, nullptr);459last_toggle = next_toggle;460}461#endif462463_new_data = true;464if (!seen_message) {465if (interim_state.status == AP_GPS::GPS_Status::NO_GPS) {466// the first time we see a fix message we change from467// NO_GPS to NO_FIX, indicating to user that a DroneCAN GPS468// has been seen469interim_state.status = AP_GPS::GPS_Status::NO_FIX;470}471seen_message = true;472}473}474475void AP_GPS_DroneCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg)476{477WITH_SEMAPHORE(sem);478479if (!isnan(msg.hdop)) {480seen_aux = true;481interim_state.hdop = msg.hdop * 100.0;482}483484if (!isnan(msg.vdop)) {485seen_aux = true;486interim_state.vdop = msg.vdop * 100.0;487}488}489490void AP_GPS_DroneCAN::handle_heading_msg(const ardupilot_gnss_Heading& msg)491{492#if GPS_MOVING_BASELINE493if (seen_relposheading && gps.params[interim_state.instance].mb_params.type.get() != 0) {494// we prefer to use the relposheading to get yaw as it allows495// the user to more easily control the relative antenna positions496return;497}498#endif499500WITH_SEMAPHORE(sem);501502if (interim_state.gps_yaw_configured == false) {503interim_state.gps_yaw_configured = msg.heading_valid;504}505506interim_state.have_gps_yaw = msg.heading_valid;507interim_state.gps_yaw = degrees(msg.heading_rad);508if (interim_state.have_gps_yaw) {509interim_state.gps_yaw_time_ms = AP_HAL::millis();510}511512interim_state.have_gps_yaw_accuracy = msg.heading_accuracy_valid;513interim_state.gps_yaw_accuracy = degrees(msg.heading_accuracy_rad);514}515516void AP_GPS_DroneCAN::handle_status_msg(const ardupilot_gnss_Status& msg)517{518WITH_SEMAPHORE(sem);519520seen_status = true;521522healthy = msg.healthy;523status_flags = msg.status;524if (error_code != msg.error_codes) {525#if HAL_LOGGING_ENABLED526AP::logger().Write_MessageF("GPS %d: error changed (0x%08x/0x%08x)",527(unsigned int)(state.instance + 1),528error_code,529msg.error_codes);530#endif531error_code = msg.error_codes;532}533}534535#if GPS_MOVING_BASELINE536/*537handle moving baseline data.538*/539void AP_GPS_DroneCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id)540{541WITH_SEMAPHORE(sem);542if (role != AP_GPS::GPS_ROLE_MB_BASE) {543GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Incorrect Role set for DroneCAN GPS, %d should be Base", node_id);544return;545}546547if (rtcm3_parser == nullptr) {548return;549}550for (int i=0; i < msg.data.len; i++) {551rtcm3_parser->read(msg.data.data[i]);552}553}554555/*556handle relposheading message557*/558void AP_GPS_DroneCAN::handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id)559{560WITH_SEMAPHORE(sem);561562interim_state.gps_yaw_configured = true;563seen_relposheading = true;564// push raw heading data to calculate moving baseline heading states565if (calculate_moving_base_yaw(interim_state,566msg.reported_heading_deg,567msg.relative_distance_m,568msg.relative_down_pos_m)) {569if (msg.reported_heading_acc_available) {570interim_state.gps_yaw_accuracy = msg.reported_heading_acc_deg;571}572interim_state.have_gps_yaw_accuracy = msg.reported_heading_acc_available;573}574}575576// support for retrieving RTCMv3 data from a moving baseline base577bool AP_GPS_DroneCAN::get_RTCMV3(const uint8_t *&bytes, uint16_t &len)578{579WITH_SEMAPHORE(sem);580if (rtcm3_parser != nullptr) {581len = rtcm3_parser->get_len(bytes);582return len > 0;583}584return false;585}586587// clear previous RTCM3 packet588void AP_GPS_DroneCAN::clear_RTCMV3(void)589{590WITH_SEMAPHORE(sem);591if (rtcm3_parser != nullptr) {592rtcm3_parser->clear_packet();593}594}595596#endif // GPS_MOVING_BASELINE597598void AP_GPS_DroneCAN::handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg)599{600WITH_SEMAPHORE(_sem_registry);601602AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);603if (driver != nullptr) {604driver->handle_fix2_msg(msg, transfer.timestamp_usec);605}606}607608void AP_GPS_DroneCAN::handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg)609{610WITH_SEMAPHORE(_sem_registry);611612AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);613if (driver != nullptr) {614driver->handle_aux_msg(msg);615}616}617618void AP_GPS_DroneCAN::handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg)619{620WITH_SEMAPHORE(_sem_registry);621622AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);623if (driver != nullptr) {624driver->handle_heading_msg(msg);625}626}627628void AP_GPS_DroneCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg)629{630WITH_SEMAPHORE(_sem_registry);631632AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);633if (driver != nullptr) {634driver->handle_status_msg(msg);635}636}637638#if GPS_MOVING_BASELINE639// Moving Baseline msg trampoline640void AP_GPS_DroneCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg)641{642WITH_SEMAPHORE(_sem_registry);643AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);644if (driver != nullptr) {645driver->handle_moving_baseline_msg(msg, transfer.source_node_id);646}647}648649// RelPosHeading msg trampoline650void AP_GPS_DroneCAN::handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg)651{652WITH_SEMAPHORE(_sem_registry);653AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);654if (driver != nullptr) {655driver->handle_relposheading_msg(msg, transfer.source_node_id);656}657}658#endif659660bool AP_GPS_DroneCAN::do_config()661{662AP_DroneCAN *ap_dronecan = _detected_modules[_detected_module].ap_dronecan;663if (ap_dronecan == nullptr) {664return false;665}666uint8_t node_id = _detected_modules[_detected_module].node_id;667668switch(cfg_step) {669case STEP_SET_TYPE:670// GPS_TYPE was renamed GPS1_TYPE. Request both and671// handle whichever we receive.672ap_dronecan->get_parameter_on_node(node_id, "GPS_TYPE", ¶m_int_cb);673ap_dronecan->get_parameter_on_node(node_id, "GPS1_TYPE", ¶m_int_cb);674break;675case STEP_SET_MB_CAN_TX:676if (role != AP_GPS::GPS_Role::GPS_ROLE_NORMAL) {677ap_dronecan->get_parameter_on_node(node_id, "GPS_MB_ONLY_PORT", ¶m_int_cb);678} else {679cfg_step++;680}681break;682case STEP_SAVE_AND_REBOOT:683if (requires_save_and_reboot) {684ap_dronecan->save_parameters_on_node(node_id, ¶m_save_cb);685} else {686cfg_step++;687}688break;689case STEP_FINISHED:690return true;691default:692break;693}694return false;695}696697// Consume new data and mark it received698bool AP_GPS_DroneCAN::read(void)699{700if (gps._auto_config >= AP_GPS::GPS_AUTO_CONFIG_ENABLE_ALL) {701if (!do_config()) {702return false;703}704}705706WITH_SEMAPHORE(sem);707708send_rtcm();709710if (_new_data) {711_new_data = false;712713// the encoding of accuracies in DroneCAN can result in infinite714// values. These cause problems with blending. Use 1000m and 1000m/s instead715interim_state.horizontal_accuracy = MIN(interim_state.horizontal_accuracy, 1000.0);716interim_state.vertical_accuracy = MIN(interim_state.vertical_accuracy, 1000.0);717interim_state.speed_accuracy = MIN(interim_state.speed_accuracy, 1000.0);718719// prevent announcing multiple times720interim_state.announced_detection = state.announced_detection;721722state = interim_state;723if (interim_state.last_corrected_gps_time_us) {724// If we were able to get a valid last_corrected_gps_time_us725// we have had a valid GPS message time, from which we calculate726// the time of week.727_last_itow_ms = interim_state.time_week_ms;728_have_itow = true;729}730return true;731}732if (!seen_message) {733// start with NO_GPS until we get first packet734state.status = AP_GPS::GPS_Status::NO_GPS;735}736737return false;738}739740bool AP_GPS_DroneCAN::is_healthy(void) const741{742// if we don't have any health reports, assume it's healthy743if (!seen_status) {744return true;745}746return healthy;747}748749bool AP_GPS_DroneCAN::logging_healthy(void) const750{751// if we don't have status, assume it's valid752if (!seen_status) {753return true;754}755756return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_LOGGING) != 0;757}758759bool AP_GPS_DroneCAN::is_configured(void) const760{761// if we don't have status assume it's configured762if (!seen_status) {763return true;764}765766return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE) != 0;767}768769/*770send pending RTCM data771*/772void AP_GPS_DroneCAN::send_rtcm(void)773{774if (_rtcm_stream.buf == nullptr) {775return;776}777WITH_SEMAPHORE(sem);778779const uint32_t now = AP_HAL::millis();780if (now - _rtcm_stream.last_send_ms < 20) {781// don't send more than 50 per second782return;783}784uint32_t outlen = 0;785const uint8_t *ptr = _rtcm_stream.buf->readptr(outlen);786if (ptr == nullptr || outlen == 0) {787return;788}789uavcan_equipment_gnss_RTCMStream msg {};790outlen = MIN(outlen, sizeof(msg.data.data));791msg.protocol_id = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_PROTOCOL_ID_RTCM3;792memcpy(msg.data.data, ptr, outlen);793msg.data.len = outlen;794if (_detected_modules[_detected_module].ap_dronecan->rtcm_stream.broadcast(msg)) {795_rtcm_stream.buf->advance(outlen);796_rtcm_stream.last_send_ms = now;797}798}799800/*801handle RTCM data from MAVLink GPS_RTCM_DATA, forwarding it over MAVLink802*/803void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len)804{805// we only handle this if we are the first DroneCAN GPS or we are806// using a different uavcan instance than the first GPS, as we807// send the data as broadcast on all DroneCAN device ports and we808// don't want to send duplicates809const uint32_t now_ms = AP_HAL::millis();810if (_detected_module == 0 ||811_detected_modules[_detected_module].ap_dronecan != _detected_modules[0].ap_dronecan ||812now_ms - _detected_modules[0].last_inject_ms > 2000) {813if (_rtcm_stream.buf == nullptr) {814// give enough space for a full round from a NTRIP server with all815// constellations816_rtcm_stream.buf = NEW_NOTHROW ByteBuffer(2400);817if (_rtcm_stream.buf == nullptr) {818return;819}820}821_detected_modules[_detected_module].last_inject_ms = now_ms;822_rtcm_stream.buf->write(data, len);823send_rtcm();824}825}826827/*828handle param get/set response829*/830bool AP_GPS_DroneCAN::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, int32_t &value)831{832Debug("AP_GPS_DroneCAN: param set/get response from %d %s %ld\n", node_id, name, value);833if (((strcmp(name, "GPS_TYPE") == 0) || (strcmp(name, "GPS1_TYPE") == 0)) && (cfg_step == STEP_SET_TYPE)) {834if (role == AP_GPS::GPS_ROLE_MB_BASE && value != AP_GPS::GPS_TYPE_UBLOX_RTK_BASE) {835value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_BASE;836requires_save_and_reboot = true;837return true;838} else if (role == AP_GPS::GPS_ROLE_MB_ROVER && value != AP_GPS::GPS_TYPE_UBLOX_RTK_ROVER) {839value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_ROVER;840requires_save_and_reboot = true;841return true;842} else {843cfg_step++;844}845}846847if (strcmp(name, "GPS_MB_ONLY_PORT") == 0 && cfg_step == STEP_SET_MB_CAN_TX) {848if (option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && !value) {849// set up so that another CAN port is used for the Moving Baseline Data850// setting this value will allow another CAN port to be used as dedicated851// line for the Moving Baseline Data852value = 1;853requires_save_and_reboot = true;854return true;855} else if (!option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && value) {856// set up so that all CAN ports are used for the Moving Baseline Data857value = 0;858requires_save_and_reboot = true;859return true;860} else {861cfg_step++;862}863}864return false;865}866867bool AP_GPS_DroneCAN::handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, float &value)868{869Debug("AP_GPS_DroneCAN: param set/get response from %d %s %f\n", node_id, name, value);870return false;871}872873void AP_GPS_DroneCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success)874{875Debug("AP_GPS_DroneCAN: param save response from %d %s\n", node_id, success ? "success" : "failure");876877if (cfg_step != STEP_SAVE_AND_REBOOT) {878return;879}880881if (success) {882cfg_step++;883}884// Also send reboot command885// this is ok as we are sending from DroneCAN thread context886Debug("AP_GPS_DroneCAN: sending reboot command %d\n", node_id);887ap_dronecan->send_reboot_request(node_id);888}889890#if AP_DRONECAN_SEND_GPS891bool AP_GPS_DroneCAN::instance_exists(const AP_DroneCAN* ap_dronecan)892{893for (uint8_t i=0; i<ARRAY_SIZE(_detected_modules); i++) {894if (ap_dronecan == _detected_modules[i].ap_dronecan) {895return true;896}897}898return false;899}900#endif // AP_DRONECAN_SEND_GPS901902#endif // AP_GPS_DRONECAN_ENABLED903904905