Copter: Fix payload place bug

This commit is contained in:
Leonard Hall 2024-08-08 14:56:39 +09:30 committed by Andrew Tridgell
parent 702c76e885
commit 36f5ea66c0
1 changed files with 3 additions and 4 deletions

View File

@ -1395,8 +1395,7 @@ void PayloadPlace::run()
copter.flightmode->land_run_horizontal_control();
// update altitude target and call position controller
pos_control->land_at_climb_rate_cm(-descent_speed_cms, true);
pos_control->update_z_controller();
return;
break;
case State::Release:
case State::Releasing:
case State::Delay:
@ -1404,8 +1403,7 @@ void PayloadPlace::run()
copter.flightmode->land_run_horizontal_control();
// update altitude target and call position controller
pos_control->land_at_climb_rate_cm(0.0, false);
pos_control->update_z_controller();
return;
break;
case State::Ascent:
case State::Done:
float vel = 0.0;
@ -1413,6 +1411,7 @@ void PayloadPlace::run()
pos_control->input_pos_vel_accel_z(descent_start_altitude_cm, vel, 0.0);
break;
}
pos_control->update_z_controller();
}
#endif