mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: Quadplane: use uint16_t for output_motor_mask
This commit is contained in:
parent
d5082e25e8
commit
d66485c60a
@ -95,7 +95,7 @@ const AP_Param::GroupInfo Tailsitter::var_info[] = {
|
||||
// @DisplayName: Tailsitter motor mask
|
||||
// @Description: Bitmask of motors to remain active in forward flight for a 'Copter' tailsitter. Non-zero indicates airframe is a Copter tailsitter and uses copter style motor layouts determined by Q_FRAME_CLASS and Q_FRAME_TYPE. This should be zero for non-Copter tailsitters.
|
||||
// @User: Standard
|
||||
// @Bitmask: 0:Motor 1,1:Motor 2,2:Motor 3,3:Motor 4, 4:Motor 5,5:Motor 6,6:Motor 7,7:Motor 8
|
||||
// @Bitmask: 0:Motor 1, 1:Motor 2, 2:Motor 3, 3:Motor 4, 4:Motor 5, 5:Motor 6, 6:Motor 7, 7:Motor 8, 8:Motor 9, 9:Motor 10, 10:Motor 11, 11:Motor 12
|
||||
AP_GROUPINFO("MOTMX", 12, Tailsitter, motor_mask, 0),
|
||||
|
||||
// @Param: GSCMSK
|
||||
|
@ -16,6 +16,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = {
|
||||
// @DisplayName: Tiltrotor mask
|
||||
// @Description: This is a bitmask of motors that are tiltable in a tiltrotor (or tiltwing). The mask is in terms of the standard motor order for the frame type.
|
||||
// @User: Standard
|
||||
// @Bitmask: 0:Motor 1, 1:Motor 2, 2:Motor 3, 3:Motor 4, 4:Motor 5, 5:Motor 6, 6:Motor 7, 7:Motor 8, 8:Motor 9, 9:Motor 10, 10:Motor 11, 11:Motor 12
|
||||
AP_GROUPINFO("MASK", 2, Tiltrotor, tilt_mask, 0),
|
||||
|
||||
// @Param: RATE_UP
|
||||
@ -242,7 +243,7 @@ void Tiltrotor::continuous_update(void)
|
||||
}
|
||||
if (!quadplane.motor_test.running) {
|
||||
// the motors are all the way forward, start using them for fwd thrust
|
||||
uint8_t mask = is_zero(current_throttle)?0:(uint8_t)tilt_mask.get();
|
||||
const uint16_t mask = is_zero(current_throttle)?0U:tilt_mask.get();
|
||||
motors->output_motor_mask(current_throttle, mask, plane.rudder_dt);
|
||||
}
|
||||
return;
|
||||
@ -346,7 +347,7 @@ void Tiltrotor::binary_update(void)
|
||||
|
||||
float new_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01f;
|
||||
if (current_tilt >= 1) {
|
||||
uint8_t mask = is_zero(new_throttle)?0:(uint8_t)tilt_mask.get();
|
||||
const uint16_t mask = is_zero(new_throttle)?0U: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