mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Plane: tailsitters use Z stopping point on transition
This commit is contained in:
parent
dce2f78d6f
commit
5f67f8130b
@ -956,10 +956,15 @@ void QuadPlane::run_z_controller(void)
|
|||||||
{
|
{
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
if (now - last_pidz_active_ms > 2000) {
|
if (now - last_pidz_active_ms > 2000) {
|
||||||
// set alt target to current height on transition. This
|
if (!is_tailsitter()) {
|
||||||
// starts the Z controller off with the right values
|
// set alt target to current height on transition. This
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Reset alt target to %.1f", (double)inertial_nav.get_altitude() / 100);
|
// starts the Z controller off with the right values
|
||||||
set_alt_target_current();
|
set_alt_target_current();
|
||||||
|
} else {
|
||||||
|
// tailsitters gain lots of vertical speed in transisison, set target to the stopping point
|
||||||
|
pos_control->set_target_to_stopping_point_z();
|
||||||
|
}
|
||||||
|
gcs().send_text(MAV_SEVERITY_INFO, "Reset alt target to %.1f", (double)pos_control->get_alt_target() * 0.01f);
|
||||||
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
|
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
|
||||||
|
|
||||||
// initialize vertical speeds and leash lengths
|
// initialize vertical speeds and leash lengths
|
||||||
|
Loading…
Reference in New Issue
Block a user