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.h
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
main Rover class, containing all vehicle specific state
17
*/
18
#pragma once
19
20
#include <cmath>
21
#include <stdarg.h>
22
#include <stdint.h>
23
24
// Libraries
25
#include <AP_Common/AP_Common.h>
26
#include <AP_HAL/AP_HAL.h>
27
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
28
#include <AP_Camera/AP_Camera.h> // Camera triggering
29
#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount
30
#include <AP_Param/AP_Param.h>
31
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
32
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
33
#include <AP_RPM/AP_RPM.h> // RPM input library
34
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
35
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
36
#include <AP_WheelEncoder/AP_WheelEncoder.h>
37
#include <AP_WheelEncoder/AP_WheelRateControl.h>
38
#include <AP_Logger/AP_Logger.h>
39
#include <AP_OSD/AP_OSD.h>
40
#include <AR_Motors/AP_MotorsUGV.h>
41
#include <AP_Mission/AP_Mission.h>
42
#include <AP_Mission/AP_Mission_ChangeDetector.h>
43
#include <AR_WPNav/AR_WPNav_OA.h>
44
#include <AP_OpticalFlow/AP_OpticalFlow.h>
45
#include <AC_PrecLand/AC_PrecLand_config.h>
46
#include <AP_Follow/AP_Follow_config.h>
47
#include <AP_ExternalControl/AP_ExternalControl_config.h>
48
#if AP_EXTERNAL_CONTROL_ENABLED
49
#include "AP_ExternalControl_Rover.h"
50
#endif
51
52
// Configuration
53
#include "defines.h"
54
#include "config.h"
55
56
#if AP_SCRIPTING_ENABLED
57
#include <AP_Scripting/AP_Scripting.h>
58
#endif
59
60
// Local modules
61
#include "AP_Arming.h"
62
#include "sailboat.h"
63
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
64
#include "afs_rover.h"
65
#endif
66
#include "Parameters.h"
67
#include "GCS_MAVLink_Rover.h"
68
#include "GCS_Rover.h"
69
#include "AP_Rally.h"
70
#if AC_PRECLAND_ENABLED
71
#include <AC_PrecLand/AC_PrecLand.h>
72
#endif
73
#include "RC_Channel_Rover.h" // RC Channel Library
74
75
#include "mode.h"
76
77
class Rover : public AP_Vehicle {
78
public:
79
friend class GCS_MAVLINK_Rover;
80
friend class Parameters;
81
friend class ParametersG2;
82
friend class AP_Rally_Rover;
83
friend class AP_Arming_Rover;
84
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
85
friend class AP_AdvancedFailsafe_Rover;
86
#endif
87
#if AP_EXTERNAL_CONTROL_ENABLED
88
friend class AP_ExternalControl_Rover;
89
#endif
90
friend class GCS_Rover;
91
friend class Mode;
92
friend class ModeAcro;
93
friend class ModeAuto;
94
friend class ModeCircle;
95
friend class ModeGuided;
96
friend class ModeHold;
97
friend class ModeLoiter;
98
friend class ModeSteering;
99
friend class ModeManual;
100
friend class ModeRTL;
101
friend class ModeSmartRTL;
102
#if MODE_FOLLOW_ENABLED
103
friend class ModeFollow;
104
#endif
105
friend class ModeSimple;
106
#if MODE_DOCK_ENABLED
107
friend class ModeDock;
108
#endif
109
110
friend class RC_Channel_Rover;
111
friend class RC_Channels_Rover;
112
113
friend class Sailboat;
114
115
Rover(void);
116
117
private:
118
119
// must be the first AP_Param variable declared to ensure its
120
// constructor runs before the constructors of the other AP_Param
121
// variables
122
AP_Param param_loader;
123
124
// all settable parameters
125
Parameters g;
126
ParametersG2 g2;
127
128
// mapping between input channels
129
RCMapper rcmap;
130
131
// primary control channels
132
RC_Channel *channel_steer;
133
RC_Channel *channel_throttle;
134
RC_Channel *channel_lateral;
135
RC_Channel *channel_roll;
136
RC_Channel *channel_pitch;
137
RC_Channel *channel_walking_height;
138
139
// flight modes convenience array
140
AP_Int8 *modes;
141
const uint8_t num_modes = 6;
142
143
#if AP_RPM_ENABLED
144
// AP_RPM Module
145
AP_RPM rpm_sensor;
146
#endif
147
148
// Arming/Disarming management class
149
AP_Arming_Rover arming;
150
151
// external control implementation
152
#if AP_EXTERNAL_CONTROL_ENABLED
153
AP_ExternalControl_Rover external_control;
154
#endif
155
156
#if AP_OPTICALFLOW_ENABLED
157
AP_OpticalFlow optflow;
158
#endif
159
160
#if OSD_ENABLED || OSD_PARAM_ENABLED
161
AP_OSD osd;
162
#endif
163
#if AC_PRECLAND_ENABLED
164
AC_PrecLand precland;
165
#endif
166
// GCS handling
167
GCS_Rover _gcs; // avoid using this; use gcs()
168
GCS_Rover &gcs() { return _gcs; }
169
170
// RC Channels:
171
RC_Channels_Rover &rc() { return g2.rc_channels; }
172
173
// The rover's current location
174
Location current_loc;
175
176
// Camera
177
#if AP_CAMERA_ENABLED
178
AP_Camera camera{MASK_LOG_CAMERA};
179
#endif
180
181
// Camera/Antenna mount tracking and stabilisation stuff
182
#if HAL_MOUNT_ENABLED
183
AP_Mount camera_mount;
184
#endif
185
186
// true if initialisation has completed
187
bool initialised;
188
189
// This is the state of the flight control system
190
// There are multiple states defined such as MANUAL, AUTO, ...
191
Mode *control_mode;
192
193
// Used to maintain the state of the previous control switch position
194
// This is set to -1 when we need to re-read the switch
195
uint8_t oldSwitchPosition;
196
197
// structure for holding failsafe state
198
struct {
199
uint8_t bits; // bit flags of failsafes that have started (but not necessarily triggered an action)
200
uint32_t start_time; // start time of the earliest failsafe
201
uint8_t triggered; // bit flags of failsafes that have triggered an action
202
uint32_t last_valid_rc_ms; // system time of most recent RC input from pilot
203
bool ekf;
204
} failsafe;
205
206
// true if we have a position estimate from AHRS
207
bool have_position;
208
209
#if AP_RANGEFINDER_ENABLED
210
// range finder last update for each instance (used for DPTH logging)
211
uint32_t rangefinder_last_reading_ms[RANGEFINDER_MAX_INSTANCES];
212
#endif
213
214
// Ground speed
215
// The amount current ground speed is below min ground speed. meters per second
216
float ground_speed;
217
218
// Battery Sensors
219
AP_BattMonitor battery{MASK_LOG_CURRENT,
220
FUNCTOR_BIND_MEMBER(&Rover::handle_battery_failsafe, void, const char*, const int8_t),
221
_failsafe_priorities};
222
223
// flyforward timer
224
uint32_t flyforward_start_ms;
225
226
static const AP_Scheduler::Task scheduler_tasks[];
227
228
static const AP_Param::Info var_info[];
229
#if HAL_LOGGING_ENABLED
230
static const LogStructure log_structure[];
231
#endif
232
233
// time that rudder/steering arming has been running
234
uint32_t rudder_arm_timer;
235
236
// latest wheel encoder values
237
float wheel_encoder_last_distance_m[WHEELENCODER_MAX_INSTANCES]; // total distance recorded by wheel encoder (for reporting to GCS)
238
bool wheel_encoder_initialised; // true once arrays below have been initialised to sensors initial values
239
float wheel_encoder_last_angle_rad[WHEELENCODER_MAX_INSTANCES]; // distance in radians at time of last update to EKF
240
uint32_t wheel_encoder_last_reading_ms[WHEELENCODER_MAX_INSTANCES]; // system time of last ping from each encoder
241
uint8_t wheel_encoder_last_index_sent; // index of the last wheel encoder sent to the EKF
242
243
// True when we are doing motor test
244
bool motor_test;
245
246
ModeInitializing mode_initializing;
247
ModeHold mode_hold;
248
ModeManual mode_manual;
249
ModeAcro mode_acro;
250
ModeGuided mode_guided;
251
ModeAuto mode_auto;
252
ModeLoiter mode_loiter;
253
ModeSteering mode_steering;
254
ModeRTL mode_rtl;
255
ModeSmartRTL mode_smartrtl;
256
#if MODE_FOLLOW_ENABLED
257
ModeFollow mode_follow;
258
#endif
259
ModeSimple mode_simple;
260
#if MODE_DOCK_ENABLED
261
ModeDock mode_dock;
262
#endif
263
264
// cruise throttle and speed learning
265
typedef struct {
266
LowPassFilterFloat speed_filt{2.0f};
267
LowPassFilterFloat throttle_filt{2.0f};
268
uint32_t learn_start_ms;
269
uint32_t log_count;
270
} cruise_learn_t;
271
cruise_learn_t cruise_learn;
272
273
// Rover.cpp
274
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
275
bool set_target_location(const Location& target_loc) override;
276
#endif
277
278
#if AP_SCRIPTING_ENABLED
279
bool set_target_velocity_NED(const Vector3f& vel_ned) override;
280
bool set_steering_and_throttle(float steering, float throttle) override;
281
bool get_steering_and_throttle(float& steering, float& throttle) override;
282
// set desired turn rate (degrees/sec) and speed (m/s). Used for scripting
283
bool set_desired_turn_rate_and_speed(float turn_rate, float speed) override;
284
bool set_desired_speed(float speed) override;
285
bool get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) override;
286
bool nav_scripting_enable(uint8_t mode) override;
287
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) override;
288
void nav_script_time_done(uint16_t id) override;
289
#endif // AP_SCRIPTING_ENABLED
290
void ahrs_update();
291
void gcs_failsafe_check(void);
292
void update_logging1(void);
293
void update_logging2(void);
294
void one_second_loop(void);
295
void update_current_mode(void);
296
297
// balance_bot.cpp
298
void balancebot_pitch_control(float &throttle);
299
bool is_balancebot() const;
300
301
// commands.cpp
302
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
303
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
304
void update_home();
305
306
// crash_check.cpp
307
void crash_check();
308
309
// cruise_learn.cpp
310
void cruise_learn_start();
311
void cruise_learn_update();
312
void cruise_learn_complete();
313
void log_write_cruise_learn() const;
314
315
// ekf_check.cpp
316
void ekf_check();
317
bool ekf_over_threshold();
318
bool ekf_position_ok();
319
void failsafe_ekf_event();
320
void failsafe_ekf_off_event(void);
321
322
// failsafe.cpp
323
void failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool on);
324
void handle_battery_failsafe(const char* type_str, const int8_t action);
325
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
326
void afs_fs_check(void);
327
#endif
328
329
// fence.cpp
330
void fence_check();
331
332
// GCS_Mavlink.cpp
333
void send_wheel_encoder_distance(mavlink_channel_t chan);
334
335
#if HAL_LOGGING_ENABLED
336
// methods for AP_Vehicle:
337
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
338
const struct LogStructure *get_log_structures() const override {
339
return log_structure;
340
}
341
uint8_t get_num_log_structures() const override;
342
343
// Log.cpp
344
void Log_Write_Attitude();
345
void Log_Write_Depth();
346
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
347
void Log_Write_Nav_Tuning();
348
void Log_Write_Sail();
349
void Log_Write_Steering();
350
void Log_Write_Throttle();
351
void Log_Write_RC(void);
352
void Log_Write_Vehicle_Startup_Messages();
353
void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page);
354
#endif
355
356
// mode.cpp
357
Mode *mode_from_mode_num(enum Mode::Number num);
358
359
// Parameters.cpp
360
void load_parameters(void) override;
361
362
// precision_landing.cpp
363
void init_precland();
364
void update_precland();
365
366
// radio.cpp
367
void set_control_channels(void) override;
368
void init_rc_in();
369
void rudder_arm_disarm_check();
370
void read_radio();
371
void radio_failsafe_check(uint16_t pwm);
372
373
// sensors.cpp
374
void update_compass(void);
375
void compass_save(void);
376
void update_wheel_encoder();
377
#if AP_RANGEFINDER_ENABLED
378
void read_rangefinders(void);
379
#endif
380
381
// Steering.cpp
382
void set_servos(void);
383
384
// Rover.cpp
385
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
386
uint8_t &task_count,
387
uint32_t &log_bit) override;
388
389
// system.cpp
390
void init_ardupilot() override;
391
void startup_ground(void);
392
void update_ahrs_flyforward();
393
bool gcs_mode_enabled(const Mode::Number mode_num) const;
394
bool set_mode(Mode &new_mode, ModeReason reason);
395
bool set_mode(const uint8_t new_mode, ModeReason reason) override;
396
bool set_mode(Mode::Number new_mode, ModeReason reason);
397
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
398
bool current_mode_requires_mission() const override {
399
return control_mode == &mode_auto;
400
}
401
402
void startup_INS(void);
403
void notify_mode(const Mode *new_mode);
404
uint8_t check_digital_pin(uint8_t pin);
405
bool should_log(uint32_t mask);
406
bool is_boat() const;
407
408
// vehicle specific waypoint info helpers
409
bool get_wp_distance_m(float &distance) const override;
410
bool get_wp_bearing_deg(float &bearing) const override;
411
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
412
413
enum class FailsafeAction: int8_t {
414
None = 0,
415
RTL = 1,
416
Hold = 2,
417
SmartRTL = 3,
418
SmartRTL_Hold = 4,
419
Terminate = 5
420
};
421
422
enum class Failsafe_Options : uint32_t {
423
Failsafe_Option_Active_In_Hold = (1<<0)
424
};
425
426
static constexpr int8_t _failsafe_priorities[] = {
427
(int8_t)FailsafeAction::Terminate,
428
(int8_t)FailsafeAction::Hold,
429
(int8_t)FailsafeAction::RTL,
430
(int8_t)FailsafeAction::SmartRTL_Hold,
431
(int8_t)FailsafeAction::SmartRTL,
432
(int8_t)FailsafeAction::None,
433
-1 // the priority list must end with a sentinel of -1
434
};
435
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
436
"_failsafe_priorities is missing the sentinel");
437
438
439
public:
440
void failsafe_check();
441
// Motor test
442
void motor_test_output();
443
bool mavlink_motor_test_check(const GCS_MAVLINK &gcs_chan, bool check_rc, AP_MotorsUGV::motor_test_order motor_instance, uint8_t throttle_type, int16_t throttle_value);
444
MAV_RESULT mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, AP_MotorsUGV::motor_test_order motor_instance, uint8_t throttle_type, int16_t throttle_value, float timeout_sec);
445
void motor_test_stop();
446
447
// frame type
448
uint8_t get_frame_type() const { return g2.frame_type.get(); }
449
AP_WheelRateControl& get_wheel_rate_control() { return g2.wheel_rate_control; }
450
451
// Simple mode
452
float simple_sin_yaw;
453
};
454
455
extern Rover rover;
456
457
using AP_HAL::millis;
458
using AP_HAL::micros;
459
460