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.h
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// DroneCAN GPS driver17//18#pragma once1920#include "AP_GPS_config.h"2122#if AP_GPS_DRONECAN_ENABLED2324#include <AP_Common/AP_Common.h>25#include <AP_HAL/AP_HAL.h>26#include "AP_GPS.h"27#include "GPS_Backend.h"28#include "RTCM3_Parser.h"29#include <AP_DroneCAN/AP_DroneCAN.h>3031class AP_GPS_DroneCAN : public AP_GPS_Backend {32public:33AP_GPS_DroneCAN(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role role);34~AP_GPS_DroneCAN();3536bool read() override;3738bool is_healthy(void) const override;3940bool logging_healthy(void) const override;4142bool is_configured(void) const override;4344const char *name() const override { return _name; }4546static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);47static AP_GPS_Backend* probe(AP_GPS &_gps, AP_GPS::GPS_State &_state);4849static void handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg);5051static void handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg);52static void handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg);53static void handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg);54#if GPS_MOVING_BASELINE55static void handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg);56static void handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg);57#endif58static bool inter_instance_pre_arm_checks(char failure_msg[], uint16_t failure_msg_len);59void inject_data(const uint8_t *data, uint16_t len) override;6061bool get_error_codes(uint32_t &error_codes) const override { error_codes = error_code; return seen_status; };6263#if GPS_MOVING_BASELINE64bool get_RTCMV3(const uint8_t *&data, uint16_t &len) override;65void clear_RTCMV3() override;66#endif6768#if AP_DRONECAN_SEND_GPS69static bool instance_exists(const AP_DroneCAN* ap_dronecan);70#endif7172private:7374bool param_configured = true;75enum config_step {76STEP_SET_TYPE = 0,77STEP_SET_MB_CAN_TX,78STEP_SAVE_AND_REBOOT,79STEP_FINISHED80};81uint8_t cfg_step;82bool requires_save_and_reboot;8384// returns true once configuration has finished85bool do_config(void);8687void handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec);88void handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg);89void handle_heading_msg(const ardupilot_gnss_Heading& msg);90void handle_status_msg(const ardupilot_gnss_Status& msg);91void handle_velocity(const float vx, const float vy, const float vz);9293#if GPS_MOVING_BASELINE94void handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id);95void handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id);96#endif9798static bool take_registry();99static void give_registry();100static AP_GPS_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id);101102bool _new_data;103AP_GPS::GPS_State interim_state;104105HAL_Semaphore sem;106107uint8_t _detected_module;108bool seen_message;109bool seen_fix2;110bool seen_aux;111bool seen_status;112bool seen_relposheading;113114bool healthy;115uint32_t status_flags;116uint32_t error_code;117char _name[16];118119// Module Detection Registry120static struct DetectedModules {121AP_DroneCAN* ap_dronecan;122uint8_t node_id;123uint8_t instance;124uint32_t last_inject_ms;125AP_GPS_DroneCAN* driver;126} _detected_modules[GPS_MAX_RECEIVERS];127128static HAL_Semaphore _sem_registry;129130#if GPS_MOVING_BASELINE131// RTCM3 parser for when in moving baseline base mode132RTCM3_Parser *rtcm3_parser;133#endif134// the role set from GPS_TYPE135AP_GPS::GPS_Role role;136137FUNCTOR_DECLARE(param_int_cb, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &);138FUNCTOR_DECLARE(param_float_cb, bool, AP_DroneCAN*, const uint8_t, const char*, float &);139FUNCTOR_DECLARE(param_save_cb, void, AP_DroneCAN*, const uint8_t, bool);140141bool handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, int32_t &value);142bool handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, float &value);143void handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success);144void send_rtcm(void);145146// GNSS RTCM injection147struct {148uint32_t last_send_ms;149ByteBuffer *buf;150} _rtcm_stream;151152// returns true if the supplied GPS_Type is a DroneCAN GPS type153static bool is_dronecan_gps_type(AP_GPS::GPS_Type type) {154return (155type == AP_GPS::GPS_TYPE_UAVCAN ||156type == AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE ||157type == AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER158);159}160};161162#endif // AP_GPS_DRONECAN_ENABLED163164165