CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_WPNav/AC_Circle.cpp
Views: 1798
1
#include <AP_HAL/AP_HAL.h>
2
#include <AP_Math/AP_Math.h>
3
#include <AP_Terrain/AP_Terrain.h>
4
#include "AC_Circle.h"
5
6
#include <AP_Logger/AP_Logger.h>
7
8
extern const AP_HAL::HAL& hal;
9
10
const AP_Param::GroupInfo AC_Circle::var_info[] = {
11
// @Param: RADIUS
12
// @DisplayName: Circle Radius
13
// @Description: Defines the radius of the circle the vehicle will fly when in Circle flight mode
14
// @Units: cm
15
// @Range: 0 200000
16
// @Increment: 100
17
// @User: Standard
18
AP_GROUPINFO("RADIUS", 0, AC_Circle, _radius_parm, AC_CIRCLE_RADIUS_DEFAULT),
19
20
// @Param: RATE
21
// @DisplayName: Circle rate
22
// @Description: Circle mode's turn rate in deg/sec. Positive to turn clockwise, negative for counter clockwise. Circle rate must be less than ATC_SLEW_YAW parameter.
23
// @Units: deg/s
24
// @Range: -90 90
25
// @Increment: 1
26
// @User: Standard
27
AP_GROUPINFO("RATE", 1, AC_Circle, _rate_parm, AC_CIRCLE_RATE_DEFAULT),
28
29
// @Param: OPTIONS
30
// @DisplayName: Circle options
31
// @Description: 0:Enable or disable using the pitch/roll stick control circle mode's radius and rate
32
// @Bitmask: 0:manual control, 1:face direction of travel, 2:Start at center rather than on perimeter, 3:Make Mount ROI the center of the circle
33
// @User: Standard
34
AP_GROUPINFO("OPTIONS", 2, AC_Circle, _options, 1),
35
36
AP_GROUPEND
37
};
38
39
// Default constructor.
40
// Note that the Vector/Matrix constructors already implicitly zero
41
// their values.
42
//
43
AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control) :
44
_inav(inav),
45
_ahrs(ahrs),
46
_pos_control(pos_control)
47
{
48
AP_Param::setup_object_defaults(this, var_info);
49
50
// init flags
51
_flags.panorama = false;
52
_rate = _rate_parm;
53
}
54
55
/// init - initialise circle controller setting center specifically
56
/// set terrain_alt to true if center.z should be interpreted as an alt-above-terrain. Rate should be +ve in deg/sec for cw turn
57
/// caller should set the position controller's x,y and z speeds and accelerations before calling this
58
void AC_Circle::init(const Vector3p& center, bool terrain_alt, float rate_deg_per_sec)
59
{
60
_center = center;
61
_terrain_alt = terrain_alt;
62
_rate = rate_deg_per_sec;
63
64
// initialise position controller (sets target roll angle, pitch angle and I terms based on vehicle current lean angles)
65
_pos_control.init_xy_controller_stopping_point();
66
_pos_control.init_z_controller_stopping_point();
67
68
// calculate velocities
69
calc_velocities(true);
70
71
// set start angle from position
72
init_start_angle(false);
73
}
74
75
/// init - initialise circle controller setting center using stopping point and projecting out based on the copter's heading
76
/// caller should set the position controller's x,y and z speeds and accelerations before calling this
77
void AC_Circle::init()
78
{
79
// initialize radius and rate from params
80
_radius = _radius_parm;
81
_last_radius_param = _radius_parm;
82
_rate = _rate_parm;
83
84
// initialise position controller (sets target roll angle, pitch angle and I terms based on vehicle current lean angles)
85
_pos_control.init_xy_controller_stopping_point();
86
_pos_control.init_z_controller_stopping_point();
87
88
// get stopping point
89
const Vector3p& stopping_point = _pos_control.get_pos_desired_cm();
90
91
// set circle center to circle_radius ahead of stopping point
92
_center = stopping_point;
93
if ((_options.get() & CircleOptions::INIT_AT_CENTER) == 0) {
94
_center.x += _radius * _ahrs.cos_yaw();
95
_center.y += _radius * _ahrs.sin_yaw();
96
}
97
_terrain_alt = false;
98
99
// calculate velocities
100
calc_velocities(true);
101
102
// set starting angle from vehicle heading
103
init_start_angle(true);
104
}
105
106
/// set circle center to a Location
107
void AC_Circle::set_center(const Location& center)
108
{
109
if (center.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) {
110
// convert Location with terrain altitude
111
Vector2f center_xy;
112
int32_t terr_alt_cm;
113
if (center.get_vector_xy_from_origin_NE(center_xy) && center.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, terr_alt_cm)) {
114
set_center(Vector3f(center_xy.x, center_xy.y, terr_alt_cm), true);
115
} else {
116
// failed to convert location so set to current position and log error
117
set_center(_inav.get_position_neu_cm(), false);
118
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
119
}
120
} else {
121
// convert Location with alt-above-home, alt-above-origin or absolute alt
122
Vector3f circle_center_neu;
123
if (!center.get_vector_from_origin_NEU(circle_center_neu)) {
124
// default to current position and log error
125
circle_center_neu = _inav.get_position_neu_cm();
126
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
127
}
128
set_center(circle_center_neu, false);
129
}
130
}
131
132
/// set_circle_rate - set circle rate in degrees per second
133
void AC_Circle::set_rate(float deg_per_sec)
134
{
135
if (!is_equal(deg_per_sec, _rate)) {
136
_rate = deg_per_sec;
137
}
138
}
139
140
/// set_circle_rate - set circle rate in degrees per second
141
void AC_Circle::set_radius_cm(float radius_cm)
142
{
143
_radius = constrain_float(radius_cm, 0, AC_CIRCLE_RADIUS_MAX);
144
}
145
146
/// returns true if update has been run recently
147
/// used by vehicle code to determine if get_yaw() is valid
148
bool AC_Circle::is_active() const
149
{
150
return (AP_HAL::millis() - _last_update_ms < 200);
151
}
152
153
/// update - update circle controller
154
bool AC_Circle::update(float climb_rate_cms)
155
{
156
calc_velocities(false);
157
158
// calculate dt
159
const float dt = _pos_control.get_dt();
160
161
// ramp angular velocity to maximum
162
if (_angular_vel < _angular_vel_max) {
163
_angular_vel += fabsf(_angular_accel) * dt;
164
_angular_vel = MIN(_angular_vel, _angular_vel_max);
165
}
166
if (_angular_vel > _angular_vel_max) {
167
_angular_vel -= fabsf(_angular_accel) * dt;
168
_angular_vel = MAX(_angular_vel, _angular_vel_max);
169
}
170
171
// update the target angle and total angle travelled
172
float angle_change = _angular_vel * dt;
173
_angle += angle_change;
174
_angle = wrap_PI(_angle);
175
_angle_total += angle_change;
176
177
// calculate terrain adjustments
178
float terr_offset = 0.0f;
179
if (_terrain_alt && !get_terrain_offset(terr_offset)) {
180
return false;
181
}
182
183
// calculate z-axis target
184
float target_z_cm;
185
if (_terrain_alt) {
186
target_z_cm = _center.z + terr_offset;
187
} else {
188
target_z_cm = _pos_control.get_pos_desired_z_cm();
189
}
190
191
// if the circle_radius is zero we are doing panorama so no need to update loiter target
192
Vector3p target {
193
_center.x,
194
_center.y,
195
target_z_cm
196
};
197
if (!is_zero(_radius)) {
198
// calculate target position
199
target.x += _radius * cosf(-_angle);
200
target.y += - _radius * sinf(-_angle);
201
202
// heading is from vehicle to center of circle
203
_yaw = get_bearing_cd(_pos_control.get_pos_desired_cm().xy().tofloat(), _center.tofloat().xy());
204
205
if ((_options.get() & CircleOptions::FACE_DIRECTION_OF_TRAVEL) != 0) {
206
_yaw += is_positive(_rate)?-9000.0f:9000.0f;
207
_yaw = wrap_360_cd(_yaw);
208
}
209
210
} else {
211
// heading is same as _angle but converted to centi-degrees
212
_yaw = _angle * DEGX100;
213
}
214
215
// update position controller target
216
Vector2f zero;
217
_pos_control.input_pos_vel_accel_xy(target.xy(), zero, zero);
218
if (_terrain_alt) {
219
float zero2 = 0;
220
float target_zf = target.z;
221
_pos_control.input_pos_vel_accel_z(target_zf, zero2, 0);
222
} else {
223
_pos_control.set_pos_target_z_from_climb_rate_cm(climb_rate_cms);
224
}
225
226
// update position controller
227
_pos_control.update_xy_controller();
228
229
// set update time
230
_last_update_ms = AP_HAL::millis();
231
232
return true;
233
}
234
235
// get_closest_point_on_circle - returns closest point on the circle
236
// circle's center should already have been set
237
// closest point on the circle will be placed in result, dist_cm will be updated with the 3D distance to the center
238
// result's altitude (i.e. z) will be set to the circle_center's altitude
239
// if vehicle is at the center of the circle, the edge directly behind vehicle will be returned
240
void AC_Circle::get_closest_point_on_circle(Vector3f& result, float& dist_cm) const
241
{
242
// get current position
243
Vector3p stopping_point;
244
_pos_control.get_stopping_point_xy_cm(stopping_point.xy());
245
_pos_control.get_stopping_point_z_cm(stopping_point.z);
246
247
// calc vector from stopping point to circle center
248
Vector3f vec = (stopping_point - _center).tofloat();
249
dist_cm = vec.length();
250
251
// return center if radius is zero
252
if (!is_positive(_radius)) {
253
result = _center.tofloat();
254
return;
255
}
256
257
// if current location is exactly at the center of the circle return edge directly behind vehicle
258
if (is_zero(dist_cm)) {
259
result.x = _center.x - _radius * _ahrs.cos_yaw();
260
result.y = _center.y - _radius * _ahrs.sin_yaw();
261
result.z = _center.z;
262
return;
263
}
264
265
// calculate closest point on edge of circle
266
result.x = _center.x + vec.x / dist_cm * _radius;
267
result.y = _center.y + vec.y / dist_cm * _radius;
268
result.z = _center.z;
269
}
270
271
// calc_velocities - calculate angular velocity max and acceleration based on radius and rate
272
// this should be called whenever the radius or rate are changed
273
// initialises the yaw and current position around the circle
274
void AC_Circle::calc_velocities(bool init_velocity)
275
{
276
// if we are doing a panorama set the circle_angle to the current heading
277
if (_radius <= 0) {
278
_angular_vel_max = ToRad(_rate);
279
_angular_accel = MAX(fabsf(_angular_vel_max),ToRad(AC_CIRCLE_ANGULAR_ACCEL_MIN)); // reach maximum yaw velocity in 1 second
280
}else{
281
// 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
282
float velocity_max = MIN(_pos_control.get_max_speed_xy_cms(), safe_sqrt(0.5f*_pos_control.get_max_accel_xy_cmss()*_radius));
283
284
// angular_velocity in radians per second
285
_angular_vel_max = velocity_max/_radius;
286
_angular_vel_max = constrain_float(ToRad(_rate),-_angular_vel_max,_angular_vel_max);
287
288
// angular_velocity in radians per second
289
_angular_accel = MAX(_pos_control.get_max_accel_xy_cmss()/_radius, ToRad(AC_CIRCLE_ANGULAR_ACCEL_MIN));
290
}
291
292
// initialise angular velocity
293
if (init_velocity) {
294
_angular_vel = 0;
295
}
296
}
297
298
// init_start_angle - sets the starting angle around the circle and initialises the angle_total
299
// if use_heading is true the vehicle's heading will be used to init the angle causing minimum yaw movement
300
// if use_heading is false the vehicle's position from the center will be used to initialise the angle
301
void AC_Circle::init_start_angle(bool use_heading)
302
{
303
// initialise angle total
304
_angle_total = 0;
305
306
// if the radius is zero we are doing panorama so init angle to the current heading
307
if (_radius <= 0) {
308
_angle = _ahrs.yaw;
309
return;
310
}
311
312
// if use_heading is true
313
if (use_heading) {
314
_angle = wrap_PI(_ahrs.yaw-M_PI);
315
} else {
316
// if we are exactly at the center of the circle, init angle to directly behind vehicle (so vehicle will backup but not change heading)
317
// curr_pos_desired is the position before we add offsets and terrain
318
const Vector3f &curr_pos_desired= _pos_control.get_pos_desired_cm().tofloat();
319
if (is_equal(curr_pos_desired.x,float(_center.x)) && is_equal(curr_pos_desired.y,float(_center.y))) {
320
_angle = wrap_PI(_ahrs.yaw-M_PI);
321
} else {
322
// get bearing from circle center to vehicle in radians
323
float bearing_rad = atan2f(curr_pos_desired.y-_center.y, curr_pos_desired.x-_center.x);
324
_angle = wrap_PI(bearing_rad);
325
}
326
}
327
}
328
329
// get expected source of terrain data
330
AC_Circle::TerrainSource AC_Circle::get_terrain_source() const
331
{
332
// use range finder if connected
333
if (_rangefinder_available) {
334
return AC_Circle::TerrainSource::TERRAIN_FROM_RANGEFINDER;
335
}
336
#if AP_TERRAIN_AVAILABLE
337
const AP_Terrain *terrain = AP_Terrain::get_singleton();
338
if ((terrain != nullptr) && terrain->enabled()) {
339
return AC_Circle::TerrainSource::TERRAIN_FROM_TERRAINDATABASE;
340
} else {
341
return AC_Circle::TerrainSource::TERRAIN_UNAVAILABLE;
342
}
343
#else
344
return AC_Circle::TerrainSource::TERRAIN_UNAVAILABLE;
345
#endif
346
}
347
348
// get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude)
349
bool AC_Circle::get_terrain_offset(float& offset_cm)
350
{
351
// calculate offset based on source (rangefinder or terrain database)
352
switch (get_terrain_source()) {
353
case AC_Circle::TerrainSource::TERRAIN_UNAVAILABLE:
354
return false;
355
case AC_Circle::TerrainSource::TERRAIN_FROM_RANGEFINDER:
356
if (_rangefinder_healthy) {
357
offset_cm = _rangefinder_terrain_offset_cm;
358
return true;
359
}
360
return false;
361
case AC_Circle::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
362
#if AP_TERRAIN_AVAILABLE
363
float terr_alt = 0.0f;
364
AP_Terrain *terrain = AP_Terrain::get_singleton();
365
if (terrain != nullptr && terrain->height_above_terrain(terr_alt, true)) {
366
offset_cm = _inav.get_position_z_up_cm() - (terr_alt * 100.0);
367
return true;
368
}
369
#endif
370
return false;
371
}
372
373
// we should never get here but just in case
374
return false;
375
}
376
377
void AC_Circle::check_param_change()
378
{
379
if (!is_equal(_last_radius_param,_radius_parm.get())) {
380
_radius = _radius_parm;
381
_last_radius_param = _radius_parm;
382
}
383
}
384
385