ardupilot/Rover/AP_Arming.h

38 lines
1.0 KiB
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-06-25 02:26:31 -03:00
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 arm_checks(AP_Arming::Method method) override;
2019-07-23 21:13:31 -03:00
bool rc_calibration_checks(const bool display_failure) override;
bool gps_checks(bool display_failure) override;
2017-06-30 15:48:35 -03:00
bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override;
bool arm(AP_Arming::Method method, bool do_arming_checks=true) override;
void update_soft_armed();
protected:
// the following check functions do not call into AP_Arming
2019-05-10 02:59:52 -03:00
bool oa_check(bool report);
bool parameter_checks(bool report);
bool mode_checks(bool report);
2021-07-13 09:14:30 -03:00
bool motor_checks(bool report);
bool pilot_throttle_checks(bool report);
2017-08-16 07:02:56 -03:00
};