mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
ArduPlane: move to a uint32_t motor mask
This commit is contained in:
parent
98e4037868
commit
1deea810e8
@ -336,7 +336,7 @@ void Tailsitter::output(void)
|
||||
|
||||
if (!quadplane.assisted_flight) {
|
||||
// set AP_MotorsMatrix throttles for forward flight
|
||||
motors->output_motor_mask(throttle, motor_mask, plane.rudder_dt);
|
||||
motors->output_motor_mask(throttle, uint32_t(motor_mask.get()), plane.rudder_dt);
|
||||
|
||||
// No tilt output unless forward gain is set
|
||||
float tilt_left = 0.0;
|
||||
|
@ -245,7 +245,7 @@ void Tiltrotor::continuous_update(void)
|
||||
}
|
||||
if (!quadplane.motor_test.running) {
|
||||
// the motors are all the way forward, start using them for fwd thrust
|
||||
const uint16_t mask = is_zero(current_throttle)?0U:tilt_mask.get();
|
||||
const uint32_t mask = is_zero(current_throttle) ? 0U : tilt_mask.get();
|
||||
motors->output_motor_mask(current_throttle, mask, plane.rudder_dt);
|
||||
}
|
||||
return;
|
||||
@ -365,7 +365,7 @@ void Tiltrotor::binary_update(void)
|
||||
|
||||
float new_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01f;
|
||||
if (current_tilt >= 1) {
|
||||
const uint16_t mask = is_zero(new_throttle)?0U:tilt_mask.get();
|
||||
const uint32_t mask = is_zero(new_throttle) ? 0 : tilt_mask.get();
|
||||
// the motors are all the way forward, start using them for fwd thrust
|
||||
motors->output_motor_mask(new_throttle, mask, plane.rudder_dt);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user