diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index f810062dfe..63e0d97fbf 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -207,6 +207,11 @@ void Rover::send_extended_status1(mavlink_channel_t chan) 0, // comm drops in pkts, 0, 0, 0, 0); +#if FRSKY_TELEM_ENABLED == ENABLED + // give mask of error flags to Frsky_Telemetry + uint32_t sensors_error_flags = (control_sensors_health ^ control_sensors_enabled) & control_sensors_present; + frsky_telemetry.update_sensor_status_flags(sensors_error_flags); +#endif } void Rover::send_location(mavlink_channel_t chan) diff --git a/APMrover2/make.inc b/APMrover2/make.inc index a742dec9a8..8feecd24b9 100644 --- a/APMrover2/make.inc +++ b/APMrover2/make.inc @@ -38,7 +38,6 @@ LIBRARIES += AP_Navigation LIBRARIES += APM_Control LIBRARIES += AP_L1_Control LIBRARIES += AP_BoardConfig -LIBRARIES += AP_InertialNav LIBRARIES += AP_Frsky_Telem LIBRARIES += AP_Notify LIBRARIES += AP_BattMonitor diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 702065e166..b881804d55 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -129,7 +129,7 @@ void Rover::init_ardupilot() // setup frsky telemetry #if FRSKY_TELEM_ENABLED == ENABLED - frsky_telemetry.init(serial_manager, (uint8_t *)&control_mode); + frsky_telemetry.init(serial_manager); #endif mavlink_system.sysid = g.sysid_this_mav; @@ -277,6 +277,10 @@ void Rover::set_mode(enum mode mode) throttle = 500; g.pidSpeedThrottle.reset_I(); +#if FRSKY_TELEM_ENABLED == ENABLED + frsky_telemetry.update_control_mode(control_mode); +#endif + if (control_mode != AUTO) { auto_triggered = false; } diff --git a/APMrover2/wscript b/APMrover2/wscript index 93192aa203..e63f470672 100644 --- a/APMrover2/wscript +++ b/APMrover2/wscript @@ -10,7 +10,6 @@ def build(bld): 'APM_Control', 'AP_Arming', 'AP_Camera', - 'AP_InertialNav', 'AP_Frsky_Telem', 'AP_L1_Control', 'AP_Menu',