21 #define AP_ARMING_COMPASS_MAGFIELD_EXPECTED 530 22 #define AP_ARMING_COMPASS_MAGFIELD_MIN 185 // 0.35 * 530 milligauss 23 #define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss 24 #define AP_ARMING_BOARD_VOLTAGE_MIN 4.3f 25 #define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f 26 #define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f 27 #define AP_ARMING_AHRS_GPS_ERROR_MAX 10 // accept up to 10m difference between AHRS and GPS 91 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) 121 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Barometer not healthy");
135 if (airspeed ==
nullptr) {
142 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Airspeed[%u] not healthy", i);
158 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Logging failed");
164 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: No SD card");
179 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Gyros not healthy");
185 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Gyros not calibrated");
191 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Accels not healthy");
197 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: 3D Accel calibration needed");
205 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Accels calibrated requires reboot");
219 Vector3f vec_diff = accel_vec - prime_accel_vec;
234 if (vec_diff.
length() <= threshold) {
239 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Accels inconsistent");
255 Vector3f vec_diff = gyro_vec - prime_gyro_vec;
263 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Gyros inconsistent");
286 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Compass not healthy");
293 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Compass not calibrated");
301 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Compass calibration running");
309 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Compass calibrated requires reboot");
318 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Compass offsets too high");
327 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Check mag field");
335 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Compasses inconsistent");
353 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Bad GPS Position");
361 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: GPS is not healthy");
371 "PreArm: GPS positions differ by %4.1fm",
378 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: GPS blending unhealthy");
390 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: GPS and AHRS differ by %4.1fm", (
double)distance);
402 "PreArm: GPS %d failing configuration checks",
403 first_unconfigured + 1);
420 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Battery failsafe on");
428 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Battery %d voltage %.1f below minimum %.1f",
448 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Hardware safety switch");
459 bool check_passed =
true;
468 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: RC%d minimum is greater than trim", i + 1);
470 check_passed =
false;
474 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: RC%d maximum is less than trim", i + 1);
476 check_passed =
false;
490 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Radio failsafe on");
505 bool check_passed =
true;
512 const uint16_t trim = ch->
get_trim();
515 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: SERVO%d minimum is greater than trim", i + 1);
517 check_passed =
false;
521 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: SERVO%d maximum is less than trim", i + 1);
523 check_passed =
false;
532 #if HAL_HAVE_BOARD_VOLTAGE 537 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: Check board voltage");
548 #if !APM_BUILD_TYPE(APM_BUILD_ArduCopter) 573 if (!
AP::gps().prepare_for_arming()) {
585 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"Arm: Logging not started");
595 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) 632 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) 641 gcs().
send_text(MAV_SEVERITY_INFO,
"Throttle disarmed");
666 const char *channel_names[] = {
"Roll",
"Pitch",
"Throttle",
"Yaw" };
668 for (uint8_t i=0; i<
ARRAY_SIZE(channel_names);i++) {
670 const char *channel_name = channel_names[i];
673 if (display_failure) {
674 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: RC %s not configured", channel_name);
679 if (display_failure) {
680 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: %s radio min too high", channel_name);
685 if (display_failure) {
686 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: %s radio max too low", channel_name);
696 if (display_failure) {
697 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: %s radio trim below min", channel_name);
704 if (display_failure) {
705 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"PreArm: %s radio trim above max", channel_name);
bool accel_cal_requires_reboot() const
bool enabled(uint8_t i) const
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
bool servo_checks(bool report) const
virtual bool arm(uint8_t method)
SRV_Channel::Aux_servo_function_t get_function(void) const
int16_t get_radio_trim() const
virtual float board_voltage(void)=0
bool logging_checks(bool report)
static RC_Channel * rc_channel(uint8_t chan)
const Vector3f & get_gyro(uint8_t i) const
virtual bool get_position(struct Location &loc) const =0
Interface definition for the various Ground Control System.
bool logging_started(void)
uint16_t get_output_max(void) const
virtual bool barometer_checks(bool report)
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define AP_ARMING_BOARD_VOLTAGE_MAX
bool all_consistent(float &distance) const
void broadcast_first_configuration_failure_reason(void) const
bool is_healthy(uint8_t instance) const
#define AP_PARAM_FRAME_ROVER
bool configured(uint8_t i)
bool use_accel(uint8_t instance) const
const Location & location(uint8_t instance) const
static uint16_t channels[SRXL_MAX_CHANNELS]
#define AP_ARMING_BOARD_VOLTAGE_MIN
void fail(const char *why)
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES]
AP_Float accel_error_threshold
virtual bool ins_checks(bool report)
static AP_InertialSensor ins
AP_Float _min_voltage[AP_BATT_MONITOR_MAX_INSTANCES]
const AP_Airspeed * get_airspeed(void) const
const Vector3f & get_accel(uint8_t i) const
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
uint16_t get_enabled_checks()
#define AP_GROUPINFO_FLAGS_FRAME(name, idx, clazz, element, def, flags, frame_flags)
static SRV_Channel * srv_channel(uint8_t i)
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
bool get_accel_health_all(void) const
static const struct AP_Param::GroupInfo var_info[]
bool use_gyro(uint8_t instance) const
Object managing one RC channel.
#define AP_PARAM_NO_SHIFT
bool manual_transmitter_checks(bool report)
bool blend_health_check() const
AP_Int16 checks_to_perform
bool min_max_configured() const
const Vector3f & get_offsets(uint8_t i) const
virtual bool pre_arm_checks(bool report)
static DataFlash_Class * instance(void)
#define AP_ARMING_COMPASS_MAGFIELD_MAX
virtual enum safety_state safety_switch_state(void)
uint16_t get_output_min(void) const
bool healthy[COMPASS_MAX_INSTANCES]
uint16_t get_offsets_max(void) const
#define AP_ARMING_COMPASS_MAGFIELD_MIN
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define AP_ARMING_ACCEL_ERROR_THRESHOLD
GPS_Status status(uint8_t instance) const
Query GPS status.
uint16_t compass_magfield_expected() const
bool hardware_safety_check(bool report)
virtual bool gps_checks(bool report)
#define AIRSPEED_MAX_SENSORS
bool learn_offsets_enabled() const
AP_BattMonitor & battery()
bool battery_checks(bool report)
uint16_t get_trim(void) const
virtual bool rc_calibration_checks(bool report)
ArmingRequired arming_required()
static constexpr float radians(float deg)
static struct notify_flags_and_values_type flags
#define AP_ARMING_COMPASS_MAGFIELD_EXPECTED
bool airspeed_checks(bool report)
int16_t get_radio_min() const
int16_t get_radio_max() const
#define AP_PARAM_FRAME_PLANE
bool arm_checks(uint8_t method)
bool gyro_calibrated_ok_all() const
virtual bool compass_checks(bool report)
bool is_calibrating() const
uint8_t get_gyro_count(void) const
AP_InertialSensor & ins()
#define AP_ARMING_AHRS_GPS_ERROR_MAX
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES]
Receiving valid messages and 3D lock.
uint8_t first_unconfigured_gps(void) const
const AP_BattMonitor & _battery
AP_Arming(const AP_AHRS &ahrs_ref, Compass &compass, const AP_BattMonitor &battery)
uint8_t num_instances(void) const
float voltage(uint8_t instance) const
voltage - returns battery voltage in millivolts
bool accel_calibrated_ok_all() const
bool healthy(uint8_t i) const
#define NUM_SERVO_CHANNELS
virtual bool board_voltage_checks(bool report)
bool compass_cal_requires_reboot()
bool get_gyro_health_all(void) const
uint8_t get_accel_count(void) const
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max=true) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
AP_HAL::AnalogIn * analogin