Skip to content

Commit

Permalink
Copter: guided calls velocity controller at 400hz
Browse files Browse the repository at this point in the history
velocity controller internally updates xy-axis at 50hz, z-axis at 400hz
  • Loading branch information
rmackay9 committed Nov 18, 2015
1 parent c9340db commit b2b8dcb
Showing 1 changed file with 2 additions and 13 deletions.
15 changes: 2 additions & 13 deletions ArduCopter/control_guided.cpp
Expand Up @@ -355,19 +355,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) {
Expand Down

0 comments on commit b2b8dcb

Please sign in to comment.