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/Rover/Rover.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
This is the ArduRover firmware. It was originally derived from
18
ArduPlane by Jean-Louis Naudin (JLN), and then rewritten after the
19
AP_HAL merge by Andrew Tridgell
20
21
Maintainer: Randy Mackay, Grant Morphett
22
23
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler, Jean-Louis Naudin, Grant Morphett
24
25
Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier
26
27
APMrover alpha version tester: Franco Borasio, Daniel Chapelat...
28
29
Please contribute your ideas! See https://ardupilot.org/dev for details
30
*/
31
32
#include "Rover.h"
33
34
#define FORCE_VERSION_H_INCLUDE
35
#include "version.h"
36
#undef FORCE_VERSION_H_INCLUDE
37
38
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
39
40
#define SCHED_TASK(func, _interval_ticks, _max_time_micros, _priority) SCHED_TASK_CLASS(Rover, &rover, func, _interval_ticks, _max_time_micros, _priority)
41
42
/*
43
scheduler table - all regular tasks should be listed here.
44
45
All entries in this table must be ordered by priority.
46
47
This table is interleaved with the table in AP_Vehicle to determine
48
the order in which tasks are run. Convenience methods SCHED_TASK
49
and SCHED_TASK_CLASS are provided to build entries in this structure:
50
51
SCHED_TASK arguments:
52
- name of static function to call
53
- rate (in Hertz) at which the function should be called
54
- expected time (in MicroSeconds) that the function should take to run
55
- priority (0 through 255, lower number meaning higher priority)
56
57
SCHED_TASK_CLASS arguments:
58
- class name of method to be called
59
- instance on which to call the method
60
- method to call on that instance
61
- rate (in Hertz) at which the method should be called
62
- expected time (in MicroSeconds) that the method should take to run
63
- priority (0 through 255, lower number meaning higher priority)
64
65
scheduler table - all regular tasks are listed here, along with how
66
often they should be called (in Hz) and the maximum time
67
they are expected to take (in microseconds)
68
*/
69
const AP_Scheduler::Task Rover::scheduler_tasks[] = {
70
// Function name, Hz, us,
71
SCHED_TASK(read_radio, 50, 200, 3),
72
SCHED_TASK(ahrs_update, 400, 400, 6),
73
#if AP_RANGEFINDER_ENABLED
74
SCHED_TASK(read_rangefinders, 50, 200, 9),
75
#endif
76
#if AP_OPTICALFLOW_ENABLED
77
SCHED_TASK_CLASS(AP_OpticalFlow, &rover.optflow, update, 200, 160, 11),
78
#endif
79
SCHED_TASK(update_current_mode, 400, 200, 12),
80
SCHED_TASK(set_servos, 400, 200, 15),
81
SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300, 18),
82
SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200, 21),
83
#if AP_BEACON_ENABLED
84
SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200, 24),
85
#endif
86
#if HAL_PROXIMITY_ENABLED
87
SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200, 27),
88
#endif
89
SCHED_TASK_CLASS(AP_WindVane, &rover.g2.windvane, update, 20, 100, 30),
90
SCHED_TASK(update_wheel_encoder, 50, 200, 36),
91
SCHED_TASK(update_compass, 10, 200, 39),
92
#if HAL_LOGGING_ENABLED
93
SCHED_TASK(update_logging1, 10, 200, 45),
94
SCHED_TASK(update_logging2, 10, 200, 48),
95
#endif
96
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_receive, 400, 500, 51),
97
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_send, 400, 1000, 54),
98
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_mode_switch, 7, 200, 57),
99
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200, 60),
100
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300, 63),
101
#if AP_SERVORELAYEVENTS_ENABLED
102
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66),
103
#endif
104
#if AC_PRECLAND_ENABLED
105
SCHED_TASK(update_precland, 400, 50, 70),
106
#endif
107
#if AP_RPM_ENABLED
108
SCHED_TASK_CLASS(AP_RPM, &rover.rpm_sensor, update, 10, 100, 72),
109
#endif
110
#if HAL_MOUNT_ENABLED
111
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200, 75),
112
#endif
113
#if AP_CAMERA_ENABLED
114
SCHED_TASK_CLASS(AP_Camera, &rover.camera, update, 50, 200, 78),
115
#endif
116
SCHED_TASK(gcs_failsafe_check, 10, 200, 81),
117
SCHED_TASK(fence_check, 10, 200, 84),
118
SCHED_TASK(ekf_check, 10, 100, 87),
119
SCHED_TASK_CLASS(ModeSmartRTL, &rover.mode_smartrtl, save_position, 3, 200, 90),
120
SCHED_TASK(one_second_loop, 1, 1500, 96),
121
#if HAL_SPRAYER_ENABLED
122
SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90, 99),
123
#endif
124
SCHED_TASK(compass_save, 0.1, 200, 105),
125
#if HAL_LOGGING_ENABLED
126
SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300, 108),
127
#endif
128
SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 400, 200, 111),
129
#if HAL_LOGGING_ENABLED
130
SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 200, 114),
131
#endif
132
#if HAL_BUTTON_ENABLED
133
SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 200, 117),
134
#endif
135
SCHED_TASK(crash_check, 10, 200, 123),
136
SCHED_TASK(cruise_learn_update, 50, 200, 126),
137
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
138
SCHED_TASK(afs_fs_check, 10, 200, 129),
139
#endif
140
};
141
142
143
void Rover::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
144
uint8_t &task_count,
145
uint32_t &log_bit)
146
{
147
tasks = &scheduler_tasks[0];
148
task_count = ARRAY_SIZE(scheduler_tasks);
149
log_bit = MASK_LOG_PM;
150
}
151
152
constexpr int8_t Rover::_failsafe_priorities[7];
153
154
Rover::Rover(void) :
155
AP_Vehicle(),
156
param_loader(var_info),
157
modes(&g.mode1),
158
control_mode(&mode_initializing)
159
{
160
}
161
162
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
163
// set target location (for use by external control and scripting)
164
bool Rover::set_target_location(const Location& target_loc)
165
{
166
// exit if vehicle is not in Guided mode or Auto-Guided mode
167
if (!control_mode->in_guided_mode()) {
168
return false;
169
}
170
171
return mode_guided.set_desired_location(target_loc);
172
}
173
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
174
175
#if AP_SCRIPTING_ENABLED
176
// set target velocity (for use by scripting)
177
bool Rover::set_target_velocity_NED(const Vector3f& vel_ned)
178
{
179
// exit if vehicle is not in Guided mode or Auto-Guided mode
180
if (!control_mode->in_guided_mode()) {
181
return false;
182
}
183
184
// convert vector length into speed
185
const float target_speed_m = safe_sqrt(sq(vel_ned.x) + sq(vel_ned.y));
186
187
// convert vector direction to target yaw
188
const float target_yaw_cd = degrees(atan2f(vel_ned.y, vel_ned.x)) * 100.0f;
189
190
// send target heading and speed
191
mode_guided.set_desired_heading_and_speed(target_yaw_cd, target_speed_m);
192
193
return true;
194
}
195
196
// set steering and throttle (-1 to +1) (for use by scripting)
197
bool Rover::set_steering_and_throttle(float steering, float throttle)
198
{
199
// exit if vehicle is not in Guided mode or Auto-Guided mode
200
if (!control_mode->in_guided_mode()) {
201
return false;
202
}
203
204
// set steering and throttle
205
mode_guided.set_steering_and_throttle(steering, throttle);
206
return true;
207
}
208
209
// get steering and throttle (-1 to +1) (for use by scripting)
210
bool Rover::get_steering_and_throttle(float& steering, float& throttle)
211
{
212
steering = g2.motors.get_steering() / 4500.0;
213
throttle = g2.motors.get_throttle() * 0.01;
214
return true;
215
}
216
217
// set desired turn rate (degrees/sec) and speed (m/s). Used for scripting
218
bool Rover::set_desired_turn_rate_and_speed(float turn_rate, float speed)
219
{
220
// exit if vehicle is not in Guided mode or Auto-Guided mode
221
if (!control_mode->in_guided_mode()) {
222
return false;
223
}
224
225
// set turn rate and speed. Turn rate is expected in centidegrees/s and speed in meters/s
226
mode_guided.set_desired_turn_rate_and_speed(turn_rate * 100.0f, speed);
227
return true;
228
}
229
230
// set desired nav speed (m/s). Used for scripting.
231
bool Rover::set_desired_speed(float speed)
232
{
233
return control_mode->set_desired_speed(speed);
234
}
235
236
// get control output (for use in scripting)
237
// returns true on success and control_value is set to a value in the range -1 to +1
238
bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value)
239
{
240
switch (control_output) {
241
case AP_Vehicle::ControlOutput::Roll:
242
control_value = constrain_float(g2.motors.get_roll(), -1.0f, 1.0f);
243
return true;
244
case AP_Vehicle::ControlOutput::Pitch:
245
control_value = constrain_float(g2.motors.get_pitch(), -1.0f, 1.0f);
246
return true;
247
case AP_Vehicle::ControlOutput::Walking_Height:
248
control_value = constrain_float(g2.motors.get_walking_height(), -1.0f, 1.0f);
249
return true;
250
case AP_Vehicle::ControlOutput::Throttle:
251
control_value = constrain_float(g2.motors.get_throttle() * 0.01f, -1.0f, 1.0f);
252
return true;
253
case AP_Vehicle::ControlOutput::Yaw:
254
control_value = constrain_float(g2.motors.get_steering() / 4500.0f, -1.0f, 1.0f);
255
return true;
256
case AP_Vehicle::ControlOutput::Lateral:
257
control_value = constrain_float(g2.motors.get_lateral() * 0.01f, -1.0f, 1.0f);
258
return true;
259
case AP_Vehicle::ControlOutput::MainSail:
260
control_value = constrain_float(g2.motors.get_mainsail() * 0.01f, -1.0f, 1.0f);
261
return true;
262
case AP_Vehicle::ControlOutput::WingSail:
263
control_value = constrain_float(g2.motors.get_wingsail() * 0.01f, -1.0f, 1.0f);
264
return true;
265
default:
266
return false;
267
}
268
return false;
269
}
270
271
// returns true if mode supports NAV_SCRIPT_TIME mission commands
272
bool Rover::nav_scripting_enable(uint8_t mode)
273
{
274
return mode == (uint8_t)mode_auto.mode_number();
275
}
276
277
// lua scripts use this to retrieve the contents of the active command
278
bool Rover::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
279
{
280
if (control_mode != &mode_auto) {
281
return false;
282
}
283
284
return mode_auto.nav_script_time(id, cmd, arg1, arg2, arg3, arg4);
285
}
286
287
// lua scripts use this to indicate when they have complete the command
288
void Rover::nav_script_time_done(uint16_t id)
289
{
290
if (control_mode != &mode_auto) {
291
return;
292
}
293
294
return mode_auto.nav_script_time_done(id);
295
}
296
#endif // AP_SCRIPTING_ENABLED
297
298
// update AHRS system
299
void Rover::ahrs_update()
300
{
301
arming.update_soft_armed();
302
303
// AHRS may use movement to calculate heading
304
update_ahrs_flyforward();
305
306
ahrs.update();
307
308
// update position
309
have_position = ahrs.get_location(current_loc);
310
311
// set home from EKF if necessary and possible
312
if (!ahrs.home_is_set()) {
313
if (!set_home_to_current_location(false)) {
314
// ignore this failure
315
}
316
}
317
318
// if using the EKF get a speed update now (from accelerometers)
319
Vector3f velocity;
320
if (ahrs.get_velocity_NED(velocity)) {
321
ground_speed = velocity.xy().length();
322
} else if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
323
ground_speed = ahrs.groundspeed();
324
}
325
326
#if HAL_LOGGING_ENABLED
327
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
328
Log_Write_Attitude();
329
Log_Write_Sail();
330
}
331
332
if (should_log(MASK_LOG_IMU)) {
333
AP::ins().Write_IMU();
334
}
335
336
if (should_log(MASK_LOG_VIDEO_STABILISATION)) {
337
ahrs.write_video_stabilisation();
338
}
339
#endif
340
}
341
342
/*
343
check for GCS failsafe - 10Hz
344
*/
345
void Rover::gcs_failsafe_check(void)
346
{
347
if (g.fs_gcs_enabled == FS_GCS_DISABLED) {
348
// gcs failsafe disabled
349
return;
350
}
351
352
const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();
353
if (gcs_last_seen_ms == 0) {
354
// we've never seen the GCS, so we never failsafe for not seeing it
355
return;
356
}
357
358
// calc time since last gcs update
359
// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs
360
const uint32_t last_gcs_update_ms = millis() - gcs_last_seen_ms;
361
const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g2.fs_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));
362
363
const bool do_failsafe = last_gcs_update_ms >= gcs_timeout_ms ? true : false;
364
365
failsafe_trigger(FAILSAFE_EVENT_GCS, "GCS", do_failsafe);
366
}
367
368
#if HAL_LOGGING_ENABLED
369
/*
370
log some key data - 10Hz
371
*/
372
void Rover::update_logging1(void)
373
{
374
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
375
Log_Write_Attitude();
376
Log_Write_Sail();
377
}
378
379
if (should_log(MASK_LOG_THR)) {
380
Log_Write_Throttle();
381
#if AP_BEACON_ENABLED
382
g2.beacon.log();
383
#endif
384
}
385
386
if (should_log(MASK_LOG_NTUN)) {
387
Log_Write_Nav_Tuning();
388
if (g2.pos_control.is_active()) {
389
g2.pos_control.write_log();
390
logger.Write_PID(LOG_PIDN_MSG, g2.pos_control.get_vel_pid().get_pid_info_x());
391
logger.Write_PID(LOG_PIDE_MSG, g2.pos_control.get_vel_pid().get_pid_info_y());
392
}
393
}
394
395
#if HAL_PROXIMITY_ENABLED
396
if (should_log(MASK_LOG_RANGEFINDER)) {
397
g2.proximity.log();
398
}
399
#endif
400
}
401
402
/*
403
log some key data - 10Hz
404
*/
405
void Rover::update_logging2(void)
406
{
407
if (should_log(MASK_LOG_STEERING)) {
408
Log_Write_Steering();
409
}
410
411
if (should_log(MASK_LOG_RC)) {
412
Log_Write_RC();
413
g2.wheel_encoder.Log_Write();
414
}
415
416
if (should_log(MASK_LOG_IMU)) {
417
AP::ins().Write_Vibration();
418
#if HAL_GYROFFT_ENABLED
419
gyro_fft.write_log_messages();
420
#endif
421
}
422
#if HAL_MOUNT_ENABLED
423
if (should_log(MASK_LOG_CAMERA)) {
424
camera_mount.write_log();
425
}
426
#endif
427
}
428
#endif // HAL_LOGGING_ENABLED
429
430
/*
431
once a second events
432
*/
433
void Rover::one_second_loop(void)
434
{
435
set_control_channels();
436
437
// cope with changes to aux functions
438
AP::srv().enable_aux_servos();
439
440
// update notify flags
441
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
442
AP_Notify::flags.pre_arm_gps_check = true;
443
AP_Notify::flags.armed = arming.is_armed();
444
AP_Notify::flags.flying = hal.util->get_soft_armed();
445
446
// cope with changes to mavlink system ID
447
mavlink_system.sysid = g.sysid_this_mav;
448
449
// attempt to update home position and baro calibration if not armed:
450
if (!hal.util->get_soft_armed()) {
451
update_home();
452
}
453
454
// need to set "likely flying" when armed to allow for compass
455
// learning to run
456
set_likely_flying(hal.util->get_soft_armed());
457
458
// send latest param values to wp_nav
459
g2.wp_nav.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());
460
g2.pos_control.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());
461
g2.wheel_rate_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
462
463
#if AP_STATS_ENABLED
464
// Update stats "flying" time
465
AP::stats()->set_flying(g2.motors.active());
466
#endif
467
}
468
469
void Rover::update_current_mode(void)
470
{
471
// check for emergency stop
472
if (SRV_Channels::get_emergency_stop()) {
473
// relax controllers, motor stopping done at output level
474
g2.attitude_control.relax_I();
475
}
476
477
control_mode->update();
478
}
479
480
// vehicle specific waypoint info helpers
481
bool Rover::get_wp_distance_m(float &distance) const
482
{
483
// see GCS_MAVLINK_Rover::send_nav_controller_output()
484
if (!rover.control_mode->is_autopilot_mode()) {
485
return false;
486
}
487
distance = control_mode->get_distance_to_destination();
488
return true;
489
}
490
491
// vehicle specific waypoint info helpers
492
bool Rover::get_wp_bearing_deg(float &bearing) const
493
{
494
// see GCS_MAVLINK_Rover::send_nav_controller_output()
495
if (!rover.control_mode->is_autopilot_mode()) {
496
return false;
497
}
498
bearing = control_mode->wp_bearing();
499
return true;
500
}
501
502
// vehicle specific waypoint info helpers
503
bool Rover::get_wp_crosstrack_error_m(float &xtrack_error) const
504
{
505
// see GCS_MAVLINK_Rover::send_nav_controller_output()
506
if (!rover.control_mode->is_autopilot_mode()) {
507
return false;
508
}
509
xtrack_error = control_mode->crosstrack_error();
510
return true;
511
}
512
513
514
Rover rover;
515
AP_Vehicle& vehicle = rover;
516
517
AP_HAL_MAIN_CALLBACKS(&rover);
518
519