Browse Source

AP_Motors: multicopter apply diffential thrust in forward flight

mission-4.1.18
IamPete1 6 years ago committed by Andrew Tridgell
parent
commit
c26948ef59
  1. 11
      libraries/AP_Motors/AP_MotorsMulticopter.cpp
  2. 2
      libraries/AP_Motors/AP_MotorsMulticopter.h

11
libraries/AP_Motors/AP_MotorsMulticopter.cpp

@ -626,13 +626,20 @@ void AP_MotorsMulticopter::set_throttle_passthrough_for_esc_calibration(float th @@ -626,13 +626,20 @@ void AP_MotorsMulticopter::set_throttle_passthrough_for_esc_calibration(float th
// output a thrust to all motors that match a given motor mask. This
// is used to control tiltrotor motors in forward flight. Thrust is in
// the range 0 to 1
void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask)
void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float rudder_dt)
{
for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
if (motor_enabled[i]) {
int16_t motor_out;
if (mask & (1U<<i)) {
motor_out = calc_thrust_to_pwm(thrust);
/*
apply rudder mixing differential thrust
copter frame roll is plane frame yaw as this only
apples to either tilted motors or tailsitters
*/
float diff_thrust = get_roll_factor(i) * rudder_dt * 0.5f;
motor_out = calc_thrust_to_pwm(thrust + diff_thrust);
} else {
motor_out = get_pwm_output_min();
}

2
libraries/AP_Motors/AP_MotorsMulticopter.h

@ -84,7 +84,7 @@ public: @@ -84,7 +84,7 @@ public:
// output a thrust to all motors that match a given motor
// mask. This is used to control tiltrotor motors in forward
// flight. Thrust is in the range 0 to 1
virtual void output_motor_mask(float thrust, uint8_t mask);
virtual void output_motor_mask(float thrust, uint8_t mask, float rudder_dt);
// get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict

Loading…
Cancel
Save