Copter: make control_sensor vars available outside of send_extended_status1

This commit is contained in:
floaledm 2016-05-03 16:34:40 -05:00 committed by Andrew Tridgell
parent c0bd21d9f2
commit 157db51b9d
2 changed files with 5 additions and 4 deletions

View File

@ -424,6 +424,11 @@ private:
AP_Frsky_Telem frsky_telemetry;
#endif
// Variables for extended status MAVLink messages
uint32_t control_sensors_present;
uint32_t control_sensors_enabled;
uint32_t control_sensors_health;
// Altitude
// The cm/s we are moving up or down based on filtered data - Positive = UP
int16_t climb_rate;

View File

@ -130,10 +130,6 @@ NOINLINE void Copter::send_limits_status(mavlink_channel_t chan)
NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
{
uint32_t control_sensors_present;
uint32_t control_sensors_enabled;
uint32_t control_sensors_health;
// default sensors present
control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT;