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/ArduSub/system.cpp
Views: 1798
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
/*
64
* setup the 'main loop is dead' check. Note that this relies on
65
* the RC library being initialised.
66
*/
67
hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
68
69
// Do GPS init
70
gps.set_log_gps_bit(MASK_LOG_GPS);
71
gps.init();
72
73
AP::compass().set_log_bit(MASK_LOG_COMPASS);
74
AP::compass().init();
75
76
#if AP_AIRSPEED_ENABLED
77
airspeed.set_log_bit(MASK_LOG_IMU);
78
#endif
79
80
#if AP_OPTICALFLOW_ENABLED
81
// initialise optical flow sensor
82
optflow.init(MASK_LOG_OPTFLOW);
83
#endif
84
85
#if HAL_MOUNT_ENABLED
86
// initialise camera mount
87
camera_mount.init();
88
// This step is necessary so that the servo is properly initialized
89
camera_mount.set_angle_target(0, 0, 0, false);
90
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
91
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
92
#endif
93
94
#if AP_CAMERA_ENABLED
95
// initialise camera
96
camera.init();
97
#endif
98
99
#ifdef USERHOOK_INIT
100
USERHOOK_INIT
101
#endif
102
103
// Init baro and determine if we have external (depth) pressure sensor
104
barometer.set_log_baro_bit(MASK_LOG_IMU);
105
barometer.calibrate(false);
106
barometer.update();
107
108
for (uint8_t i = 0; i < barometer.num_instances(); i++) {
109
if (barometer.get_type(i) == AP_Baro::BARO_TYPE_WATER) {
110
barometer.set_primary_baro(i);
111
depth_sensor_idx = i;
112
ap.depth_sensor_present = true;
113
sensor_health.depth = barometer.healthy(depth_sensor_idx); // initialize health flag
114
break; // Go with the first one we find
115
}
116
}
117
118
if (!ap.depth_sensor_present) {
119
// We only have onboard baro
120
// No external underwater depth sensor detected
121
barometer.set_primary_baro(0);
122
ahrs.set_alt_measurement_noise(10.0f); // Readings won't correspond with rest of INS
123
} else {
124
ahrs.set_alt_measurement_noise(0.1f);
125
}
126
127
leak_detector.init();
128
129
last_pilot_heading = ahrs.yaw_sensor;
130
131
// initialise rangefinder
132
#if AP_RANGEFINDER_ENABLED
133
init_rangefinder();
134
#endif
135
136
// initialise AP_RPM library
137
#if AP_RPM_ENABLED
138
rpm_sensor.init();
139
#endif
140
141
// initialise mission library
142
mission.init();
143
#if HAL_LOGGING_ENABLED
144
mission.set_log_start_mission_item_bit(MASK_LOG_CMD);
145
#endif
146
147
// initialise AP_Logger library
148
#if HAL_LOGGING_ENABLED
149
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));
150
#endif
151
152
startup_INS_ground();
153
154
// enable CPU failsafe
155
mainloop_failsafe_enable();
156
157
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
158
159
// flag that initialisation has completed
160
ap.initialised = true;
161
}
162
163
164
//******************************************************************************
165
//This function does all the calibrations, etc. that we need during a ground start
166
//******************************************************************************
167
void Sub::startup_INS_ground()
168
{
169
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
170
ahrs.init();
171
ahrs.set_vehicle_class(AP_AHRS::VehicleClass::SUBMARINE);
172
ahrs.set_fly_forward(false);
173
174
// Warm up and calibrate gyro offsets
175
ins.init(scheduler.get_loop_rate_hz());
176
177
// reset ahrs including gyro bias
178
ahrs.reset();
179
}
180
181
// calibrate gyros - returns true if successfully calibrated
182
// position_ok - returns true if the horizontal absolute position is ok and home position is set
183
bool Sub::position_ok()
184
{
185
// return false if ekf failsafe has triggered
186
if (failsafe.ekf) {
187
return false;
188
}
189
190
// check ekf position estimate
191
return (ekf_position_ok() || optflow_position_ok());
192
}
193
194
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
195
bool Sub::ekf_position_ok()
196
{
197
if (!ahrs.have_inertial_nav()) {
198
// do not allow navigation with dcm position
199
return false;
200
}
201
202
// with EKF use filter status and ekf check
203
nav_filter_status filt_status = inertial_nav.get_filter_status();
204
205
// if disarmed we accept a predicted horizontal position
206
if (!motors.armed()) {
207
return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs));
208
}
209
210
// once armed we require a good absolute position and EKF must not be in const_pos_mode
211
return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
212
}
213
214
// optflow_position_ok - returns true if optical flow based position estimate is ok
215
bool Sub::optflow_position_ok()
216
{
217
// return immediately if EKF not used
218
if (!ahrs.have_inertial_nav()) {
219
return false;
220
}
221
222
// return immediately if neither optflow nor visual odometry is enabled
223
bool enabled = false;
224
#if AP_OPTICALFLOW_ENABLED
225
if (optflow.enabled()) {
226
enabled = true;
227
}
228
#endif
229
#if HAL_VISUALODOM_ENABLED
230
if (visual_odom.enabled()) {
231
enabled = true;
232
}
233
#endif
234
if (!enabled) {
235
return false;
236
}
237
238
// get filter status from EKF
239
nav_filter_status filt_status = inertial_nav.get_filter_status();
240
241
// if disarmed we accept a predicted horizontal relative position
242
if (!motors.armed()) {
243
return (filt_status.flags.pred_horiz_pos_rel);
244
}
245
return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);
246
}
247
248
#if HAL_LOGGING_ENABLED
249
/*
250
should we log a message type now?
251
*/
252
bool Sub::should_log(uint32_t mask)
253
{
254
ap.logging_started = logger.logging_started();
255
return logger.should_log(mask);
256
}
257
#endif
258
259
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
260
#include <AP_Avoidance/AP_Avoidance.h>
261
#include <AP_ADSB/AP_ADSB.h>
262
263
// dummy method to avoid linking AFS
264
#if AP_ADVANCEDFAILSAFE_ENABLED
265
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }
266
AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }
267
#endif
268
269
#if HAL_ADSB_ENABLED
270
// dummy method to avoid linking AP_Avoidance
271
AP_Avoidance *AP::ap_avoidance() { return nullptr; }
272
#endif
273
274