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/Rover/mode_circle.cpp
Views: 1798
1
#include "Rover.h"
2
3
#define AR_CIRCLE_ACCEL_DEFAULT 1.0 // default acceleration in m/s/s if not specified by user
4
#define AR_CIRCLE_RADIUS_MIN 0.5 // minimum radius in meters
5
#define AR_CIRCLE_REACHED_EDGE_DIST 0.2 // vehicle has reached edge if within 0.2m
6
7
const AP_Param::GroupInfo ModeCircle::var_info[] = {
8
9
// @Param: _RADIUS
10
// @DisplayName: Circle Radius
11
// @Description: Vehicle will circle the center at this distance
12
// @Units: m
13
// @Range: 0 100
14
// @Increment: 1
15
// @User: Standard
16
AP_GROUPINFO("_RADIUS", 1, ModeCircle, radius, 20),
17
18
// @Param: _SPEED
19
// @DisplayName: Circle Speed
20
// @Description: Vehicle will move at this speed around the circle. If set to zero WP_SPEED will be used
21
// @Units: m/s
22
// @Range: 0 10
23
// @Increment: 0.1
24
// @User: Standard
25
AP_GROUPINFO("_SPEED", 2, ModeCircle, speed, 0),
26
27
// @Param: _DIR
28
// @DisplayName: Circle Direction
29
// @Description: Circle Direction
30
// @Values: 0:Clockwise, 1:Counter-Clockwise
31
// @User: Standard
32
AP_GROUPINFO("_DIR", 3, ModeCircle, direction, 0),
33
34
AP_GROUPEND
35
};
36
37
ModeCircle::ModeCircle() : Mode()
38
{
39
AP_Param::setup_object_defaults(this, var_info);
40
}
41
42
// initialise with specific center location, radius (in meters) and direction
43
// replaces use of _enter when initialised from within Auto mode
44
bool ModeCircle::set_center(const Location& center_loc, float radius_m, bool dir_ccw)
45
{
46
Vector2f center_pos_cm;
47
if (!center_loc.get_vector_xy_from_origin_NE(center_pos_cm)) {
48
return false;
49
}
50
if (!_enter()) {
51
return false;
52
}
53
54
// convert center position from cm to m
55
config.center_pos = center_pos_cm * 0.01;
56
57
// set radius
58
config.radius = MAX(fabsf(radius_m), AR_CIRCLE_RADIUS_MIN);
59
check_config_radius();
60
61
// set direction
62
config.dir = dir_ccw ? Direction::CCW : Direction::CW;
63
64
// set target yaw rad (target point on circle)
65
init_target_yaw_rad();
66
67
// record center as location (only used for reporting)
68
config.center_loc = center_loc;
69
70
return true;
71
}
72
73
// initialize circle mode from current position
74
bool ModeCircle::_enter()
75
{
76
// capture starting point and yaw
77
if (!AP::ahrs().get_relative_position_NE_origin(config.center_pos)) {
78
return false;
79
}
80
config.radius = MAX(fabsf(radius), AR_CIRCLE_RADIUS_MIN);
81
check_config_radius();
82
83
config.dir = (direction == 1) ? Direction::CCW : Direction::CW;
84
config.speed = is_positive(speed) ? speed : g2.wp_nav.get_default_speed();
85
target.yaw_rad = AP::ahrs().get_yaw();
86
target.speed = 0;
87
88
// record center as location (only used for reporting)
89
config.center_loc = rover.current_loc;
90
91
// check speed around circle does not lead to excessive lateral acceleration
92
check_config_speed();
93
94
// reset tracking_back
95
tracking_back = false;
96
97
// calculate speed, accel and jerk limits
98
// otherwise the vehicle uses wp_nav default speed limit
99
float atc_accel_max = MIN(g2.attitude_control.get_accel_max(), g2.attitude_control.get_decel_max());
100
if (!is_positive(atc_accel_max)) {
101
atc_accel_max = AR_CIRCLE_ACCEL_DEFAULT;
102
}
103
const float accel_max = is_positive(g2.wp_nav.get_default_accel()) ? MIN(g2.wp_nav.get_default_accel(), atc_accel_max) : atc_accel_max;
104
const float jerk_max = is_positive(g2.wp_nav.get_default_jerk()) ? g2.wp_nav.get_default_jerk() : accel_max;
105
106
// initialise position controller
107
g2.pos_control.set_limits(config.speed, accel_max, g2.attitude_control.get_turn_lat_accel_max(), jerk_max);
108
g2.pos_control.init();
109
110
// initialise angles covered and reached_edge state
111
angle_total_rad = 0;
112
reached_edge = false;
113
dist_to_edge_m = 0;
114
115
return true;
116
}
117
118
// initialise target_yaw_rad using the vehicle's position and yaw
119
// if there is no current position estimate target_yaw_rad is set to 0
120
void ModeCircle::init_target_yaw_rad()
121
{
122
// if no position estimate use vehicle yaw
123
Vector2f curr_pos_NE;
124
if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) {
125
target.yaw_rad = AP::ahrs().get_yaw();
126
return;
127
}
128
129
// calc vector from circle center to vehicle
130
Vector2f center_to_veh = (curr_pos_NE - config.center_pos);
131
float dist_m = center_to_veh.length();
132
133
// if current position is exactly at the center of the circle return vehicle yaw
134
if (is_zero(dist_m)) {
135
target.yaw_rad = AP::ahrs().get_yaw();
136
} else {
137
target.yaw_rad = center_to_veh.angle();
138
}
139
}
140
141
void ModeCircle::update()
142
{
143
// get current position
144
Vector2f curr_pos;
145
const bool position_ok = AP::ahrs().get_relative_position_NE_origin(curr_pos);
146
147
// if no position estimate stop vehicle
148
if (!position_ok) {
149
stop_vehicle();
150
return;
151
}
152
153
// Update distance to destination and distance to edge
154
const Vector2f center_to_veh = curr_pos - config.center_pos;
155
_distance_to_destination = (target.pos.tofloat() - curr_pos).length();
156
dist_to_edge_m = fabsf(center_to_veh.length() - config.radius);
157
158
// Update depending on stage
159
if (!reached_edge) {
160
update_drive_to_radius();
161
} else if (dist_to_edge_m > 2 * MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST) && !tracking_back) {
162
// if more than 2* turn_radius outside circle radius, slow vehicle by 20%
163
config.speed = 0.8 * config.speed;
164
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Circle: cannot keep up, slowing to %.1fm/s", config.speed);
165
tracking_back = true;
166
} else if (dist_to_edge_m < MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST) && tracking_back) {
167
// if within turn_radius, call the vehicle back on track
168
tracking_back = false;
169
} else {
170
update_circling();
171
}
172
173
g2.pos_control.update(rover.G_Dt);
174
175
// get desired speed and turn rate from pos_control
176
const float desired_speed = g2.pos_control.get_desired_speed();
177
const float desired_turn_rate = g2.pos_control.get_desired_turn_rate_rads();
178
179
// run steering and throttle controllers
180
calc_steering_from_turn_rate(desired_turn_rate);
181
calc_throttle(desired_speed, true);
182
}
183
184
void ModeCircle::update_drive_to_radius()
185
{
186
// check if vehicle has reached edge of circle
187
const float dist_thresh_m = MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST);
188
reached_edge |= dist_to_edge_m <= dist_thresh_m;
189
190
// calculate target point's position, velocity and acceleration
191
target.pos = config.center_pos.topostype();
192
target.pos.offset_bearing(degrees(target.yaw_rad), config.radius);
193
194
g2.pos_control.input_pos_target(target.pos, rover.G_Dt);
195
}
196
197
// Update position controller targets while circling
198
void ModeCircle::update_circling()
199
{
200
201
// accelerate speed up to desired speed
202
const float speed_change_max = (g2.pos_control.get_accel_max() * 0.5 * rover.G_Dt);
203
const float accel_fb = constrain_float(config.speed - target.speed, -speed_change_max, speed_change_max);
204
target.speed += accel_fb;
205
206
// calculate angular rate and update target angle, if the vehicle is not trying to track back
207
if (!tracking_back) {
208
const float circumference = 2.0 * M_PI * config.radius;
209
const float angular_rate_rad = (target.speed / circumference) * M_2PI * (config.dir == Direction::CW ? 1.0 : -1.0);
210
const float angle_dt = angular_rate_rad * rover.G_Dt;
211
target.yaw_rad = wrap_PI(target.yaw_rad + angle_dt);
212
angle_total_rad += angle_dt;
213
} else {
214
init_target_yaw_rad();
215
}
216
217
// calculate target point's position, velocity and acceleration
218
target.pos = config.center_pos.topostype();
219
target.pos.offset_bearing(degrees(target.yaw_rad), config.radius);
220
221
// velocity is perpendicular to angle from the circle's center to the target point on the edge of the circle
222
target.vel = Vector2f(target.speed, 0);
223
target.vel.rotate(target.yaw_rad + radians(90));
224
225
// acceleration is towards center of circle and is speed^2 / radius
226
target.accel = Vector2f(-sq(target.speed) / config.radius, accel_fb / rover.G_Dt);
227
target.accel.rotate(target.yaw_rad);
228
229
g2.pos_control.set_pos_vel_accel_target(target.pos, target.vel, target.accel);
230
231
}
232
233
// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
234
float ModeCircle::wp_bearing() const
235
{
236
Vector2f curr_pos_NE;
237
if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) {
238
return 0;
239
}
240
// calc vector from circle center to vehicle
241
Vector2f veh_to_center = (target.pos.tofloat() - curr_pos_NE);
242
if (veh_to_center.is_zero()) {
243
return 0;
244
}
245
return degrees(veh_to_center.angle());
246
}
247
248
float ModeCircle::nav_bearing() const
249
{
250
// get position error as a vector from the current position to the target position
251
const Vector2p pos_error = g2.pos_control.get_pos_error();
252
if (pos_error.is_zero()) {
253
return 0;
254
}
255
return degrees(pos_error.angle());
256
}
257
258
float ModeCircle::get_desired_lat_accel() const
259
{
260
return g2.pos_control.get_desired_lat_accel();
261
}
262
263
// set desired speed in m/s
264
bool ModeCircle::set_desired_speed(float speed_ms)
265
{
266
if (is_positive(speed_ms)) {
267
config.speed = speed_ms;
268
269
// check desired speed does not lead to excessive lateral acceleration
270
check_config_speed();
271
272
// update position controller limits if required
273
if (config.speed > g2.pos_control.get_speed_max()) {
274
g2.pos_control.set_limits(config.speed, g2.pos_control.get_accel_max(), g2.pos_control.get_lat_accel_max(), g2.pos_control.get_jerk_max());
275
}
276
return true;
277
}
278
279
return false;
280
}
281
282
// return desired location
283
bool ModeCircle::get_desired_location(Location& destination) const
284
{
285
destination = config.center_loc;
286
destination.offset_bearing(degrees(target.yaw_rad), config.radius);
287
return true;
288
}
289
290
// limit config speed so that lateral acceleration is within limits
291
// assumes that config.radius and attitude controller lat accel max have been set
292
// outputs warning to user if speed is reduced
293
void ModeCircle::check_config_speed()
294
{
295
// calculate maximum speed based on radius and max lateral acceleration max
296
const float speed_max = MAX(safe_sqrt(g2.attitude_control.get_turn_lat_accel_max() * config.radius), 0);
297
298
if (config.speed > speed_max) {
299
config.speed = speed_max;
300
gcs().send_text(MAV_SEVERITY_WARNING, "Circle: max speed is %4.1f", (double)config.speed);
301
}
302
}
303
304
// ensure config radius is no smaller then vehicle's TURN_RADIUS
305
// assumes that config.radius has been set
306
// radius is increased if necessary and warning is output to the user
307
void ModeCircle::check_config_radius()
308
{
309
// ensure radius is at least as large as vehicle's turn radius
310
if (config.radius < g2.turn_radius) {
311
config.radius = g2.turn_radius;
312
gcs().send_text(MAV_SEVERITY_WARNING, "Circle: radius increased to TURN_RADIUS (%4.1f)", (double)g2.turn_radius);
313
}
314
}
315
316