mirror of https://github.com/ArduPilot/ardupilot
Copter: Fix payload place bug
This commit is contained in:
parent
f2017fd99d
commit
88896154d6
|
@ -1395,8 +1395,7 @@ void PayloadPlace::run()
|
||||||
copter.flightmode->land_run_horizontal_control();
|
copter.flightmode->land_run_horizontal_control();
|
||||||
// update altitude target and call position controller
|
// update altitude target and call position controller
|
||||||
pos_control->land_at_climb_rate_cm(-descent_speed_cms, true);
|
pos_control->land_at_climb_rate_cm(-descent_speed_cms, true);
|
||||||
pos_control->update_z_controller();
|
break;
|
||||||
return;
|
|
||||||
case State::Release:
|
case State::Release:
|
||||||
case State::Releasing:
|
case State::Releasing:
|
||||||
case State::Delay:
|
case State::Delay:
|
||||||
|
@ -1404,8 +1403,7 @@ void PayloadPlace::run()
|
||||||
copter.flightmode->land_run_horizontal_control();
|
copter.flightmode->land_run_horizontal_control();
|
||||||
// update altitude target and call position controller
|
// update altitude target and call position controller
|
||||||
pos_control->land_at_climb_rate_cm(0.0, false);
|
pos_control->land_at_climb_rate_cm(0.0, false);
|
||||||
pos_control->update_z_controller();
|
break;
|
||||||
return;
|
|
||||||
case State::Ascent:
|
case State::Ascent:
|
||||||
case State::Done:
|
case State::Done:
|
||||||
float vel = 0.0;
|
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);
|
pos_control->input_pos_vel_accel_z(descent_start_altitude_cm, vel, 0.0);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
pos_control->update_z_controller();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue