mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use singleton to get AP_AdvancedFailsafe pointer
This commit is contained in:
parent
9f8553d422
commit
2f60b230cd
|
@ -282,7 +282,6 @@ protected:
|
|||
// overridable method to check for packet acceptance. Allows for
|
||||
// enforcement of GCS sysid
|
||||
bool accept_packet(const mavlink_status_t &status, const mavlink_message_t &msg);
|
||||
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
|
||||
virtual bool set_mode(uint8_t mode) = 0;
|
||||
void set_ekf_origin(const Location& loc);
|
||||
|
||||
|
|
|
@ -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
|
|||
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;
|
||||
|
|
Loading…
Reference in New Issue