mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: control rudder arming with ARMING_RUDDER parameter
allow for 3 states: 0: no rudder arming 1: arm only 2: arm and disarm
This commit is contained in:
parent
da41d85433
commit
54254c89d7
|
@ -27,13 +27,6 @@ const AP_Param::GroupInfo AP_Arming::var_info[] PROGMEM = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("REQUIRE", 0, AP_Arming, require, 1),
|
||||
|
||||
// @Param: DIS_RUD
|
||||
// @DisplayName: Disable Rudder Arming
|
||||
// @Description: Do not allow arming via the rudder input stick.
|
||||
// @Values: 0:Disabled (Rudder Arming Allowed),1:Enabled(No Rudder Arming)
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DIS_RUD", 1, AP_Arming, disable_rudder_arm, 0),
|
||||
|
||||
// @Param: CHECK
|
||||
// @DisplayName: Arm Checks to Peform (bitmask)
|
||||
// @Description: Checks prior to arming motor. This is a bitmask of checks that will be performed befor allowing arming. The default is no checks, allowing arming at any time. You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72. For most users it is recommended that you set this to 1 to enable all checks.
|
||||
|
@ -41,6 +34,13 @@ const AP_Param::GroupInfo AP_Arming::var_info[] PROGMEM = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("CHECK", 2, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),
|
||||
|
||||
// @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
|
||||
// @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RUDDER", 3, AP_Arming, rudder_arming_value, ARMING_RUDDER_ARMONLY),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -414,10 +414,3 @@ AP_Arming::ArmingRequired AP_Arming::arming_required()
|
|||
return (AP_Arming::ArmingRequired)require.get();
|
||||
}
|
||||
|
||||
bool AP_Arming::rudder_arming_enabled()
|
||||
{
|
||||
if (disable_rudder_arm == 0)
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -37,6 +37,12 @@ public:
|
|||
YES_ZERO_PWM = 2
|
||||
};
|
||||
|
||||
enum ArmingRudder {
|
||||
ARMING_RUDDER_DISABLED = 0,
|
||||
ARMING_RUDDER_ARMONLY = 1,
|
||||
ARMING_RUDDER_ARMDISARM = 2
|
||||
};
|
||||
|
||||
// for the hacky function pointer to gcs_send_text_p
|
||||
FUNCTOR_TYPEDEF(gcs_send_t_p, void, gcs_severity, const prog_char_t *);
|
||||
|
||||
|
@ -47,7 +53,7 @@ public:
|
|||
bool arm(uint8_t method);
|
||||
bool disarm();
|
||||
bool is_armed();
|
||||
bool rudder_arming_enabled();
|
||||
ArmingRudder rudder_arming() const { return (ArmingRudder)rudder_arming_value.get(); }
|
||||
uint16_t get_enabled_checks();
|
||||
|
||||
/*
|
||||
|
@ -69,7 +75,7 @@ protected:
|
|||
|
||||
//Parameters
|
||||
AP_Int8 require;
|
||||
AP_Int8 disable_rudder_arm;
|
||||
AP_Int8 rudder_arming_value;
|
||||
//bitmask for which checks are required
|
||||
AP_Int16 checks_to_perform;
|
||||
|
||||
|
|
Loading…
Reference in New Issue