mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AC_WPNav: Cope with AC_PosControl renaming
This commit is contained in:
parent
1d13aff711
commit
d3bee76f0b
@ -91,8 +91,8 @@ void AC_Loiter::init_target(const Vector3f& position)
|
||||
sanity_check_params();
|
||||
|
||||
// initialise pos controller speed, acceleration
|
||||
_pos_control.set_speed_xy(LOITER_VEL_CORRECTION_MAX);
|
||||
_pos_control.set_accel_xy(_accel_cmss);
|
||||
_pos_control.set_max_speed_xy(LOITER_VEL_CORRECTION_MAX);
|
||||
_pos_control.set_max_accel_xy(_accel_cmss);
|
||||
|
||||
// initialise desired acceleration and angles to zero to remain on station
|
||||
_predicted_accel.zero();
|
||||
@ -119,8 +119,8 @@ void AC_Loiter::init_target()
|
||||
sanity_check_params();
|
||||
|
||||
// initialise pos controller speed and acceleration
|
||||
_pos_control.set_speed_xy(LOITER_VEL_CORRECTION_MAX);
|
||||
_pos_control.set_accel_xy(_accel_cmss);
|
||||
_pos_control.set_max_speed_xy(LOITER_VEL_CORRECTION_MAX);
|
||||
_pos_control.set_max_accel_xy(_accel_cmss);
|
||||
_pos_control.set_leash_length_xy(LOITER_POS_CORRECTION_MAX);
|
||||
|
||||
_predicted_accel = _desired_accel;
|
||||
@ -210,8 +210,8 @@ void AC_Loiter::update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
|
||||
}
|
||||
|
||||
// initialise pos controller speed and acceleration
|
||||
_pos_control.set_speed_xy(_speed_cms);
|
||||
_pos_control.set_accel_xy(_accel_cmss);
|
||||
_pos_control.set_max_speed_xy(_speed_cms);
|
||||
_pos_control.set_max_accel_xy(_accel_cmss);
|
||||
|
||||
calc_desired_velocity(dt,ekfGndSpdLimit);
|
||||
_pos_control.update_xy_controller(ekfNavVelGainScaler);
|
||||
@ -240,8 +240,8 @@ void AC_Loiter::calc_desired_velocity(float nav_dt, float ekfGndSpdLimit)
|
||||
return;
|
||||
}
|
||||
|
||||
_pos_control.set_speed_xy(gnd_speed_limit_cms);
|
||||
_pos_control.set_accel_xy(_accel_cmss);
|
||||
_pos_control.set_max_speed_xy(gnd_speed_limit_cms);
|
||||
_pos_control.set_max_accel_xy(_accel_cmss);
|
||||
_pos_control.set_leash_length_xy(LOITER_POS_CORRECTION_MAX);
|
||||
|
||||
// get loiters desired velocity from the position controller where it is being stored.
|
||||
|
@ -108,8 +108,8 @@ void AC_WPNav::init_brake_target(float accel_cmss)
|
||||
_pos_control.init_xy_controller();
|
||||
|
||||
// initialise pos controller speed and acceleration
|
||||
_pos_control.set_speed_xy(curr_vel.length());
|
||||
_pos_control.set_accel_xy(accel_cmss);
|
||||
_pos_control.set_max_speed_xy(curr_vel.length());
|
||||
_pos_control.set_max_accel_xy(accel_cmss);
|
||||
_pos_control.calc_leash_length_xy();
|
||||
|
||||
// set target position
|
||||
@ -148,10 +148,10 @@ void AC_WPNav::wp_and_spline_init()
|
||||
_pos_control.set_desired_velocity_xy(0.0f, 0.0f);
|
||||
|
||||
// initialise position controller speed and acceleration
|
||||
_pos_control.set_speed_xy(_wp_speed_cms);
|
||||
_pos_control.set_accel_xy(_wp_accel_cmss);
|
||||
_pos_control.set_speed_z(-_wp_speed_down_cms, _wp_speed_up_cms);
|
||||
_pos_control.set_accel_z(_wp_accel_z_cmss);
|
||||
_pos_control.set_max_speed_xy(_wp_speed_cms);
|
||||
_pos_control.set_max_accel_xy(_wp_accel_cmss);
|
||||
_pos_control.set_max_speed_z(-_wp_speed_down_cms, _wp_speed_up_cms);
|
||||
_pos_control.set_max_accel_z(_wp_accel_z_cmss);
|
||||
_pos_control.calc_leash_length_xy();
|
||||
_pos_control.calc_leash_length_z();
|
||||
|
||||
@ -165,7 +165,7 @@ void AC_WPNav::set_speed_xy(float speed_cms)
|
||||
// range check new target speed and update position controller
|
||||
if (speed_cms >= WPNAV_WP_SPEED_MIN) {
|
||||
_wp_speed_cms = speed_cms;
|
||||
_pos_control.set_speed_xy(_wp_speed_cms);
|
||||
_pos_control.set_max_speed_xy(_wp_speed_cms);
|
||||
// flag that wp leash must be recalculated
|
||||
_flags.recalc_wp_leash = true;
|
||||
}
|
||||
@ -507,8 +507,8 @@ bool AC_WPNav::update_wpnav()
|
||||
|
||||
// allow the accel and speed values to be set without changing
|
||||
// out of auto mode. This makes it easier to tune auto flight
|
||||
_pos_control.set_accel_xy(_wp_accel_cmss);
|
||||
_pos_control.set_accel_z(_wp_accel_z_cmss);
|
||||
_pos_control.set_max_accel_xy(_wp_accel_cmss);
|
||||
_pos_control.set_max_accel_z(_wp_accel_z_cmss);
|
||||
|
||||
// advance the target if necessary
|
||||
if (!advance_wp_target_along_track(dt)) {
|
||||
|
Loading…
Reference in New Issue
Block a user