mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Motors: output_motor_mask mask to uint16_t
This commit is contained in:
parent
148c8d6eec
commit
d5082e25e8
@ -760,7 +760,7 @@ 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, float rudder_dt)
|
||||
void AP_MotorsMulticopter::output_motor_mask(float thrust, uint16_t mask, float rudder_dt)
|
||||
{
|
||||
const int16_t pwm_min = get_pwm_output_min();
|
||||
const int16_t pwm_range = get_pwm_output_max() - pwm_min;
|
||||
|
@ -64,7 +64,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, float rudder_dt);
|
||||
virtual void output_motor_mask(float thrust, uint16_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
|
||||
|
@ -333,7 +333,7 @@ void AP_MotorsTri::thrust_compensation(void)
|
||||
/*
|
||||
override tricopter tail servo output in output_motor_mask
|
||||
*/
|
||||
void AP_MotorsTri::output_motor_mask(float thrust, uint8_t mask, float rudder_dt)
|
||||
void AP_MotorsTri::output_motor_mask(float thrust, uint16_t mask, float rudder_dt)
|
||||
{
|
||||
// normal multicopter output
|
||||
AP_MotorsMulticopter::output_motor_mask(thrust, mask, rudder_dt);
|
||||
|
@ -43,7 +43,7 @@ public:
|
||||
// mask. This is used to control tiltrotor motors in forward
|
||||
// flight. Thrust is in the range 0 to 1
|
||||
// rudder_dt applys diffential thrust for yaw in the range 0 to 1
|
||||
void output_motor_mask(float thrust, uint8_t mask, float rudder_dt) override;
|
||||
void output_motor_mask(float thrust, uint16_t mask, float rudder_dt) override;
|
||||
|
||||
// return the roll factor of any motor, this is used for tilt rotors and tail sitters
|
||||
// using copter motors for forward flight
|
||||
|
Loading…
Reference in New Issue
Block a user