mirror of https://github.com/ArduPilot/ardupilot
Plane: FrSky support has moved to GCS
This commit is contained in:
parent
0194cd69a1
commit
1a55f0ffab
|
@ -2,7 +2,7 @@
|
|||
|
||||
#include "Plane.h"
|
||||
|
||||
MAV_TYPE GCS_MAVLINK_Plane::frame_type() const
|
||||
MAV_TYPE GCS_Plane::frame_type() const
|
||||
{
|
||||
return plane.quadplane.get_mav_type();
|
||||
}
|
||||
|
@ -87,7 +87,7 @@ MAV_MODE GCS_MAVLINK_Plane::base_mode() const
|
|||
return (MAV_MODE)_base_mode;
|
||||
}
|
||||
|
||||
uint32_t GCS_MAVLINK_Plane::custom_mode() const
|
||||
uint32_t GCS_Plane::custom_mode() const
|
||||
{
|
||||
return plane.control_mode;
|
||||
}
|
||||
|
|
|
@ -55,9 +55,7 @@ private:
|
|||
bool try_send_message(enum ap_message id) override;
|
||||
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;
|
||||
|
||||
uint8_t radio_in_rssi() const;
|
||||
|
|
|
@ -218,9 +218,4 @@ void GCS_Plane::update_sensor_status_flags(void)
|
|||
if (!plane.battery.healthy() || plane.battery.has_failsafed()) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_BATTERY;
|
||||
}
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// give mask of error flags to Frsky_Telemetry
|
||||
plane.frsky_telemetry.update_sensor_status_flags(~control_sensors_health & control_sensors_enabled & control_sensors_present);
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -23,6 +23,8 @@ public:
|
|||
protected:
|
||||
|
||||
void update_sensor_status_flags(void) override;
|
||||
uint32_t custom_mode() const override;
|
||||
MAV_TYPE frame_type() const override;
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -405,10 +405,6 @@ private:
|
|||
FUNCTOR_BIND_MEMBER(&Plane::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
|
||||
// DEVO-M telemetry support
|
||||
AP_DEVO_Telem devo_telemetry;
|
||||
|
|
|
@ -155,9 +155,6 @@ void Plane::update_is_flying_5Hz(void)
|
|||
}
|
||||
previous_is_flying = new_is_flying;
|
||||
adsb.set_is_flying(new_is_flying);
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
frsky_telemetry.set_is_flying(new_is_flying);
|
||||
#endif
|
||||
#if STATS_ENABLED == ENABLED
|
||||
g2.stats.set_flying(new_is_flying);
|
||||
#endif
|
||||
|
|
|
@ -139,6 +139,8 @@ public:
|
|||
float throttle_mix;
|
||||
};
|
||||
|
||||
MAV_TYPE get_mav_type(void) const;
|
||||
|
||||
private:
|
||||
AP_AHRS_NavEKF &ahrs;
|
||||
AP_Vehicle::MultiCopter aparm;
|
||||
|
@ -296,7 +298,6 @@ private:
|
|||
|
||||
// HEARTBEAT mav_type override
|
||||
AP_Int8 mav_type;
|
||||
MAV_TYPE get_mav_type(void) const;
|
||||
|
||||
// time we last got an EKF yaw reset
|
||||
uint32_t ekfYawReset_ms;
|
||||
|
|
|
@ -96,11 +96,6 @@ void Plane::init_ardupilot()
|
|||
// setup telem slots with serial ports
|
||||
gcs().setup_uarts(serial_manager);
|
||||
|
||||
// setup frsky
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// setup frsky, and pass a number of parameters to the library
|
||||
frsky_telemetry.init(MAV_TYPE_FIXED_WING);
|
||||
#endif
|
||||
#if DEVO_TELEM_ENABLED == ENABLED
|
||||
devo_telemetry.init();
|
||||
#endif
|
||||
|
@ -308,9 +303,6 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason)
|
|||
previous_mode_reason = control_mode_reason;
|
||||
control_mode_reason = reason;
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
frsky_telemetry.update_control_mode(control_mode);
|
||||
#endif
|
||||
#if DEVO_TELEM_ENABLED == ENABLED
|
||||
devo_telemetry.update_control_mode(control_mode);
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue