Browse Source

AC_WPNav: update usage of update_xy_controller

mission-4.1.18
Jonathan Challinger 10 years ago committed by Randy Mackay
parent
commit
626521c366
  1. 2
      libraries/AC_WPNav/AC_Circle.cpp
  2. 6
      libraries/AC_WPNav/AC_WPNav.cpp

2
libraries/AC_WPNav/AC_Circle.cpp

@ -151,7 +151,7 @@ void AC_Circle::update() @@ -151,7 +151,7 @@ void AC_Circle::update()
}
// update position controller
_pos_control.update_xy_controller(false, 1.0f);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f);
}
}

6
libraries/AC_WPNav/AC_WPNav.cpp

@ -304,7 +304,7 @@ void AC_WPNav::update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler) @@ -304,7 +304,7 @@ void AC_WPNav::update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler)
dt = 0.0f;
}
calc_loiter_desired_velocity(dt,ekfGndSpdLimit);
_pos_control.update_xy_controller(true, ekfNavVelGainScaler);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_SLOW_POS_AND_VEL, ekfNavVelGainScaler);
}
}
@ -612,7 +612,7 @@ void AC_WPNav::update_wpnav() @@ -612,7 +612,7 @@ void AC_WPNav::update_wpnav()
}
_pos_control.freeze_ff_z();
_pos_control.update_xy_controller(false, 1.0f);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f);
check_wp_leash_length();
_wp_last_update = hal.scheduler->millis();
@ -875,7 +875,7 @@ void AC_WPNav::update_spline() @@ -875,7 +875,7 @@ void AC_WPNav::update_spline()
_pos_control.freeze_ff_z();
// run horizontal position controller
_pos_control.update_xy_controller(false, 1.0f);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f);
_wp_last_update = hal.scheduler->millis();
}

Loading…
Cancel
Save