ardupilot/Rover/afs_rover.cpp
Ep Pravitra 9700e65d19 AP_AdvancedFailsafe: option to automatically set mode to auto when datalink is loss
When enabled, it ensures vehicle enters AUTO even if it is currently in other autonomous modes (for example Guided)
2023-09-12 09:09:39 +10:00

38 lines
882 B
C++

/*
Rover specific AP_AdvancedFailsafe class
*/
#include "Rover.h"
#if ADVANCED_FAILSAFE == ENABLED
/*
Setup radio_out values for all channels to termination values
*/
void AP_AdvancedFailsafe_Rover::terminate_vehicle(void)
{
// disarm as well
AP::arming().disarm(AP_Arming::Method::AFS);
// Set to HOLD mode
rover.set_mode(rover.mode_hold, ModeReason::CRASH_FAILSAFE);
}
/*
Return an AFS_MODE for current control mode
*/
AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Rover::afs_mode(void)
{
if (rover.control_mode->is_autopilot_mode()) {
return AP_AdvancedFailsafe::AFS_AUTO;
}
return AP_AdvancedFailsafe::AFS_STABILIZED;
}
//to force entering auto mode when datalink loss
void AP_AdvancedFailsafe_Rover::set_mode_auto(void)
{
over.set_mode(rover.mode_auto,ModeReason::GCS_FAILSAFE);
}
#endif // ADVANCED_FAILSAFE