Skip to content
Snippets Groups Projects
Commit e906310b authored by Randy Mackay's avatar Randy Mackay
Browse files

Plane: rudder_arming moved to AP_Arming_Plane

parent 7cc8b723
No related branches found
No related tags found
No related merge requests found
......@@ -8,6 +8,12 @@
class AP_Arming_Plane : public AP_Arming
{
public:
enum ArmingRudder {
ARMING_RUDDER_DISABLED = 0,
ARMING_RUDDER_ARMONLY = 1,
ARMING_RUDDER_ARMDISARM = 2
};
AP_Arming_Plane(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery) :
AP_Arming(ahrs_ref, baro, compass, battery) {
......@@ -16,6 +22,8 @@ public:
bool pre_arm_checks(bool report);
bool arm(uint8_t method) override;
ArmingRudder rudder_arming() const { return (ArmingRudder)rudder_arming_value.get(); }
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
......
......@@ -103,9 +103,9 @@ void Plane::init_rc_out_aux()
*/
void Plane::rudder_arm_disarm_check()
{
AP_Arming::ArmingRudder arming_rudder = arming.rudder_arming();
AP_Arming_Plane::ArmingRudder arming_rudder = arming.rudder_arming();
if (arming_rudder == AP_Arming::ARMING_RUDDER_DISABLED) {
if (arming_rudder == AP_Arming_Plane::ARMING_RUDDER_DISABLED) {
//parameter disallows rudder arming/disabling
return;
}
......@@ -144,7 +144,7 @@ void Plane::rudder_arm_disarm_check()
// not at full right rudder
rudder_arm_timer = 0;
}
} else if (arming_rudder == AP_Arming::ARMING_RUDDER_ARMDISARM && !is_flying()) {
} else if (arming_rudder == AP_Arming_Plane::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();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment