ardupilot/libraries/AP_Arming/AP_Arming.h

113 lines
3.4 KiB
C
Raw Normal View History

#pragma once
#include <AP_AHRS/AP_AHRS.h>
2016-02-09 19:31:12 -04:00
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <RC_Channel/RC_Channel.h>
class AP_Arming {
public:
enum ArmingChecks {
ARMING_CHECK_NONE = 0x0000,
ARMING_CHECK_ALL = 0x0001,
ARMING_CHECK_BARO = 0x0002,
ARMING_CHECK_COMPASS = 0x0004,
ARMING_CHECK_GPS = 0x0008,
ARMING_CHECK_INS = 0x0010,
ARMING_CHECK_PARAMETERS = 0x0020,
ARMING_CHECK_RC = 0x0040,
ARMING_CHECK_VOLTAGE = 0x0080,
ARMING_CHECK_BATTERY = 0x0100,
ARMING_CHECK_AIRSPEED = 0x0200,
ARMING_CHECK_LOGGING = 0x0400,
ARMING_CHECK_SWITCH = 0x0800,
2016-02-19 16:28:29 -04:00
ARMING_CHECK_GPS_CONFIG = 0x1000,
};
enum ArmingMethod {
NONE = 0,
RUDDER,
MAVLINK
};
enum ArmingRequired {
2013-12-19 20:59:05 -04:00
NO = 0,
YES_MIN_PWM = 1,
YES_ZERO_PWM = 2
};
// these functions should not be used by Copter which holds the armed state in the motors library
ArmingRequired arming_required();
virtual bool arm(uint8_t method);
2013-12-11 01:09:11 -04:00
bool disarm();
bool is_armed();
// get bitmask of enabled checks
2013-12-11 01:09:11 -04:00
uint16_t get_enabled_checks();
// pre_arm_checks() is virtual so it can be modified in a vehicle specific subclass
virtual bool pre_arm_checks(bool report);
// some arming checks have side-effects, or require some form of state
// change to have occurred, and thus should not be done as pre-arm
// checks. Those go here:
bool arm_checks(uint8_t method);
// get expected magnetic field strength
uint16_t compass_magfield_expected() const;
static const struct AP_Param::GroupInfo var_info[];
protected:
2017-08-30 17:09:05 -03:00
AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery);
2015-10-12 02:29:27 -03:00
// Parameters
AP_Int8 require;
AP_Int16 checks_to_perform; // bitmask for which checks are required
AP_Float accel_error_threshold;
AP_Float _min_voltage[AP_BATT_MONITOR_MAX_INSTANCES];
2015-10-12 02:29:27 -03:00
// references
const AP_AHRS &ahrs;
const AP_Baro &barometer;
Compass &_compass;
2016-02-09 19:31:12 -04:00
const AP_BattMonitor &_battery;
2015-10-12 02:29:27 -03:00
// internal members
bool armed:1;
bool logging_available:1;
uint8_t arming_method; // how the vehicle was armed
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
virtual bool barometer_checks(bool report);
bool airspeed_checks(bool report);
bool logging_checks(bool report);
2015-10-16 00:51:46 -03:00
virtual bool ins_checks(bool report);
virtual bool compass_checks(bool report);
virtual bool gps_checks(bool report);
bool battery_checks(bool report);
bool hardware_safety_check(bool report);
virtual bool board_voltage_checks(bool report);
2015-10-16 00:13:53 -03:00
virtual bool rc_calibration_checks(bool report);
bool manual_transmitter_checks(bool report);
virtual enum HomeState home_status() const = 0;
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max = true) const;
};