Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/Sub.cpp
9347 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
#include "Sub.h"
17
18
#define FORCE_VERSION_H_INCLUDE
19
#include "version.h"
20
#undef FORCE_VERSION_H_INCLUDE
21
22
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
23
24
/*
25
constructor for main Sub class
26
*/
27
Sub::Sub()
28
:
29
30
#if AP_SUB_RC_ENABLED
31
flight_modes(&g.flight_mode1),
32
#else
33
control_mode(Mode::Number::MANUAL),
34
#endif
35
motors(MAIN_LOOP_RATE),
36
auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP),
37
inertial_nav(ahrs),
38
ahrs_view(ahrs, ROTATION_NONE),
39
attitude_control(ahrs_view, motors),
40
pos_control(ahrs_view, motors, attitude_control),
41
wp_nav(ahrs_view, pos_control, attitude_control),
42
loiter_nav(ahrs_view, pos_control, attitude_control),
43
circle_nav(ahrs_view, pos_control),
44
param_loader(var_info),
45
flightmode(&mode_manual),
46
auto_mode(Auto_WP),
47
guided_mode(Guided_WP)
48
{
49
failsafe.pilot_input = true;
50
if (_singleton != nullptr) {
51
AP_HAL::panic("Can only be one Sub");
52
}
53
_singleton = this;
54
}
55
56
#define SCHED_TASK(func, rate_hz, max_time_micros, priority) SCHED_TASK_CLASS(Sub, &sub, func, rate_hz, max_time_micros, priority)
57
#define FAST_TASK(func) FAST_TASK_CLASS(Sub, &sub, func)
58
59
/*
60
scheduler table - all tasks should be listed here.
61
62
All entries in this table must be ordered by priority.
63
64
This table is interleaved with the table in AP_Vehicle to determine
65
the order in which tasks are run. Convenience methods SCHED_TASK
66
and SCHED_TASK_CLASS are provided to build entries in this structure:
67
68
SCHED_TASK arguments:
69
- name of static function to call
70
- rate (in Hertz) at which the function should be called
71
- expected time (in MicroSeconds) that the function should take to run
72
- priority (0 through 255, lower number meaning higher priority)
73
74
SCHED_TASK_CLASS arguments:
75
- class name of method to be called
76
- instance on which to call the method
77
- method to call on that instance
78
- rate (in Hertz) at which the method should be called
79
- expected time (in MicroSeconds) that the method should take to run
80
- priority (0 through 255, lower number meaning higher priority)
81
82
*/
83
84
const AP_Scheduler::Task Sub::scheduler_tasks[] = {
85
// update INS immediately to get current gyro data populated
86
FAST_TASK_CLASS(AP_InertialSensor, &sub.ins, update),
87
// run low level rate controllers that only require IMU data
88
FAST_TASK(run_rate_controller),
89
// send outputs to the motors library immediately
90
FAST_TASK(motors_output),
91
// run EKF state estimator (expensive)
92
FAST_TASK(read_AHRS),
93
// Inertial Nav
94
FAST_TASK(read_inertia),
95
// check if ekf has reset target heading
96
FAST_TASK(check_ekf_yaw_reset),
97
// run the attitude controllers
98
FAST_TASK(update_flight_mode),
99
// update home from EKF if necessary
100
FAST_TASK(update_home_from_EKF),
101
// check if we've reached the surface or bottom
102
FAST_TASK(update_surface_and_bottom_detector),
103
#if HAL_MOUNT_ENABLED
104
// camera mount's fast update
105
FAST_TASK_CLASS(AP_Mount, &sub.camera_mount, update_fast),
106
#endif
107
108
SCHED_TASK(fifty_hz_loop, 50, 75, 3),
109
#if AP_SUB_RC_ENABLED
110
SCHED_TASK(rc_loop, 50, 130, 3),
111
#endif
112
SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200, 6),
113
#if AP_OPTICALFLOW_ENABLED
114
SCHED_TASK_CLASS(AP_OpticalFlow, &sub.optflow, update, 200, 160, 9),
115
#endif
116
SCHED_TASK(update_batt_compass, 10, 120, 12),
117
SCHED_TASK(read_rangefinder, 20, 100, 15),
118
SCHED_TASK(update_altitude, 10, 100, 18),
119
#if AP_SUB_RC_ENABLED
120
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&sub.g2.rc_channels, read_aux_all, 10, 50, 18),
121
#endif
122
SCHED_TASK(three_hz_loop, 3, 75, 21),
123
SCHED_TASK(update_turn_counter, 10, 50, 24),
124
SCHED_TASK(one_hz_loop, 1, 100, 33),
125
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36),
126
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39),
127
#if HAL_MOUNT_ENABLED
128
SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75, 45),
129
#endif
130
#if AP_CAMERA_ENABLED
131
SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75, 48),
132
#endif
133
#if HAL_LOGGING_ENABLED
134
SCHED_TASK(ten_hz_logging_loop, 10, 350, 51),
135
SCHED_TASK(twentyfive_hz_logging, 25, 110, 54),
136
SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 55),
137
SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300, 57),
138
#endif
139
SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50, 60),
140
#if HAL_LOGGING_ENABLED
141
SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75, 63),
142
#endif
143
SCHED_TASK(terrain_update, 10, 100, 72),
144
#if AP_STATS_ENABLED
145
SCHED_TASK(stats_update, 1, 200, 76),
146
#endif
147
#ifdef USERHOOK_FASTLOOP
148
SCHED_TASK(userhook_FastLoop, 100, 75, 78),
149
#endif
150
#ifdef USERHOOK_50HZLOOP
151
SCHED_TASK(userhook_50Hz, 50, 75, 81),
152
#endif
153
#ifdef USERHOOK_MEDIUMLOOP
154
SCHED_TASK(userhook_MediumLoop, 10, 75, 84),
155
#endif
156
#ifdef USERHOOK_SLOWLOOP
157
SCHED_TASK(userhook_SlowLoop, 3.3, 75, 87),
158
#endif
159
#ifdef USERHOOK_SUPERSLOWLOOP
160
SCHED_TASK(userhook_SuperSlowLoop, 1, 75, 90),
161
#endif
162
163
};
164
165
void Sub::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
166
uint8_t &task_count,
167
uint32_t &log_bit)
168
{
169
tasks = &scheduler_tasks[0];
170
task_count = ARRAY_SIZE(scheduler_tasks);
171
log_bit = MASK_LOG_PM;
172
}
173
174
constexpr int8_t Sub::_failsafe_priorities[5];
175
176
void Sub::run_rate_controller()
177
{
178
const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();
179
motors.set_dt_s(last_loop_time_s);
180
attitude_control.set_dt_s(last_loop_time_s);
181
pos_control.set_dt_s(last_loop_time_s);
182
183
//don't run rate controller in manual or motordetection modes
184
if (control_mode != Mode::Number::MANUAL && control_mode != Mode::Number::MOTOR_DETECT) {
185
// run low level rate controllers that only require IMU data and set loop time
186
attitude_control.rate_controller_run();
187
}
188
}
189
190
// 50 Hz tasks
191
void Sub::fifty_hz_loop()
192
{
193
// check pilot input failsafe
194
failsafe_pilot_input_check();
195
196
failsafe_crash_check();
197
198
failsafe_ekf_check();
199
200
failsafe_sensors_check();
201
#if !AP_SUB_RC_ENABLED
202
rc().read_input();
203
#endif
204
g2.actuators.update_actuators();
205
}
206
207
// update_batt_compass - read battery and compass
208
// should be called at 10hz
209
void Sub::update_batt_compass()
210
{
211
// read battery before compass because it may be used for motor interference compensation
212
battery.read();
213
214
if (AP::compass().available()) {
215
// update compass with throttle value - used for compassmot
216
compass.set_throttle(motors.get_throttle());
217
compass.read();
218
}
219
}
220
221
#if HAL_LOGGING_ENABLED
222
// ten_hz_logging_loop
223
// should be run at 10hz
224
void Sub::ten_hz_logging_loop()
225
{
226
// log attitude data if we're not already logging at the higher rate
227
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
228
Log_Write_Attitude();
229
attitude_control.Write_ANG();
230
attitude_control.Write_Rate(pos_control);
231
if (should_log(MASK_LOG_PID)) {
232
logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
233
logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
234
logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
235
logger.Write_PID(LOG_PIDA_MSG, pos_control.D_get_accel_pid().get_pid_info());
236
}
237
}
238
if (should_log(MASK_LOG_MOTBATT)) {
239
motors.Log_Write();
240
}
241
if (should_log(MASK_LOG_RCIN)) {
242
logger.Write_RCIN();
243
}
244
if (should_log(MASK_LOG_RCOUT)) {
245
logger.Write_RCOUT();
246
}
247
if (should_log(MASK_LOG_NTUN) && (sub.flightmode->requires_GPS() || sub.flightmode->requires_altitude())) {
248
pos_control.write_log();
249
}
250
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
251
AP::ins().Write_Vibration();
252
}
253
#if HAL_MOUNT_ENABLED
254
if (should_log(MASK_LOG_CAMERA)) {
255
camera_mount.write_log();
256
}
257
#endif
258
}
259
260
// twentyfive_hz_logging_loop
261
// should be run at 25hz
262
void Sub::twentyfive_hz_logging()
263
{
264
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
265
Log_Write_Attitude();
266
attitude_control.Write_ANG();
267
attitude_control.Write_Rate(pos_control);
268
if (should_log(MASK_LOG_PID)) {
269
logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
270
logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
271
logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
272
logger.Write_PID(LOG_PIDA_MSG, pos_control.D_get_accel_pid().get_pid_info());
273
}
274
}
275
276
// log IMU data if we're not already logging at the higher rate
277
if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_FAST)) {
278
AP::ins().Write_IMU();
279
}
280
}
281
282
// Full rate logging of IMU
283
void Sub::loop_rate_logging()
284
{
285
if (should_log(MASK_LOG_IMU_FAST)) {
286
AP::ins().Write_IMU();
287
}
288
}
289
#endif // HAL_LOGGING_ENABLED
290
291
// three_hz_loop - 3.3hz loop
292
void Sub::three_hz_loop()
293
{
294
leak_detector.update();
295
296
failsafe_leak_check();
297
298
failsafe_internal_pressure_check();
299
300
failsafe_internal_temperature_check();
301
302
// check if we've lost contact with the ground station
303
failsafe_gcs_check();
304
305
// check if we've lost terrain data
306
failsafe_terrain_check();
307
308
#if AP_SERVORELAYEVENTS_ENABLED
309
ServoRelayEvents.update_events();
310
#endif
311
}
312
313
// one_hz_loop - runs at 1Hz
314
void Sub::one_hz_loop()
315
{
316
bool arm_check = arming.pre_arm_checks(false);
317
ap.pre_arm_check = arm_check;
318
AP_Notify::flags.pre_arm_check = arm_check;
319
AP_Notify::flags.pre_arm_gps_check = position_ok();
320
AP_Notify::flags.flying = motors.armed();
321
322
#if HAL_LOGGING_ENABLED
323
if (should_log(MASK_LOG_ANY)) {
324
Log_Write_Data(LogDataID::AP_STATE, ap.value);
325
}
326
#endif
327
328
if (!motors.armed()) {
329
motors.update_throttle_range();
330
}
331
332
// update assigned functions and enable auxiliary servos
333
AP::srv().enable_aux_servos();
334
335
#if HAL_LOGGING_ENABLED
336
// log terrain data
337
terrain_logging();
338
#endif
339
340
// need to set "likely flying" when armed to allow for compass
341
// learning to run
342
set_likely_flying(hal.util->get_soft_armed());
343
344
attitude_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
345
pos_control.D_get_accel_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
346
}
347
348
void Sub::read_AHRS()
349
{
350
// Perform IMU calculations and get attitude info
351
//-----------------------------------------------
352
// <true> tells AHRS to skip INS update as we have already done it in fast_loop()
353
ahrs.update(true);
354
ahrs_view.update();
355
}
356
357
// read baro and rangefinder altitude at 10hz
358
void Sub::update_altitude()
359
{
360
// read in baro altitude
361
read_barometer();
362
363
#if HAL_LOGGING_ENABLED
364
if (should_log(MASK_LOG_CTUN)) {
365
Log_Write_Control_Tuning();
366
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
367
AP::ins().write_notch_log_messages();
368
#endif
369
#if HAL_GYROFFT_ENABLED
370
gyro_fft.write_log_messages();
371
#endif
372
}
373
#endif // HAL_LOGGING_ENABLED
374
}
375
376
bool Sub::control_check_barometer()
377
{
378
if (!ap.depth_sensor_present) { // can't hold depth without a depth sensor
379
gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor is not connected.");
380
return false;
381
} else if (failsafe.sensor_health) {
382
gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor error.");
383
return false;
384
}
385
return true;
386
}
387
388
// vehicle specific waypoint info helpers
389
bool Sub::get_wp_distance_m(float &distance) const
390
{
391
// see GCS_MAVLINK_Sub::send_nav_controller_output()
392
distance = sub.wp_nav.get_wp_distance_to_destination_cm() * 0.01;
393
return true;
394
}
395
396
// vehicle specific waypoint info helpers
397
bool Sub::get_wp_bearing_deg(float &bearing) const
398
{
399
// see GCS_MAVLINK_Sub::send_nav_controller_output()
400
bearing = sub.wp_nav.get_wp_bearing_to_destination_cd() * 0.01;
401
return true;
402
}
403
404
// vehicle specific waypoint info helpers
405
bool Sub::get_wp_crosstrack_error_m(float &xtrack_error) const
406
{
407
// no crosstrack error reported, see GCS_MAVLINK_Sub::send_nav_controller_output()
408
xtrack_error = 0;
409
return true;
410
}
411
412
#if AP_STATS_ENABLED
413
/*
414
update AP_Stats
415
*/
416
void Sub::stats_update(void)
417
{
418
AP::stats()->set_flying(motors.armed());
419
}
420
#endif
421
422
// get the altitude relative to the home position or the ekf origin
423
float Sub::get_alt_rel() const
424
{
425
if (!ap.depth_sensor_present) {
426
return 0;
427
}
428
429
// get relative position
430
float posD;
431
ahrs.get_relative_position_D_home(posD);
432
return -posD;
433
}
434
435
// get the altitude above mean sea level
436
float Sub::get_alt_msl() const
437
{
438
if (!ap.depth_sensor_present) {
439
return 0;
440
}
441
442
Location origin;
443
if (!ahrs.get_origin(origin)) {
444
return 0;
445
}
446
447
// get relative position
448
float posD;
449
if (!ahrs.get_relative_position_D_origin_float(posD)) {
450
// fall back to the barometer reading
451
posD = -AP::baro().get_altitude();
452
}
453
454
// add in the ekf origin altitude
455
posD -= static_cast<float>(origin.alt) * 0.01f;
456
457
// convert down to up
458
return -posD;
459
}
460
461
#if AP_SUB_RC_ENABLED
462
void Sub::rc_loop()
463
{
464
// Read radio and 3-position switch on radio
465
// -----------------------------------------
466
read_radio();
467
rc().read_mode_switch();
468
}
469
#endif
470
471
Sub *Sub::_singleton = nullptr;
472
473
Sub sub;
474
AP_Vehicle& vehicle = sub;
475
476
AP_HAL_MAIN_CALLBACKS(&sub);
477
478