mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 18:34:19 -04:00
Rover: fixes for Frsky_Telem API changes
This commit is contained in:
parent
185ef73684
commit
203e0c7472
@ -207,6 +207,11 @@ void Rover::send_extended_status1(mavlink_channel_t chan)
|
|||||||
0, // comm drops in pkts,
|
0, // comm drops in pkts,
|
||||||
0, 0, 0, 0);
|
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)
|
void Rover::send_location(mavlink_channel_t chan)
|
||||||
|
@ -38,7 +38,6 @@ LIBRARIES += AP_Navigation
|
|||||||
LIBRARIES += APM_Control
|
LIBRARIES += APM_Control
|
||||||
LIBRARIES += AP_L1_Control
|
LIBRARIES += AP_L1_Control
|
||||||
LIBRARIES += AP_BoardConfig
|
LIBRARIES += AP_BoardConfig
|
||||||
LIBRARIES += AP_InertialNav
|
|
||||||
LIBRARIES += AP_Frsky_Telem
|
LIBRARIES += AP_Frsky_Telem
|
||||||
LIBRARIES += AP_Notify
|
LIBRARIES += AP_Notify
|
||||||
LIBRARIES += AP_BattMonitor
|
LIBRARIES += AP_BattMonitor
|
||||||
|
@ -129,7 +129,7 @@ void Rover::init_ardupilot()
|
|||||||
|
|
||||||
// setup frsky telemetry
|
// setup frsky telemetry
|
||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
frsky_telemetry.init(serial_manager, (uint8_t *)&control_mode);
|
frsky_telemetry.init(serial_manager);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
mavlink_system.sysid = g.sysid_this_mav;
|
mavlink_system.sysid = g.sysid_this_mav;
|
||||||
@ -277,6 +277,10 @@ void Rover::set_mode(enum mode mode)
|
|||||||
throttle = 500;
|
throttle = 500;
|
||||||
g.pidSpeedThrottle.reset_I();
|
g.pidSpeedThrottle.reset_I();
|
||||||
|
|
||||||
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
|
frsky_telemetry.update_control_mode(control_mode);
|
||||||
|
#endif
|
||||||
|
|
||||||
if (control_mode != AUTO) {
|
if (control_mode != AUTO) {
|
||||||
auto_triggered = false;
|
auto_triggered = false;
|
||||||
}
|
}
|
||||||
|
@ -10,7 +10,6 @@ def build(bld):
|
|||||||
'APM_Control',
|
'APM_Control',
|
||||||
'AP_Arming',
|
'AP_Arming',
|
||||||
'AP_Camera',
|
'AP_Camera',
|
||||||
'AP_InertialNav',
|
|
||||||
'AP_Frsky_Telem',
|
'AP_Frsky_Telem',
|
||||||
'AP_L1_Control',
|
'AP_L1_Control',
|
||||||
'AP_Menu',
|
'AP_Menu',
|
||||||
|
Loading…
Reference in New Issue
Block a user