Skip to content

Commit 7a405a0

Browse files
committed
Map transition tilt from throttle to handle THR_MIN and THR_MAX
1 parent 1d810bf commit 7a405a0

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

ArduPlane/tiltrotor.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -325,8 +325,8 @@ void Tiltrotor::continuous_update(void)
325325
// Q_TILT_MAX. Anything above 50% throttle gets
326326
// Q_TILT_MAX. Below 50% throttle we decrease linearly. This
327327
// relies heavily on Q_VFWD_GAIN being set appropriately.
328-
float settilt = constrain_float((SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)-MAX(plane.aparm.throttle_min.get(),0)) * 0.02, 0, 1);
329-
slew(MIN(settilt * max_angle_deg * (1/90.0), get_forward_flight_tilt()));
328+
float settilt = constrain_float(((SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)-MAX(plane.aparm.throttle_min.get(),0))*2) / (MIN(plane.aparm.throttle_max.get(),100) - MAX(plane.aparm.throttle_min.get(),0)), 0, 1);
329+
slew(MIN(settilt * max_angle_deg * (1/90.0), get_forward_flight_tilt()));
330330
}
331331
}
332332

0 commit comments

Comments
 (0)