Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/Copter.cpp
9405 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
/*
17
* ArduCopter (also known as APM, APM:Copter or just Copter)
18
* Wiki: copter.ardupilot.org
19
* Creator: Jason Short
20
* Lead Developer: Randy Mackay
21
* Lead Tester: Marco Robustini
22
* Based on code and ideas from the Arducopter team: Leonard Hall, Andrew Tridgell, Robert Lefebvre, Pat Hickey, Michael Oborne, Jani Hirvinen,
23
Olivier Adler, Kevin Hester, Arthur Benemann, Jonathan Challinger, John Arne Birkeland,
24
Jean-Louis Naudin, Mike Smith, and more
25
* Thanks to: Chris Anderson, Jordi Munoz, Jason Short, Doug Weibel, Jose Julio
26
*
27
* Special Thanks to contributors (in alphabetical order by first name):
28
*
29
* Adam M Rivera :Auto Compass Declination
30
* Amilcar Lucas :Camera mount library
31
* Andrew Tridgell :General development, Mavlink Support
32
* Andy Piper :Harmonic notch, In-flight FFT, Bi-directional DShot, various drivers
33
* Angel Fernandez :Alpha testing
34
* AndreasAntonopoulous:GeoFence
35
* Arthur Benemann :DroidPlanner GCS
36
* Benjamin Pelletier :Libraries
37
* Bill King :Single Copter
38
* Christof Schmid :Alpha testing
39
* Craig Elder :Release Management, Support
40
* Dani Saez :V Octo Support
41
* Doug Weibel :DCM, Libraries, Control law advice
42
* Emile Castelnuovo :VRBrain port, bug fixes
43
* Gregory Fletcher :Camera mount orientation math
44
* Guntars :Arming safety suggestion
45
* HappyKillmore :Mavlink GCS
46
* Hein Hollander :Octo Support, Heli Testing
47
* Igor van Airde :Control Law optimization
48
* Jack Dunkle :Alpha testing
49
* James Goppert :Mavlink Support
50
* Jani Hiriven :Testing feedback
51
* Jean-Louis Naudin :Auto Landing
52
* John Arne Birkeland :PPM Encoder
53
* Jose Julio :Stabilization Control laws, MPU6k driver
54
* Julien Dubois :PosHold flight mode
55
* Julian Oes :Pixhawk
56
* Jonathan Challinger :Inertial Navigation, CompassMot, Spin-When-Armed
57
* Kevin Hester :Andropilot GCS
58
* Max Levine :Tri Support, Graphics
59
* Leonard Hall :Flight Dynamics, Throttle, Loiter and Navigation Controllers
60
* Marco Robustini :Lead tester
61
* Michael Oborne :Mission Planner GCS
62
* Mike Smith :Pixhawk driver, coding support
63
* Olivier Adler :PPM Encoder, piezo buzzer
64
* Pat Hickey :Hardware Abstraction Layer (HAL)
65
* Robert Lefebvre :Heli Support, Copter LEDs
66
* Roberto Navoni :Library testing, Porting to VRBrain
67
* Sandro Benigno :Camera support, MinimOSD
68
* Sandro Tognana :PosHold flight mode
69
* Sebastian Quilter :SmartRTL
70
* ..and many more.
71
*
72
* Code commit statistics can be found here: https://github.com/ArduPilot/ardupilot/graphs/contributors
73
* Wiki: https://copter.ardupilot.org/
74
*
75
*/
76
77
#include "Copter.h"
78
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
79
80
#define FORCE_VERSION_H_INCLUDE
81
#include "version.h"
82
#undef FORCE_VERSION_H_INCLUDE
83
84
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
85
86
#define SCHED_TASK(func, rate_hz, _max_time_micros, _prio) SCHED_TASK_CLASS(Copter, &copter, func, rate_hz, _max_time_micros, _prio)
87
#define FAST_TASK(func) FAST_TASK_CLASS(Copter, &copter, func)
88
89
/*
90
scheduler table - all tasks should be listed here.
91
92
All entries in this table must be ordered by priority.
93
94
This table is interleaved with the table in AP_Vehicle to determine
95
the order in which tasks are run. Convenience methods SCHED_TASK
96
and SCHED_TASK_CLASS are provided to build entries in this structure:
97
98
SCHED_TASK arguments:
99
- name of static function to call
100
- rate (in Hertz) at which the function should be called
101
- expected time (in MicroSeconds) that the function should take to run
102
- priority (0 through 255, lower number meaning higher priority)
103
104
SCHED_TASK_CLASS arguments:
105
- class name of method to be called
106
- instance on which to call the method
107
- method to call on that instance
108
- rate (in Hertz) at which the method should be called
109
- expected time (in MicroSeconds) that the method should take to run
110
- priority (0 through 255, lower number meaning higher priority)
111
112
*/
113
const AP_Scheduler::Task Copter::scheduler_tasks[] = {
114
// update INS immediately to get current gyro data populated
115
FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update),
116
// run low level rate controllers that only require IMU data
117
FAST_TASK(run_rate_controller_main),
118
#if AC_CUSTOMCONTROL_MULTI_ENABLED
119
FAST_TASK(run_custom_controller),
120
#endif
121
#if FRAME_CONFIG == HELI_FRAME
122
FAST_TASK(heli_update_autorotation),
123
#endif //HELI_FRAME
124
// send outputs to the motors library immediately
125
FAST_TASK(motors_output_main),
126
// run EKF state estimator (expensive)
127
FAST_TASK(read_AHRS),
128
#if FRAME_CONFIG == HELI_FRAME
129
FAST_TASK(update_heli_control_dynamics),
130
#endif //HELI_FRAME
131
// Inertial Nav
132
FAST_TASK(read_inertia),
133
// check if ekf has reset target heading or position
134
FAST_TASK(check_ekf_reset),
135
// run the attitude controllers
136
FAST_TASK(update_flight_mode),
137
// update home from EKF if necessary
138
FAST_TASK(update_home_from_EKF),
139
// check if we've landed or crashed
140
FAST_TASK(update_land_and_crash_detectors),
141
// surface tracking update
142
FAST_TASK(update_rangefinder_terrain_offset),
143
#if HAL_MOUNT_ENABLED
144
// camera mount's fast update
145
FAST_TASK_CLASS(AP_Mount, &copter.camera_mount, update_fast),
146
#endif
147
#if HAL_LOGGING_ENABLED
148
FAST_TASK(Log_Video_Stabilisation),
149
#endif
150
151
SCHED_TASK(rc_loop, 250, 130, 3),
152
SCHED_TASK(throttle_loop, 50, 75, 6),
153
#if AP_FENCE_ENABLED
154
SCHED_TASK(fence_check, 25, 100, 7),
155
#endif
156
SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9),
157
#if AP_OPTICALFLOW_ENABLED
158
SCHED_TASK_CLASS(AP_OpticalFlow, &copter.optflow, update, 200, 160, 12),
159
#endif
160
SCHED_TASK(update_batt_compass, 10, 120, 15),
161
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&copter.g2.rc_channels, read_aux_all, 10, 50, 18),
162
#if TOY_MODE_ENABLED
163
SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50, 24),
164
#endif
165
SCHED_TASK(auto_disarm_check, 10, 50, 27),
166
#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
167
SCHED_TASK_CLASS(RC_Channels_Copter, &copter.g2.rc_channels, auto_trim_run, 10, 75, 30),
168
#endif
169
#if AP_RANGEFINDER_ENABLED
170
SCHED_TASK(read_rangefinder, 20, 100, 33),
171
#endif
172
#if HAL_PROXIMITY_ENABLED
173
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50, 36),
174
#endif
175
#if AP_BEACON_ENABLED
176
SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50, 39),
177
#endif
178
SCHED_TASK(update_altitude, 10, 100, 42),
179
SCHED_TASK(run_nav_updates, 50, 100, 45),
180
SCHED_TASK(update_throttle_hover,100, 90, 48),
181
#if MODE_SMARTRTL_ENABLED
182
SCHED_TASK_CLASS(ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100, 51),
183
#endif
184
#if HAL_SPRAYER_ENABLED
185
SCHED_TASK_CLASS(AC_Sprayer, &copter.sprayer, update, 3, 90, 54),
186
#endif
187
SCHED_TASK(three_hz_loop, 3, 75, 57),
188
#if AP_SERVORELAYEVENTS_ENABLED
189
SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60),
190
#endif
191
#if AC_PRECLAND_ENABLED
192
SCHED_TASK(update_precland, 400, 50, 69),
193
#endif
194
#if FRAME_CONFIG == HELI_FRAME
195
SCHED_TASK(check_dynamic_flight, 50, 75, 72),
196
#endif
197
#if HAL_LOGGING_ENABLED
198
SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 75),
199
#endif
200
SCHED_TASK(one_hz_loop, 1, 100, 81),
201
SCHED_TASK(ekf_check, 10, 75, 84),
202
SCHED_TASK(check_vibration, 10, 50, 87),
203
SCHED_TASK(gpsglitch_check, 10, 50, 90),
204
SCHED_TASK(takeoff_check, 50, 50, 91),
205
#if AP_LANDINGGEAR_ENABLED
206
SCHED_TASK(landinggear_update, 10, 75, 93),
207
#endif
208
SCHED_TASK(standby_update, 100, 75, 96),
209
SCHED_TASK(lost_vehicle_check, 10, 50, 99),
210
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_receive, 400, 180, 102),
211
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_send, 400, 550, 105),
212
#if HAL_MOUNT_ENABLED
213
SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75, 108),
214
#endif
215
#if AP_CAMERA_ENABLED
216
SCHED_TASK_CLASS(AP_Camera, &copter.camera, update, 50, 75, 111),
217
#endif
218
#if HAL_LOGGING_ENABLED
219
SCHED_TASK(ten_hz_logging_loop, 10, 350, 114),
220
SCHED_TASK(twentyfive_hz_logging, 25, 110, 117),
221
SCHED_TASK_CLASS(AP_Logger, &copter.logger, periodic_tasks, 400, 300, 120),
222
#endif
223
SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50, 123),
224
225
#if HAL_LOGGING_ENABLED
226
SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75, 126),
227
#endif
228
#if AP_TEMPCALIBRATION_ENABLED
229
SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100, 135),
230
#endif
231
#if HAL_ADSB_ENABLED || AP_ADSB_AVOIDANCE_ENABLED
232
SCHED_TASK(avoidance_adsb_update, 10, 100, 138),
233
#endif // HAL_ADSB_ENABLED || AP_ADSB_AVOIDANCE_ENABLED
234
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
235
SCHED_TASK(afs_fs_check, 10, 100, 141),
236
#endif
237
#if AP_TERRAIN_AVAILABLE
238
SCHED_TASK(terrain_update, 10, 100, 144),
239
#endif
240
#if AP_WINCH_ENABLED
241
SCHED_TASK_CLASS(AP_Winch, &copter.g2.winch, update, 50, 50, 150),
242
#endif
243
#ifdef USERHOOK_FASTLOOP
244
SCHED_TASK(userhook_FastLoop, 100, 75, 153),
245
#endif
246
#ifdef USERHOOK_50HZLOOP
247
SCHED_TASK(userhook_50Hz, 50, 75, 156),
248
#endif
249
#ifdef USERHOOK_MEDIUMLOOP
250
SCHED_TASK(userhook_MediumLoop, 10, 75, 159),
251
#endif
252
#ifdef USERHOOK_SLOWLOOP
253
SCHED_TASK(userhook_SlowLoop, 3.3, 75, 162),
254
#endif
255
#ifdef USERHOOK_SUPERSLOWLOOP
256
SCHED_TASK(userhook_SuperSlowLoop, 1, 75, 165),
257
#endif
258
#if HAL_BUTTON_ENABLED
259
SCHED_TASK_CLASS(AP_Button, &copter.button, update, 5, 100, 168),
260
#endif
261
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
262
// don't delete this, there is an equivalent (virtual) in AP_Vehicle for the non-rate loop case
263
SCHED_TASK(update_dynamic_notch_at_specified_rate_main, LOOP_RATE, 200, 215),
264
#endif
265
};
266
267
void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
268
uint8_t &task_count,
269
uint32_t &log_bit)
270
{
271
tasks = &scheduler_tasks[0];
272
task_count = ARRAY_SIZE(scheduler_tasks);
273
log_bit = MASK_LOG_PM;
274
}
275
276
constexpr int8_t Copter::_failsafe_priorities[7];
277
278
279
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
280
#if MODE_GUIDED_ENABLED
281
// set target location (for use by external control and scripting)
282
bool Copter::set_target_location(const Location& target_loc)
283
{
284
// exit if vehicle is not in Guided mode or Auto-Guided mode
285
if (!flightmode->in_guided_mode()) {
286
return false;
287
}
288
289
return mode_guided.set_destination(target_loc);
290
}
291
292
// start takeoff to given altitude (for use by scripting)
293
bool Copter::start_takeoff(const float alt_m)
294
{
295
// exit if vehicle is not in Guided mode or Auto-Guided mode
296
if (!flightmode->in_guided_mode()) {
297
return false;
298
}
299
300
if (mode_guided.do_user_takeoff_start_m(alt_m)) {
301
copter.set_auto_armed(true);
302
return true;
303
}
304
return false;
305
}
306
#endif //MODE_GUIDED_ENABLED
307
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
308
309
#if AP_SCRIPTING_ENABLED
310
#if MODE_GUIDED_ENABLED
311
// set target position (for use by scripting)
312
bool Copter::set_target_pos_NED(const Vector3f& target_pos_ned_m, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool is_terrain_alt)
313
{
314
// exit if vehicle is not in Guided mode or Auto-Guided mode
315
if (!flightmode->in_guided_mode()) {
316
return false;
317
}
318
319
return mode_guided.set_pos_NED_m(target_pos_ned_m.topostype(), use_yaw, radians(yaw_deg), use_yaw_rate, radians(yaw_rate_degs), yaw_relative, is_terrain_alt);
320
}
321
322
// set target position and velocity (for use by scripting)
323
bool Copter::set_target_posvel_NED(const Vector3f& target_pos_ned_m, const Vector3f& target_vel_ned_ms)
324
{
325
// exit if vehicle is not in Guided mode or Auto-Guided mode
326
if (!flightmode->in_guided_mode()) {
327
return false;
328
}
329
330
return mode_guided.set_pos_vel_accel_NED_m(target_pos_ned_m.topostype(), target_vel_ned_ms, Vector3f());
331
}
332
333
// set target position, velocity and acceleration (for use by scripting)
334
bool Copter::set_target_posvelaccel_NED(const Vector3f& target_pos_ned_m, const Vector3f& target_vel_ned_ms, const Vector3f& target_accel_ned_mss, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative)
335
{
336
// exit if vehicle is not in Guided mode or Auto-Guided mode
337
if (!flightmode->in_guided_mode()) {
338
return false;
339
}
340
341
return mode_guided.set_pos_vel_accel_NED_m(target_pos_ned_m.topostype(), target_vel_ned_ms, target_accel_ned_mss, use_yaw, radians(yaw_deg), use_yaw_rate, radians(yaw_rate_degs), yaw_relative);
342
}
343
344
bool Copter::set_target_velocity_NED(const Vector3f& target_vel_ned_ms, bool align_yaw_to_target)
345
{
346
// exit if vehicle is not in Guided mode or Auto-Guided mode
347
if (!flightmode->in_guided_mode()) {
348
return false;
349
}
350
351
// optionally line up the copter with the velocity vector
352
float yaw_rads = 0.0f;
353
if (align_yaw_to_target) {
354
const float speed_sq = target_vel_ned_ms.xy().length_squared();
355
if (copter.position_ok() && (speed_sq > (YAW_LOOK_AHEAD_MIN_SPEED_MS * YAW_LOOK_AHEAD_MIN_SPEED_MS))) {
356
yaw_rads = atan2f(target_vel_ned_ms.y, target_vel_ned_ms.x);
357
}
358
}
359
360
mode_guided.set_vel_accel_NED_m(target_vel_ned_ms, Vector3f(), align_yaw_to_target, yaw_rads);
361
return true;
362
}
363
364
// set target velocity and acceleration (for use by scripting)
365
bool Copter::set_target_velaccel_NED(const Vector3f& target_vel_ned_ms, const Vector3f& target_accel_ned_mss, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool relative_yaw)
366
{
367
// exit if vehicle is not in Guided mode or Auto-Guided mode
368
if (!flightmode->in_guided_mode()) {
369
return false;
370
}
371
372
mode_guided.set_vel_accel_NED_m(target_vel_ned_ms, target_accel_ned_mss, use_yaw, radians(yaw_deg), use_yaw_rate, radians(yaw_rate_degs), relative_yaw);
373
return true;
374
}
375
376
// set target roll pitch and yaw angles with throttle (for use by scripting)
377
bool Copter::set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs)
378
{
379
// exit if vehicle is not in Guided mode or Auto-Guided mode
380
if (!flightmode->in_guided_mode()) {
381
return false;
382
}
383
384
Quaternion q;
385
q.from_euler(radians(roll_deg),radians(pitch_deg),radians(yaw_deg));
386
387
mode_guided.set_angle(q, Vector3f{}, climb_rate_ms*100, false);
388
return true;
389
}
390
391
// set target roll pitch and yaw rates with throttle (for use by scripting)
392
bool Copter::set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle)
393
{
394
// exit if vehicle is not in Guided mode or Auto-Guided mode
395
if (!flightmode->in_guided_mode()) {
396
return false;
397
}
398
399
// Zero quaternion indicates rate control
400
Quaternion q;
401
q.zero();
402
403
// Convert from degrees per second to radians per second
404
Vector3f ang_vel_body { roll_rate_dps, pitch_rate_dps, yaw_rate_dps };
405
ang_vel_body *= DEG_TO_RAD;
406
407
// Pass to guided mode
408
mode_guided.set_angle(q, ang_vel_body, throttle, true);
409
return true;
410
}
411
412
// set target roll pitch and yaw angles and roll pitch and yaw rates with throttle (for use by scripting)
413
bool Copter::set_target_angle_and_rate_and_throttle(float roll_deg, float pitch_deg, float yaw_deg, float roll_rate_degs, float pitch_rate_degs, float yaw_rate_degs, float throttle)
414
{
415
// exit if vehicle is not in Guided mode or Auto-Guided mode
416
if (!flightmode->in_guided_mode()) {
417
return false;
418
}
419
420
Quaternion q;
421
q.from_euler(radians(roll_deg),radians(pitch_deg),radians(yaw_deg));
422
423
// Convert from degrees per second to radians per second
424
Vector3f ang_vel_body_degs { roll_rate_degs, pitch_rate_degs, yaw_rate_degs };
425
ang_vel_body_degs *= DEG_TO_RAD;
426
427
mode_guided.set_angle(q, ang_vel_body_degs, throttle, true);
428
return true;
429
}
430
431
// Register a custom mode with given number and names
432
AP_Vehicle::custom_mode_state* Copter::register_custom_mode(const uint8_t num, const char* full_name, const char* short_name)
433
{
434
const Mode::Number number = (Mode::Number)num;
435
436
// See if this mode has been registered already, if it has return the state for it
437
// This allows scripting restarts
438
for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {
439
if (mode_guided_custom[i] == nullptr) {
440
break;
441
}
442
if ((mode_guided_custom[i]->mode_number() == number) &&
443
(strcmp(mode_guided_custom[i]->name(), full_name) == 0) &&
444
(strncmp(mode_guided_custom[i]->name4(), short_name, 4) == 0)) {
445
return &mode_guided_custom[i]->state;
446
}
447
}
448
449
// Number already registered to existing mode
450
if (mode_from_mode_num(number) != nullptr) {
451
return nullptr;
452
}
453
454
// Find free slot
455
for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {
456
if (mode_guided_custom[i] == nullptr) {
457
// Duplicate strings so were not pointing to unknown memory
458
const char* full_name_copy = strdup(full_name);
459
const char* short_name_copy = strndup(short_name, 4);
460
if ((full_name_copy != nullptr) && (short_name_copy != nullptr)) {
461
mode_guided_custom[i] = NEW_NOTHROW ModeGuidedCustom(number, full_name_copy, short_name_copy);
462
}
463
if (mode_guided_custom[i] == nullptr) {
464
// Allocation failure
465
free((void*)full_name_copy);
466
free((void*)short_name_copy);
467
return nullptr;
468
}
469
470
// Registration successful, notify the GCS that it should re-request the available modes
471
gcs().available_modes_changed();
472
473
return &mode_guided_custom[i]->state;
474
}
475
}
476
477
// No free slots
478
return nullptr;
479
}
480
#endif // MODE_GUIDED_ENABLED
481
482
#if MODE_CIRCLE_ENABLED
483
// circle mode controls
484
bool Copter::get_circle_radius(float &radius_m)
485
{
486
radius_m = circle_nav->get_radius_m();
487
return true;
488
}
489
490
bool Copter::set_circle_rate(float rate_degs)
491
{
492
circle_nav->set_rate_degs(rate_degs);
493
return true;
494
}
495
#endif
496
497
// set desired speed (m/s). Used for scripting.
498
bool Copter::set_desired_speed(float speed_ms)
499
{
500
return flightmode->set_speed_NE_ms(speed_ms);
501
}
502
503
#if MODE_AUTO_ENABLED
504
// returns true if mode supports NAV_SCRIPT_TIME mission commands
505
bool Copter::nav_scripting_enable(uint8_t mode)
506
{
507
return mode == (uint8_t)mode_auto.mode_number();
508
}
509
510
// lua scripts use this to retrieve the contents of the active command
511
bool Copter::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
512
{
513
if (flightmode != &mode_auto) {
514
return false;
515
}
516
517
return mode_auto.nav_script_time(id, cmd, arg1, arg2, arg3, arg4);
518
}
519
520
// lua scripts use this to indicate when they have complete the command
521
void Copter::nav_script_time_done(uint16_t id)
522
{
523
if (flightmode != &mode_auto) {
524
return;
525
}
526
527
return mode_auto.nav_script_time_done(id);
528
}
529
#endif
530
531
// returns true if the EKF failsafe has triggered. Only used by Lua scripts
532
bool Copter::has_ekf_failsafed() const
533
{
534
return failsafe.ekf;
535
}
536
537
// get target location (for use by scripting)
538
bool Copter::get_target_location(Location& target_loc)
539
{
540
return flightmode->get_wp(target_loc);
541
}
542
543
/*
544
update_target_location() acts as a wrapper for set_target_location
545
*/
546
bool Copter::update_target_location(const Location &old_loc, const Location &new_loc)
547
{
548
/*
549
by checking the caller has provided the correct old target
550
location we prevent a race condition where the user changes mode
551
or commands a different target in the controlling lua script
552
*/
553
Location next_WP_loc;
554
flightmode->get_wp(next_WP_loc);
555
if (!old_loc.same_loc_as(next_WP_loc) ||
556
old_loc.get_alt_frame() != new_loc.get_alt_frame()) {
557
return false;
558
}
559
560
return set_target_location(new_loc);
561
}
562
563
#endif // AP_SCRIPTING_ENABLED
564
565
// returns true if vehicle is landing.
566
bool Copter::is_landing() const
567
{
568
return flightmode->is_landing();
569
}
570
571
// returns true if vehicle is taking off.
572
bool Copter::is_taking_off() const
573
{
574
return flightmode->is_taking_off();
575
}
576
577
bool Copter::current_mode_requires_mission() const
578
{
579
#if MODE_AUTO_ENABLED
580
return flightmode == &mode_auto;
581
#else
582
return false;
583
#endif
584
}
585
586
// rc_loops - reads user input from transmitter/receiver
587
// called at 100hz
588
void Copter::rc_loop()
589
{
590
// Read radio and 3-position switch on radio
591
// -----------------------------------------
592
read_radio();
593
rc().read_mode_switch();
594
}
595
596
// throttle_loop - should be run at 50 hz
597
// ---------------------------
598
void Copter::throttle_loop()
599
{
600
// update throttle_low_comp value (controls priority of throttle vs attitude control)
601
update_throttle_mix();
602
603
// check auto_armed status
604
update_auto_armed();
605
606
#if FRAME_CONFIG == HELI_FRAME
607
// update rotor speed
608
heli_update_rotor_speed_targets();
609
610
// update trad heli swash plate movement
611
heli_update_landing_swash();
612
#endif
613
614
// compensate for ground effect (if enabled)
615
update_ground_effect_detector();
616
update_ekf_terrain_height_stable();
617
}
618
619
// update_batt_compass - read battery and compass
620
// should be called at 10hz
621
void Copter::update_batt_compass(void)
622
{
623
// read battery before compass because it may be used for motor interference compensation
624
battery.read();
625
626
if(AP::compass().available()) {
627
// update compass with throttle value - used for compassmot
628
compass.set_throttle(motors->get_throttle());
629
compass.set_voltage(battery.voltage());
630
compass.read();
631
}
632
}
633
634
#if HAL_LOGGING_ENABLED
635
// Full rate logging of attitude, rate and pid loops
636
// should be run at loop rate
637
void Copter::loop_rate_logging()
638
{
639
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
640
Log_Write_Attitude();
641
if (!using_rate_thread) {
642
Log_Write_Rate();
643
Log_Write_PIDS(); // only logs if PIDS bitmask is set
644
}
645
}
646
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
647
if (should_log(MASK_LOG_FTN_FAST) && !using_rate_thread) {
648
AP::ins().write_notch_log_messages();
649
}
650
#endif
651
if (should_log(MASK_LOG_IMU_FAST)) {
652
AP::ins().Write_IMU();
653
}
654
}
655
656
// ten_hz_logging_loop
657
// should be run at 10hz
658
void Copter::ten_hz_logging_loop()
659
{
660
// always write AHRS attitude at 10Hz
661
ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);
662
// log attitude controller data if we're not already logging at the higher rate
663
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
664
Log_Write_Attitude();
665
if (!using_rate_thread) {
666
Log_Write_Rate();
667
}
668
}
669
if (!should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
670
// log at 10Hz if PIDS bitmask is selected, even if no ATT bitmask is selected; logs at looprate if ATT_FAST and PIDS bitmask set
671
if (!using_rate_thread) {
672
Log_Write_PIDS();
673
}
674
}
675
// log EKF attitude data always at 10Hz unless ATTITUDE_FAST, then do it in the 25Hz loop
676
if (!should_log(MASK_LOG_ATTITUDE_FAST)) {
677
Log_Write_EKF_POS();
678
}
679
if ((FRAME_CONFIG == HELI_FRAME) || should_log(MASK_LOG_MOTBATT)) {
680
// always write motors log if we are a heli
681
motors->Log_Write();
682
}
683
if (should_log(MASK_LOG_RCIN)) {
684
logger.Write_RCIN();
685
#if AP_RSSI_ENABLED
686
if (rssi.enabled()) {
687
logger.Write_RSSI();
688
}
689
#endif
690
}
691
if (should_log(MASK_LOG_RCOUT)) {
692
logger.Write_RCOUT();
693
}
694
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_position() || landing_with_GPS() || !flightmode->has_manual_throttle())) {
695
pos_control->write_log();
696
}
697
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
698
AP::ins().Write_Vibration();
699
}
700
if (should_log(MASK_LOG_CTUN)) {
701
#if HAL_PROXIMITY_ENABLED
702
g2.proximity.log(); // Write proximity sensor distances
703
#endif
704
#if AP_BEACON_ENABLED
705
g2.beacon.log();
706
#endif
707
}
708
#if AP_WINCH_ENABLED
709
if (should_log(MASK_LOG_ANY)) {
710
g2.winch.write_log();
711
}
712
#endif
713
#if HAL_MOUNT_ENABLED
714
if (should_log(MASK_LOG_CAMERA)) {
715
camera_mount.write_log();
716
}
717
#endif
718
}
719
720
// twentyfive_hz_logging - should be run at 25hz
721
void Copter::twentyfive_hz_logging()
722
{
723
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
724
Log_Write_EKF_POS();
725
}
726
727
if (should_log(MASK_LOG_IMU) && !(should_log(MASK_LOG_IMU_FAST))) {
728
AP::ins().Write_IMU();
729
}
730
731
#if HAL_GYROFFT_ENABLED
732
if (should_log(MASK_LOG_FTN_FAST)) {
733
gyro_fft.write_log_messages();
734
}
735
#endif
736
}
737
#endif // HAL_LOGGING_ENABLED
738
739
// three_hz_loop - 3hz loop
740
void Copter::three_hz_loop()
741
{
742
// check if we've lost contact with the ground station
743
failsafe_gcs_check();
744
745
// check if we've lost terrain data
746
failsafe_terrain_check();
747
748
// check for deadreckoning failsafe
749
failsafe_deadreckon_check();
750
751
#if AP_RC_TRANSMITTER_TUNING_ENABLED
752
//update transmitter based in flight tuning
753
tuning();
754
#endif // AP_RC_TRANSMITTER_TUNING_ENABLED
755
756
// check if avoidance should be enabled based on alt
757
low_alt_avoidance();
758
}
759
760
// ap_value calculates a 32-bit bitmask representing various pieces of
761
// state about the Copter. It replaces a global variable which was
762
// used to track this state.
763
uint32_t Copter::ap_value() const
764
{
765
uint32_t ret = 0;
766
767
const bool *b = (const bool *)&ap;
768
for (uint8_t i=0; i<sizeof(ap); i++) {
769
if (b[i]) {
770
ret |= 1U<<i;
771
}
772
}
773
774
return ret;
775
}
776
777
// one_hz_loop - runs at 1Hz
778
void Copter::one_hz_loop()
779
{
780
#if HAL_LOGGING_ENABLED
781
if (should_log(MASK_LOG_ANY)) {
782
Log_Write_Data(LogDataID::AP_STATE, ap_value());
783
}
784
#endif
785
786
if (!motors->armed()) {
787
update_using_interlock();
788
789
// check the user hasn't updated the frame class or type
790
motors->set_frame_class_and_type((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
791
792
#if FRAME_CONFIG != HELI_FRAME
793
// set all throttle channel settings
794
motors->update_throttle_range();
795
#endif
796
}
797
798
// update assigned functions and enable auxiliary servos
799
AP::srv().enable_aux_servos();
800
801
#if HAL_LOGGING_ENABLED
802
// log terrain data
803
terrain_logging();
804
#endif
805
806
#if HAL_ADSB_ENABLED
807
adsb.set_is_flying(!ap.land_complete);
808
#endif
809
810
AP_Notify::flags.flying = !ap.land_complete;
811
812
// slowly update the PID notches with the average loop rate
813
if (!using_rate_thread) {
814
attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
815
}
816
pos_control->D_get_accel_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
817
#if AC_CUSTOMCONTROL_MULTI_ENABLED
818
custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
819
#endif
820
821
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
822
// see if we should have a separate rate thread
823
if (!started_rate_thread && get_fast_rate_type() != FastRateType::FAST_RATE_DISABLED) {
824
if (hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&Copter::rate_controller_thread, void),
825
"rate",
826
1536, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) {
827
started_rate_thread = true;
828
} else {
829
AP_BoardConfig::allocation_error("rate thread");
830
}
831
}
832
#endif
833
}
834
835
void Copter::init_simple_bearing()
836
{
837
// capture current cos_yaw and sin_yaw values
838
simple_cos_yaw = ahrs.cos_yaw();
839
simple_sin_yaw = ahrs.sin_yaw();
840
841
// initialise super simple heading (i.e. heading towards home) to be 180 deg from simple mode heading
842
super_simple_last_bearing_rad = wrap_2PI(ahrs.get_yaw_rad() + radians(180.0));
843
super_simple_cos_yaw = simple_cos_yaw;
844
super_simple_sin_yaw = simple_sin_yaw;
845
846
#if HAL_LOGGING_ENABLED
847
// log the simple bearing
848
if (should_log(MASK_LOG_ANY)) {
849
Log_Write_Data(LogDataID::INIT_SIMPLE_BEARING, ahrs.yaw_sensor);
850
}
851
#endif
852
}
853
854
// update_simple_mode - rotates pilot input if we are in simple mode
855
void Copter::update_simple_mode(void)
856
{
857
float rollx, pitchx;
858
859
// exit immediately if no new radio frame or not in simple mode
860
if (simple_mode == SimpleMode::NONE || !ap.new_radio_frame) {
861
return;
862
}
863
864
// mark radio frame as consumed
865
ap.new_radio_frame = false;
866
867
// avoid processing bind-time RC values:
868
if (!rc().has_valid_input()) {
869
return;
870
}
871
872
if (simple_mode == SimpleMode::SIMPLE) {
873
// rotate roll, pitch input by -initial simple heading (i.e. north facing)
874
rollx = channel_roll->get_control_in()*simple_cos_yaw - channel_pitch->get_control_in()*simple_sin_yaw;
875
pitchx = channel_roll->get_control_in()*simple_sin_yaw + channel_pitch->get_control_in()*simple_cos_yaw;
876
}else{
877
// rotate roll, pitch input by -super simple heading (reverse of heading to home)
878
rollx = channel_roll->get_control_in()*super_simple_cos_yaw - channel_pitch->get_control_in()*super_simple_sin_yaw;
879
pitchx = channel_roll->get_control_in()*super_simple_sin_yaw + channel_pitch->get_control_in()*super_simple_cos_yaw;
880
}
881
882
// rotate roll, pitch input from north facing to vehicle's perspective
883
channel_roll->set_control_in(rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw());
884
channel_pitch->set_control_in(-rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw());
885
}
886
887
// update_super_simple_bearing - adjusts simple bearing based on location
888
// should be called after home_bearing_rad has been updated
889
void Copter::update_super_simple_bearing(bool force_update)
890
{
891
if (!force_update) {
892
if (simple_mode != SimpleMode::SUPERSIMPLE) {
893
return;
894
}
895
if (home_distance_m() < SUPER_SIMPLE_RADIUS_M) {
896
return;
897
}
898
}
899
900
const float bearing_rad = home_bearing_rad();
901
902
// check the bearing to home has changed by at least 5 degrees
903
// todo: consider updating this continuously
904
if (fabsf(wrap_PI(super_simple_last_bearing_rad - bearing_rad)) < radians(5.0)) {
905
return;
906
}
907
908
super_simple_last_bearing_rad = bearing_rad;
909
const float angle_rad = super_simple_last_bearing_rad + radians(180.0);
910
super_simple_cos_yaw = cosf(angle_rad);
911
super_simple_sin_yaw = sinf(angle_rad);
912
}
913
914
void Copter::read_AHRS(void)
915
{
916
// we tell AHRS to skip INS update as we have already done it in FAST_TASK.
917
ahrs.update(true);
918
}
919
920
// read baro and log control tuning
921
void Copter::update_altitude()
922
{
923
// read in baro altitude
924
read_barometer();
925
926
#if HAL_LOGGING_ENABLED
927
if (should_log(MASK_LOG_CTUN)) {
928
Log_Write_Control_Tuning();
929
if (!should_log(MASK_LOG_FTN_FAST)) {
930
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
931
AP::ins().write_notch_log_messages();
932
#endif
933
#if HAL_GYROFFT_ENABLED
934
gyro_fft.write_log_messages();
935
#endif
936
}
937
}
938
#endif
939
}
940
941
// vehicle specific waypoint info helpers
942
bool Copter::get_wp_distance_m(float &distance) const
943
{
944
// see GCS_MAVLINK_Copter::send_nav_controller_output()
945
distance = flightmode->wp_distance_m();
946
return true;
947
}
948
949
// vehicle specific waypoint info helpers
950
bool Copter::get_wp_bearing_deg(float &bearing) const
951
{
952
// see GCS_MAVLINK_Copter::send_nav_controller_output()
953
bearing = flightmode->wp_bearing_deg();
954
return true;
955
}
956
957
// vehicle specific waypoint info helpers
958
bool Copter::get_wp_crosstrack_error_m(float &xtrack_error) const
959
{
960
// see GCS_MAVLINK_Copter::send_nav_controller_output()
961
xtrack_error = flightmode->crosstrack_error_m() * 0.01;
962
return true;
963
}
964
965
// get the target earth-frame angular velocities in rad/s (Z-axis component used by some gimbals)
966
bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const
967
{
968
// always returns zero vector if landed or disarmed
969
if (copter.ap.land_complete) {
970
rate_ef_targets.zero();
971
} else {
972
rate_ef_targets = attitude_control->get_rate_ef_targets();
973
}
974
return true;
975
}
976
977
/*
978
constructor for main Copter class
979
*/
980
Copter::Copter(void)
981
:
982
flight_modes(&g.flight_mode1),
983
pos_variance_filt(FS_EKF_FILT_DEFAULT),
984
vel_variance_filt(FS_EKF_FILT_DEFAULT),
985
flightmode(&mode_stabilize),
986
simple_cos_yaw(1.0f),
987
super_simple_cos_yaw(1.0),
988
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),
989
rc_throttle_control_in_filter(1.0f),
990
param_loader(var_info)
991
{
992
}
993
994
Copter copter;
995
AP_Vehicle& vehicle = copter;
996
997
AP_HAL_MAIN_CALLBACKS(&copter);
998
999