APM:Libraries
AC_Circle.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AC_Circle.h"
3 #include <AP_Math/AP_Math.h>
4 
5 extern const AP_HAL::HAL& hal;
6 
8  // @Param: RADIUS
9  // @DisplayName: Circle Radius
10  // @Description: Defines the radius of the circle the vehicle will fly when in Circle flight mode
11  // @Units: cm
12  // @Range: 0 10000
13  // @Increment: 100
14  // @User: Standard
15  AP_GROUPINFO("RADIUS", 0, AC_Circle, _radius, AC_CIRCLE_RADIUS_DEFAULT),
16 
17  // @Param: RATE
18  // @DisplayName: Circle rate
19  // @Description: Circle mode's turn rate in deg/sec. Positive to turn clockwise, negative for counter clockwise
20  // @Units: deg/s
21  // @Range: -90 90
22  // @Increment: 1
23  // @User: Standard
24  AP_GROUPINFO("RATE", 1, AC_Circle, _rate, AC_CIRCLE_RATE_DEFAULT),
25 
27 };
28 
29 // Default constructor.
30 // Note that the Vector/Matrix constructors already implicitly zero
31 // their values.
32 //
34  _inav(inav),
35  _ahrs(ahrs),
36  _pos_control(pos_control),
37  _yaw(0.0f),
38  _angle(0.0f),
39  _angle_total(0.0f),
40  _angular_vel(0.0f),
41  _angular_vel_max(0.0f),
42  _angular_accel(0.0f)
43 {
45 
46  // init flags
47  _flags.panorama = false;
48 }
49 
52 void AC_Circle::init(const Vector3f& center)
53 {
54  _center = center;
55 
56  // initialise position controller (sets target roll angle, pitch angle and I terms based on vehicle current lean angles)
60 
61  // set initial position target to reasonable stopping point
64 
65  // calculate velocities
66  calc_velocities(true);
67 
68  // set start angle from position
69  init_start_angle(false);
70 }
71 
75 {
76  // initialise position controller (sets target roll angle, pitch angle and I terms based on vehicle current lean angles)
80 
81  // set initial position target to reasonable stopping point
84 
85  // get stopping point
86  const Vector3f& stopping_point = _pos_control.get_pos_target();
87 
88  // set circle center to circle_radius ahead of stopping point
89  _center.x = stopping_point.x + _radius * _ahrs.cos_yaw();
90  _center.y = stopping_point.y + _radius * _ahrs.sin_yaw();
91  _center.z = stopping_point.z;
92 
93  // calculate velocities
94  calc_velocities(true);
95 
96  // set starting angle from vehicle heading
97  init_start_angle(true);
98 }
99 
101 void AC_Circle::set_rate(float deg_per_sec)
102 {
103  if (!is_equal(deg_per_sec, _rate.get())) {
104  _rate = deg_per_sec;
105  calc_velocities(false);
106  }
107 }
108 
111 {
112  // calculate dt
114  if (dt >= 0.2f) {
115  dt = 0.0f;
116  }
117 
118  // ramp angular velocity to maximum
120  _angular_vel += fabsf(_angular_accel) * dt;
122  }
124  _angular_vel -= fabsf(_angular_accel) * dt;
126  }
127 
128  // update the target angle and total angle traveled
129  float angle_change = _angular_vel * dt;
130  _angle += angle_change;
131  _angle = wrap_PI(_angle);
132  _angle_total += angle_change;
133 
134  // if the circle_radius is zero we are doing panorama so no need to update loiter target
135  if (!is_zero(_radius)) {
136  // calculate target position
137  Vector3f target;
138  target.x = _center.x + _radius * cosf(-_angle);
139  target.y = _center.y - _radius * sinf(-_angle);
140  target.z = _pos_control.get_alt_target();
141 
142  // update position controller target
143  _pos_control.set_xy_target(target.x, target.y);
144 
145  // heading is 180 deg from vehicles target position around circle
147  } else {
148  // set target position to center
149  Vector3f target;
150  target.x = _center.x;
151  target.y = _center.y;
152  target.z = _pos_control.get_alt_target();
153 
154  // update position controller target
155  _pos_control.set_xy_target(target.x, target.y);
156 
157  // heading is same as _angle but converted to centi-degrees
158  _yaw = _angle * DEGX100;
159  }
160 
161  // update position controller
163 }
164 
165 // get_closest_point_on_circle - returns closest point on the circle
166 // circle's center should already have been set
167 // closest point on the circle will be placed in result
168 // result's altitude (i.e. z) will be set to the circle_center's altitude
169 // if vehicle is at the center of the circle, the edge directly behind vehicle will be returned
171 {
172  // return center if radius is zero
173  if (_radius <= 0) {
174  result = _center;
175  return;
176  }
177 
178  // get current position
179  const Vector3f &curr_pos = _inav.get_position();
180 
181  // calc vector from current location to circle center
182  Vector2f vec; // vector from circle center to current location
183  vec.x = (curr_pos.x - _center.x);
184  vec.y = (curr_pos.y - _center.y);
185  float dist = norm(vec.x, vec.y);
186 
187  // if current location is exactly at the center of the circle return edge directly behind vehicle
188  if (is_zero(dist)) {
189  result.x = _center.x - _radius * _ahrs.cos_yaw();
190  result.y = _center.y - _radius * _ahrs.sin_yaw();
191  result.z = _center.z;
192  return;
193  }
194 
195  // calculate closest point on edge of circle
196  result.x = _center.x + vec.x / dist * _radius;
197  result.y = _center.y + vec.y / dist * _radius;
198  result.z = _center.z;
199 }
200 
201 // calc_velocities - calculate angular velocity max and acceleration based on radius and rate
202 // this should be called whenever the radius or rate are changed
203 // initialises the yaw and current position around the circle
204 void AC_Circle::calc_velocities(bool init_velocity)
205 {
206  // if we are doing a panorama set the circle_angle to the current heading
207  if (_radius <= 0) {
209  _angular_accel = MAX(fabsf(_angular_vel_max),ToRad(AC_CIRCLE_ANGULAR_ACCEL_MIN)); // reach maximum yaw velocity in 1 second
210  }else{
211  // calculate max velocity based on waypoint speed ensuring we do not use more than half our max acceleration for accelerating towards the center of the circle
212  float velocity_max = MIN(_pos_control.get_speed_xy(), safe_sqrt(0.5f*_pos_control.get_accel_xy()*_radius));
213 
214  // angular_velocity in radians per second
215  _angular_vel_max = velocity_max/_radius;
217 
218  // angular_velocity in radians per second
220  }
221 
222  // initialise angular velocity
223  if (init_velocity) {
224  _angular_vel = 0;
225  }
226 }
227 
228 // init_start_angle - sets the starting angle around the circle and initialises the angle_total
229 // if use_heading is true the vehicle's heading will be used to init the angle causing minimum yaw movement
230 // if use_heading is false the vehicle's position from the center will be used to initialise the angle
231 void AC_Circle::init_start_angle(bool use_heading)
232 {
233  // initialise angle total
234  _angle_total = 0;
235 
236  // if the radius is zero we are doing panorama so init angle to the current heading
237  if (_radius <= 0) {
238  _angle = _ahrs.yaw;
239  return;
240  }
241 
242  // if use_heading is true
243  if (use_heading) {
245  } else {
246  // if we are exactly at the center of the circle, init angle to directly behind vehicle (so vehicle will backup but not change heading)
247  const Vector3f &curr_pos = _inav.get_position();
248  if (is_equal(curr_pos.x,_center.x) && is_equal(curr_pos.y,_center.y)) {
250  } else {
251  // get bearing from circle center to vehicle in radians
252  float bearing_rad = atan2f(curr_pos.y-_center.y,curr_pos.x-_center.x);
253  _angle = wrap_PI(bearing_rad);
254  }
255  }
256 }
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
float get_speed_xy() const
void calc_velocities(bool init_velocity)
Definition: AC_Circle.cpp:204
float get_alt_target() const
void set_desired_velocity_xy(float vel_lat_cms, float vel_lon_cms)
AC_PosControl & _pos_control
Definition: AC_Circle.h:90
virtual const Vector3f & get_position() const =0
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
float _yaw
Definition: AC_Circle.h:98
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
#define ToRad(x)
Definition: AP_Common.h:53
void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms)
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void update_xy_controller(float ekfNavVelGainScaler)
update_xy_controller - run the horizontal position controller - should be called at 100hz or higher ...
void update()
update - update circle controller
Definition: AC_Circle.cpp:110
const char * result
Definition: Printf.cpp:16
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
float _angular_vel
Definition: AC_Circle.h:101
#define MIN(a, b)
Definition: usb_conf.h:215
void init_start_angle(bool use_heading)
Definition: AC_Circle.cpp:231
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
void set_xy_target(float x, float y)
set_xy_target in cm from home
T y
Definition: vector2.h:37
float get_accel_xy() const
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
const Vector3f & get_pos_target() const
get_pos_target - get target as position vector (from home in cm)
#define AC_CIRCLE_ANGULAR_ACCEL_MIN
Definition: AC_Circle.h:12
#define AC_CIRCLE_RADIUS_DEFAULT
Definition: AC_Circle.h:10
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
void init_xy_controller(bool reset_I=true)
T y
Definition: vector3.h:67
const AP_AHRS_View & _ahrs
Definition: AC_Circle.h:89
float _angular_vel_max
Definition: AC_Circle.h:102
T z
Definition: vector3.h:67
void set_rate(float deg_per_sec)
set_circle_rate - set circle rate in degrees per second
Definition: AC_Circle.cpp:101
float _angular_accel
Definition: AC_Circle.h:103
void init()
Definition: AC_Circle.cpp:74
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_Circle.h:67
const AP_InertialNav & _inav
Definition: AC_Circle.h:88
AP_Float _radius
Definition: AC_Circle.h:93
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
void set_target_to_stopping_point_xy()
set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from h...
#define AC_CIRCLE_RATE_DEFAULT
Definition: AC_Circle.h:11
#define DEGX100
Definition: definitions.h:34
AC_Circle(const AP_InertialNav &inav, const AP_AHRS_View &ahrs, AC_PosControl &pos_control)
Constructor.
Definition: AC_Circle.cpp:33
void get_closest_point_on_circle(Vector3f &result)
Definition: AC_Circle.cpp:170
void set_target_to_stopping_point_z()
set_target_to_stopping_point_z - sets altitude target to reasonable stopping altitude in cm above hom...
float _angle
Definition: AC_Circle.h:99
float time_since_last_xy_update() const
#define M_PI
Definition: definitions.h:10
AP_Float _rate
Definition: AC_Circle.h:94
Vector3f _center
Definition: AC_Circle.h:97
float _angle_total
Definition: AC_Circle.h:100
struct AC_Circle::circle_flags _flags
#define AP_GROUPEND
Definition: AP_Param.h:121
T x
Definition: vector3.h:67
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214