mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Motors: fixed tricopter tail servo in fwd flight
in quadplane forward flight the with tilt-tricopter tail servo needs to be at its trim position. Thanks to Marco for noticing this.
This commit is contained in:
parent
b6568b1c7e
commit
46d9a1dcb5
@ -87,7 +87,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
|
||||
void output_motor_mask(float thrust, uint8_t mask);
|
||||
virtual void output_motor_mask(float thrust, uint8_t mask);
|
||||
|
||||
// get minimum or maximum pwm value that can be output to motors
|
||||
int16_t get_pwm_output_min() const;
|
||||
|
@ -320,3 +320,15 @@ void AP_MotorsTri::thrust_compensation(void)
|
||||
_thrust_rear = thrust[3];
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
override tricopter tail servo output in output_motor_mask
|
||||
*/
|
||||
void AP_MotorsTri::output_motor_mask(float thrust, uint8_t mask)
|
||||
{
|
||||
// normal multicopter output
|
||||
AP_MotorsMulticopter::output_motor_mask(thrust, mask);
|
||||
|
||||
// and override yaw servo
|
||||
rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo->get_trim());
|
||||
}
|
||||
|
@ -47,6 +47,11 @@ public:
|
||||
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
||||
virtual uint16_t get_motor_mask();
|
||||
|
||||
// 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 output_motor_mask(float thrust, uint8_t mask) override;
|
||||
|
||||
protected:
|
||||
// output - sends commands to the motors
|
||||
void output_armed_stabilizing();
|
||||
|
Loading…
Reference in New Issue
Block a user