|
|
|
@ -2490,7 +2490,7 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
@@ -2490,7 +2490,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) |
|
|
|
|
{ |
|
|
|
|
AP_AdvancedFailsafe *failsafe = get_advanced_failsafe(); |
|
|
|
|
AP_AdvancedFailsafe *failsafe = AP::advancedfailsafe(); |
|
|
|
|
if (failsafe == nullptr) { |
|
|
|
|
return MAV_RESULT_UNSUPPORTED; |
|
|
|
|
} |
|
|
|
@ -4631,7 +4631,7 @@ uint64_t GCS_MAVLINK::capabilities() const
@@ -4631,7 +4631,7 @@ uint64_t GCS_MAVLINK::capabilities() const
|
|
|
|
|
ret |= MAV_PROTOCOL_CAPABILITY_MAVLINK2; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
AP_AdvancedFailsafe *failsafe = get_advanced_failsafe(); |
|
|
|
|
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; |
|
|
|
|