mirror of https://github.com/ArduPilot/ardupilot
AC_PosControl: Replace update_vel_controller_xy() with update_xy_controller()
This commit is contained in:
parent
7e835d1037
commit
6a98ab569e
|
@ -966,45 +966,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);
|
||||
|
|
|
@ -263,12 +263,6 @@ public:
|
|||
/// 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
|
||||
|
|
Loading…
Reference in New Issue