Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Rover/Rover.cpp
9320 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
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, rate_hz, _max_time_micros, _priority) SCHED_TASK_CLASS(Rover, &rover, func, rate_hz, _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 HAL_MOUNT_ENABLED
108
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200, 75),
109
#endif
110
#if AP_CAMERA_ENABLED
111
SCHED_TASK_CLASS(AP_Camera, &rover.camera, update, 50, 200, 78),
112
#endif
113
SCHED_TASK(gcs_failsafe_check, 10, 200, 81),
114
#if AP_FENCE_ENABLED
115
SCHED_TASK(fence_check, 10, 200, 84),
116
#endif
117
SCHED_TASK(ekf_check, 10, 100, 87),
118
SCHED_TASK_CLASS(ModeSmartRTL, &rover.mode_smartrtl, save_position, 3, 200, 90),
119
SCHED_TASK(one_second_loop, 1, 1500, 96),
120
#if HAL_SPRAYER_ENABLED
121
SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90, 99),
122
#endif
123
#if HAL_LOGGING_ENABLED
124
SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300, 108),
125
#endif
126
SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 400, 200, 111),
127
#if HAL_LOGGING_ENABLED
128
SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 200, 114),
129
#endif
130
#if HAL_BUTTON_ENABLED
131
SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 200, 117),
132
#endif
133
SCHED_TASK(crash_check, 10, 200, 123),
134
SCHED_TASK(cruise_learn_update, 50, 200, 126),
135
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
136
SCHED_TASK(afs_fs_check, 10, 200, 129),
137
#endif
138
};
139
140
141
void Rover::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
142
uint8_t &task_count,
143
uint32_t &log_bit)
144
{
145
tasks = &scheduler_tasks[0];
146
task_count = ARRAY_SIZE(scheduler_tasks);
147
log_bit = MASK_LOG_PM;
148
}
149
150
constexpr int8_t Rover::_failsafe_priorities[7];
151
152
Rover::Rover(void) :
153
AP_Vehicle(),
154
param_loader(var_info),
155
modes(&g.mode1),
156
control_mode(&mode_initializing)
157
{
158
}
159
160
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
161
// set target location (for use by external control and scripting)
162
bool Rover::set_target_location(const Location& target_loc)
163
{
164
// exit if vehicle is not in Guided mode or Auto-Guided mode
165
if (!control_mode->in_guided_mode()) {
166
return false;
167
}
168
169
return mode_guided.set_desired_location(target_loc);
170
}
171
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
172
173
#if AP_SCRIPTING_ENABLED
174
// set target velocity (for use by scripting)
175
bool Rover::set_target_velocity_NED(const Vector3f& vel_ned, bool align_yaw_to_target)
176
{
177
// exit if vehicle is not in Guided mode or Auto-Guided mode
178
if (!control_mode->in_guided_mode()) {
179
return false;
180
}
181
182
// convert vector length into speed
183
const float target_speed_m = safe_sqrt(sq(vel_ned.x) + sq(vel_ned.y));
184
185
// convert vector direction to target yaw
186
const float target_yaw_cd = degrees(atan2f(vel_ned.y, vel_ned.x)) * 100.0f;
187
188
// send target heading and speed
189
mode_guided.set_desired_heading_and_speed(target_yaw_cd, target_speed_m);
190
191
return true;
192
}
193
194
// set steering and throttle (-1 to +1) (for use by scripting)
195
bool Rover::set_steering_and_throttle(float steering, float throttle)
196
{
197
// exit if vehicle is not in Guided mode or Auto-Guided mode
198
if (!control_mode->in_guided_mode()) {
199
return false;
200
}
201
202
// set steering and throttle
203
mode_guided.set_steering_and_throttle(steering, throttle);
204
return true;
205
}
206
207
// get steering and throttle (-1 to +1) (for use by scripting)
208
bool Rover::get_steering_and_throttle(float& steering, float& throttle)
209
{
210
steering = g2.motors.get_steering() / 4500.0;
211
throttle = g2.motors.get_throttle() * 0.01;
212
return true;
213
}
214
215
// set desired turn rate (degrees/sec) and speed (m/s). Used for scripting
216
bool Rover::set_desired_turn_rate_and_speed(float turn_rate, float speed)
217
{
218
// exit if vehicle is not in Guided mode or Auto-Guided mode
219
if (!control_mode->in_guided_mode()) {
220
return false;
221
}
222
223
// set turn rate and speed. Turn rate is expected in centidegrees/s and speed in meters/s
224
mode_guided.set_desired_turn_rate_and_speed(turn_rate * 100.0f, speed);
225
return true;
226
}
227
228
// set desired nav speed (m/s). Used for scripting.
229
bool Rover::set_desired_speed(float speed)
230
{
231
return control_mode->set_desired_speed(speed);
232
}
233
234
// get control output (for use in scripting)
235
// returns true on success and control_value is set to a value in the range -1 to +1
236
bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value)
237
{
238
switch (control_output) {
239
case AP_Vehicle::ControlOutput::Roll:
240
control_value = constrain_float(g2.motors.get_roll(), -1.0f, 1.0f);
241
return true;
242
case AP_Vehicle::ControlOutput::Pitch:
243
control_value = constrain_float(g2.motors.get_pitch(), -1.0f, 1.0f);
244
return true;
245
case AP_Vehicle::ControlOutput::Walking_Height:
246
control_value = constrain_float(g2.motors.get_walking_height(), -1.0f, 1.0f);
247
return true;
248
case AP_Vehicle::ControlOutput::Throttle:
249
control_value = constrain_float(g2.motors.get_throttle() * 0.01f, -1.0f, 1.0f);
250
return true;
251
case AP_Vehicle::ControlOutput::Yaw:
252
control_value = constrain_float(g2.motors.get_steering() / 4500.0f, -1.0f, 1.0f);
253
return true;
254
case AP_Vehicle::ControlOutput::Lateral:
255
control_value = constrain_float(g2.motors.get_lateral() * 0.01f, -1.0f, 1.0f);
256
return true;
257
case AP_Vehicle::ControlOutput::MainSail:
258
control_value = constrain_float(g2.motors.get_mainsail() * 0.01f, -1.0f, 1.0f);
259
return true;
260
case AP_Vehicle::ControlOutput::WingSail:
261
control_value = constrain_float(g2.motors.get_wingsail() * 0.01f, -1.0f, 1.0f);
262
return true;
263
default:
264
return false;
265
}
266
return false;
267
}
268
269
// returns true if mode supports NAV_SCRIPT_TIME mission commands
270
bool Rover::nav_scripting_enable(uint8_t mode)
271
{
272
return mode == (uint8_t)mode_auto.mode_number();
273
}
274
275
// lua scripts use this to retrieve the contents of the active command
276
bool Rover::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
277
{
278
if (control_mode != &mode_auto) {
279
return false;
280
}
281
282
return mode_auto.nav_script_time(id, cmd, arg1, arg2, arg3, arg4);
283
}
284
285
// lua scripts use this to indicate when they have complete the command
286
void Rover::nav_script_time_done(uint16_t id)
287
{
288
if (control_mode != &mode_auto) {
289
return;
290
}
291
292
return mode_auto.nav_script_time_done(id);
293
}
294
#endif // AP_SCRIPTING_ENABLED
295
296
// update AHRS system
297
void Rover::ahrs_update()
298
{
299
arming.update_soft_armed();
300
301
// AHRS may use movement to calculate heading
302
update_ahrs_flyforward();
303
304
ahrs.update();
305
306
// update position
307
have_position = ahrs.get_location(current_loc);
308
309
// set home from EKF if necessary and possible
310
if (!ahrs.home_is_set()) {
311
if (!set_home_to_current_location(false)) {
312
// ignore this failure
313
}
314
}
315
316
// if using the EKF get a speed update now (from accelerometers)
317
Vector3f velocity;
318
if (ahrs.get_velocity_NED(velocity)) {
319
ground_speed = velocity.xy().length();
320
} else if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
321
ground_speed = ahrs.groundspeed();
322
}
323
324
#if AP_FOLLOW_ENABLED
325
g2.follow.update_estimates();
326
#endif
327
328
#if HAL_LOGGING_ENABLED
329
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
330
Log_Write_Attitude();
331
Log_Write_Sail();
332
}
333
334
if (should_log(MASK_LOG_IMU)) {
335
AP::ins().Write_IMU();
336
}
337
338
if (should_log(MASK_LOG_VIDEO_STABILISATION)) {
339
ahrs.write_video_stabilisation();
340
}
341
#endif
342
}
343
344
/*
345
check for GCS failsafe - 10Hz
346
*/
347
void Rover::gcs_failsafe_check(void)
348
{
349
if (g.fs_gcs_enabled == FS_GCS_DISABLED) {
350
// gcs failsafe disabled
351
return;
352
}
353
354
const uint32_t gcs_last_seen_ms = gcs().sysid_mygcs_last_seen_time_ms();
355
if (gcs_last_seen_ms == 0) {
356
// we've never seen the GCS, so we never failsafe for not seeing it
357
return;
358
}
359
360
// calc time since last gcs update
361
// note: this only looks at the heartbeat from the device ids approved by gcs().sysid_is_gcs()
362
const uint32_t last_gcs_update_ms = millis() - gcs_last_seen_ms;
363
const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g2.fs_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));
364
365
const bool do_failsafe = last_gcs_update_ms >= gcs_timeout_ms ? true : false;
366
367
failsafe_trigger(FAILSAFE_EVENT_GCS, "GCS", do_failsafe);
368
}
369
370
#if HAL_LOGGING_ENABLED
371
/*
372
log some key data - 10Hz
373
*/
374
void Rover::update_logging1(void)
375
{
376
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
377
Log_Write_Attitude();
378
Log_Write_Sail();
379
}
380
381
if (should_log(MASK_LOG_THR)) {
382
Log_Write_Throttle();
383
#if AP_BEACON_ENABLED
384
g2.beacon.log();
385
#endif
386
}
387
388
if (should_log(MASK_LOG_NTUN)) {
389
Log_Write_Nav_Tuning();
390
if (g2.pos_control.is_active()) {
391
g2.pos_control.write_log();
392
logger.Write_PID(LOG_PIDN_MSG, g2.pos_control.get_vel_pid().get_pid_info_x());
393
logger.Write_PID(LOG_PIDE_MSG, g2.pos_control.get_vel_pid().get_pid_info_y());
394
}
395
}
396
397
#if HAL_PROXIMITY_ENABLED
398
if (should_log(MASK_LOG_RANGEFINDER)) {
399
g2.proximity.log();
400
}
401
#endif
402
}
403
404
/*
405
log some key data - 10Hz
406
*/
407
void Rover::update_logging2(void)
408
{
409
if (should_log(MASK_LOG_STEERING)) {
410
Log_Write_Steering();
411
}
412
413
if (should_log(MASK_LOG_RC)) {
414
Log_Write_RC();
415
g2.wheel_encoder.Log_Write();
416
}
417
418
if (should_log(MASK_LOG_IMU)) {
419
AP::ins().Write_Vibration();
420
#if HAL_GYROFFT_ENABLED
421
gyro_fft.write_log_messages();
422
#endif
423
}
424
#if HAL_MOUNT_ENABLED
425
if (should_log(MASK_LOG_CAMERA)) {
426
camera_mount.write_log();
427
}
428
#endif
429
}
430
#endif // HAL_LOGGING_ENABLED
431
432
#if AP_ROVER_AUTO_ARM_ONCE_ENABLED
433
void Rover::handle_auto_arm_once()
434
{
435
if (arming.is_armed()) {
436
// never re-arm automatically if the user ever armed the vehicle
437
auto_arm_once.done = true;
438
return;
439
}
440
if (auto_arm_once.done) {
441
return;
442
}
443
switch (arming.arming_required()) {
444
case AP_Arming::Required::NO:
445
case AP_Arming::Required::YES_MIN_PWM:
446
case AP_Arming::Required::YES_ZERO_PWM:
447
// in case the user changes the require parameter at runtime,
448
// don't auto-arm:
449
auto_arm_once.done = true;
450
return;
451
case AP_Arming::Required::YES_AUTO_ARM_MIN_PWM:
452
case AP_Arming::Required::YES_AUTO_ARM_ZERO_PWM:
453
break;
454
}
455
456
// don't try to arm if prearms are not passing:
457
if (!arming.get_last_prearm_checks_result()) {
458
return;
459
}
460
461
const uint32_t now_ms = AP_HAL::millis();
462
// only attempt to auto arm once per 5 seconds:
463
if (now_ms - auto_arm_once.last_arm_attempt_ms < 5000) {
464
return;
465
}
466
auto_arm_once.last_arm_attempt_ms = now_ms;
467
468
if (!arming.arm(AP_Arming::Method::AUTO_ARM_ONCE)) {
469
return;
470
}
471
472
auto_arm_once.done = true;
473
}
474
#endif // AP_ROVER_AUTO_ARM_ONCE_ENABLED
475
476
/*
477
once a second events
478
*/
479
void Rover::one_second_loop(void)
480
{
481
set_control_channels();
482
483
// cope with changes to aux functions
484
AP::srv().enable_aux_servos();
485
486
// update notify flags
487
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
488
AP_Notify::flags.pre_arm_gps_check = true;
489
AP_Notify::flags.armed = arming.is_armed();
490
AP_Notify::flags.flying = hal.util->get_soft_armed();
491
492
#if AP_ROVER_AUTO_ARM_ONCE_ENABLED
493
handle_auto_arm_once();
494
#endif // AP_ROVER_AUTO_ARM_ONCE_ENABLED
495
496
// attempt to update home position and baro calibration if not armed:
497
if (!hal.util->get_soft_armed()) {
498
update_home();
499
}
500
501
// need to set "likely flying" when armed to allow for compass
502
// learning to run
503
set_likely_flying(hal.util->get_soft_armed());
504
505
// send latest param values to wp_nav
506
g2.wp_nav.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());
507
g2.pos_control.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());
508
g2.wheel_rate_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
509
510
#if AP_STATS_ENABLED
511
// Update stats "flying" time
512
AP::stats()->set_flying(g2.motors.active());
513
#endif
514
}
515
516
void Rover::update_current_mode(void)
517
{
518
// check for emergency stop
519
if (SRV_Channels::get_emergency_stop()) {
520
// relax controllers, motor stopping done at output level
521
g2.attitude_control.relax_I();
522
}
523
524
control_mode->update();
525
}
526
527
// vehicle specific waypoint info helpers
528
bool Rover::get_wp_distance_m(float &distance) const
529
{
530
// see GCS_MAVLINK_Rover::send_nav_controller_output()
531
if (!rover.control_mode->is_autopilot_mode()) {
532
return false;
533
}
534
distance = control_mode->get_distance_to_destination();
535
return true;
536
}
537
538
// vehicle specific waypoint info helpers
539
bool Rover::get_wp_bearing_deg(float &bearing) const
540
{
541
// see GCS_MAVLINK_Rover::send_nav_controller_output()
542
if (!rover.control_mode->is_autopilot_mode()) {
543
return false;
544
}
545
bearing = control_mode->wp_bearing();
546
return true;
547
}
548
549
// vehicle specific waypoint info helpers
550
bool Rover::get_wp_crosstrack_error_m(float &xtrack_error) const
551
{
552
// see GCS_MAVLINK_Rover::send_nav_controller_output()
553
if (!rover.control_mode->is_autopilot_mode()) {
554
return false;
555
}
556
xtrack_error = control_mode->crosstrack_error();
557
return true;
558
}
559
560
561
Rover rover;
562
AP_Vehicle& vehicle = rover;
563
564
AP_HAL_MAIN_CALLBACKS(&rover);
565
566