Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/system.cpp
9389 views
1
#include "Sub.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
sub.mainloop_failsafe_check();
13
}
14
15
void Sub::init_ardupilot()
16
{
17
// initialise notify system
18
notify.init();
19
20
// initialise battery monitor
21
battery.init();
22
23
barometer.init();
24
25
#if AP_FEATURE_BOARD_DETECT
26
// Detection won't work until after BoardConfig.init()
27
switch (AP_BoardConfig::get_board_type()) {
28
case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
29
AP_Param::set_default_by_name("BARO_EXT_BUS", 0);
30
break;
31
case AP_BoardConfig::PX4_BOARD_PIXHAWK:
32
AP_Param::set_by_name("BARO_EXT_BUS", 1);
33
break;
34
default:
35
AP_Param::set_default_by_name("BARO_EXT_BUS", 1);
36
break;
37
}
38
#elif CONFIG_HAL_BOARD != HAL_BOARD_LINUX
39
AP_Param::set_default_by_name("BARO_EXT_BUS", 1);
40
#endif
41
42
#if AP_TEMPERATURE_SENSOR_ENABLED
43
// In order to preserve Sub's previous AP_TemperatureSensor Behavior we set the Default I2C Bus Here
44
AP_Param::set_default_by_name("TEMP1_BUS", barometer.external_bus());
45
#endif
46
47
// setup telem slots with serial ports
48
gcs().setup_uarts();
49
50
// initialise rc channels including setting mode
51
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
52
rc().init();
53
54
55
init_rc_in(); // sets up rc channels from radio
56
init_rc_out(); // sets up motors and output to escs
57
init_joystick(); // joystick initialization
58
59
#if AP_RELAY_ENABLED
60
relay.init();
61
#endif
62
63
#if OSD_ENABLED
64
osd.init();
65
#endif
66
67
/*
68
* setup the 'main loop is dead' check. Note that this relies on
69
* the RC library being initialised.
70
*/
71
hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
72
73
// Do GPS init
74
gps.set_log_gps_bit(MASK_LOG_GPS);
75
gps.init();
76
77
AP::compass().set_log_bit(MASK_LOG_COMPASS);
78
AP::compass().init();
79
80
#if AP_AIRSPEED_ENABLED
81
airspeed.set_log_bit(MASK_LOG_IMU);
82
#endif
83
84
#if AP_OPTICALFLOW_ENABLED
85
// initialise optical flow sensor
86
optflow.init(MASK_LOG_OPTFLOW);
87
#endif
88
89
#if HAL_MOUNT_ENABLED
90
// initialise camera mount
91
camera_mount.init();
92
// This step is necessary so that the servo is properly initialized
93
camera_mount.set_angle_target(0, 0, 0, false);
94
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
95
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
96
#endif
97
98
#if AP_CAMERA_ENABLED
99
// initialise camera
100
camera.init();
101
#endif
102
103
#ifdef USERHOOK_INIT
104
USERHOOK_INIT
105
#endif
106
107
// Init baro and determine if we have external (depth) pressure sensor
108
barometer.set_log_baro_bit(MASK_LOG_IMU);
109
barometer.calibrate(false);
110
barometer.update();
111
112
for (uint8_t i = 0; i < barometer.num_instances(); i++) {
113
if (barometer.get_type(i) == AP_Baro::BARO_TYPE_WATER) {
114
barometer.set_primary_baro(i);
115
depth_sensor_idx = i;
116
ap.depth_sensor_present = true;
117
sensor_health.depth = barometer.healthy(depth_sensor_idx); // initialize health flag
118
break; // Go with the first one we find
119
}
120
}
121
122
if (!ap.depth_sensor_present) {
123
// We only have onboard baro
124
// No external underwater depth sensor detected
125
barometer.set_primary_baro(0);
126
ahrs.set_alt_measurement_noise(10.0f); // Readings won't correspond with rest of INS
127
} else {
128
ahrs.set_alt_measurement_noise(0.1f);
129
}
130
131
leak_detector.init();
132
133
last_pilot_heading_rad = ahrs.get_yaw_rad();
134
135
// initialise rangefinder
136
#if AP_RANGEFINDER_ENABLED
137
init_rangefinder();
138
#endif
139
140
// initialise mission library
141
mission.init();
142
#if HAL_LOGGING_ENABLED
143
mission.set_log_start_mission_item_bit(MASK_LOG_CMD);
144
#endif
145
146
// initialise AP_Logger library
147
#if HAL_LOGGING_ENABLED
148
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));
149
#endif
150
151
startup_INS_ground();
152
153
// enable CPU failsafe
154
mainloop_failsafe_enable();
155
156
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
157
g2.actuators.initialize_actuators();
158
159
#if LEAKDETECTOR_MAX_INSTANCES > 0
160
update_leak_pins();
161
#endif
162
#if AP_RELAY_ENABLED
163
update_relay_pins();
164
#endif
165
// flag that initialisation has completed
166
ap.initialised = true;
167
}
168
169
170
//******************************************************************************
171
//This function does all the calibrations, etc. that we need during a ground start
172
//******************************************************************************
173
void Sub::startup_INS_ground()
174
{
175
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
176
ahrs.init();
177
ahrs.set_vehicle_class(AP_AHRS::VehicleClass::SUBMARINE);
178
ahrs.set_fly_forward(false);
179
180
// Warm up and calibrate gyro offsets
181
ins.init(scheduler.get_loop_rate_hz());
182
183
// reset ahrs including gyro bias
184
ahrs.reset();
185
}
186
187
// calibrate gyros - returns true if successfully calibrated
188
// position_ok - returns true if the horizontal absolute position is ok and home position is set
189
bool Sub::position_ok()
190
{
191
// return false if ekf failsafe has triggered
192
if (failsafe.ekf) {
193
return false;
194
}
195
196
// check ekf position estimate
197
return (ekf_position_ok() || optflow_position_ok());
198
}
199
200
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
201
bool Sub::ekf_position_ok()
202
{
203
if (!ahrs.have_inertial_nav()) {
204
// do not allow navigation with dcm position
205
return false;
206
}
207
208
// if disarmed we accept a predicted horizontal position
209
if (!motors.armed()) {
210
if (ahrs.has_status(AP_AHRS::Status::HORIZ_POS_ABS)) {
211
return true;
212
}
213
if (ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_ABS)) {
214
return true;
215
}
216
return false;
217
}
218
219
// once armed we require a good absolute position and EKF must not be in const_pos_mode
220
if (ahrs.has_status(AP_AHRS::Status::CONST_POS_MODE)) {
221
return false;
222
}
223
return ahrs.has_status(AP_AHRS::Status::HORIZ_POS_ABS);
224
}
225
226
// optflow_position_ok - returns true if optical flow based position estimate is ok
227
bool Sub::optflow_position_ok()
228
{
229
// return immediately if EKF not used
230
if (!ahrs.have_inertial_nav()) {
231
return false;
232
}
233
234
// return immediately if neither optflow nor visual odometry is enabled
235
bool enabled = false;
236
#if AP_OPTICALFLOW_ENABLED
237
if (optflow.enabled()) {
238
enabled = true;
239
}
240
#endif
241
#if HAL_VISUALODOM_ENABLED
242
if (visual_odom.enabled()) {
243
enabled = true;
244
}
245
#endif
246
if (!enabled) {
247
return false;
248
}
249
250
// if disarmed we accept a predicted horizontal relative position
251
if (!motors.armed()) {
252
return ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_REL);
253
}
254
255
if (ahrs.has_status(AP_AHRS::Status::CONST_POS_MODE)) {
256
return false;
257
}
258
259
return ahrs.has_status(AP_AHRS::Status::HORIZ_POS_REL);
260
}
261
262
#if HAL_LOGGING_ENABLED
263
/*
264
should we log a message type now?
265
*/
266
bool Sub::should_log(uint32_t mask)
267
{
268
ap.logging_started = logger.logging_started();
269
return logger.should_log(mask);
270
}
271
#endif
272
273
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
274
#include <AP_Avoidance/AP_Avoidance.h>
275
#include <AP_ADSB/AP_ADSB.h>
276
277
// dummy method to avoid linking AFS
278
#if AP_ADVANCEDFAILSAFE_ENABLED
279
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }
280
AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }
281
#endif
282
283
#if AP_ADSB_AVOIDANCE_ENABLED
284
// dummy method to avoid linking AP_Avoidance
285
AP_Avoidance *AP::ap_avoidance() { return nullptr; }
286
#endif // AP_ADSB_AVOIDANCE_ENABLED
287
288