ardupilot/APMrover2/AP_Arming.h

34 lines
831 B
C
Raw Normal View History

#pragma once
#include <AP_Arming/AP_Arming.h>
2017-08-16 07:02:56 -03:00
#include <AC_Fence/AC_Fence.h>
/*
a rover-specific arming class
*/
class AP_Arming_Rover : public AP_Arming
{
public:
2018-03-05 16:36:56 -04:00
AP_Arming_Rover(const AP_AHRS &ahrs_ref, Compass &compass,
2017-08-16 07:02:56 -03:00
const AP_BattMonitor &battery, const AC_Fence &fence)
2018-03-05 16:36:56 -04:00
: AP_Arming(ahrs_ref, compass, battery),
2017-08-16 07:02:56 -03:00
_fence(fence)
{
}
/* Do not allow copies */
AP_Arming_Rover(const AP_Arming_Rover &other) = delete;
AP_Arming_Rover &operator=(const AP_Arming_Rover&) = delete;
bool pre_arm_checks(bool report) override;
2017-06-30 15:48:35 -03:00
bool pre_arm_rc_checks(const bool display_failure);
bool gps_checks(bool display_failure) override;
2017-06-30 15:48:35 -03:00
protected:
2017-08-16 07:02:56 -03:00
bool fence_checks(bool report);
2017-08-16 07:57:42 -03:00
bool proximity_check(bool report);
2017-08-16 07:02:56 -03:00
private:
const AC_Fence& _fence;
};