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/Copter.cpp
Views: 1798
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, _interval_ticks, _max_time_micros, _prio) SCHED_TASK_CLASS(Copter, &copter, func, _interval_ticks, _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
SCHED_TASK(arm_motors_check, 10, 50, 21),
163
#if TOY_MODE_ENABLED
164
SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50, 24),
165
#endif
166
SCHED_TASK(auto_disarm_check, 10, 50, 27),
167
SCHED_TASK(auto_trim, 10, 75, 30),
168
#if AP_RANGEFINDER_ENABLED
169
SCHED_TASK(read_rangefinder, 20, 100, 33),
170
#endif
171
#if HAL_PROXIMITY_ENABLED
172
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50, 36),
173
#endif
174
#if AP_BEACON_ENABLED
175
SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50, 39),
176
#endif
177
SCHED_TASK(update_altitude, 10, 100, 42),
178
SCHED_TASK(run_nav_updates, 50, 100, 45),
179
SCHED_TASK(update_throttle_hover,100, 90, 48),
180
#if MODE_SMARTRTL_ENABLED
181
SCHED_TASK_CLASS(ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100, 51),
182
#endif
183
#if HAL_SPRAYER_ENABLED
184
SCHED_TASK_CLASS(AC_Sprayer, &copter.sprayer, update, 3, 90, 54),
185
#endif
186
SCHED_TASK(three_hz_loop, 3, 75, 57),
187
#if AP_SERVORELAYEVENTS_ENABLED
188
SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60),
189
#endif
190
#if AC_PRECLAND_ENABLED
191
SCHED_TASK(update_precland, 400, 50, 69),
192
#endif
193
#if FRAME_CONFIG == HELI_FRAME
194
SCHED_TASK(check_dynamic_flight, 50, 75, 72),
195
#endif
196
#if HAL_LOGGING_ENABLED
197
SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 75),
198
#endif
199
SCHED_TASK(one_hz_loop, 1, 100, 81),
200
SCHED_TASK(ekf_check, 10, 75, 84),
201
SCHED_TASK(check_vibration, 10, 50, 87),
202
SCHED_TASK(gpsglitch_check, 10, 50, 90),
203
SCHED_TASK(takeoff_check, 50, 50, 91),
204
#if AP_LANDINGGEAR_ENABLED
205
SCHED_TASK(landinggear_update, 10, 75, 93),
206
#endif
207
SCHED_TASK(standby_update, 100, 75, 96),
208
SCHED_TASK(lost_vehicle_check, 10, 50, 99),
209
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_receive, 400, 180, 102),
210
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_send, 400, 550, 105),
211
#if HAL_MOUNT_ENABLED
212
SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75, 108),
213
#endif
214
#if AP_CAMERA_ENABLED
215
SCHED_TASK_CLASS(AP_Camera, &copter.camera, update, 50, 75, 111),
216
#endif
217
#if HAL_LOGGING_ENABLED
218
SCHED_TASK(ten_hz_logging_loop, 10, 350, 114),
219
SCHED_TASK(twentyfive_hz_logging, 25, 110, 117),
220
SCHED_TASK_CLASS(AP_Logger, &copter.logger, periodic_tasks, 400, 300, 120),
221
#endif
222
SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50, 123),
223
224
#if HAL_LOGGING_ENABLED
225
SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75, 126),
226
#endif
227
#if AP_RPM_ENABLED
228
SCHED_TASK_CLASS(AP_RPM, &copter.rpm_sensor, update, 40, 200, 129),
229
#endif
230
#if AP_TEMPCALIBRATION_ENABLED
231
SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100, 135),
232
#endif
233
#if HAL_ADSB_ENABLED
234
SCHED_TASK(avoidance_adsb_update, 10, 100, 138),
235
#endif
236
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
237
SCHED_TASK(afs_fs_check, 10, 100, 141),
238
#endif
239
#if AP_TERRAIN_AVAILABLE
240
SCHED_TASK(terrain_update, 10, 100, 144),
241
#endif
242
#if AP_WINCH_ENABLED
243
SCHED_TASK_CLASS(AP_Winch, &copter.g2.winch, update, 50, 50, 150),
244
#endif
245
#ifdef USERHOOK_FASTLOOP
246
SCHED_TASK(userhook_FastLoop, 100, 75, 153),
247
#endif
248
#ifdef USERHOOK_50HZLOOP
249
SCHED_TASK(userhook_50Hz, 50, 75, 156),
250
#endif
251
#ifdef USERHOOK_MEDIUMLOOP
252
SCHED_TASK(userhook_MediumLoop, 10, 75, 159),
253
#endif
254
#ifdef USERHOOK_SLOWLOOP
255
SCHED_TASK(userhook_SlowLoop, 3.3, 75, 162),
256
#endif
257
#ifdef USERHOOK_SUPERSLOWLOOP
258
SCHED_TASK(userhook_SuperSlowLoop, 1, 75, 165),
259
#endif
260
#if HAL_BUTTON_ENABLED
261
SCHED_TASK_CLASS(AP_Button, &copter.button, update, 5, 100, 168),
262
#endif
263
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
264
// don't delete this, there is an equivalent (virtual) in AP_Vehicle for the non-rate loop case
265
SCHED_TASK(update_dynamic_notch_at_specified_rate_main, LOOP_RATE, 200, 215),
266
#endif
267
};
268
269
void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
270
uint8_t &task_count,
271
uint32_t &log_bit)
272
{
273
tasks = &scheduler_tasks[0];
274
task_count = ARRAY_SIZE(scheduler_tasks);
275
log_bit = MASK_LOG_PM;
276
}
277
278
constexpr int8_t Copter::_failsafe_priorities[7];
279
280
281
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
282
#if MODE_GUIDED_ENABLED
283
// set target location (for use by external control and scripting)
284
bool Copter::set_target_location(const Location& target_loc)
285
{
286
// exit if vehicle is not in Guided mode or Auto-Guided mode
287
if (!flightmode->in_guided_mode()) {
288
return false;
289
}
290
291
return mode_guided.set_destination(target_loc);
292
}
293
294
// start takeoff to given altitude (for use by scripting)
295
bool Copter::start_takeoff(const float alt)
296
{
297
// exit if vehicle is not in Guided mode or Auto-Guided mode
298
if (!flightmode->in_guided_mode()) {
299
return false;
300
}
301
302
if (mode_guided.do_user_takeoff_start(alt * 100.0f)) {
303
copter.set_auto_armed(true);
304
return true;
305
}
306
return false;
307
}
308
#endif //MODE_GUIDED_ENABLED
309
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
310
311
#if AP_SCRIPTING_ENABLED
312
#if MODE_GUIDED_ENABLED
313
// set target position (for use by scripting)
314
bool Copter::set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt)
315
{
316
// exit if vehicle is not in Guided mode or Auto-Guided mode
317
if (!flightmode->in_guided_mode()) {
318
return false;
319
}
320
321
const Vector3f pos_neu_cm(target_pos.x * 100.0f, target_pos.y * 100.0f, -target_pos.z * 100.0f);
322
323
return mode_guided.set_destination(pos_neu_cm, use_yaw, yaw_deg * 100.0, use_yaw_rate, yaw_rate_degs * 100.0, yaw_relative, terrain_alt);
324
}
325
326
// set target position and velocity (for use by scripting)
327
bool Copter::set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel)
328
{
329
// exit if vehicle is not in Guided mode or Auto-Guided mode
330
if (!flightmode->in_guided_mode()) {
331
return false;
332
}
333
334
const Vector3f pos_neu_cm(target_pos.x * 100.0f, target_pos.y * 100.0f, -target_pos.z * 100.0f);
335
const Vector3f vel_neu_cms(target_vel.x * 100.0f, target_vel.y * 100.0f, -target_vel.z * 100.0f);
336
337
return mode_guided.set_destination_posvelaccel(pos_neu_cm, vel_neu_cms, Vector3f());
338
}
339
340
// set target position, velocity and acceleration (for use by scripting)
341
bool Copter::set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative)
342
{
343
// exit if vehicle is not in Guided mode or Auto-Guided mode
344
if (!flightmode->in_guided_mode()) {
345
return false;
346
}
347
348
const Vector3f pos_neu_cm(target_pos.x * 100.0f, target_pos.y * 100.0f, -target_pos.z * 100.0f);
349
const Vector3f vel_neu_cms(target_vel.x * 100.0f, target_vel.y * 100.0f, -target_vel.z * 100.0f);
350
const Vector3f accel_neu_cms(target_accel.x * 100.0f, target_accel.y * 100.0f, -target_accel.z * 100.0f);
351
352
return mode_guided.set_destination_posvelaccel(pos_neu_cm, vel_neu_cms, accel_neu_cms, use_yaw, yaw_deg * 100.0, use_yaw_rate, yaw_rate_degs * 100.0, yaw_relative);
353
}
354
355
bool Copter::set_target_velocity_NED(const Vector3f& vel_ned)
356
{
357
// exit if vehicle is not in Guided mode or Auto-Guided mode
358
if (!flightmode->in_guided_mode()) {
359
return false;
360
}
361
362
// convert vector to neu in cm
363
const Vector3f vel_neu_cms(vel_ned.x * 100.0f, vel_ned.y * 100.0f, -vel_ned.z * 100.0f);
364
mode_guided.set_velocity(vel_neu_cms);
365
return true;
366
}
367
368
// set target velocity and acceleration (for use by scripting)
369
bool Copter::set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool relative_yaw)
370
{
371
// exit if vehicle is not in Guided mode or Auto-Guided mode
372
if (!flightmode->in_guided_mode()) {
373
return false;
374
}
375
376
// convert vector to neu in cm
377
const Vector3f vel_neu_cms(target_vel.x * 100.0f, target_vel.y * 100.0f, -target_vel.z * 100.0f);
378
const Vector3f accel_neu_cms(target_accel.x * 100.0f, target_accel.y * 100.0f, -target_accel.z * 100.0f);
379
380
mode_guided.set_velaccel(vel_neu_cms, accel_neu_cms, use_yaw, yaw_deg * 100.0, use_yaw_rate, yaw_rate_degs * 100.0, relative_yaw);
381
return true;
382
}
383
384
// set target roll pitch and yaw angles with throttle (for use by scripting)
385
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)
386
{
387
// exit if vehicle is not in Guided mode or Auto-Guided mode
388
if (!flightmode->in_guided_mode()) {
389
return false;
390
}
391
392
Quaternion q;
393
q.from_euler(radians(roll_deg),radians(pitch_deg),radians(yaw_deg));
394
395
mode_guided.set_angle(q, Vector3f{}, climb_rate_ms*100, false);
396
return true;
397
}
398
399
// set target roll pitch and yaw rates with throttle (for use by scripting)
400
bool Copter::set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle)
401
{
402
// exit if vehicle is not in Guided mode or Auto-Guided mode
403
if (!flightmode->in_guided_mode()) {
404
return false;
405
}
406
407
// Zero quaternion indicates rate control
408
Quaternion q;
409
q.zero();
410
411
// Convert from degrees per second to radians per second
412
Vector3f ang_vel_body { roll_rate_dps, pitch_rate_dps, yaw_rate_dps };
413
ang_vel_body *= DEG_TO_RAD;
414
415
// Pass to guided mode
416
mode_guided.set_angle(q, ang_vel_body, throttle, true);
417
return true;
418
}
419
420
// Register a custom mode with given number and names
421
AP_Vehicle::custom_mode_state* Copter::register_custom_mode(const uint8_t num, const char* full_name, const char* short_name)
422
{
423
const Mode::Number number = (Mode::Number)num;
424
425
// See if this mode has been registered already, if it has return the state for it
426
// This allows scripting restarts
427
for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {
428
if (mode_guided_custom[i] == nullptr) {
429
break;
430
}
431
if ((mode_guided_custom[i]->mode_number() == number) &&
432
(strcmp(mode_guided_custom[i]->name(), full_name) == 0) &&
433
(strncmp(mode_guided_custom[i]->name4(), short_name, 4) == 0)) {
434
return &mode_guided_custom[i]->state;
435
}
436
}
437
438
// Number already registered to existing mode
439
if (mode_from_mode_num(number) != nullptr) {
440
return nullptr;
441
}
442
443
// Find free slot
444
for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {
445
if (mode_guided_custom[i] == nullptr) {
446
// Duplicate strings so were not pointing to unknown memory
447
const char* full_name_copy = strdup(full_name);
448
const char* short_name_copy = strndup(short_name, 4);
449
if ((full_name_copy != nullptr) && (short_name_copy != nullptr)) {
450
mode_guided_custom[i] = NEW_NOTHROW ModeGuidedCustom(number, full_name_copy, short_name_copy);
451
}
452
if (mode_guided_custom[i] == nullptr) {
453
// Allocation failure
454
return nullptr;
455
}
456
457
// Registration sucsessful, notify the GCS that it should re-request the avalable modes
458
gcs().available_modes_changed();
459
460
return &mode_guided_custom[i]->state;
461
}
462
}
463
464
// No free slots
465
return nullptr;
466
}
467
#endif // MODE_GUIDED_ENABLED
468
469
#if MODE_CIRCLE_ENABLED
470
// circle mode controls
471
bool Copter::get_circle_radius(float &radius_m)
472
{
473
radius_m = circle_nav->get_radius() * 0.01f;
474
return true;
475
}
476
477
bool Copter::set_circle_rate(float rate_dps)
478
{
479
circle_nav->set_rate(rate_dps);
480
return true;
481
}
482
#endif
483
484
// set desired speed (m/s). Used for scripting.
485
bool Copter::set_desired_speed(float speed)
486
{
487
return flightmode->set_speed_xy(speed * 100.0f);
488
}
489
490
#if MODE_AUTO_ENABLED
491
// returns true if mode supports NAV_SCRIPT_TIME mission commands
492
bool Copter::nav_scripting_enable(uint8_t mode)
493
{
494
return mode == (uint8_t)mode_auto.mode_number();
495
}
496
497
// lua scripts use this to retrieve the contents of the active command
498
bool Copter::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
499
{
500
if (flightmode != &mode_auto) {
501
return false;
502
}
503
504
return mode_auto.nav_script_time(id, cmd, arg1, arg2, arg3, arg4);
505
}
506
507
// lua scripts use this to indicate when they have complete the command
508
void Copter::nav_script_time_done(uint16_t id)
509
{
510
if (flightmode != &mode_auto) {
511
return;
512
}
513
514
return mode_auto.nav_script_time_done(id);
515
}
516
#endif
517
518
// returns true if the EKF failsafe has triggered. Only used by Lua scripts
519
bool Copter::has_ekf_failsafed() const
520
{
521
return failsafe.ekf;
522
}
523
524
// get target location (for use by scripting)
525
bool Copter::get_target_location(Location& target_loc)
526
{
527
return flightmode->get_wp(target_loc);
528
}
529
530
/*
531
update_target_location() acts as a wrapper for set_target_location
532
*/
533
bool Copter::update_target_location(const Location &old_loc, const Location &new_loc)
534
{
535
/*
536
by checking the caller has provided the correct old target
537
location we prevent a race condition where the user changes mode
538
or commands a different target in the controlling lua script
539
*/
540
Location next_WP_loc;
541
flightmode->get_wp(next_WP_loc);
542
if (!old_loc.same_loc_as(next_WP_loc) ||
543
old_loc.get_alt_frame() != new_loc.get_alt_frame()) {
544
return false;
545
}
546
547
return set_target_location(new_loc);
548
}
549
550
#endif // AP_SCRIPTING_ENABLED
551
552
// returns true if vehicle is landing.
553
bool Copter::is_landing() const
554
{
555
return flightmode->is_landing();
556
}
557
558
// returns true if vehicle is taking off.
559
bool Copter::is_taking_off() const
560
{
561
return flightmode->is_taking_off();
562
}
563
564
bool Copter::current_mode_requires_mission() const
565
{
566
#if MODE_AUTO_ENABLED
567
return flightmode == &mode_auto;
568
#else
569
return false;
570
#endif
571
}
572
573
// rc_loops - reads user input from transmitter/receiver
574
// called at 100hz
575
void Copter::rc_loop()
576
{
577
// Read radio and 3-position switch on radio
578
// -----------------------------------------
579
read_radio();
580
rc().read_mode_switch();
581
}
582
583
// throttle_loop - should be run at 50 hz
584
// ---------------------------
585
void Copter::throttle_loop()
586
{
587
// update throttle_low_comp value (controls priority of throttle vs attitude control)
588
update_throttle_mix();
589
590
// check auto_armed status
591
update_auto_armed();
592
593
#if FRAME_CONFIG == HELI_FRAME
594
// update rotor speed
595
heli_update_rotor_speed_targets();
596
597
// update trad heli swash plate movement
598
heli_update_landing_swash();
599
#endif
600
601
// compensate for ground effect (if enabled)
602
update_ground_effect_detector();
603
update_ekf_terrain_height_stable();
604
}
605
606
// update_batt_compass - read battery and compass
607
// should be called at 10hz
608
void Copter::update_batt_compass(void)
609
{
610
// read battery before compass because it may be used for motor interference compensation
611
battery.read();
612
613
if(AP::compass().available()) {
614
// update compass with throttle value - used for compassmot
615
compass.set_throttle(motors->get_throttle());
616
compass.set_voltage(battery.voltage());
617
compass.read();
618
}
619
}
620
621
#if HAL_LOGGING_ENABLED
622
// Full rate logging of attitude, rate and pid loops
623
// should be run at loop rate
624
void Copter::loop_rate_logging()
625
{
626
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
627
Log_Write_Attitude();
628
if (!using_rate_thread) {
629
Log_Write_Rate();
630
Log_Write_PIDS(); // only logs if PIDS bitmask is set
631
}
632
}
633
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
634
if (should_log(MASK_LOG_FTN_FAST) && !using_rate_thread) {
635
AP::ins().write_notch_log_messages();
636
}
637
#endif
638
if (should_log(MASK_LOG_IMU_FAST)) {
639
AP::ins().Write_IMU();
640
}
641
}
642
643
// ten_hz_logging_loop
644
// should be run at 10hz
645
void Copter::ten_hz_logging_loop()
646
{
647
// always write AHRS attitude at 10Hz
648
ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);
649
// log attitude controller data if we're not already logging at the higher rate
650
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
651
Log_Write_Attitude();
652
if (!using_rate_thread) {
653
Log_Write_Rate();
654
}
655
}
656
if (!should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
657
// 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
658
if (!using_rate_thread) {
659
Log_Write_PIDS();
660
}
661
}
662
// log EKF attitude data always at 10Hz unless ATTITUDE_FAST, then do it in the 25Hz loop
663
if (!should_log(MASK_LOG_ATTITUDE_FAST)) {
664
Log_Write_EKF_POS();
665
}
666
if ((FRAME_CONFIG == HELI_FRAME) || should_log(MASK_LOG_MOTBATT)) {
667
// always write motors log if we are a heli
668
motors->Log_Write();
669
}
670
if (should_log(MASK_LOG_RCIN)) {
671
logger.Write_RCIN();
672
#if AP_RSSI_ENABLED
673
if (rssi.enabled()) {
674
logger.Write_RSSI();
675
}
676
#endif
677
}
678
if (should_log(MASK_LOG_RCOUT)) {
679
logger.Write_RCOUT();
680
}
681
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS() || !flightmode->has_manual_throttle())) {
682
pos_control->write_log();
683
}
684
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
685
AP::ins().Write_Vibration();
686
}
687
if (should_log(MASK_LOG_CTUN)) {
688
attitude_control->control_monitor_log();
689
#if HAL_PROXIMITY_ENABLED
690
g2.proximity.log(); // Write proximity sensor distances
691
#endif
692
#if AP_BEACON_ENABLED
693
g2.beacon.log();
694
#endif
695
}
696
#if AP_WINCH_ENABLED
697
if (should_log(MASK_LOG_ANY)) {
698
g2.winch.write_log();
699
}
700
#endif
701
#if HAL_MOUNT_ENABLED
702
if (should_log(MASK_LOG_CAMERA)) {
703
camera_mount.write_log();
704
}
705
#endif
706
}
707
708
// twentyfive_hz_logging - should be run at 25hz
709
void Copter::twentyfive_hz_logging()
710
{
711
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
712
Log_Write_EKF_POS();
713
}
714
715
if (should_log(MASK_LOG_IMU) && !(should_log(MASK_LOG_IMU_FAST))) {
716
AP::ins().Write_IMU();
717
}
718
719
#if MODE_AUTOROTATE_ENABLED
720
if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) {
721
//update autorotation log
722
g2.arot.Log_Write_Autorotation();
723
}
724
#endif
725
#if HAL_GYROFFT_ENABLED
726
if (should_log(MASK_LOG_FTN_FAST)) {
727
gyro_fft.write_log_messages();
728
}
729
#endif
730
}
731
#endif // HAL_LOGGING_ENABLED
732
733
// three_hz_loop - 3hz loop
734
void Copter::three_hz_loop()
735
{
736
// check if we've lost contact with the ground station
737
failsafe_gcs_check();
738
739
// check if we've lost terrain data
740
failsafe_terrain_check();
741
742
// check for deadreckoning failsafe
743
failsafe_deadreckon_check();
744
745
//update transmitter based in flight tuning
746
tuning();
747
748
// check if avoidance should be enabled based on alt
749
low_alt_avoidance();
750
}
751
752
// ap_value calculates a 32-bit bitmask representing various pieces of
753
// state about the Copter. It replaces a global variable which was
754
// used to track this state.
755
uint32_t Copter::ap_value() const
756
{
757
uint32_t ret = 0;
758
759
const bool *b = (const bool *)&ap;
760
for (uint8_t i=0; i<sizeof(ap); i++) {
761
if (b[i]) {
762
ret |= 1U<<i;
763
}
764
}
765
766
return ret;
767
}
768
769
// one_hz_loop - runs at 1Hz
770
void Copter::one_hz_loop()
771
{
772
#if HAL_LOGGING_ENABLED
773
if (should_log(MASK_LOG_ANY)) {
774
Log_Write_Data(LogDataID::AP_STATE, ap_value());
775
}
776
#endif
777
778
if (!motors->armed()) {
779
update_using_interlock();
780
781
// check the user hasn't updated the frame class or type
782
motors->set_frame_class_and_type((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
783
784
#if FRAME_CONFIG != HELI_FRAME
785
// set all throttle channel settings
786
motors->update_throttle_range();
787
#endif
788
}
789
790
// update assigned functions and enable auxiliary servos
791
AP::srv().enable_aux_servos();
792
793
#if HAL_LOGGING_ENABLED
794
// log terrain data
795
terrain_logging();
796
#endif
797
798
#if HAL_ADSB_ENABLED
799
adsb.set_is_flying(!ap.land_complete);
800
#endif
801
802
AP_Notify::flags.flying = !ap.land_complete;
803
804
// slowly update the PID notches with the average loop rate
805
if (!using_rate_thread) {
806
attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
807
}
808
pos_control->get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
809
#if AC_CUSTOMCONTROL_MULTI_ENABLED
810
custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
811
#endif
812
813
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
814
// see if we should have a separate rate thread
815
if (!started_rate_thread && get_fast_rate_type() != FastRateType::FAST_RATE_DISABLED) {
816
if (hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&Copter::rate_controller_thread, void),
817
"rate",
818
1536, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) {
819
started_rate_thread = true;
820
} else {
821
AP_BoardConfig::allocation_error("rate thread");
822
}
823
}
824
#endif
825
}
826
827
void Copter::init_simple_bearing()
828
{
829
// capture current cos_yaw and sin_yaw values
830
simple_cos_yaw = ahrs.cos_yaw();
831
simple_sin_yaw = ahrs.sin_yaw();
832
833
// initialise super simple heading (i.e. heading towards home) to be 180 deg from simple mode heading
834
super_simple_last_bearing = wrap_360_cd(ahrs.yaw_sensor+18000);
835
super_simple_cos_yaw = simple_cos_yaw;
836
super_simple_sin_yaw = simple_sin_yaw;
837
838
#if HAL_LOGGING_ENABLED
839
// log the simple bearing
840
if (should_log(MASK_LOG_ANY)) {
841
Log_Write_Data(LogDataID::INIT_SIMPLE_BEARING, ahrs.yaw_sensor);
842
}
843
#endif
844
}
845
846
// update_simple_mode - rotates pilot input if we are in simple mode
847
void Copter::update_simple_mode(void)
848
{
849
float rollx, pitchx;
850
851
// exit immediately if no new radio frame or not in simple mode
852
if (simple_mode == SimpleMode::NONE || !ap.new_radio_frame) {
853
return;
854
}
855
856
// mark radio frame as consumed
857
ap.new_radio_frame = false;
858
859
if (simple_mode == SimpleMode::SIMPLE) {
860
// rotate roll, pitch input by -initial simple heading (i.e. north facing)
861
rollx = channel_roll->get_control_in()*simple_cos_yaw - channel_pitch->get_control_in()*simple_sin_yaw;
862
pitchx = channel_roll->get_control_in()*simple_sin_yaw + channel_pitch->get_control_in()*simple_cos_yaw;
863
}else{
864
// rotate roll, pitch input by -super simple heading (reverse of heading to home)
865
rollx = channel_roll->get_control_in()*super_simple_cos_yaw - channel_pitch->get_control_in()*super_simple_sin_yaw;
866
pitchx = channel_roll->get_control_in()*super_simple_sin_yaw + channel_pitch->get_control_in()*super_simple_cos_yaw;
867
}
868
869
// rotate roll, pitch input from north facing to vehicle's perspective
870
channel_roll->set_control_in(rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw());
871
channel_pitch->set_control_in(-rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw());
872
}
873
874
// update_super_simple_bearing - adjusts simple bearing based on location
875
// should be called after home_bearing has been updated
876
void Copter::update_super_simple_bearing(bool force_update)
877
{
878
if (!force_update) {
879
if (simple_mode != SimpleMode::SUPERSIMPLE) {
880
return;
881
}
882
if (home_distance() < SUPER_SIMPLE_RADIUS) {
883
return;
884
}
885
}
886
887
const int32_t bearing = home_bearing();
888
889
// check the bearing to home has changed by at least 5 degrees
890
if (labs(super_simple_last_bearing - bearing) < 500) {
891
return;
892
}
893
894
super_simple_last_bearing = bearing;
895
const float angle_rad = radians((super_simple_last_bearing+18000)/100);
896
super_simple_cos_yaw = cosf(angle_rad);
897
super_simple_sin_yaw = sinf(angle_rad);
898
}
899
900
void Copter::read_AHRS(void)
901
{
902
// we tell AHRS to skip INS update as we have already done it in FAST_TASK.
903
ahrs.update(true);
904
}
905
906
// read baro and log control tuning
907
void Copter::update_altitude()
908
{
909
// read in baro altitude
910
read_barometer();
911
912
#if HAL_LOGGING_ENABLED
913
if (should_log(MASK_LOG_CTUN)) {
914
Log_Write_Control_Tuning();
915
if (!should_log(MASK_LOG_FTN_FAST)) {
916
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
917
AP::ins().write_notch_log_messages();
918
#endif
919
#if HAL_GYROFFT_ENABLED
920
gyro_fft.write_log_messages();
921
#endif
922
}
923
}
924
#endif
925
}
926
927
// vehicle specific waypoint info helpers
928
bool Copter::get_wp_distance_m(float &distance) const
929
{
930
// see GCS_MAVLINK_Copter::send_nav_controller_output()
931
distance = flightmode->wp_distance() * 0.01;
932
return true;
933
}
934
935
// vehicle specific waypoint info helpers
936
bool Copter::get_wp_bearing_deg(float &bearing) const
937
{
938
// see GCS_MAVLINK_Copter::send_nav_controller_output()
939
bearing = flightmode->wp_bearing() * 0.01;
940
return true;
941
}
942
943
// vehicle specific waypoint info helpers
944
bool Copter::get_wp_crosstrack_error_m(float &xtrack_error) const
945
{
946
// see GCS_MAVLINK_Copter::send_nav_controller_output()
947
xtrack_error = flightmode->crosstrack_error() * 0.01;
948
return true;
949
}
950
951
// get the target earth-frame angular velocities in rad/s (Z-axis component used by some gimbals)
952
bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const
953
{
954
// always returns zero vector if landed or disarmed
955
if (copter.ap.land_complete) {
956
rate_ef_targets.zero();
957
} else {
958
rate_ef_targets = attitude_control->get_rate_ef_targets();
959
}
960
return true;
961
}
962
963
/*
964
constructor for main Copter class
965
*/
966
Copter::Copter(void)
967
:
968
flight_modes(&g.flight_mode1),
969
pos_variance_filt(FS_EKF_FILT_DEFAULT),
970
vel_variance_filt(FS_EKF_FILT_DEFAULT),
971
hgt_variance_filt(FS_EKF_FILT_DEFAULT),
972
flightmode(&mode_stabilize),
973
simple_cos_yaw(1.0f),
974
super_simple_cos_yaw(1.0),
975
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),
976
rc_throttle_control_in_filter(1.0f),
977
inertial_nav(ahrs),
978
param_loader(var_info)
979
{
980
}
981
982
Copter copter;
983
AP_Vehicle& vehicle = copter;
984
985
AP_HAL_MAIN_CALLBACKS(&copter);
986
987