Plane: Zero Yaw correction during transition
and relax attitude controller when not using lift motors.
This commit is contained in:
parent
8f5f664e9f
commit
0943ace7a9
@ -1324,6 +1324,13 @@ void QuadPlane::update_transition(void)
|
|||||||
climb_rate_cms = MIN(climb_rate_cms, 0.0f);
|
climb_rate_cms = MIN(climb_rate_cms, 0.0f);
|
||||||
}
|
}
|
||||||
hold_hover(climb_rate_cms);
|
hold_hover(climb_rate_cms);
|
||||||
|
|
||||||
|
// set desired yaw to current yaw in both desired angle and
|
||||||
|
// rate request. This reduces wing twist in transition due to
|
||||||
|
// multicopter yaw demands
|
||||||
|
attitude_control->set_yaw_target_to_current_heading();
|
||||||
|
attitude_control->rate_bf_yaw_target(ahrs.get_gyro().z);
|
||||||
|
|
||||||
last_throttle = motors->get_throttle();
|
last_throttle = motors->get_throttle();
|
||||||
|
|
||||||
// reset integrators while we are below target airspeed as we
|
// reset integrators while we are below target airspeed as we
|
||||||
@ -1361,6 +1368,13 @@ void QuadPlane::update_transition(void)
|
|||||||
}
|
}
|
||||||
assisted_flight = true;
|
assisted_flight = true;
|
||||||
hold_stabilize(throttle_scaled);
|
hold_stabilize(throttle_scaled);
|
||||||
|
|
||||||
|
// set desired yaw to current yaw in both desired angle and
|
||||||
|
// rate request while waiting for transition to
|
||||||
|
// complete. Navigation should be controlled by fixed wing
|
||||||
|
// control surfaces at this stage
|
||||||
|
attitude_control->set_yaw_target_to_current_heading();
|
||||||
|
attitude_control->rate_bf_yaw_target(ahrs.get_gyro().z);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user