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/ArduCopter/autoyaw.cpp
Views: 1798
1
#include "Copter.h"
2
3
Mode::AutoYaw Mode::auto_yaw;
4
5
// roi_yaw - returns heading towards location held in roi
6
float Mode::AutoYaw::roi_yaw() const
7
{
8
return get_bearing_cd(copter.inertial_nav.get_position_xy_cm(), roi.xy());
9
}
10
11
// returns a yaw in degrees, direction of vehicle travel:
12
float Mode::AutoYaw::look_ahead_yaw()
13
{
14
const Vector3f& vel = copter.inertial_nav.get_velocity_neu_cms();
15
const float speed_sq = vel.xy().length_squared();
16
// Commanded Yaw to automatically look ahead.
17
if (copter.position_ok() && (speed_sq > (YAW_LOOK_AHEAD_MIN_SPEED * YAW_LOOK_AHEAD_MIN_SPEED))) {
18
_look_ahead_yaw = degrees(atan2f(vel.y,vel.x));
19
}
20
return _look_ahead_yaw;
21
}
22
23
void Mode::AutoYaw::set_mode_to_default(bool rtl)
24
{
25
set_mode(default_mode(rtl));
26
}
27
28
// default_mode - returns auto_yaw.mode() based on WP_YAW_BEHAVIOR parameter
29
// set rtl parameter to true if this is during an RTL
30
Mode::AutoYaw::Mode Mode::AutoYaw::default_mode(bool rtl) const
31
{
32
switch (copter.g.wp_yaw_behavior) {
33
34
case WP_YAW_BEHAVIOR_NONE:
35
return Mode::HOLD;
36
37
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL:
38
if (rtl) {
39
return Mode::HOLD;
40
} else {
41
return Mode::LOOK_AT_NEXT_WP;
42
}
43
44
case WP_YAW_BEHAVIOR_LOOK_AHEAD:
45
return Mode::LOOK_AHEAD;
46
47
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP:
48
default:
49
return Mode::LOOK_AT_NEXT_WP;
50
}
51
}
52
53
// set_mode - sets the yaw mode for auto
54
void Mode::AutoYaw::set_mode(Mode yaw_mode)
55
{
56
// return immediately if no change
57
if (_mode == yaw_mode) {
58
return;
59
}
60
_last_mode = _mode;
61
_mode = yaw_mode;
62
63
// perform initialisation
64
switch (_mode) {
65
66
case Mode::HOLD:
67
break;
68
69
case Mode::LOOK_AT_NEXT_WP:
70
// wpnav will initialise heading when wpnav's set_destination method is called
71
break;
72
73
case Mode::ROI:
74
// look ahead until we know otherwise
75
break;
76
77
case Mode::FIXED:
78
// keep heading pointing in the direction held in fixed_yaw
79
// caller should set the fixed_yaw
80
break;
81
82
case Mode::LOOK_AHEAD:
83
// Commanded Yaw to automatically look ahead.
84
_look_ahead_yaw = copter.ahrs.yaw_sensor * 0.01; // cdeg -> deg
85
break;
86
87
case Mode::RESETTOARMEDYAW:
88
// initial_armed_bearing will be set during arming so no init required
89
break;
90
91
case Mode::ANGLE_RATE:
92
break;
93
94
case Mode::RATE:
95
// initialise target yaw rate to zero
96
_yaw_rate_cds = 0.0;
97
break;
98
99
case Mode::CIRCLE:
100
case Mode::PILOT_RATE:
101
case Mode::WEATHERVANE:
102
// no initialisation required
103
break;
104
}
105
}
106
107
// set_fixed_yaw - sets the yaw look at heading for auto mode
108
void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t direction, bool relative_angle)
109
{
110
_last_update_ms = millis();
111
112
// calculate final angle as relative to vehicle heading or absolute
113
if (relative_angle) {
114
if (_mode == Mode::HOLD) {
115
_yaw_angle_cd = copter.ahrs.yaw_sensor;
116
}
117
_fixed_yaw_offset_cd = angle_deg * 100.0 * (direction >= 0 ? 1.0 : -1.0);
118
} else {
119
// absolute angle
120
_fixed_yaw_offset_cd = wrap_180_cd(angle_deg * 100.0 - _yaw_angle_cd);
121
if (direction < 0 && is_positive(_fixed_yaw_offset_cd)) {
122
_fixed_yaw_offset_cd -= 36000.0;
123
} else if (direction > 0 && is_negative(_fixed_yaw_offset_cd)) {
124
_fixed_yaw_offset_cd += 36000.0;
125
}
126
}
127
128
// get turn speed
129
if (!is_positive(turn_rate_ds)) {
130
// default to default slew rate
131
_fixed_yaw_slewrate_cds = copter.attitude_control->get_slew_yaw_max_degs() * 100.0;
132
} else {
133
_fixed_yaw_slewrate_cds = MIN(copter.attitude_control->get_slew_yaw_max_degs(), turn_rate_ds) * 100.0;
134
}
135
136
// set yaw mode
137
set_mode(Mode::FIXED);
138
}
139
140
// set_fixed_yaw - sets the yaw look at heading for auto mode
141
void Mode::AutoYaw::set_yaw_angle_rate(float yaw_angle_d, float yaw_rate_ds)
142
{
143
_last_update_ms = millis();
144
145
_yaw_angle_cd = yaw_angle_d * 100.0;
146
_yaw_rate_cds = yaw_rate_ds * 100.0;
147
148
// set yaw mode
149
set_mode(Mode::ANGLE_RATE);
150
}
151
152
// set_yaw_angle_offset - sets the yaw look at heading for auto mode, as an offset from the current yaw angle
153
void Mode::AutoYaw::set_yaw_angle_offset(const float yaw_angle_offset_d)
154
{
155
_last_update_ms = millis();
156
157
_yaw_angle_cd = wrap_360_cd(_yaw_angle_cd + (yaw_angle_offset_d * 100.0));
158
_yaw_rate_cds = 0.0f;
159
160
// set yaw mode
161
set_mode(Mode::ANGLE_RATE);
162
}
163
164
// set_roi - sets the yaw to look at roi for auto mode
165
void Mode::AutoYaw::set_roi(const Location &roi_location)
166
{
167
// if location is zero lat, lon and altitude turn off ROI
168
if (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0) {
169
// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
170
auto_yaw.set_mode_to_default(false);
171
#if HAL_MOUNT_ENABLED
172
// switch off the camera tracking if enabled
173
copter.camera_mount.clear_roi_target();
174
#endif // HAL_MOUNT_ENABLED
175
} else {
176
#if HAL_MOUNT_ENABLED
177
// check if mount type requires us to rotate the quad
178
if (!copter.camera_mount.has_pan_control()) {
179
if (roi_location.get_vector_from_origin_NEU(roi)) {
180
auto_yaw.set_mode(Mode::ROI);
181
}
182
}
183
// send the command to the camera mount
184
copter.camera_mount.set_roi_target(roi_location);
185
186
// TO-DO: expand handling of the do_nav_roi to support all modes of the MAVLink. Currently we only handle mode 4 (see below)
187
// 0: do nothing
188
// 1: point at next waypoint
189
// 2: point at a waypoint taken from WP# parameter (2nd parameter?)
190
// 3: point at a location given by alt, lon, lat parameters
191
// 4: point at a target given a target id (can't be implemented)
192
#else
193
// if we have no camera mount aim the quad at the location
194
if (roi_location.get_vector_from_origin_NEU(roi)) {
195
auto_yaw.set_mode(Mode::ROI);
196
}
197
#endif // HAL_MOUNT_ENABLED
198
}
199
}
200
201
// set auto yaw rate in centi-degrees per second
202
void Mode::AutoYaw::set_rate(float turn_rate_cds)
203
{
204
set_mode(Mode::RATE);
205
_yaw_rate_cds = turn_rate_cds;
206
}
207
208
// return true if fixed yaw target has been reached
209
bool Mode::AutoYaw::reached_fixed_yaw_target()
210
{
211
if (mode() != Mode::FIXED) {
212
// should not happen, not in the right mode
213
return true;
214
}
215
216
if (!is_zero(_fixed_yaw_offset_cd)) {
217
// still slewing yaw target
218
return false;
219
}
220
221
// Within 2 deg of target
222
return (fabsf(wrap_180_cd(copter.ahrs.yaw_sensor-_yaw_angle_cd)) <= 200);
223
}
224
225
// yaw_cd - returns target heading depending upon auto_yaw.mode()
226
float Mode::AutoYaw::yaw_cd()
227
{
228
switch (_mode) {
229
230
case Mode::ROI:
231
// point towards a location held in roi
232
_yaw_angle_cd = roi_yaw();
233
break;
234
235
case Mode::FIXED: {
236
// keep heading pointing in the direction held in fixed_yaw
237
// with no pilot input allowed
238
const uint32_t now_ms = millis();
239
float dt = (now_ms - _last_update_ms) * 0.001;
240
_last_update_ms = now_ms;
241
float yaw_angle_step = constrain_float(_fixed_yaw_offset_cd, - dt * _fixed_yaw_slewrate_cds, dt * _fixed_yaw_slewrate_cds);
242
_fixed_yaw_offset_cd -= yaw_angle_step;
243
_yaw_angle_cd += yaw_angle_step;
244
break;
245
}
246
247
case Mode::LOOK_AHEAD:
248
// Commanded Yaw to automatically look ahead.
249
_yaw_angle_cd = look_ahead_yaw() * 100.0;
250
break;
251
252
case Mode::RESETTOARMEDYAW:
253
// changes yaw to be same as when quad was armed
254
_yaw_angle_cd = copter.initial_armed_bearing;
255
break;
256
257
case Mode::CIRCLE:
258
#if MODE_CIRCLE_ENABLED
259
if (copter.circle_nav->is_active()) {
260
_yaw_angle_cd = copter.circle_nav->get_yaw();
261
}
262
#endif
263
break;
264
265
case Mode::ANGLE_RATE:{
266
const uint32_t now_ms = millis();
267
float dt = (now_ms - _last_update_ms) * 0.001;
268
_last_update_ms = now_ms;
269
_yaw_angle_cd += _yaw_rate_cds * dt;
270
break;
271
}
272
273
case Mode::RATE:
274
case Mode::WEATHERVANE:
275
case Mode::PILOT_RATE:
276
_yaw_angle_cd = copter.attitude_control->get_att_target_euler_cd().z;
277
break;
278
279
case Mode::LOOK_AT_NEXT_WP:
280
default:
281
// point towards next waypoint.
282
// we don't use wp_bearing because we don't want the copter to turn too much during flight
283
_yaw_angle_cd = copter.pos_control->get_yaw_cd();
284
break;
285
}
286
287
return _yaw_angle_cd;
288
}
289
290
// returns yaw rate normally set by SET_POSITION_TARGET mavlink
291
// messages (positive is clockwise, negative is counter clockwise)
292
float Mode::AutoYaw::rate_cds()
293
{
294
switch (_mode) {
295
296
case Mode::HOLD:
297
case Mode::ROI:
298
case Mode::FIXED:
299
case Mode::LOOK_AHEAD:
300
case Mode::RESETTOARMEDYAW:
301
case Mode::CIRCLE:
302
_yaw_rate_cds = 0.0f;
303
break;
304
305
case Mode::LOOK_AT_NEXT_WP:
306
_yaw_rate_cds = copter.pos_control->get_yaw_rate_cds();
307
break;
308
309
case Mode::PILOT_RATE:
310
_yaw_rate_cds = _pilot_yaw_rate_cds;
311
break;
312
313
case Mode::ANGLE_RATE:
314
case Mode::RATE:
315
case Mode::WEATHERVANE:
316
break;
317
}
318
319
// return zero turn rate (this should never happen)
320
return _yaw_rate_cds;
321
}
322
323
AC_AttitudeControl::HeadingCommand Mode::AutoYaw::get_heading()
324
{
325
// process pilot's yaw input
326
_pilot_yaw_rate_cds = 0.0;
327
if (!copter.failsafe.radio && copter.flightmode->use_pilot_yaw()) {
328
// get pilot's desired yaw rate
329
_pilot_yaw_rate_cds = copter.flightmode->get_pilot_desired_yaw_rate();
330
if (!is_zero(_pilot_yaw_rate_cds)) {
331
auto_yaw.set_mode(AutoYaw::Mode::PILOT_RATE);
332
}
333
} else if (auto_yaw.mode() == AutoYaw::Mode::PILOT_RATE) {
334
// RC failsafe, or disabled make sure not in pilot control
335
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
336
}
337
338
#if WEATHERVANE_ENABLED
339
update_weathervane(_pilot_yaw_rate_cds);
340
#endif
341
342
AC_AttitudeControl::HeadingCommand heading;
343
heading.yaw_angle_cd = auto_yaw.yaw_cd();
344
heading.yaw_rate_cds = auto_yaw.rate_cds();
345
346
switch (auto_yaw.mode()) {
347
case Mode::HOLD:
348
case Mode::RATE:
349
case Mode::PILOT_RATE:
350
case Mode::WEATHERVANE:
351
heading.heading_mode = AC_AttitudeControl::HeadingMode::Rate_Only;
352
break;
353
case Mode::LOOK_AT_NEXT_WP:
354
case Mode::ROI:
355
case Mode::FIXED:
356
case Mode::LOOK_AHEAD:
357
case Mode::RESETTOARMEDYAW:
358
case Mode::ANGLE_RATE:
359
case Mode::CIRCLE:
360
heading.heading_mode = AC_AttitudeControl::HeadingMode::Angle_And_Rate;
361
break;
362
}
363
364
return heading;
365
}
366
367
// handle the interface to the weathervane library
368
// pilot_yaw can be an angle or a rate or rcin from yaw channel. It just needs to represent a pilot's request to yaw the vehicle to enable pilot overrides.
369
#if WEATHERVANE_ENABLED
370
void Mode::AutoYaw::update_weathervane(const int16_t pilot_yaw_cds)
371
{
372
if (!copter.flightmode->allows_weathervaning()) {
373
return;
374
}
375
376
float yaw_rate_cds;
377
if (copter.g2.weathervane.get_yaw_out(yaw_rate_cds, pilot_yaw_cds, copter.flightmode->get_alt_above_ground_cm()*0.01,
378
copter.pos_control->get_roll_cd()-copter.attitude_control->get_roll_trim_cd(),
379
copter.pos_control->get_pitch_cd(),
380
copter.flightmode->is_taking_off(),
381
copter.flightmode->is_landing())) {
382
set_mode(Mode::WEATHERVANE);
383
_yaw_rate_cds = yaw_rate_cds;
384
return;
385
}
386
387
// if the weathervane controller has previously been activated we need to ensure we return control back to what was previously set
388
if (mode() == Mode::WEATHERVANE) {
389
_yaw_rate_cds = 0.0;
390
if (_last_mode == Mode::HOLD) {
391
set_mode_to_default(false);
392
} else {
393
set_mode(_last_mode);
394
}
395
}
396
}
397
#endif // WEATHERVANE_ENABLED
398
399