Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduSub/system.cpp
Views: 1798
#include "Sub.h"12/*****************************************************************************3* The init_ardupilot function processes everything we need for an in - air restart4* We will determine later if we are actually on the ground and process a5* ground start in that case.6*7*****************************************************************************/89static void failsafe_check_static()10{11sub.mainloop_failsafe_check();12}1314void Sub::init_ardupilot()15{16// initialise notify system17notify.init();1819// initialise battery monitor20battery.init();2122barometer.init();2324#if AP_FEATURE_BOARD_DETECT25// Detection won't work until after BoardConfig.init()26switch (AP_BoardConfig::get_board_type()) {27case AP_BoardConfig::PX4_BOARD_PIXHAWK2:28AP_Param::set_default_by_name("BARO_EXT_BUS", 0);29break;30case AP_BoardConfig::PX4_BOARD_PIXHAWK:31AP_Param::set_by_name("BARO_EXT_BUS", 1);32break;33default:34AP_Param::set_default_by_name("BARO_EXT_BUS", 1);35break;36}37#elif CONFIG_HAL_BOARD != HAL_BOARD_LINUX38AP_Param::set_default_by_name("BARO_EXT_BUS", 1);39#endif4041#if AP_TEMPERATURE_SENSOR_ENABLED42// In order to preserve Sub's previous AP_TemperatureSensor Behavior we set the Default I2C Bus Here43AP_Param::set_default_by_name("TEMP1_BUS", barometer.external_bus());44#endif4546// setup telem slots with serial ports47gcs().setup_uarts();4849// initialise rc channels including setting mode50rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);51rc().init();525354init_rc_in(); // sets up rc channels from radio55init_rc_out(); // sets up motors and output to escs56init_joystick(); // joystick initialization5758#if AP_RELAY_ENABLED59relay.init();60#endif6162/*63* setup the 'main loop is dead' check. Note that this relies on64* the RC library being initialised.65*/66hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);6768// Do GPS init69gps.set_log_gps_bit(MASK_LOG_GPS);70gps.init();7172AP::compass().set_log_bit(MASK_LOG_COMPASS);73AP::compass().init();7475#if AP_AIRSPEED_ENABLED76airspeed.set_log_bit(MASK_LOG_IMU);77#endif7879#if AP_OPTICALFLOW_ENABLED80// initialise optical flow sensor81optflow.init(MASK_LOG_OPTFLOW);82#endif8384#if HAL_MOUNT_ENABLED85// initialise camera mount86camera_mount.init();87// This step is necessary so that the servo is properly initialized88camera_mount.set_angle_target(0, 0, 0, false);89// for some reason the call to set_angle_targets changes the mode to mavlink targeting!90camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);91#endif9293#if AP_CAMERA_ENABLED94// initialise camera95camera.init();96#endif9798#ifdef USERHOOK_INIT99USERHOOK_INIT100#endif101102// Init baro and determine if we have external (depth) pressure sensor103barometer.set_log_baro_bit(MASK_LOG_IMU);104barometer.calibrate(false);105barometer.update();106107for (uint8_t i = 0; i < barometer.num_instances(); i++) {108if (barometer.get_type(i) == AP_Baro::BARO_TYPE_WATER) {109barometer.set_primary_baro(i);110depth_sensor_idx = i;111ap.depth_sensor_present = true;112sensor_health.depth = barometer.healthy(depth_sensor_idx); // initialize health flag113break; // Go with the first one we find114}115}116117if (!ap.depth_sensor_present) {118// We only have onboard baro119// No external underwater depth sensor detected120barometer.set_primary_baro(0);121ahrs.set_alt_measurement_noise(10.0f); // Readings won't correspond with rest of INS122} else {123ahrs.set_alt_measurement_noise(0.1f);124}125126leak_detector.init();127128last_pilot_heading = ahrs.yaw_sensor;129130// initialise rangefinder131#if AP_RANGEFINDER_ENABLED132init_rangefinder();133#endif134135// initialise AP_RPM library136#if AP_RPM_ENABLED137rpm_sensor.init();138#endif139140// initialise mission library141mission.init();142#if HAL_LOGGING_ENABLED143mission.set_log_start_mission_item_bit(MASK_LOG_CMD);144#endif145146// initialise AP_Logger library147#if HAL_LOGGING_ENABLED148logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));149#endif150151startup_INS_ground();152153// enable CPU failsafe154mainloop_failsafe_enable();155156ins.set_log_raw_bit(MASK_LOG_IMU_RAW);157158// flag that initialisation has completed159ap.initialised = true;160}161162163//******************************************************************************164//This function does all the calibrations, etc. that we need during a ground start165//******************************************************************************166void Sub::startup_INS_ground()167{168// initialise ahrs (may push imu calibration into the mpu6000 if using that device).169ahrs.init();170ahrs.set_vehicle_class(AP_AHRS::VehicleClass::SUBMARINE);171ahrs.set_fly_forward(false);172173// Warm up and calibrate gyro offsets174ins.init(scheduler.get_loop_rate_hz());175176// reset ahrs including gyro bias177ahrs.reset();178}179180// calibrate gyros - returns true if successfully calibrated181// position_ok - returns true if the horizontal absolute position is ok and home position is set182bool Sub::position_ok()183{184// return false if ekf failsafe has triggered185if (failsafe.ekf) {186return false;187}188189// check ekf position estimate190return (ekf_position_ok() || optflow_position_ok());191}192193// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set194bool Sub::ekf_position_ok()195{196if (!ahrs.have_inertial_nav()) {197// do not allow navigation with dcm position198return false;199}200201// with EKF use filter status and ekf check202nav_filter_status filt_status = inertial_nav.get_filter_status();203204// if disarmed we accept a predicted horizontal position205if (!motors.armed()) {206return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs));207}208209// once armed we require a good absolute position and EKF must not be in const_pos_mode210return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);211}212213// optflow_position_ok - returns true if optical flow based position estimate is ok214bool Sub::optflow_position_ok()215{216// return immediately if EKF not used217if (!ahrs.have_inertial_nav()) {218return false;219}220221// return immediately if neither optflow nor visual odometry is enabled222bool enabled = false;223#if AP_OPTICALFLOW_ENABLED224if (optflow.enabled()) {225enabled = true;226}227#endif228#if HAL_VISUALODOM_ENABLED229if (visual_odom.enabled()) {230enabled = true;231}232#endif233if (!enabled) {234return false;235}236237// get filter status from EKF238nav_filter_status filt_status = inertial_nav.get_filter_status();239240// if disarmed we accept a predicted horizontal relative position241if (!motors.armed()) {242return (filt_status.flags.pred_horiz_pos_rel);243}244return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);245}246247#if HAL_LOGGING_ENABLED248/*249should we log a message type now?250*/251bool Sub::should_log(uint32_t mask)252{253ap.logging_started = logger.logging_started();254return logger.should_log(mask);255}256#endif257258#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>259#include <AP_Avoidance/AP_Avoidance.h>260#include <AP_ADSB/AP_ADSB.h>261262// dummy method to avoid linking AFS263#if AP_ADVANCEDFAILSAFE_ENABLED264bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }265AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }266#endif267268#if HAL_ADSB_ENABLED269// dummy method to avoid linking AP_Avoidance270AP_Avoidance *AP::ap_avoidance() { return nullptr; }271#endif272273274