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/Blimp/system.cpp
Views: 1798
#include "Blimp.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{11blimp.failsafe_check();12}1314void Blimp::init_ardupilot()15{16// initialise notify system17notify.init();18notify_flight_mode();1920// initialise battery monitor21battery.init();2223#if AP_RSSI_ENABLED24// Init RSSI25rssi.init();26#endif2728barometer.init();2930// setup telem slots with serial ports31gcs().setup_uarts();3233init_rc_in(); // sets up rc channels from radio3435// allocate the motors class36allocate_motors();37loiter = NEW_NOTHROW Loiter(blimp.scheduler.get_loop_rate_hz());3839// initialise rc channels including setting mode40rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);41rc().init();4243// sets up motors and output to escs44init_rc_out();454647// motors initialised so parameters can be sent48ap.initialised_params = true;4950#if AP_RELAY_ENABLED51relay.init();52#endif5354/*55* setup the 'main loop is dead' check. Note that this relies on56* the RC library being initialised.57*/58hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);5960// Do GPS init61gps.set_log_gps_bit(MASK_LOG_GPS);62gps.init();6364AP::compass().set_log_bit(MASK_LOG_COMPASS);65AP::compass().init();6667// read Baro pressure at ground68//-----------------------------69barometer.set_log_baro_bit(MASK_LOG_IMU);70barometer.calibrate();7172#if HAL_LOGGING_ENABLED73// initialise AP_Logger library74logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&blimp, &Blimp::Log_Write_Vehicle_Startup_Messages, void));75#endif7677startup_INS_ground();7879ins.set_log_raw_bit(MASK_LOG_IMU_RAW);8081// setup fin output82motors->setup_fins();8384// enable output to motors85if (arming.rc_calibration_checks(true)) {86enable_motor_output();87}8889//Initialise fin filters90vel_xy_filter.init(scheduler.get_loop_rate_hz(), motors->freq_hz, 0.5f, 15.0f);91vel_z_filter.init(scheduler.get_loop_rate_hz(), motors->freq_hz, 1.0f, 15.0f);92vel_yaw_filter.init(scheduler.get_loop_rate_hz(),motors->freq_hz, 5.0f, 15.0f);9394// attempt to switch to MANUAL, if this fails then switch to Land95if (!set_mode((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED)) {96// set mode to MANUAL will trigger mode change notification to pilot97set_mode(Mode::Number::MANUAL, ModeReason::UNAVAILABLE);98} else {99// alert pilot to mode change100AP_Notify::events.failsafe_mode_change = 1;101}102103// flag that initialisation has completed104ap.initialised = true;105}106107108//******************************************************************************109//This function does all the calibrations, etc. that we need during a ground start110//******************************************************************************111void Blimp::startup_INS_ground()112{113// initialise ahrs (may push imu calibration into the mpu6000 if using that device).114ahrs.init();115ahrs.set_vehicle_class(AP_AHRS::VehicleClass::COPTER);116117// Warm up and calibrate gyro offsets118ins.init(scheduler.get_loop_rate_hz());119120// reset ahrs including gyro bias121ahrs.reset();122}123124// position_ok - returns true if the horizontal absolute position is ok and home position is set125bool Blimp::position_ok() const126{127// return false if ekf failsafe has triggered128if (failsafe.ekf) {129return false;130}131132// check ekf position estimate133return (ekf_has_absolute_position() || ekf_has_relative_position());134}135136// ekf_has_absolute_position - returns true if the EKF can provide an absolute WGS-84 position estimate137bool Blimp::ekf_has_absolute_position() const138{139if (!ahrs.have_inertial_nav()) {140// do not allow navigation with dcm position141return false;142}143144// with EKF use filter status and ekf check145nav_filter_status filt_status = inertial_nav.get_filter_status();146147// if disarmed we accept a predicted horizontal position148if (!motors->armed()) {149return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs));150} else {151// once armed we require a good absolute position and EKF must not be in const_pos_mode152return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);153}154}155156// ekf_has_relative_position - returns true if the EKF can provide a position estimate relative to it's starting position157bool Blimp::ekf_has_relative_position() const158{159// return immediately if EKF not used160if (!ahrs.have_inertial_nav()) {161return false;162}163164// return immediately if neither optflow nor visual odometry is enabled165bool enabled = false;166if (!enabled) {167return false;168}169170// get filter status from EKF171nav_filter_status filt_status = inertial_nav.get_filter_status();172173// if disarmed we accept a predicted horizontal relative position174if (!motors->armed()) {175return (filt_status.flags.pred_horiz_pos_rel);176} else {177return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);178}179}180181// returns true if the ekf has a good altitude estimate (required for modes which do AltHold)182bool Blimp::ekf_alt_ok() const183{184if (!ahrs.have_inertial_nav()) {185// do not allow alt control with only dcm186return false;187}188189// with EKF use filter status and ekf check190nav_filter_status filt_status = inertial_nav.get_filter_status();191192// require both vertical velocity and position193return (filt_status.flags.vert_vel && filt_status.flags.vert_pos);194}195196// update_auto_armed - update status of auto_armed flag197void Blimp::update_auto_armed()198{199// disarm checks200if (ap.auto_armed) {201// if motors are disarmed, auto_armed should also be false202if (!motors->armed()) {203set_auto_armed(false);204return;205}206// if in a manual flight mode and throttle is zero, auto-armed should become false207if (flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio) {208set_auto_armed(false);209}210}211}212213#if HAL_LOGGING_ENABLED214/*215should we log a message type now?216*/217bool Blimp::should_log(uint32_t mask)218{219ap.logging_started = logger.logging_started();220return logger.should_log(mask);221}222#endif223224// return MAV_TYPE corresponding to frame class225MAV_TYPE Blimp::get_frame_mav_type()226{227return MAV_TYPE_AIRSHIP;228}229230// return string corresponding to frame_class231const char* Blimp::get_frame_string()232{233return "AIRFISH"; //TODO: Change to be able to change with different frame_classes234}235236/*237allocate the motors class238*/239void Blimp::allocate_motors(void)240{241switch ((Fins::motor_frame_class)g2.frame_class.get()) {242case Fins::MOTOR_FRAME_AIRFISH:243default:244motors = NEW_NOTHROW Fins(blimp.scheduler.get_loop_rate_hz());245break;246}247if (motors == nullptr) {248AP_BoardConfig::allocation_error("FRAME_CLASS=%u", (unsigned)g2.frame_class.get());249}250AP_Param::load_object_from_eeprom(motors, Fins::var_info);251252// reload lines from the defaults file that may now be accessible253AP_Param::reload_defaults_file(true);254255// param count could have changed256AP_Param::invalidate_count();257}258259260