mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: add and use AP_ADVANCEDFAILSAFE_ENABLED
This commit is contained in:
parent
c12486829a
commit
8259f3f870
|
@ -7,6 +7,7 @@
|
|||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe_config.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include "GCS_MAVLink.h"
|
||||
|
@ -531,6 +532,7 @@ protected:
|
|||
MAV_RESULT handle_command_request_message(const mavlink_command_long_t &packet);
|
||||
|
||||
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
|
||||
|
||||
virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet);
|
||||
|
||||
void handle_send_autopilot_version(const mavlink_message_t &msg);
|
||||
|
|
|
@ -3048,6 +3048,7 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
|
|||
*/
|
||||
MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_long_t &packet)
|
||||
{
|
||||
#if AP_ADVANCEDFAILSAFE_ENABLED
|
||||
AP_AdvancedFailsafe *failsafe = AP::advancedfailsafe();
|
||||
if (failsafe == nullptr) {
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
|
@ -3059,6 +3060,9 @@ MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_long_t &
|
|||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
#else
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -6249,11 +6253,13 @@ uint64_t GCS_MAVLINK::capabilities() const
|
|||
ret |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
|
||||
}
|
||||
|
||||
#if AP_ADVANCEDFAILSAFE_ENABLED
|
||||
AP_AdvancedFailsafe *failsafe = AP::advancedfailsafe();
|
||||
if (failsafe != nullptr && failsafe->enabled()) {
|
||||
// Copter and Sub may also set this bit as they can always terminate
|
||||
ret |= MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAL_RALLY_ENABLED
|
||||
if (AP::rally()) {
|
||||
|
|
Loading…
Reference in New Issue