Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Blimp/system.cpp
9417 views
1
#include "Blimp.h"
2
3
/*****************************************************************************
4
* The init_ardupilot function processes everything we need for an in - air restart
5
* We will determine later if we are actually on the ground and process a
6
* ground start in that case.
7
*
8
*****************************************************************************/
9
10
static void failsafe_check_static()
11
{
12
blimp.failsafe_check();
13
}
14
15
void Blimp::init_ardupilot()
16
{
17
// initialise notify system
18
notify.init();
19
notify_flight_mode();
20
21
// initialise battery monitor
22
battery.init();
23
24
#if AP_RSSI_ENABLED
25
// Init RSSI
26
rssi.init();
27
#endif
28
29
barometer.init();
30
31
// setup telem slots with serial ports
32
gcs().setup_uarts();
33
34
init_rc_in(); // sets up rc channels from radio
35
36
// allocate the motors class
37
allocate_motors();
38
loiter = NEW_NOTHROW Loiter(blimp.scheduler.get_loop_rate_hz());
39
40
// initialise rc channels including setting mode
41
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
42
rc().init();
43
44
// sets up motors and output to escs
45
init_rc_out();
46
47
48
// motors initialised so parameters can be sent
49
ap.initialised_params = true;
50
51
#if AP_RELAY_ENABLED
52
relay.init();
53
#endif
54
55
/*
56
* setup the 'main loop is dead' check. Note that this relies on
57
* the RC library being initialised.
58
*/
59
hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
60
61
// Do GPS init
62
gps.set_log_gps_bit(MASK_LOG_GPS);
63
gps.init();
64
65
AP::compass().set_log_bit(MASK_LOG_COMPASS);
66
AP::compass().init();
67
68
// read Baro pressure at ground
69
//-----------------------------
70
barometer.set_log_baro_bit(MASK_LOG_IMU);
71
barometer.calibrate();
72
73
#if HAL_LOGGING_ENABLED
74
// initialise AP_Logger library
75
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&blimp, &Blimp::Log_Write_Vehicle_Startup_Messages, void));
76
#endif
77
78
startup_INS_ground();
79
80
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
81
82
// setup fin output
83
motors->setup_fins();
84
85
// enable output to motors
86
if (arming.rc_calibration_checks(true)) {
87
enable_motor_output();
88
}
89
90
//Initialise fin filters
91
vel_xy_filter.init(scheduler.get_loop_rate_hz(), motors->freq_hz, 0.5f, 15.0f);
92
vel_z_filter.init(scheduler.get_loop_rate_hz(), motors->freq_hz, 1.0f, 15.0f);
93
vel_yaw_filter.init(scheduler.get_loop_rate_hz(),motors->freq_hz, 5.0f, 15.0f);
94
95
// attempt to switch to MANUAL, if this fails then switch to Land
96
if (!set_mode((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED)) {
97
// set mode to MANUAL will trigger mode change notification to pilot
98
set_mode(Mode::Number::MANUAL, ModeReason::UNAVAILABLE);
99
} else {
100
// alert pilot to mode change
101
AP_Notify::events.failsafe_mode_change = 1;
102
}
103
104
// flag that initialisation has completed
105
ap.initialised = true;
106
}
107
108
109
//******************************************************************************
110
//This function does all the calibrations, etc. that we need during a ground start
111
//******************************************************************************
112
void Blimp::startup_INS_ground()
113
{
114
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
115
ahrs.init();
116
ahrs.set_vehicle_class(AP_AHRS::VehicleClass::COPTER);
117
118
// Warm up and calibrate gyro offsets
119
ins.init(scheduler.get_loop_rate_hz());
120
121
// reset ahrs including gyro bias
122
ahrs.reset();
123
}
124
125
// position_ok - returns true if the horizontal absolute position is ok and home position is set
126
bool Blimp::position_ok() const
127
{
128
// return false if ekf failsafe has triggered
129
if (failsafe.ekf) {
130
return false;
131
}
132
133
// check ekf position estimate
134
return (ekf_has_absolute_position() || ekf_has_relative_position());
135
}
136
137
// ekf_has_absolute_position - returns true if the EKF can provide an absolute WGS-84 position estimate
138
bool Blimp::ekf_has_absolute_position() const
139
{
140
if (!ahrs.have_inertial_nav()) {
141
// do not allow navigation with dcm position
142
return false;
143
}
144
145
// if disarmed we accept a predicted horizontal position
146
if (!motors->armed()) {
147
if (ahrs.has_status(AP_AHRS::Status::HORIZ_POS_ABS)) {
148
return true;
149
}
150
if (ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_ABS)) {
151
return true;
152
}
153
return false;
154
}
155
// once armed we require a good absolute position and EKF must not be in const_pos_mode
156
if (ahrs.has_status(AP_AHRS::Status::CONST_POS_MODE)) {
157
return false;
158
}
159
return ahrs.has_status(AP_AHRS::Status::HORIZ_POS_ABS);
160
}
161
162
// ekf_has_relative_position - returns true if the EKF can provide a position estimate relative to it's starting position
163
bool Blimp::ekf_has_relative_position() const
164
{
165
// return immediately if EKF not used
166
if (!ahrs.have_inertial_nav()) {
167
return false;
168
}
169
170
// return immediately if neither optflow nor visual odometry is enabled
171
bool enabled = false;
172
if (!enabled) {
173
return false;
174
}
175
176
// if disarmed we accept a predicted horizontal relative position
177
if (!motors->armed()) {
178
return ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_REL);
179
}
180
if (ahrs.has_status(AP_AHRS::Status::CONST_POS_MODE)) {
181
return false;
182
}
183
return ahrs.has_status(AP_AHRS::Status::HORIZ_POS_REL);
184
}
185
186
// returns true if the ekf has a good altitude estimate (required for modes which do AltHold)
187
bool Blimp::ekf_alt_ok() const
188
{
189
if (!ahrs.have_inertial_nav()) {
190
// do not allow alt control with only dcm
191
return false;
192
}
193
194
// require both vertical velocity and position
195
if (!ahrs.has_status(AP_AHRS::Status::VERT_VEL)) {
196
return false;
197
}
198
if (!ahrs.has_status(AP_AHRS::Status::VERT_POS)) {
199
return false;
200
}
201
202
return true;
203
}
204
205
// update_auto_armed - update status of auto_armed flag
206
void Blimp::update_auto_armed()
207
{
208
// disarm checks
209
if (ap.auto_armed) {
210
// if motors are disarmed, auto_armed should also be false
211
if (!motors->armed()) {
212
set_auto_armed(false);
213
return;
214
}
215
// if in a manual flight mode and throttle is zero, auto-armed should become false
216
if (flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio) {
217
set_auto_armed(false);
218
}
219
}
220
}
221
222
#if HAL_LOGGING_ENABLED
223
/*
224
should we log a message type now?
225
*/
226
bool Blimp::should_log(uint32_t mask)
227
{
228
ap.logging_started = logger.logging_started();
229
return logger.should_log(mask);
230
}
231
#endif
232
233
// return MAV_TYPE corresponding to frame class
234
MAV_TYPE Blimp::get_frame_mav_type()
235
{
236
return MAV_TYPE_AIRSHIP;
237
}
238
239
// return string corresponding to frame_class
240
const char* Blimp::get_frame_string()
241
{
242
return "AIRFISH"; //TODO: Change to be able to change with different frame_classes
243
}
244
245
/*
246
allocate the motors class
247
*/
248
void Blimp::allocate_motors(void)
249
{
250
switch ((Fins::motor_frame_class)g2.frame_class.get()) {
251
case Fins::MOTOR_FRAME_AIRFISH:
252
default:
253
motors = NEW_NOTHROW Fins(blimp.scheduler.get_loop_rate_hz());
254
break;
255
}
256
if (motors == nullptr) {
257
AP_BoardConfig::allocation_error("FRAME_CLASS=%u", (unsigned)g2.frame_class.get());
258
}
259
AP_Param::load_object_from_eeprom(motors, Fins::var_info);
260
261
// reload lines from the defaults file that may now be accessible
262
AP_Param::reload_defaults_file(true);
263
264
// param count could have changed
265
AP_Param::invalidate_count();
266
}
267
268