Skip to content

Commit

Permalink
Map transition tilt from throttle to handle THR_MIN and THR_MAX
Browse files Browse the repository at this point in the history
  • Loading branch information
stw2nf committed May 29, 2024
1 parent 1d810bf commit 7a405a0
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduPlane/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -325,8 +325,8 @@ void Tiltrotor::continuous_update(void)
// Q_TILT_MAX. Anything above 50% throttle gets
// Q_TILT_MAX. Below 50% throttle we decrease linearly. This
// relies heavily on Q_VFWD_GAIN being set appropriately.
float settilt = constrain_float((SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)-MAX(plane.aparm.throttle_min.get(),0)) * 0.02, 0, 1);
slew(MIN(settilt * max_angle_deg * (1/90.0), get_forward_flight_tilt()));
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);
slew(MIN(settilt * max_angle_deg * (1/90.0), get_forward_flight_tilt()));
}
}

Expand Down

0 comments on commit 7a405a0

Please sign in to comment.