Plane: use parent AP_Arming rudder value

This commit is contained in:
Randy Mackay 2018-09-08 12:35:18 +09:00 committed by Andrew Tridgell
parent f039c6d5f4
commit 96d494c2e8
4 changed files with 5 additions and 19 deletions

View File

@ -8,12 +8,7 @@ const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = {
// variables from parent vehicle
AP_NESTEDGROUPINFO(AP_Arming, 0),
// @Param: RUDDER
// @DisplayName: Rudder Arming
// @Description: Control arm/disarm by rudder input. When enabled arming is done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero +- deadzone (RCx_DZ)
// @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm
// @User: Advanced
AP_GROUPINFO("RUDDER", 3, AP_Arming_Plane, rudder_arming_value, ARMING_RUDDER_ARMONLY),
// index 3 was RUDDER and should not be used
AP_GROUPEND
};

View File

@ -14,26 +14,16 @@ public:
AP_Param::setup_object_defaults(this, var_info);
}
enum ArmingRudder {
ARMING_RUDDER_DISABLED = 0,
ARMING_RUDDER_ARMONLY = 1,
ARMING_RUDDER_ARMDISARM = 2
};
/* Do not allow copies */
AP_Arming_Plane(const AP_Arming_Plane &other) = delete;
AP_Arming_Plane &operator=(const AP_Arming_Plane&) = delete;
bool pre_arm_checks(bool report);
ArmingRudder rudder_arming() const { return (ArmingRudder)rudder_arming_value.get(); }
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
protected:
bool ins_checks(bool report);
// parameters
AP_Int8 rudder_arming_value;
};

View File

@ -1260,6 +1260,7 @@ const AP_Param::ConversionInfo conversion_table[] = {
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_FS_LOW_VOLT" },
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_FS_LOW_MAH" },
{ Parameters::k_param_arming, 3, AP_PARAM_INT8, "ARMING_RUDDER" },
};
void Plane::load_parameters(void)

View File

@ -106,9 +106,9 @@ void Plane::init_rc_out_aux()
*/
void Plane::rudder_arm_disarm_check()
{
AP_Arming_Plane::ArmingRudder arming_rudder = arming.rudder_arming();
AP_Arming::ArmingRudder arming_rudder = arming.rudder_arming();
if (arming_rudder == AP_Arming_Plane::ARMING_RUDDER_DISABLED) {
if (arming_rudder == AP_Arming::ARMING_RUDDER_DISABLED) {
//parameter disallows rudder arming/disabling
return;
}
@ -147,7 +147,7 @@ void Plane::rudder_arm_disarm_check()
// not at full right rudder
rudder_arm_timer = 0;
}
} else if (arming_rudder == AP_Arming_Plane::ARMING_RUDDER_ARMDISARM && !is_flying()) {
} else if ((arming_rudder == AP_Arming::ARMING_RUDDER_ARMDISARM) && !is_flying()) {
// when armed and not flying, full left rudder starts disarming counter
if (channel_rudder->get_control_in() < -4000) {
uint32_t now = millis();