ardupilot/APMrover2/AP_Arming.h

29 lines
587 B
C++

#pragma once
#include <AP_Arming/AP_Arming.h>
#include <AC_Fence/AC_Fence.h>
/*
a rover-specific arming class
*/
class AP_Arming_Rover : public AP_Arming
{
public:
AP_Arming_Rover() : AP_Arming() { }
/* 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;
bool pre_arm_rc_checks(const bool display_failure);
bool gps_checks(bool display_failure) override;
protected:
bool proximity_check(bool report);
private:
};