Browse Source

AP_Motors: make init_targets_on_arming global

master
Bill Geyer 5 years ago committed by Randy Mackay
parent
commit
63d9b47530
  1. 2
      libraries/AP_Motors/AP_MotorsHeli.h
  2. 4
      libraries/AP_Motors/AP_Motors_Class.h

2
libraries/AP_Motors/AP_MotorsHeli.h

@ -122,7 +122,7 @@ public: @@ -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[];

4
libraries/AP_Motors/AP_Motors_Class.h

@ -182,6 +182,10 @@ public: @@ -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,

Loading…
Cancel
Save