Browse Source

AP_Motors: add get roll factor

master
IamPete1 6 years ago committed by Andrew Tridgell
parent
commit
c82f158b56
  1. 4
      libraries/AP_Motors/AP_MotorsMatrix.h
  2. 4
      libraries/AP_Motors/AP_Motors_Class.h

4
libraries/AP_Motors/AP_MotorsMatrix.h

@ -51,6 +51,10 @@ public:
// return number of motor that has failed. Should only be called if get_thrust_boost() returns true // return number of motor that has failed. Should only be called if get_thrust_boost() returns true
uint8_t get_lost_motor() const override { return _motor_lost_index; } uint8_t get_lost_motor() const override { return _motor_lost_index; }
// return the roll factor of any motor, this is used for tilt rotors and tail sitters
// using copter motors for forward flight
float get_roll_factor(uint8_t i) override { return _roll_factor[i]; }
protected: protected:
// output - sends commands to the motors // output - sends commands to the motors
void output_armed_stabilizing() override; void output_armed_stabilizing() override;

4
libraries/AP_Motors/AP_Motors_Class.h

@ -157,6 +157,10 @@ public:
// set loop rate. Used to support loop rate as a parameter // set loop rate. Used to support loop rate as a parameter
void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; } void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; }
// return the roll factor of any motor, this is used for tilt rotors and tail sitters
// using copter motors for forward flight
virtual float get_roll_factor(uint8_t i) { return 0.0f; }
enum pwm_type { PWM_TYPE_NORMAL = 0, enum pwm_type { PWM_TYPE_NORMAL = 0,
PWM_TYPE_ONESHOT = 1, PWM_TYPE_ONESHOT = 1,
PWM_TYPE_ONESHOT125 = 2, PWM_TYPE_ONESHOT125 = 2,

Loading…
Cancel
Save