mirror of https://github.com/ArduPilot/ardupilot
AP_DDS: status topic to report RC failsafe with callback function
This commit is contained in:
parent
c03960cba4
commit
86f216703d
|
@ -632,15 +632,17 @@ bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Status& msg)
|
|||
msg.external_control = true; // Always true for now. To be filled after PR#28429.
|
||||
uint8_t fs_iter = 0;
|
||||
msg.failsafe_size = 0;
|
||||
if (AP_Notify::flags.failsafe_radio) {
|
||||
if (rc().in_rc_failsafe()) {
|
||||
msg.failsafe[fs_iter++] = FS_RADIO;
|
||||
}
|
||||
if (battery.has_failsafed()) {
|
||||
msg.failsafe[fs_iter++] = FS_BATTERY;
|
||||
}
|
||||
// TODO: replace flag with function.
|
||||
if (AP_Notify::flags.failsafe_gcs) {
|
||||
msg.failsafe[fs_iter++] = FS_GCS;
|
||||
}
|
||||
// TODO: replace flag with function.
|
||||
if (AP_Notify::flags.failsafe_ekf) {
|
||||
msg.failsafe[fs_iter++] = FS_EKF;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue