mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Plane: fixes for Fraky_Telem API changes
This commit is contained in:
parent
a14ff8ac77
commit
a0fb426a34
@ -344,6 +344,12 @@ void Plane::send_extended_status1(mavlink_channel_t chan)
|
||||
0, // comm drops %,
|
||||
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 Plane::send_location(mavlink_channel_t chan)
|
||||
|
@ -160,7 +160,7 @@ void Plane::init_ardupilot()
|
||||
// setup frsky
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// setup frsky, and pass a number of parameters to the library
|
||||
frsky_telemetry.init(serial_manager, (uint8_t *)&control_mode);
|
||||
frsky_telemetry.init(serial_manager);
|
||||
#endif
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
@ -356,6 +356,10 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason)
|
||||
previous_mode_reason = control_mode_reason;
|
||||
control_mode_reason = reason;
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
frsky_telemetry.update_control_mode(control_mode);
|
||||
#endif
|
||||
|
||||
if (previous_mode == AUTOTUNE && control_mode != AUTOTUNE) {
|
||||
// restore last gains
|
||||
autotune_restore();
|
||||
|
Loading…
Reference in New Issue
Block a user