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