mirror of https://github.com/ArduPilot/ardupilot
Copter: run guided velocity control at main loop rate
This commit is contained in:
parent
21abe1194e
commit
d7ea8f073f
|
@ -536,8 +536,6 @@ void Copter::ModeGuided::posvel_control_run()
|
|||
// calculate dt
|
||||
float dt = pos_control->time_since_last_xy_update();
|
||||
|
||||
// update at poscontrol update rate
|
||||
if (dt >= pos_control->get_dt_xy()) {
|
||||
// sanity check dt
|
||||
if (dt >= 0.2f) {
|
||||
dt = 0.0f;
|
||||
|
@ -550,10 +548,8 @@ void Copter::ModeGuided::posvel_control_run()
|
|||
pos_control->set_pos_target(guided_pos_target_cm);
|
||||
pos_control->set_desired_velocity_xy(guided_vel_target_cms.x, guided_vel_target_cms.y);
|
||||
|
||||
// run position controller
|
||||
// run position controllers
|
||||
pos_control->update_xy_controller(ekfNavVelGainScaler);
|
||||
}
|
||||
|
||||
pos_control->update_z_controller();
|
||||
|
||||
// call attitude controller
|
||||
|
|
Loading…
Reference in New Issue