mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: tailsitter forward transition bugfix
This commit is contained in:
parent
e7dcee0dd8
commit
5c81a78c9c
@ -1423,7 +1423,7 @@ void QuadPlane::update_transition(void)
|
|||||||
// millisecond. Assume we want to get to the transition angle
|
// millisecond. Assume we want to get to the transition angle
|
||||||
// in half the transition time
|
// in half the transition time
|
||||||
float transition_rate = tailsitter.transition_angle / float(transition_time_ms/2);
|
float transition_rate = tailsitter.transition_angle / float(transition_time_ms/2);
|
||||||
uint32_t dt = now - transition_low_airspeed_ms;
|
uint32_t dt = now - transition_start_ms;
|
||||||
plane.nav_pitch_cd = constrain_float((-transition_rate * dt)*100, -8500, 0);
|
plane.nav_pitch_cd = constrain_float((-transition_rate * dt)*100, -8500, 0);
|
||||||
plane.nav_roll_cd = 0;
|
plane.nav_roll_cd = 0;
|
||||||
check_attitude_relax();
|
check_attitude_relax();
|
||||||
|
Loading…
Reference in New Issue
Block a user