2015-12-22 19:12:15 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#include "Copter.h"
|
|
|
|
|
|
|
|
// performs pre-arm checks. expects to be called at 1hz.
|
|
|
|
void Copter::update_arming_checks(void)
|
|
|
|
{
|
|
|
|
// perform pre-arm checks & display failures every 30 seconds
|
|
|
|
static uint8_t pre_arm_display_counter = PREARM_DISPLAY_PERIOD/2;
|
|
|
|
pre_arm_display_counter++;
|
|
|
|
bool display_fail = false;
|
|
|
|
if (pre_arm_display_counter >= PREARM_DISPLAY_PERIOD) {
|
|
|
|
display_fail = true;
|
|
|
|
pre_arm_display_counter = 0;
|
|
|
|
}
|
|
|
|
|
2015-12-24 01:08:00 -04:00
|
|
|
if (pre_arm_checks(display_fail)) {
|
2015-12-22 19:12:15 -04:00
|
|
|
set_pre_arm_check(true);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// performs pre-arm checks and arming checks
|
|
|
|
bool Copter::all_arming_checks_passing(bool arming_from_gcs)
|
|
|
|
{
|
|
|
|
if (pre_arm_checks(true)) {
|
|
|
|
set_pre_arm_check(true);
|
2016-01-21 22:59:47 -04:00
|
|
|
} else {
|
|
|
|
return false;
|
2015-12-22 19:12:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
return ap.pre_arm_check && arm_checks(true, arming_from_gcs);
|
|
|
|
}
|
|
|
|
|
|
|
|
// perform pre-arm checks and set ap.pre_arm_check flag
|
|
|
|
// return true if the checks pass successfully
|
|
|
|
bool Copter::pre_arm_checks(bool display_failure)
|
|
|
|
{
|
|
|
|
// exit immediately if already armed
|
|
|
|
if (motors.armed()) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if motor interlock and Emergency Stop aux switches are used
|
|
|
|
// at the same time. This cannot be allowed.
|
|
|
|
if (check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) && check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Interlock/E-Stop Conflict");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if motor interlock aux switch is in use
|
|
|
|
// if it is, switch needs to be in disabled position to arm
|
|
|
|
// otherwise exit immediately. This check to be repeated,
|
|
|
|
// as state can change at any time.
|
2016-01-21 22:59:47 -04:00
|
|
|
if (ap.using_interlock && ap.motor_interlock_switch) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Motor Interlock Enabled");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// exit immediately if we've already successfully performed the pre-arm check
|
|
|
|
if (ap.pre_arm_check) {
|
|
|
|
// run gps checks because results may change and affect LED colour
|
|
|
|
// no need to display failures because arm_checks will do that if the pilot tries to arm
|
|
|
|
pre_arm_gps_checks(false);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// succeed if pre arm checks are disabled
|
2015-12-24 01:08:00 -04:00
|
|
|
if (g.arming_check == ARMING_CHECK_NONE) {
|
2015-12-22 19:12:15 -04:00
|
|
|
set_pre_arm_check(true);
|
|
|
|
set_pre_arm_rc_check(true);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-10-13 12:51:55 -03:00
|
|
|
return barometer_checks(display_failure)
|
|
|
|
& rc_calibration_checks(display_failure)
|
|
|
|
& compass_checks(display_failure)
|
|
|
|
& gps_checks(display_failure)
|
|
|
|
& fence_checks(display_failure)
|
|
|
|
& ins_checks(display_failure)
|
|
|
|
& board_voltage_checks(display_failure)
|
|
|
|
& parameter_checks(display_failure)
|
|
|
|
& pilot_throttle_checks(display_failure);
|
2016-08-15 09:02:48 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool Copter::rc_calibration_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
// pre-arm rc checks a prerequisite
|
|
|
|
pre_arm_rc_checks();
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!ap.pre_arm_rc_check) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: RC not calibrated");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2016-08-15 09:02:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Copter::barometer_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
// check Baro
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) {
|
|
|
|
// barometer health check
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!barometer.all_healthy()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Barometer not healthy");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// Check baro & inav alt are within 1m if EKF is operating in an absolute position mode.
|
|
|
|
// Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height
|
|
|
|
// that may differ from the baro height due to baro drift.
|
|
|
|
nav_filter_status filt_status = inertial_nav.get_filter_status();
|
|
|
|
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
|
|
|
|
if (using_baro_ref) {
|
|
|
|
if (fabsf(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Altitude disparity");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2016-08-15 09:02:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
2015-12-22 19:12:15 -04:00
|
|
|
|
2016-08-15 09:02:48 -03:00
|
|
|
bool Copter::compass_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
// check Compass
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_COMPASS)) {
|
2015-12-29 00:40:04 -04:00
|
|
|
//check if compass has calibrated and requires reboot
|
|
|
|
if (compass.compass_cal_requires_reboot()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass calibrated requires reboot");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-12-22 19:12:15 -04:00
|
|
|
// check the primary compass is healthy
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!compass.healthy()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not healthy");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check compass learning is on or offsets have been set
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!compass.configured()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not calibrated");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for unreasonable compass offsets
|
|
|
|
Vector3f offsets = compass.get_offsets();
|
2015-12-24 01:08:00 -04:00
|
|
|
if (offsets.length() > COMPASS_OFFSETS_MAX) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass offsets too high");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for unreasonable mag field length
|
|
|
|
float mag_field = compass.get_field().length();
|
|
|
|
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check mag field");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check all compasses point in roughly same direction
|
|
|
|
if (!compass.consistent()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent compasses");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
|
2016-08-15 09:02:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Copter::gps_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
// check GPS
|
|
|
|
if (!pre_arm_gps_checks(display_failure)) {
|
|
|
|
return false;
|
|
|
|
}
|
2016-08-15 09:02:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
2015-12-22 19:12:15 -04:00
|
|
|
|
2016-08-15 09:02:48 -03:00
|
|
|
bool Copter::fence_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
#if AC_FENCE == ENABLED
|
|
|
|
// check fence is initialised
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!fence.pre_arm_check()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check fence");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif
|
2016-08-15 09:02:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
2015-12-22 19:12:15 -04:00
|
|
|
|
2016-08-15 09:02:48 -03:00
|
|
|
bool Copter::ins_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
// check INS
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
|
|
|
// check accelerometers have been calibrated
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!ins.accel_calibrated_ok_all()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Accels not calibrated");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check accels are healthy
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!ins.get_accel_health_all()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Accelerometers not healthy");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-12-29 00:36:11 -04:00
|
|
|
//check if accelerometers have calibrated and require reboot
|
|
|
|
if (ins.accel_cal_requires_reboot()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accelerometers calibrated requires reboot");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-12-22 19:12:15 -04:00
|
|
|
// check all accelerometers point in roughly same direction
|
|
|
|
if (ins.get_accel_count() > 1) {
|
|
|
|
const Vector3f &prime_accel_vec = ins.get_accel();
|
|
|
|
for(uint8_t i=0; i<ins.get_accel_count(); i++) {
|
|
|
|
// get next accel vector
|
|
|
|
const Vector3f &accel_vec = ins.get_accel(i);
|
|
|
|
Vector3f vec_diff = accel_vec - prime_accel_vec;
|
|
|
|
float threshold = PREARM_MAX_ACCEL_VECTOR_DIFF;
|
|
|
|
if (i >= 2) {
|
|
|
|
/*
|
2015-12-24 01:08:00 -04:00
|
|
|
* for boards with 3 IMUs we only use the first two
|
|
|
|
* in the EKF. Allow for larger accel discrepancy
|
|
|
|
* for IMU3 as it may be running at a different temperature
|
2015-12-22 19:12:15 -04:00
|
|
|
*/
|
|
|
|
threshold *= 2;
|
|
|
|
}
|
2016-07-27 22:22:39 -03:00
|
|
|
|
|
|
|
// EKF is less sensitive to Z-axis error
|
|
|
|
vec_diff.z *= 0.5f;
|
|
|
|
|
2015-12-22 19:12:15 -04:00
|
|
|
if (vec_diff.length() > threshold) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Accelerometers");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// check gyros are healthy
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!ins.get_gyro_health_all()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Gyros not healthy");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check all gyros are consistent
|
|
|
|
if (ins.get_gyro_count() > 1) {
|
|
|
|
for(uint8_t i=0; i<ins.get_gyro_count(); i++) {
|
|
|
|
// get rotation rate difference between gyro #i and primary gyro
|
|
|
|
Vector3f vec_diff = ins.get_gyro(i) - ins.get_gyro();
|
|
|
|
if (vec_diff.length() > PREARM_MAX_GYRO_VECTOR_DIFF) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Gyros");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// get ekf attitude (if bad, it's usually the gyro biases)
|
|
|
|
if (!pre_arm_ekf_attitude_check()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: gyros still settling");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
2016-08-15 09:02:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Copter::board_voltage_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
#if CONFIG_HAL_BOARD != HAL_BOARD_VRBRAIN
|
|
|
|
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
|
|
|
|
// check board voltage
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
|
2015-12-24 01:08:00 -04:00
|
|
|
if (hal.analogin->board_voltage() < BOARD_VOLTAGE_MIN || hal.analogin->board_voltage() > BOARD_VOLTAGE_MAX) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check Board Voltage");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// check battery voltage
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
|
|
|
|
if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check Battery");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-08-15 09:02:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Copter::parameter_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
// check various parameter values
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) {
|
|
|
|
|
|
|
|
// ensure ch7 and ch8 have different functions
|
|
|
|
if (check_duplicate_auxsw()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Duplicate Aux Switch Options");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// failsafe parameter checks
|
|
|
|
if (g.failsafe_throttle) {
|
|
|
|
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (channel_throttle->get_radio_min() <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check FS_THR_VALUE");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// lean angle parameter check
|
|
|
|
if (aparm.angle_max < 1000 || aparm.angle_max > 8000) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check ANGLE_MAX");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// acro balance parameter check
|
2016-02-15 02:27:29 -04:00
|
|
|
if ((g.acro_balance_roll > attitude_control.get_angle_roll_p().kP()) || (g.acro_balance_pitch > attitude_control.get_angle_pitch_p().kP())) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: ACRO_BAL_ROLL/PITCH");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-04-27 07:55:35 -03:00
|
|
|
#if RANGEFINDER_ENABLED == ENABLED && OPTFLOW == ENABLED
|
2015-12-22 19:12:15 -04:00
|
|
|
// check range finder if optflow enabled
|
2016-04-27 08:37:04 -03:00
|
|
|
if (optflow.enabled() && !rangefinder.pre_arm_check()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check range finder");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif
|
2016-08-22 04:13:46 -03:00
|
|
|
|
|
|
|
#if PROXIMITY_ENABLED == ENABLED
|
|
|
|
// check proximity sensor if enabled
|
2016-10-14 02:02:29 -03:00
|
|
|
if (copter.g2.proximity.get_status() == AP_Proximity::Proximity_NoData) {
|
2016-08-22 04:13:46 -03:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check proximity sensor");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2015-12-22 19:12:15 -04:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
// check helicopter parameters
|
|
|
|
if (!motors.parameter_check(display_failure)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif // HELI_FRAME
|
2016-03-19 03:26:10 -03:00
|
|
|
|
|
|
|
// check for missing terrain data
|
2016-04-28 01:57:52 -03:00
|
|
|
if (!pre_arm_terrain_check(display_failure)) {
|
2016-03-19 03:26:10 -03:00
|
|
|
return false;
|
|
|
|
}
|
2016-07-21 09:42:32 -03:00
|
|
|
|
|
|
|
// check adsb avoidance failsafe
|
|
|
|
if (failsafe.adsb) {
|
|
|
|
if (display_failure) {
|
2016-08-12 16:52:49 -03:00
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: ADSB threat detected");
|
2016-07-21 09:42:32 -03:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2015-12-22 19:12:15 -04:00
|
|
|
}
|
|
|
|
|
2016-08-15 09:02:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Copter::pilot_throttle_checks(bool display_failure)
|
|
|
|
{
|
2015-12-22 19:12:15 -04:00
|
|
|
// check throttle is above failsafe throttle
|
|
|
|
// this is near the bottom to allow other failures to be displayed before checking pilot throttle
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->get_radio_in() < g.failsafe_throttle_value) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Collective below Failsafe");
|
|
|
|
#else
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Throttle below Failsafe");
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// perform pre_arm_rc_checks checks and set ap.pre_arm_rc_check flag
|
|
|
|
void Copter::pre_arm_rc_checks()
|
|
|
|
{
|
|
|
|
// exit immediately if we've already successfully performed the pre-arm rc check
|
2015-12-24 01:08:00 -04:00
|
|
|
if (ap.pre_arm_rc_check) {
|
2015-12-22 19:12:15 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set rc-checks to success if RC checks are disabled
|
|
|
|
if ((g.arming_check != ARMING_CHECK_ALL) && !(g.arming_check & ARMING_CHECK_RC)) {
|
|
|
|
set_pre_arm_rc_check(true);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if radio has been calibrated
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (!channel_throttle->min_max_configured()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check channels 1 & 2 have min <= 1300 and max >= 1700
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (channel_roll->get_radio_min() > 1300 || channel_roll->get_radio_max() < 1700 || channel_pitch->get_radio_min() > 1300 || channel_pitch->get_radio_max() < 1700) {
|
2015-12-22 19:12:15 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check channels 3 & 4 have min <= 1300 and max >= 1700
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (channel_throttle->get_radio_min() > 1300 || channel_throttle->get_radio_max() < 1700 || channel_yaw->get_radio_min() > 1300 || channel_yaw->get_radio_max() < 1700) {
|
2015-12-22 19:12:15 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check channels 1 & 2 have trim >= 1300 and <= 1700
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (channel_roll->get_radio_trim() < 1300 || channel_roll->get_radio_trim() > 1700 || channel_pitch->get_radio_trim() < 1300 || channel_pitch->get_radio_trim() > 1700) {
|
2015-12-22 19:12:15 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check channel 4 has trim >= 1300 and <= 1700
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (channel_yaw->get_radio_trim() < 1300 || channel_yaw->get_radio_trim() > 1700) {
|
2015-12-22 19:12:15 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if we've gotten this far rc is ok
|
|
|
|
set_pre_arm_rc_check(true);
|
|
|
|
}
|
|
|
|
|
|
|
|
// performs pre_arm gps related checks and returns true if passed
|
|
|
|
bool Copter::pre_arm_gps_checks(bool display_failure)
|
|
|
|
{
|
|
|
|
// always check if inertial nav has started and is ready
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!ahrs.healthy()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Nav Checks");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if flight mode requires GPS
|
|
|
|
bool gps_required = mode_requires_GPS(control_mode);
|
|
|
|
|
|
|
|
#if AC_FENCE == ENABLED
|
|
|
|
// if circular fence is enabled we need GPS
|
|
|
|
if ((fence.get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) != 0) {
|
|
|
|
gps_required = true;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// return true if GPS is not required
|
|
|
|
if (!gps_required) {
|
|
|
|
AP_Notify::flags.pre_arm_gps_check = true;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// ensure GPS is ok
|
|
|
|
if (!position_ok()) {
|
|
|
|
if (display_failure) {
|
|
|
|
const char *reason = ahrs.prearm_failure_reason();
|
|
|
|
if (reason) {
|
|
|
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
|
|
|
|
} else {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Need 3D Fix");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
AP_Notify::flags.pre_arm_gps_check = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check EKF compass variance is below failsafe threshold
|
|
|
|
float vel_variance, pos_variance, hgt_variance, tas_variance;
|
|
|
|
Vector3f mag_variance;
|
|
|
|
Vector2f offset;
|
|
|
|
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset);
|
|
|
|
if (mag_variance.length() >= g.fs_ekf_thresh) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: EKF compass variance");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check home and EKF origin are not too far
|
|
|
|
if (far_from_EKF_origin(ahrs.get_home())) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: EKF-home variance");
|
|
|
|
}
|
|
|
|
AP_Notify::flags.pre_arm_gps_check = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return true immediately if gps check is disabled
|
|
|
|
if (!(g.arming_check == ARMING_CHECK_ALL || g.arming_check & ARMING_CHECK_GPS)) {
|
|
|
|
AP_Notify::flags.pre_arm_gps_check = true;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-10-07 23:41:45 -03:00
|
|
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
|
|
|
// check GPS configuration has completed
|
|
|
|
uint8_t first_unconfigured = gps.first_unconfigured_gps();
|
|
|
|
if (first_unconfigured != AP_GPS::GPS_ALL_CONFIGURED) {
|
|
|
|
if (display_failure) {
|
|
|
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,
|
|
|
|
"PreArm: GPS %d failing configuration checks",
|
|
|
|
first_unconfigured + 1);
|
|
|
|
gps.broadcast_first_configuration_failure_reason();
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2015-12-22 19:12:15 -04:00
|
|
|
// warn about hdop separately - to prevent user confusion with no gps lock
|
|
|
|
if (gps.get_hdop() > g.gps_hdop_good) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: High GPS HDOP");
|
|
|
|
}
|
|
|
|
AP_Notify::flags.pre_arm_gps_check = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if we got here all must be ok
|
|
|
|
AP_Notify::flags.pre_arm_gps_check = true;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check ekf attitude is acceptable
|
|
|
|
bool Copter::pre_arm_ekf_attitude_check()
|
|
|
|
{
|
|
|
|
// get ekf filter status
|
|
|
|
nav_filter_status filt_status = inertial_nav.get_filter_status();
|
|
|
|
|
|
|
|
return filt_status.flags.attitude;
|
|
|
|
}
|
|
|
|
|
2016-03-19 03:26:10 -03:00
|
|
|
// check we have required terrain data
|
2016-04-28 01:57:52 -03:00
|
|
|
bool Copter::pre_arm_terrain_check(bool display_failure)
|
2016-03-19 03:26:10 -03:00
|
|
|
{
|
2016-04-21 22:58:36 -03:00
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
2016-03-19 03:26:10 -03:00
|
|
|
// succeed if not using terrain data
|
|
|
|
if (!terrain_use()) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-04-28 01:57:52 -03:00
|
|
|
// check if terrain following is enabled, using a range finder but RTL_ALT is higher than rangefinder's max range
|
|
|
|
// To-Do: modify RTL return path to fly at or above the RTL_ALT and remove this check
|
|
|
|
if ((rangefinder.num_sensors() > 0) && (g.rtl_altitude > rangefinder.max_distance_cm())) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: RTL_ALT above rangefinder max range");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-03-19 03:26:10 -03:00
|
|
|
// show terrain statistics
|
|
|
|
uint16_t terr_pending, terr_loaded;
|
|
|
|
terrain.get_statistics(terr_pending, terr_loaded);
|
2016-04-28 01:57:52 -03:00
|
|
|
bool have_all_data = (terr_pending <= 0);
|
|
|
|
if (!have_all_data && display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Terrain data");
|
|
|
|
}
|
|
|
|
return have_all_data;
|
2016-04-21 22:58:36 -03:00
|
|
|
#else
|
|
|
|
return true;
|
|
|
|
#endif
|
2016-03-19 03:26:10 -03:00
|
|
|
}
|
|
|
|
|
2015-12-22 19:12:15 -04:00
|
|
|
// arm_checks - perform final checks before arming
|
|
|
|
// always called just before arming. Return true if ok to arm
|
|
|
|
// has side-effect that logging is started
|
|
|
|
bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|
|
|
{
|
|
|
|
#if LOGGING_ENABLED == ENABLED
|
|
|
|
// start dataflash
|
|
|
|
start_logging();
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// check accels and gyro are healthy
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
2015-12-29 00:36:11 -04:00
|
|
|
//check if accelerometers have calibrated and require reboot
|
|
|
|
if (ins.accel_cal_requires_reboot()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accelerometers calibrated requires reboot");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!ins.get_accel_health_all()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Accelerometers not healthy");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!ins.get_gyro_health_all()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Gyros not healthy");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// get ekf attitude (if bad, it's usually the gyro biases)
|
|
|
|
if (!pre_arm_ekf_attitude_check()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: gyros still settling");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// always check if inertial nav has started and is ready
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!ahrs.healthy()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Waiting for Nav Checks");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-12-24 01:08:00 -04:00
|
|
|
if (compass.is_calibrating()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-12-29 00:40:04 -04:00
|
|
|
//check if compass has calibrated and requires reboot
|
|
|
|
if (compass.compass_cal_requires_reboot()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass calibrated requires reboot");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-12-22 19:12:15 -04:00
|
|
|
// always check if the current mode allows arming
|
|
|
|
if (!mode_allows_arming(control_mode, arming_from_gcs)) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Mode not armable");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// always check gps
|
|
|
|
if (!pre_arm_gps_checks(display_failure)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if we are using motor interlock switch and it's enabled, fail to arm
|
2016-08-02 04:07:48 -03:00
|
|
|
// skip check in Throw mode which takes control of the motor interlock
|
|
|
|
if (ap.using_interlock && motors.get_interlock()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Interlock Enabled");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if we are not using Emergency Stop switch option, force Estop false to ensure motors
|
|
|
|
// can run normally
|
|
|
|
if (!check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){
|
|
|
|
set_motor_emergency_stop(false);
|
|
|
|
// if we are using motor Estop switch, it must not be in Estop position
|
|
|
|
} else if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_emergency_stop){
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// succeed if arming checks are disabled
|
|
|
|
if (g.arming_check == ARMING_CHECK_NONE) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// baro checks
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) {
|
|
|
|
// baro health check
|
|
|
|
if (!barometer.all_healthy()) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Barometer not healthy");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// Check baro & inav alt are within 1m if EKF is operating in an absolute position mode.
|
|
|
|
// Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height
|
|
|
|
// that may differ from the baro height due to baro drift.
|
|
|
|
nav_filter_status filt_status = inertial_nav.get_filter_status();
|
|
|
|
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
|
|
|
|
if (using_baro_ref && (fabsf(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM)) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Altitude disparity");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
#if AC_FENCE == ENABLED
|
|
|
|
// check vehicle is within fence
|
2015-12-24 01:08:00 -04:00
|
|
|
if (!fence.pre_arm_check()) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: check fence");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// check lean angle
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
|
|
|
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > aparm.angle_max) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Leaning");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// check battery voltage
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
|
|
|
|
if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Check Battery");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-03-19 03:26:10 -03:00
|
|
|
// check for missing terrain data
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) {
|
2016-04-28 01:57:52 -03:00
|
|
|
if (!pre_arm_terrain_check(display_failure)) {
|
2016-03-19 03:26:10 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-07-21 09:42:32 -03:00
|
|
|
// check adsb
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) {
|
|
|
|
if (failsafe.adsb) {
|
|
|
|
if (display_failure) {
|
2016-08-12 16:52:49 -03:00
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: ADSB threat detected");
|
2016-07-21 09:42:32 -03:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-12-22 19:12:15 -04:00
|
|
|
// check throttle
|
|
|
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
|
|
|
|
// check throttle is not too low - must be above failsafe throttle
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->get_radio_in() < g.failsafe_throttle_value) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective below Failsafe");
|
|
|
|
#else
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle below Failsafe");
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check throttle is not too high - skips checks if arming from GCS in Guided
|
2016-08-01 05:44:12 -03:00
|
|
|
if (!(arming_from_gcs && (control_mode == GUIDED || control_mode == GUIDED_NOGPS))) {
|
2015-12-22 19:12:15 -04:00
|
|
|
// above top of deadband is too always high
|
2016-08-04 03:04:59 -03:00
|
|
|
if (get_pilot_desired_climb_rate(channel_throttle->get_control_in()) > 0.0f) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
|
|
|
|
#else
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// in manual modes throttle must be at zero
|
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
|
|
|
if ((mode_has_manual_throttle(control_mode) || control_mode == DRIFT) && channel_throttle->get_control_in() > 0) {
|
2015-12-22 19:12:15 -04:00
|
|
|
if (display_failure) {
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
|
|
|
|
#else
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if safety switch has been pushed
|
|
|
|
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
|
|
|
if (display_failure) {
|
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Safety Switch");
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if we've gotten this far all is ok
|
|
|
|
return true;
|
|
|
|
}
|