Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AC_Circle: Always restore the radius from parameters #16757

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions libraries/AC_WPNav/AC_Circle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ const AP_Param::GroupInfo AC_Circle::var_info[] = {
// @Range: 0 200000
// @Increment: 100
// @User: Standard
AP_GROUPINFO("RADIUS", 0, AC_Circle, _radius, AC_CIRCLE_RADIUS_DEFAULT),
AP_GROUPINFO("RADIUS", 0, AC_Circle, _radius_parm, AC_CIRCLE_RADIUS_DEFAULT),

// @Param: RATE
// @DisplayName: Circle rate
Expand Down Expand Up @@ -62,7 +62,6 @@ void AC_Circle::init(const Vector3f& center, bool terrain_alt)
{
_center = center;
_terrain_alt = terrain_alt;

// initialise position controller (sets target roll angle, pitch angle and I terms based on vehicle current lean angles)
_pos_control.set_desired_accel_xy(0.0f,0.0f);
_pos_control.set_desired_velocity_xy(0.0f,0.0f);
Expand All @@ -82,7 +81,9 @@ void AC_Circle::init(const Vector3f& center, bool terrain_alt)
/// init - initialise circle controller setting center using stopping point and projecting out based on the copter's heading
/// caller should set the position controller's x,y and z speeds and accelerations before calling this
void AC_Circle::init()
{
{
//initialize radius from params
_radius =_radius_parm;
// initialise position controller (sets target roll angle, pitch angle and I terms based on vehicle current lean angles)
_pos_control.set_desired_accel_xy(0.0f,0.0f);
_pos_control.set_desired_velocity_xy(0.0f,0.0f);
Expand Down
5 changes: 3 additions & 2 deletions libraries/AC_WPNav/AC_Circle.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class AC_Circle
bool center_is_terrain_alt() const { return _terrain_alt; }

/// get_radius - returns radius of circle in cm
float get_radius() const { return _radius; }
float get_radius() const { return is_positive(_radius)?_radius:_radius_parm; }

/// set_radius - sets circle radius in cm
void set_radius(float radius_cm);
Expand Down Expand Up @@ -134,12 +134,13 @@ class AC_Circle
};

// parameters
AP_Float _radius; // maximum horizontal speed in cm/s during missions
AP_Float _radius_parm; // radius of circle in cm loaded from params
AP_Float _rate; // rotation speed in deg/sec
AP_Int16 _options; // stick control enable/disable

// internal variables
Vector3f _center; // center of circle in cm from home
float _radius; // radius of circle in cm
float _yaw; // yaw heading (normally towards circle center)
float _angle; // current angular position around circle in radians (0=directly north of the center of the circle)
float _angle_total; // total angle traveled in radians
Expand Down