Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AC_PosControl: Replace update_vel_controller_xy() with update_xy_controller() #13934

Merged
merged 2 commits into from Apr 20, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.cpp
Expand Up @@ -2243,7 +2243,7 @@ void QuadPlane::vtol_position_controller(void)
pos_control->set_desired_accel_xy(0.0f,0.0f);

// run horizontal velocity controller
pos_control->update_vel_controller_xy();
pos_control->update_xy_controller();

// nav roll and pitch are controller by position controller
plane.nav_roll_cd = pos_control->get_roll();
Expand Down
34 changes: 1 addition & 33 deletions libraries/AC_AttitudeControl/AC_PosControl.cpp
Expand Up @@ -951,45 +951,13 @@ void AC_PosControl::init_vel_controller_xyz()
init_ekf_z_reset();
}

/// update_velocity_controller_xy - run the velocity controller - should be called at 100hz or higher
/// velocity targets should we set using set_desired_velocity_xy() method
/// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
/// throttle targets will be sent directly to the motors
void AC_PosControl::update_vel_controller_xy()
{
// capture time since last iteration
const uint64_t now_us = AP_HAL::micros64();
float dt = (now_us - _last_update_xy_us) * 1.0e-6f;

// sanity check dt
if (dt >= 0.2f) {
dt = 0.0f;
}

// check for ekf xy position reset
check_for_ekf_xy_reset();

// check if xy leash needs to be recalculated
calc_leash_length_xy();

// apply desired velocity request to position target
// TODO: this will need to be removed and added to the calling function.
desired_vel_to_pos(dt);

// run position controller
run_xy_controller(dt);

// update xy update time
_last_update_xy_us = now_us;
}

/// update_velocity_controller_xyz - run the velocity controller - should be called at 100hz or higher
/// velocity targets should we set using set_desired_velocity_xyz() method
/// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
/// throttle targets will be sent directly to the motors
void AC_PosControl::update_vel_controller_xyz()
{
update_vel_controller_xy();
update_xy_controller();

// update altitude target
set_alt_target_from_climb_rate_ff(_vel_desired.z, _dt, false);
Expand Down
6 changes: 0 additions & 6 deletions libraries/AC_AttitudeControl/AC_PosControl.h
Expand Up @@ -263,12 +263,6 @@ class AC_PosControl
/// init_vel_controller_xyz - initialise the velocity controller - should be called once before the caller attempts to use the controller
void init_vel_controller_xyz();

/// update_velocity_controller_xy - run the XY velocity controller - should be called at 100hz or higher
/// velocity targets should we set using set_desired_velocity_xy() method
/// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
/// throttle targets will be sent directly to the motors
void update_vel_controller_xy();

/// update_velocity_controller_xyz - run the velocity controller - should be called at 100hz or higher
/// velocity targets should we set using set_desired_velocity_xyz() method
/// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
Expand Down