Rover: move FRsky telemetry up into common GCS telemetry class

This commit is contained in:
Peter Barker 2019-02-12 22:55:31 +11:00 committed by Peter Barker
parent 4e49e89b33
commit 5e73648d2a
6 changed files with 5 additions and 20 deletions

View File

@ -4,7 +4,7 @@
#include <AP_RangeFinder/RangeFinder_Backend.h>
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();
}

View File

@ -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;

View File

@ -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
}

View File

@ -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:

View File

@ -37,7 +37,6 @@
#include <AP_Camera/AP_Camera.h> // Camera triggering
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_Declination/AP_Declination.h> // Compass declination library
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_Devo_Telem/AP_Devo_Telem.h>
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
#include <AP_InertialSensor/AP_InertialSensor.h> // 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

View File

@ -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