Rover: fixes for Frsky_Telem API changes

This commit is contained in:
Andrew Tridgell 2016-08-10 08:27:42 +10:00
parent 185ef73684
commit 203e0c7472
4 changed files with 10 additions and 3 deletions

View File

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

View File

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

View File

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

View File

@ -10,7 +10,6 @@ def build(bld):
'APM_Control',
'AP_Arming',
'AP_Camera',
'AP_InertialNav',
'AP_Frsky_Telem',
'AP_L1_Control',
'AP_Menu',