Plane: start tailsitter forward transition from current pitch angle

This commit is contained in:
Henry Wurzburg 2020-04-09 08:54:33 -05:00 committed by Andrew Tridgell
parent 87108b86c8
commit 6c730ccfec
2 changed files with 6 additions and 1 deletions

View File

@ -1702,7 +1702,10 @@ void QuadPlane::update_transition(void)
// in half the transition time
float transition_rate = tailsitter.transition_angle / float(transition_time_ms/2);
uint32_t dt = now - transition_start_ms;
plane.nav_pitch_cd = constrain_float((-transition_rate * dt)*100, -8500, 0);
float pitch_cd;
pitch_cd = constrain_float((-transition_rate * dt)*100, -8500, 0);
// if already pitched forward at start of transition, wait until curve catches up
plane.nav_pitch_cd = (pitch_cd > transition_initial_pitch)? transition_initial_pitch : pitch_cd;
plane.nav_roll_cd = 0;
check_attitude_relax();
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
@ -1816,6 +1819,7 @@ void QuadPlane::update(void)
*/
transition_state = TRANSITION_ANGLE_WAIT_FW;
transition_start_ms = now;
transition_initial_pitch= constrain_float(ahrs_view->pitch_sensor,-8500,0);
} else {
/*
setup for airspeed wait for later

View File

@ -347,6 +347,7 @@ private:
// timer start for transition
uint32_t transition_start_ms;
float transition_initial_pitch;
uint32_t transition_low_airspeed_ms;
Location last_auto_target;