mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_PosControl: add set_leash_length_xy
This commit is contained in:
parent
e5bc2b26fe
commit
dadc6a63c4
@ -932,6 +932,7 @@ float AC_PosControl::get_horizontal_error() const
|
||||
/// should be called whenever the speed, acceleration or position kP is modified
|
||||
void AC_PosControl::calc_leash_length_xy()
|
||||
{
|
||||
// todo: remove _flags.recalc_leash_xy or don't call this function after each variable change.
|
||||
if (_flags.recalc_leash_xy) {
|
||||
_leash = calc_leash_length(_speed_cms, _accel_cms, _p_pos_xy.kP());
|
||||
_flags.recalc_leash_xy = false;
|
||||
|
@ -187,6 +187,9 @@ public:
|
||||
/// should be called whenever the speed, acceleration or position kP is modified
|
||||
void calc_leash_length_xy();
|
||||
|
||||
/// set the horizontal leash length
|
||||
void set_leash_length_xy(float leash) { _leash = leash; _flags.recalc_leash_xy = false; }
|
||||
|
||||
/// get_pos_target - get target as position vector (from home in cm)
|
||||
const Vector3f& get_pos_target() const { return _pos_target; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user