diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 324479e0aa..c676bd0a48 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -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; diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index d7439f2ac6..7e650dba58 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -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; }