AP_Arming: remove required, min-volt, min-volt2 params from Copter

This commit is contained in:
Randy Mackay 2016-12-28 14:41:21 +09:00
parent 5be3d14648
commit 593f035c53
2 changed files with 26 additions and 2 deletions

View File

@ -31,12 +31,15 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_Arming::var_info[] = { const AP_Param::GroupInfo AP_Arming::var_info[] = {
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
// @Param: REQUIRE // @Param: REQUIRE
// @DisplayName: Require Arming Motors // @DisplayName: Require Arming Motors
// @Description: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, require rudder stick or GCS arming before arming motors and send THR_MIN PWM to throttle channel when disarmed. If 2, require rudder stick or GCS arming and send 0 PWM to throttle channel when disarmed. See the ARMING_CHECK_* parameters to see what checks are done before arming. Note, if setting this parameter to 0 a reboot is required to arm the plane. Also note, even with this parameter at 0, if ARMING_CHECK parameter is not also zero the plane may fail to arm throttle at boot due to a pre-arm check failure. This parameter is relevant for ArduPlane only. // @Description: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, require rudder stick or GCS arming before arming motors and send THR_MIN PWM to throttle channel when disarmed. If 2, require rudder stick or GCS arming and send 0 PWM to throttle channel when disarmed. See the ARMING_CHECK_* parameters to see what checks are done before arming. Note, if setting this parameter to 0 a reboot is required to arm the plane. Also note, even with this parameter at 0, if ARMING_CHECK parameter is not also zero the plane may fail to arm throttle at boot due to a pre-arm check failure. This parameter is relevant for ArduPlane only.
// @Values: 0:Disabled,1:THR_MIN PWM when disarmed,2:0 PWM when disarmed // @Values: 0:Disabled,1:THR_MIN PWM when disarmed,2:0 PWM when disarmed
// @User: Advanced // @User: Advanced
AP_GROUPINFO_FLAGS("REQUIRE", 0, AP_Arming, require, 1, AP_PARAM_NO_SHIFT), AP_GROUPINFO_FLAGS("REQUIRE", 0, AP_Arming, require, 1, AP_PARAM_NO_SHIFT),
#endif
// @Param: CHECK // @Param: CHECK
// @DisplayName: Arm Checks to Peform (bitmask) // @DisplayName: Arm Checks to Peform (bitmask)
@ -54,6 +57,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD), AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
// @Param: MIN_VOLT // @Param: MIN_VOLT
// @DisplayName: Minimum arming voltage on the first battery // @DisplayName: Minimum arming voltage on the first battery
// @Description: The minimum voltage on the first battery to arm, 0 disables the check. This parameter is relevant for ArduPlane only. // @Description: The minimum voltage on the first battery to arm, 0 disables the check. This parameter is relevant for ArduPlane only.
@ -69,6 +73,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
// @Increment: 0.1 // @Increment: 0.1
// @User: Standard // @User: Standard
AP_GROUPINFO("MIN_VOLT2", 5, AP_Arming, _min_voltage[1], 0), AP_GROUPINFO("MIN_VOLT2", 5, AP_Arming, _min_voltage[1], 0),
#endif
AP_GROUPEND AP_GROUPEND
}; };
@ -85,6 +90,12 @@ AP_Arming::AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &comp
arming_method(NONE) arming_method(NONE)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
// default REQUIRE parameter to 1 (needed for Copter which is missing the parameter declaration above)
require.set_default(YES_MIN_PWM);
#endif
memset(last_accel_pass_ms, 0, sizeof(last_accel_pass_ms)); memset(last_accel_pass_ms, 0, sizeof(last_accel_pass_ms));
memset(last_gyro_pass_ms, 0, sizeof(last_gyro_pass_ms)); memset(last_gyro_pass_ms, 0, sizeof(last_gyro_pass_ms));
} }
@ -95,8 +106,8 @@ uint16_t AP_Arming::compass_magfield_expected() const
} }
bool AP_Arming::is_armed() bool AP_Arming::is_armed()
{ {
return require == NONE || armed; return require == NONE || armed;
} }
uint16_t AP_Arming::get_enabled_checks() uint16_t AP_Arming::get_enabled_checks()
@ -450,11 +461,13 @@ bool AP_Arming::board_voltage_checks(bool report)
bool AP_Arming::pre_arm_checks(bool report) bool AP_Arming::pre_arm_checks(bool report)
{ {
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
if (armed || require == NONE) { if (armed || require == NONE) {
// if we are already armed or don't need any arming checks // if we are already armed or don't need any arming checks
// then skip the checks // then skip the checks
return true; return true;
} }
#endif
return hardware_safety_check(report) return hardware_safety_check(report)
& barometer_checks(report) & barometer_checks(report)
@ -482,6 +495,10 @@ bool AP_Arming::arm_checks(uint8_t method)
//returns true if arming occurred successfully //returns true if arming occurred successfully
bool AP_Arming::arm(uint8_t method) bool AP_Arming::arm(uint8_t method)
{ {
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
// Copter should never use this function
return false;
#else
if (armed) { //already armed if (armed) { //already armed
return false; return false;
} }
@ -509,11 +526,16 @@ bool AP_Arming::arm(uint8_t method)
} }
return armed; return armed;
#endif
} }
//returns true if disarming occurred successfully //returns true if disarming occurred successfully
bool AP_Arming::disarm() bool AP_Arming::disarm()
{ {
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
// Copter should never use this function
return false;
#else
if (!armed) { // already disarmed if (!armed) { // already disarmed
return false; return false;
} }
@ -525,6 +547,7 @@ bool AP_Arming::disarm()
//Can't do this from this class until there is a unified logging library. //Can't do this from this class until there is a unified logging library.
return true; return true;
#endif
} }
AP_Arming::ArmingRequired AP_Arming::arming_required() AP_Arming::ArmingRequired AP_Arming::arming_required()

View File

@ -40,6 +40,7 @@ public:
AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass, AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery); const AP_BattMonitor &battery);
// these functions should not be used by Copter which holds the armed state in the motors library
ArmingRequired arming_required(); ArmingRequired arming_required();
virtual bool arm(uint8_t method); virtual bool arm(uint8_t method);
bool disarm(); bool disarm();