From 63d9b47530512409ddb099fd67253b4dc1b9d48a Mon Sep 17 00:00:00 2001 From: Bill Geyer Date: Mon, 30 Sep 2019 16:54:29 -0400 Subject: [PATCH] AP_Motors: make init_targets_on_arming global --- libraries/AP_Motors/AP_MotorsHeli.h | 2 +- libraries/AP_Motors/AP_Motors_Class.h | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index accd845524..f4a4f46dc3 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -122,7 +122,7 @@ public: float get_throttle_hover() const override { return 0.5f; } // support passing init_targets_on_arming flag to greater code - bool init_targets_on_arming() const { return _heliflags.init_targets_on_arming; } + bool init_targets_on_arming() const override { return _heliflags.init_targets_on_arming; } // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index ddd69d5186..d7d484fbff 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -182,6 +182,10 @@ public: // using copter motors for forward flight virtual float get_roll_factor(uint8_t i) { return 0.0f; } + // This function required for tradheli. Tradheli initializes targets when going from unarmed to armed state. + // This function is overriden in motors_heli class. Always true for multicopters. + virtual bool init_targets_on_arming() const { return true; } + enum pwm_type { PWM_TYPE_NORMAL = 0, PWM_TYPE_ONESHOT = 1, PWM_TYPE_ONESHOT125 = 2,