diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 937e567b30..fe6e6a541a 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -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; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index efcecf9ae7..345cd8ee1e 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -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;