system.cpp 8.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304
  1. #include "Sub.h"
  2. /*****************************************************************************
  3. * The init_ardupilot function processes everything we need for an in - air restart
  4. * We will determine later if we are actually on the ground and process a
  5. * ground start in that case.
  6. *
  7. *****************************************************************************/
  8. static void mavlink_delay_cb_static()
  9. {
  10. sub.mavlink_delay_cb();
  11. }
  12. static void failsafe_check_static()
  13. {
  14. sub.mainloop_failsafe_check();
  15. }
  16. void Sub::init_ardupilot()
  17. {
  18. // initialise serial port
  19. serial_manager.init_console();
  20. hal.console->printf("\n\nInit %s"
  21. "\n\nFree RAM: %u\n",
  22. AP::fwversion().fw_string,
  23. (unsigned)hal.util->available_memory());
  24. // load parameters from EEPROM
  25. load_parameters();
  26. BoardConfig.init();
  27. #if HAL_WITH_UAVCAN
  28. BoardConfig_CAN.init();
  29. #endif
  30. #if AP_FEATURE_BOARD_DETECT
  31. // Detection won't work until after BoardConfig.init()
  32. switch (AP_BoardConfig::get_board_type()) {
  33. case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
  34. AP_Param::set_by_name("GND_EXT_BUS", 0);
  35. celsius.init(0);
  36. break;
  37. default:
  38. AP_Param::set_by_name("GND_EXT_BUS", 1);
  39. celsius.init(1);
  40. break;
  41. }
  42. #else
  43. AP_Param::set_default_by_name("GND_EXT_BUS", 1);
  44. celsius.init(1);
  45. #endif
  46. // identify ourselves correctly with the ground station
  47. mavlink_system.sysid = g.sysid_this_mav;
  48. // initialise serial port
  49. serial_manager.init();
  50. // setup first port early to allow BoardConfig to report errors
  51. gcs().setup_console();
  52. // init cargo gripper
  53. #if GRIPPER_ENABLED == ENABLED
  54. g2.gripper.init();
  55. #endif
  56. // initialise notify system
  57. notify.init();
  58. // initialise battery monitor
  59. battery.init();
  60. barometer.init();
  61. // Register the mavlink service callback. This will run
  62. // anytime there are more than 5ms remaining in a call to
  63. // hal.scheduler->delay.
  64. hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
  65. // setup telem slots with serial ports
  66. gcs().setup_uarts();
  67. #if LOGGING_ENABLED == ENABLED
  68. log_init();
  69. #endif
  70. // initialise rc channels including setting mode
  71. rc().init();
  72. init_rc_in(); // sets up rc channels from radio
  73. init_rc_out(); // sets up motors and output to escs
  74. init_joystick(); // joystick initialization
  75. relay.init();
  76. /*
  77. * setup the 'main loop is dead' check. Note that this relies on
  78. * the RC library being initialised.
  79. */
  80. hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
  81. // Do GPS init
  82. gps.set_log_gps_bit(MASK_LOG_GPS);
  83. gps.init(serial_manager);
  84. AP::compass().set_log_bit(MASK_LOG_COMPASS);
  85. AP::compass().init();
  86. #if OPTFLOW == ENABLED
  87. // make optflow available to AHRS
  88. ahrs.set_optflow(&optflow);
  89. #endif
  90. // init Location class
  91. #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
  92. Location::set_terrain(&terrain);
  93. wp_nav.set_terrain(&terrain);
  94. #endif
  95. pos_control.set_dt(MAIN_LOOP_SECONDS);
  96. // init the optical flow sensor
  97. #if OPTFLOW == ENABLED
  98. init_optflow();
  99. #endif
  100. #if MOUNT == ENABLED
  101. // initialise camera mount
  102. camera_mount.init();
  103. // This step ncessary so the servo is properly initialized
  104. camera_mount.set_angle_targets(0, 0, 0);
  105. // for some reason the call to set_angle_targets changes the mode to mavlink targeting!
  106. camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
  107. #endif
  108. #ifdef USERHOOK_INIT
  109. USERHOOK_INIT
  110. #endif
  111. // Init baro and determine if we have external (depth) pressure sensor
  112. barometer.set_log_baro_bit(MASK_LOG_IMU);
  113. barometer.calibrate(false);
  114. barometer.update();
  115. for (uint8_t i = 0; i < barometer.num_instances(); i++) {
  116. if (barometer.get_type(i) == AP_Baro::BARO_TYPE_WATER) {
  117. barometer.set_primary_baro(i);
  118. depth_sensor_idx = i;
  119. ap.depth_sensor_present = true;
  120. sensor_health.depth = barometer.healthy(depth_sensor_idx); // initialize health flag
  121. break; // Go with the first one we find
  122. }
  123. }
  124. if (!ap.depth_sensor_present) {
  125. // We only have onboard baro
  126. // No external underwater depth sensor detected
  127. barometer.set_primary_baro(0);
  128. EKF2.set_baro_alt_noise(10.0f); // Readings won't correspond with rest of INS
  129. EKF3.set_baro_alt_noise(10.0f);
  130. } else {
  131. EKF2.set_baro_alt_noise(0.1f);
  132. EKF3.set_baro_alt_noise(0.1f);
  133. }
  134. leak_detector.init();
  135. last_pilot_heading = ahrs.yaw_sensor;
  136. // initialise rangefinder
  137. #if RANGEFINDER_ENABLED == ENABLED
  138. init_rangefinder();
  139. #endif
  140. // initialise AP_RPM library
  141. #if RPM_ENABLED == ENABLED
  142. rpm_sensor.init();
  143. #endif
  144. // initialise mission library
  145. mission.init();
  146. // initialise AP_Logger library
  147. #if LOGGING_ENABLED == ENABLED
  148. logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));
  149. #endif
  150. startup_INS_ground();
  151. #ifdef ENABLE_SCRIPTING
  152. if (!g2.scripting.init()) {
  153. gcs().send_text(MAV_SEVERITY_ERROR, "Scripting failed to start");
  154. }
  155. #endif // ENABLE_SCRIPTING
  156. // we don't want writes to the serial port to cause us to pause
  157. // mid-flight, so set the serial ports non-blocking once we are
  158. // ready to fly
  159. serial_manager.set_blocking_writes_all(false);
  160. // enable CPU failsafe
  161. mainloop_failsafe_enable();
  162. ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
  163. // disable safety if requested
  164. BoardConfig.init_safety();
  165. hal.console->print("\nInit complete");
  166. // flag that initialisation has completed
  167. ap.initialised = true;
  168. #if AP_PARAM_KEY_DUMP
  169. AP_Param::show_all(hal.console, true);
  170. #endif
  171. }
  172. //******************************************************************************
  173. //This function does all the calibrations, etc. that we need during a ground start
  174. //******************************************************************************
  175. void Sub::startup_INS_ground()
  176. {
  177. // initialise ahrs (may push imu calibration into the mpu6000 if using that device).
  178. ahrs.init();
  179. ahrs.set_vehicle_class(AHRS_VEHICLE_SUBMARINE);
  180. // Warm up and calibrate gyro offsets
  181. ins.init(scheduler.get_loop_rate_hz());
  182. // reset ahrs including gyro bias
  183. ahrs.reset();
  184. }
  185. // calibrate gyros - returns true if successfully calibrated
  186. // position_ok - returns true if the horizontal absolute position is ok and home position is set
  187. bool Sub::position_ok()
  188. {
  189. // return false if ekf failsafe has triggered
  190. if (failsafe.ekf) {
  191. return false;
  192. }
  193. // check ekf position estimate
  194. return (ekf_position_ok() || optflow_position_ok());
  195. }
  196. // ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
  197. bool Sub::ekf_position_ok()
  198. {
  199. if (!ahrs.have_inertial_nav()) {
  200. // do not allow navigation with dcm position
  201. return false;
  202. }
  203. // with EKF use filter status and ekf check
  204. nav_filter_status filt_status = inertial_nav.get_filter_status();
  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. // once armed we require a good absolute position and EKF must not be in const_pos_mode
  210. return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
  211. }
  212. // optflow_position_ok - returns true if optical flow based position estimate is ok
  213. bool Sub::optflow_position_ok()
  214. {
  215. #if OPTFLOW != ENABLED
  216. return false;
  217. #else
  218. // return immediately if optflow is not enabled or EKF not used
  219. if (!optflow.enabled() || !ahrs.have_inertial_nav()) {
  220. return false;
  221. }
  222. // get filter status from EKF
  223. nav_filter_status filt_status = inertial_nav.get_filter_status();
  224. // if disarmed we accept a predicted horizontal relative position
  225. if (!motors.armed()) {
  226. return (filt_status.flags.pred_horiz_pos_rel);
  227. }
  228. return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);
  229. #endif
  230. }
  231. /*
  232. should we log a message type now?
  233. */
  234. bool Sub::should_log(uint32_t mask)
  235. {
  236. #if LOGGING_ENABLED == ENABLED
  237. ap.logging_started = logger.logging_started();
  238. return logger.should_log(mask);
  239. #else
  240. return false;
  241. #endif
  242. }