From 5e73648d2a3024a7167587ab6bcd2c2123a5920e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Feb 2019 22:55:31 +1100 Subject: [PATCH] Rover: move FRsky telemetry up into common GCS telemetry class --- APMrover2/GCS_Mavlink.cpp | 4 ++-- APMrover2/GCS_Mavlink.h | 2 -- APMrover2/GCS_Rover.cpp | 4 ---- APMrover2/GCS_Rover.h | 3 +++ APMrover2/Rover.h | 5 ----- APMrover2/system.cpp | 7 ------- 6 files changed, 5 insertions(+), 20 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 6c3b987627..87e0923d9a 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -4,7 +4,7 @@ #include -MAV_TYPE GCS_MAVLINK_Rover::frame_type() const +MAV_TYPE GCS_Rover::frame_type() const { if (rover.is_boat()) { return MAV_TYPE_SURFACE_BOAT; @@ -55,7 +55,7 @@ MAV_MODE GCS_MAVLINK_Rover::base_mode() const return (MAV_MODE)_base_mode; } -uint32_t GCS_MAVLINK_Rover::custom_mode() const +uint32_t GCS_Rover::custom_mode() const { return rover.control_mode->mode_number(); } diff --git a/APMrover2/GCS_Mavlink.h b/APMrover2/GCS_Mavlink.h index 85d8f2b0d3..7d71ccac96 100644 --- a/APMrover2/GCS_Mavlink.h +++ b/APMrover2/GCS_Mavlink.h @@ -47,9 +47,7 @@ private: void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg) override; - MAV_TYPE frame_type() const override; MAV_MODE base_mode() const override; - uint32_t custom_mode() const override; MAV_STATE system_status() const override; int16_t vfr_hud_throttle() const override; diff --git a/APMrover2/GCS_Rover.cpp b/APMrover2/GCS_Rover.cpp index e77cde926b..fe2f740b33 100644 --- a/APMrover2/GCS_Rover.cpp +++ b/APMrover2/GCS_Rover.cpp @@ -117,8 +117,4 @@ void GCS_Rover::update_sensor_status_flags(void) control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL); control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL); } -#if FRSKY_TELEM_ENABLED == ENABLED - // give mask of error flags to Frsky_Telemetry - rover.frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present); -#endif } diff --git a/APMrover2/GCS_Rover.h b/APMrover2/GCS_Rover.h index db130b7b49..88b30b8dc6 100644 --- a/APMrover2/GCS_Rover.h +++ b/APMrover2/GCS_Rover.h @@ -17,6 +17,9 @@ public: // return GCS link at offset ofs const GCS_MAVLINK_Rover &chan(const uint8_t ofs) const override { return _chan[ofs]; }; + uint32_t custom_mode() const override; + MAV_TYPE frame_type() const override; + void update_sensor_status_flags(void) override; private: diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index d1aa60ceb0..0a079cd0a8 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -37,7 +37,6 @@ #include // Camera triggering #include // ArduPilot Mega Magnetometer Library #include // Compass declination library -#include #include #include // ArduPilot GPS library #include // Inertial Sensor (uncalibated IMU) Library @@ -299,10 +298,6 @@ private: FUNCTOR_BIND_MEMBER(&Rover::handle_battery_failsafe, void, const char*, const int8_t), _failsafe_priorities}; -#if FRSKY_TELEM_ENABLED == ENABLED - // FrSky telemetry support - AP_Frsky_Telem frsky_telemetry; -#endif #if DEVO_TELEM_ENABLED == ENABLED AP_DEVO_Telem devo_telemetry; #endif diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index e08b0dff57..b6d3a3a379 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -80,10 +80,6 @@ void Rover::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(serial_manager); - // setup frsky telemetry -#if FRSKY_TELEM_ENABLED == ENABLED - frsky_telemetry.init((is_boat() ? MAV_TYPE_SURFACE_BOAT : MAV_TYPE_GROUND_ROVER)); -#endif #if DEVO_TELEM_ENABLED == ENABLED devo_telemetry.init(); #endif @@ -260,9 +256,6 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason) // but it should be harmless to disable the fence temporarily in these situations as well g2.fence.manual_recovery_start(); -#if FRSKY_TELEM_ENABLED == ENABLED - frsky_telemetry.update_control_mode(control_mode->mode_number()); -#endif #if DEVO_TELEM_ENABLED == ENABLED devo_telemetry.update_control_mode(control_mode->mode_number()); #endif