ardupilot/Rover/afs_rover.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

38 lines
882 B
C++
Raw Normal View History

2017-01-30 10:21:55 -04:00
/*
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
2020-02-21 09:09:57 -04:00
AP::arming().disarm(AP_Arming::Method::AFS);
2017-01-30 10:21:55 -04:00
// Set to HOLD mode
rover.set_mode(rover.mode_hold, ModeReason::CRASH_FAILSAFE);
2017-01-30 10:21:55 -04:00
}
/*
Return an AFS_MODE for current control mode
*/
AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Rover::afs_mode(void)
{
2017-07-19 01:34:04 -03:00
if (rover.control_mode->is_autopilot_mode()) {
2017-01-30 10:21:55 -04:00
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);
}
2017-01-30 10:21:55 -04:00
#endif // ADVANCED_FAILSAFE