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/Blimp/Blimp.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
#pragma once
16
/*
17
This is the main Blimp class
18
*/
19
20
////////////////////////////////////////////////////////////////////////////////
21
// Header includes
22
////////////////////////////////////////////////////////////////////////////////
23
24
#include <cmath>
25
#include <stdio.h>
26
#include <stdarg.h>
27
28
#include <AP_HAL/AP_HAL.h>
29
30
// Common dependencies
31
#include <AP_Common/AP_Common.h>
32
#include <AP_Common/Location.h>
33
#include <AP_Param/AP_Param.h>
34
#include <StorageManager/StorageManager.h>
35
36
// Application dependencies
37
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
38
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
39
// #include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
40
// #include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
41
#include <AP_AHRS/AP_AHRS.h>
42
#include <Filter/Filter.h> // Filter library
43
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
44
#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library
45
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
46
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
47
#include <AP_Arming/AP_Arming.h>
48
#include <AP_Scripting/AP_Scripting.h>
49
#include <AC_PID/AC_PID_2D.h>
50
#include <AC_PID/AC_PID_Basic.h>
51
#include <AC_PID/AC_PID.h>
52
#include <AP_Vehicle/AP_MultiCopter.h>
53
54
#include <Filter/NotchFilter.h>
55
56
// Configuration
57
#include "defines.h"
58
#include "config.h"
59
60
#include "Fins.h"
61
#include "Loiter.h"
62
63
#include "RC_Channel_Blimp.h" // RC Channel Library
64
65
#include "GCS_MAVLink_Blimp.h"
66
#include "GCS_Blimp.h"
67
#include "AP_Arming.h"
68
69
#include <AP_Mount/AP_Mount.h>
70
71
// Local modules
72
73
#include "Parameters.h"
74
75
#include "mode.h"
76
77
class Blimp : public AP_Vehicle
78
{
79
public:
80
friend class GCS_MAVLINK_Blimp;
81
friend class GCS_Blimp;
82
friend class Parameters;
83
friend class ParametersG2;
84
85
friend class AP_Arming_Blimp;
86
friend class RC_Channel_Blimp;
87
friend class RC_Channels_Blimp;
88
89
friend class Mode;
90
friend class ModeManual;
91
friend class ModeLand;
92
friend class ModeVelocity;
93
friend class ModeLoiter;
94
friend class ModeRTL;
95
96
friend class Fins;
97
friend class Loiter;
98
99
Blimp(void);
100
101
private:
102
103
// key aircraft parameters passed to multiple libraries
104
AP_MultiCopter aparm;
105
106
// Global parameters are all contained within the 'g' class.
107
Parameters g;
108
ParametersG2 g2;
109
110
// primary input control channels
111
RC_Channel *channel_right;
112
RC_Channel *channel_front;
113
RC_Channel *channel_up;
114
RC_Channel *channel_yaw;
115
116
// flight modes convenience array
117
AP_Int8 *flight_modes;
118
const uint8_t num_flight_modes = 6;
119
120
// Arming/Disarming management class
121
AP_Arming_Blimp arming;
122
123
// system time in milliseconds of last recorded yaw reset from ekf
124
uint32_t ekfYawReset_ms;
125
int8_t ekf_primary_core;
126
127
// vibration check
128
struct {
129
bool high_vibes; // true while high vibration are detected
130
uint32_t start_ms; // system time high vibration were last detected
131
uint32_t clear_ms; // system time high vibrations stopped
132
} vibration_check;
133
134
// GCS selection
135
GCS_Blimp _gcs; // avoid using this; use gcs()
136
GCS_Blimp &gcs()
137
{
138
return _gcs;
139
}
140
141
// Documentation of Globals:
142
typedef union {
143
struct {
144
uint8_t pre_arm_rc_check : 1; // 1 // true if rc input pre-arm checks have been completed successfully
145
uint8_t pre_arm_check : 1; // 2 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
146
uint8_t auto_armed : 1; // 3 // stops auto missions from beginning until throttle is raised
147
uint8_t logging_started : 1; // 4 // true if logging has started
148
uint8_t land_complete : 1; // 5 // true if we have detected a landing
149
uint8_t new_radio_frame : 1; // 6 // Set true if we have new PWM data to act on from the Radio
150
uint8_t rc_receiver_present_unused : 1; // 7 // UNUSED
151
uint8_t compass_mot : 1; // 8 // true if we are currently performing compassmot calibration
152
uint8_t motor_test : 1; // 9 // true if we are currently performing the motors test
153
uint8_t initialised : 1; // 10 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
154
uint8_t land_complete_maybe : 1; // 11 // true if we may have landed (less strict version of land_complete)
155
uint8_t throttle_zero : 1; // 12 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down
156
uint8_t gps_glitching : 1; // 13 // true if GPS glitching is affecting navigation accuracy
157
uint8_t in_arming_delay : 1; // 14 // true while we are armed but waiting to spin motors
158
uint8_t initialised_params : 1; // 15 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
159
};
160
uint32_t value;
161
} ap_t;
162
163
ap_t ap;
164
165
static_assert(sizeof(uint32_t) == sizeof(ap), "ap_t must be uint32_t");
166
167
// This is the state of the flight control system
168
// There are multiple states defined such as STABILIZE, ACRO,
169
Mode::Number control_mode;
170
ModeReason control_mode_reason = ModeReason::UNKNOWN;
171
172
RCMapper rcmap;
173
174
// inertial nav alt when we armed
175
float arming_altitude_m;
176
177
// Failsafe
178
struct {
179
int8_t radio_counter; // number of iterations with throttle below throttle_fs_value
180
181
uint8_t radio : 1; // A status flag for the radio failsafe
182
uint8_t gcs : 1; // A status flag for the ground station failsafe
183
uint8_t ekf : 1; // true if ekf failsafe has occurred
184
} failsafe;
185
186
bool any_failsafe_triggered() const
187
{
188
return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf;
189
}
190
191
// Motor Output
192
Fins *motors;
193
Loiter *loiter;
194
195
int32_t _home_bearing;
196
uint32_t _home_distance;
197
198
// Stores initial bearing when armed - initial simple bearing is modified in super simple mode so not suitable
199
int32_t initial_armed_bearing;
200
201
// Battery Sensors
202
AP_BattMonitor battery{MASK_LOG_CURRENT,
203
FUNCTOR_BIND_MEMBER(&Blimp::handle_battery_failsafe, void, const char*, const int8_t),
204
_failsafe_priorities};
205
206
// Altitude
207
int32_t baro_alt; // barometer altitude in cm above home
208
209
// filtered pilot's throttle input used to cancel landing if throttle held high
210
LowPassFilterFloat rc_throttle_control_in_filter;
211
212
// 3D Location vectors
213
// Current location of the vehicle (altitude is relative to home)
214
Location current_loc;
215
Vector3f vel_ned;
216
Vector3f vel_ned_filtd;
217
218
Vector3f pos_ned;
219
float vel_yaw;
220
float vel_yaw_filtd;
221
NotchFilterVector2f vel_xy_filter;
222
NotchFilterFloat vel_z_filter;
223
NotchFilterFloat vel_yaw_filter;
224
225
// Inertial Navigation
226
AP_InertialNav inertial_nav;
227
228
// Vel & pos PIDs
229
AC_PID_2D pid_vel_xy{3, 0.2, 0, 0, 0.2, 3, 3}; //These are the defaults - P I D FF IMAX FiltHz FiltDHz DT
230
AC_PID_Basic pid_vel_z{7, 1.5, 0, 0, 1, 3, 3};
231
AC_PID_Basic pid_vel_yaw{3, 0.4, 0, 0, 0.2, 3, 3};
232
233
AC_PID_2D pid_pos_xy{1, 0.05, 0, 0, 0.1, 3, 3};
234
AC_PID_Basic pid_pos_z{0.7, 0, 0, 0, 0, 3, 3};
235
AC_PID pid_pos_yaw{1.2, 0.5, 0, 0, 2, 3, 3, 3}; //p, i, d, ff, imax, filt_t, filt_e, filt_d, dt, opt srmax, opt srtau
236
237
// System Timers
238
// --------------
239
// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
240
uint32_t arm_time_ms;
241
242
// Used to exit the roll and pitch auto trim function
243
uint8_t auto_trim_counter;
244
bool auto_trim_started = false;
245
246
// last valid RC input time
247
uint32_t last_radio_update_ms;
248
249
// Top-level logic
250
// setup the var_info table
251
AP_Param param_loader;
252
253
bool standby_active;
254
255
static const AP_Scheduler::Task scheduler_tasks[];
256
static const AP_Param::Info var_info[];
257
static const struct LogStructure log_structure[];
258
259
enum Failsafe_Action {
260
Failsafe_Action_None = 0,
261
Failsafe_Action_Land = 1,
262
Failsafe_Action_Terminate = 5
263
};
264
265
enum class FailsafeOption {
266
RC_CONTINUE_IF_AUTO = (1<<0), // 1
267
GCS_CONTINUE_IF_AUTO = (1<<1), // 2
268
RC_CONTINUE_IF_GUIDED = (1<<2), // 4
269
CONTINUE_IF_LANDING = (1<<3), // 8
270
GCS_CONTINUE_IF_PILOT_CONTROL = (1<<4), // 16
271
RELEASE_GRIPPER = (1<<5), // 32
272
};
273
274
static constexpr int8_t _failsafe_priorities[] = {
275
Failsafe_Action_Terminate,
276
Failsafe_Action_Land,
277
Failsafe_Action_None,
278
-1 // the priority list must end with a sentinel of -1
279
};
280
281
#define FAILSAFE_LAND_PRIORITY 1
282
static_assert(_failsafe_priorities[FAILSAFE_LAND_PRIORITY] == Failsafe_Action_Land,
283
"FAILSAFE_LAND_PRIORITY must match the entry in _failsafe_priorities");
284
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
285
"_failsafe_priorities is missing the sentinel");
286
287
// AP_State.cpp
288
void set_auto_armed(bool b);
289
void set_failsafe_radio(bool b);
290
void set_failsafe_gcs(bool b);
291
292
// Blimp.cpp
293
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
294
uint8_t &task_count,
295
uint32_t &log_bit) override;
296
void rc_loop();
297
void throttle_loop();
298
void update_batt_compass(void);
299
void full_rate_logging();
300
void ten_hz_logging_loop();
301
void twentyfive_hz_logging();
302
void three_hz_loop();
303
void one_hz_loop();
304
void read_AHRS(void);
305
void update_altitude();
306
void rotate_NE_to_BF(Vector2f &vec);
307
void rotate_BF_to_NE(Vector2f &vec);
308
309
// commands.cpp
310
void update_home_from_EKF();
311
void set_home_to_current_location_inflight();
312
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
313
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
314
315
// ekf_check.cpp
316
void ekf_check();
317
bool ekf_over_threshold();
318
void failsafe_ekf_event();
319
void failsafe_ekf_off_event(void);
320
void check_ekf_reset();
321
void check_vibration();
322
323
// events.cpp
324
bool failsafe_option(FailsafeOption opt) const;
325
void failsafe_radio_on_event();
326
void failsafe_radio_off_event();
327
void handle_battery_failsafe(const char* type_str, const int8_t action);
328
void failsafe_gcs_check();
329
bool should_disarm_on_failsafe();
330
void do_failsafe_action(Failsafe_Action action, ModeReason reason);
331
void gpsglitch_check();
332
333
// failsafe.cpp
334
void failsafe_enable();
335
void failsafe_disable();
336
337
// fence.cpp
338
void fence_check();
339
340
// inertia.cpp
341
void read_inertia();
342
343
// landing_detector.cpp
344
void update_land_and_crash_detectors();
345
void update_land_detector();
346
347
// landing_gear.cpp
348
void landinggear_update();
349
350
#if HAL_LOGGING_ENABLED
351
// methods for AP_Vehicle:
352
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
353
const struct LogStructure *get_log_structures() const override {
354
return log_structure;
355
}
356
uint8_t get_num_log_structures() const override;
357
358
// Log.cpp
359
void Log_Write_Attitude();
360
void Log_Write_PIDs();
361
void Log_Write_EKF_POS();
362
void Log_Write_Data(LogDataID id, int32_t value);
363
void Log_Write_Data(LogDataID id, uint32_t value);
364
void Log_Write_Data(LogDataID id, int16_t value);
365
void Log_Write_Data(LogDataID id, uint16_t value);
366
void Log_Write_Data(LogDataID id, float value);
367
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max);
368
369
370
void Log_Write_Vehicle_Startup_Messages();
371
void Write_FINI(float right, float front, float down, float yaw);
372
void Write_FINO(float *amp, float *off);
373
#endif
374
375
// mode.cpp
376
bool set_mode(Mode::Number mode, ModeReason reason);
377
bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
378
uint8_t get_mode() const override
379
{
380
return (uint8_t)control_mode;
381
}
382
void update_flight_mode();
383
void notify_flight_mode();
384
385
// mode_land.cpp
386
void set_mode_land_failsafe(ModeReason reason);
387
bool landing_with_GPS();
388
389
// // motors.cpp
390
void arm_motors_check();
391
void motors_output();
392
393
// Parameters.cpp
394
void load_parameters(void) override;
395
void convert_pid_parameters(void);
396
void convert_lgr_parameters(void);
397
void convert_fs_options_params(void);
398
399
// radio.cpp
400
void default_dead_zones();
401
void init_rc_in();
402
void init_rc_out();
403
void enable_motor_output();
404
void read_radio();
405
void set_throttle_and_failsafe(uint16_t throttle_pwm);
406
void set_throttle_zero_flag(int16_t throttle_control);
407
408
// sensors.cpp
409
void read_barometer(void);
410
void init_rangefinder(void);
411
void read_rangefinder(void);
412
bool rangefinder_alt_ok();
413
bool rangefinder_up_ok();
414
415
// RC_Channel.cpp
416
void save_trim();
417
void auto_trim();
418
void auto_trim_cancel();
419
420
// system.cpp
421
void init_ardupilot() override;
422
void startup_INS_ground();
423
bool position_ok() const;
424
bool ekf_has_absolute_position() const;
425
bool ekf_has_relative_position() const;
426
bool ekf_alt_ok() const;
427
void update_auto_armed();
428
bool should_log(uint32_t mask);
429
MAV_TYPE get_frame_mav_type();
430
const char* get_frame_string();
431
void allocate_motors(void);
432
433
Mode *flightmode;
434
ModeManual mode_manual;
435
ModeLand mode_land;
436
ModeVelocity mode_velocity;
437
ModeLoiter mode_loiter;
438
ModeRTL mode_rtl;
439
440
// mode.cpp
441
Mode *mode_from_mode_num(const Mode::Number mode);
442
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
443
444
public:
445
void failsafe_check(); // failsafe.cpp
446
};
447
448
extern Blimp blimp;
449
450
using AP_HAL::millis;
451
using AP_HAL::micros;
452
453