mirror of https://github.com/ArduPilot/ardupilot
Copter: guided calls velocity controller at 400hz
velocity controller internally updates xy-axis at 50hz, z-axis at 400hz
This commit is contained in:
parent
339d49d34a
commit
4941b19e33
|
@ -305,19 +305,8 @@ void Copter::guided_vel_control_run()
|
|||
pos_control.set_desired_velocity(Vector3f(0,0,0));
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
|
||||
// call velocity controller which includes z axis controller
|
||||
pos_control.update_vel_controller_xyz(ekfNavVelGainScaler);
|
||||
}
|
||||
// call velocity controller which includes z axis controller
|
||||
pos_control.update_vel_controller_xyz(ekfNavVelGainScaler);
|
||||
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
|
|
Loading…
Reference in New Issue