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/ArduSub.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415// ArduSub scheduling, originally copied from ArduCopter1617#include "Sub.h"1819#define SCHED_TASK(func, rate_hz, max_time_micros, priority) SCHED_TASK_CLASS(Sub, &sub, func, rate_hz, max_time_micros, priority)20#define FAST_TASK(func) FAST_TASK_CLASS(Sub, &sub, func)2122/*23scheduler table - all tasks should be listed here.2425All entries in this table must be ordered by priority.2627This table is interleaved with the table in AP_Vehicle to determine28the order in which tasks are run. Convenience methods SCHED_TASK29and SCHED_TASK_CLASS are provided to build entries in this structure:3031SCHED_TASK arguments:32- name of static function to call33- rate (in Hertz) at which the function should be called34- expected time (in MicroSeconds) that the function should take to run35- priority (0 through 255, lower number meaning higher priority)3637SCHED_TASK_CLASS arguments:38- class name of method to be called39- instance on which to call the method40- method to call on that instance41- rate (in Hertz) at which the method should be called42- expected time (in MicroSeconds) that the method should take to run43- priority (0 through 255, lower number meaning higher priority)4445*/4647const AP_Scheduler::Task Sub::scheduler_tasks[] = {48// update INS immediately to get current gyro data populated49FAST_TASK_CLASS(AP_InertialSensor, &sub.ins, update),50// run low level rate controllers that only require IMU data51FAST_TASK(run_rate_controller),52// send outputs to the motors library immediately53FAST_TASK(motors_output),54// run EKF state estimator (expensive)55FAST_TASK(read_AHRS),56// Inertial Nav57FAST_TASK(read_inertia),58// check if ekf has reset target heading59FAST_TASK(check_ekf_yaw_reset),60// run the attitude controllers61FAST_TASK(update_flight_mode),62// update home from EKF if necessary63FAST_TASK(update_home_from_EKF),64// check if we've reached the surface or bottom65FAST_TASK(update_surface_and_bottom_detector),66#if HAL_MOUNT_ENABLED67// camera mount's fast update68FAST_TASK_CLASS(AP_Mount, &sub.camera_mount, update_fast),69#endif7071SCHED_TASK(fifty_hz_loop, 50, 75, 3),72SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200, 6),73#if AP_OPTICALFLOW_ENABLED74SCHED_TASK_CLASS(AP_OpticalFlow, &sub.optflow, update, 200, 160, 9),75#endif76SCHED_TASK(update_batt_compass, 10, 120, 12),77SCHED_TASK(read_rangefinder, 20, 100, 15),78SCHED_TASK(update_altitude, 10, 100, 18),79SCHED_TASK(three_hz_loop, 3, 75, 21),80SCHED_TASK(update_turn_counter, 10, 50, 24),81SCHED_TASK(one_hz_loop, 1, 100, 33),82SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36),83SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39),84#if HAL_MOUNT_ENABLED85SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75, 45),86#endif87#if AP_CAMERA_ENABLED88SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75, 48),89#endif90#if HAL_LOGGING_ENABLED91SCHED_TASK(ten_hz_logging_loop, 10, 350, 51),92SCHED_TASK(twentyfive_hz_logging, 25, 110, 54),93SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300, 57),94#endif95SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50, 60),96#if HAL_LOGGING_ENABLED97SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75, 63),98#endif99#if AP_RPM_ENABLED100SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update, 10, 200, 66),101#endif102SCHED_TASK(terrain_update, 10, 100, 72),103#if AP_STATS_ENABLED104SCHED_TASK(stats_update, 1, 200, 76),105#endif106#ifdef USERHOOK_FASTLOOP107SCHED_TASK(userhook_FastLoop, 100, 75, 78),108#endif109#ifdef USERHOOK_50HZLOOP110SCHED_TASK(userhook_50Hz, 50, 75, 81),111#endif112#ifdef USERHOOK_MEDIUMLOOP113SCHED_TASK(userhook_MediumLoop, 10, 75, 84),114#endif115#ifdef USERHOOK_SLOWLOOP116SCHED_TASK(userhook_SlowLoop, 3.3, 75, 87),117#endif118#ifdef USERHOOK_SUPERSLOWLOOP119SCHED_TASK(userhook_SuperSlowLoop, 1, 75, 90),120#endif121};122123void Sub::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,124uint8_t &task_count,125uint32_t &log_bit)126{127tasks = &scheduler_tasks[0];128task_count = ARRAY_SIZE(scheduler_tasks);129log_bit = MASK_LOG_PM;130}131132constexpr int8_t Sub::_failsafe_priorities[5];133134void Sub::run_rate_controller()135{136const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();137motors.set_dt(last_loop_time_s);138attitude_control.set_dt(last_loop_time_s);139pos_control.set_dt(last_loop_time_s);140141//don't run rate controller in manual or motordetection modes142if (control_mode != Mode::Number::MANUAL && control_mode != Mode::Number::MOTOR_DETECT) {143// run low level rate controllers that only require IMU data and set loop time144attitude_control.rate_controller_run();145}146}147148// 50 Hz tasks149void Sub::fifty_hz_loop()150{151// check pilot input failsafe152failsafe_pilot_input_check();153154failsafe_crash_check();155156failsafe_ekf_check();157158failsafe_sensors_check();159160rc().read_input();161}162163// update_batt_compass - read battery and compass164// should be called at 10hz165void Sub::update_batt_compass()166{167// read battery before compass because it may be used for motor interference compensation168battery.read();169170if (AP::compass().available()) {171// update compass with throttle value - used for compassmot172compass.set_throttle(motors.get_throttle());173compass.read();174}175}176177#if HAL_LOGGING_ENABLED178// ten_hz_logging_loop179// should be run at 10hz180void Sub::ten_hz_logging_loop()181{182// log attitude data if we're not already logging at the higher rate183if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {184Log_Write_Attitude();185attitude_control.Write_ANG();186attitude_control.Write_Rate(pos_control);187if (should_log(MASK_LOG_PID)) {188logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());189logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());190logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());191logger.Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info());192}193}194if (should_log(MASK_LOG_MOTBATT)) {195motors.Log_Write();196}197if (should_log(MASK_LOG_RCIN)) {198logger.Write_RCIN();199}200if (should_log(MASK_LOG_RCOUT)) {201logger.Write_RCOUT();202}203if (should_log(MASK_LOG_NTUN) && (sub.flightmode->requires_GPS() || !sub.flightmode->has_manual_throttle())) {204pos_control.write_log();205}206if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {207AP::ins().Write_Vibration();208}209if (should_log(MASK_LOG_CTUN)) {210attitude_control.control_monitor_log();211}212#if HAL_MOUNT_ENABLED213if (should_log(MASK_LOG_CAMERA)) {214camera_mount.write_log();215}216#endif217}218219// twentyfive_hz_logging_loop220// should be run at 25hz221void Sub::twentyfive_hz_logging()222{223if (should_log(MASK_LOG_ATTITUDE_FAST)) {224Log_Write_Attitude();225attitude_control.Write_ANG();226attitude_control.Write_Rate(pos_control);227if (should_log(MASK_LOG_PID)) {228logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());229logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());230logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());231logger.Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info());232}233}234235// log IMU data if we're not already logging at the higher rate236if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_RAW)) {237AP::ins().Write_IMU();238}239}240#endif // HAL_LOGGING_ENABLED241242// three_hz_loop - 3.3hz loop243void Sub::three_hz_loop()244{245leak_detector.update();246247failsafe_leak_check();248249failsafe_internal_pressure_check();250251failsafe_internal_temperature_check();252253// check if we've lost contact with the ground station254failsafe_gcs_check();255256// check if we've lost terrain data257failsafe_terrain_check();258259#if AP_FENCE_ENABLED260// check if we have breached a fence261fence_check();262#endif // AP_FENCE_ENABLED263264#if AP_SERVORELAYEVENTS_ENABLED265ServoRelayEvents.update_events();266#endif267}268269// one_hz_loop - runs at 1Hz270void Sub::one_hz_loop()271{272// sync MAVLink system ID273mavlink_system.sysid = g.sysid_this_mav;274275bool arm_check = arming.pre_arm_checks(false);276ap.pre_arm_check = arm_check;277AP_Notify::flags.pre_arm_check = arm_check;278AP_Notify::flags.pre_arm_gps_check = position_ok();279AP_Notify::flags.flying = motors.armed();280281#if HAL_LOGGING_ENABLED282if (should_log(MASK_LOG_ANY)) {283Log_Write_Data(LogDataID::AP_STATE, ap.value);284}285#endif286287if (!motors.armed()) {288motors.update_throttle_range();289}290291// update assigned functions and enable auxiliary servos292AP::srv().enable_aux_servos();293294#if HAL_LOGGING_ENABLED295// log terrain data296terrain_logging();297#endif298299// need to set "likely flying" when armed to allow for compass300// learning to run301set_likely_flying(hal.util->get_soft_armed());302303attitude_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());304pos_control.get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());305}306307void Sub::read_AHRS()308{309// Perform IMU calculations and get attitude info310//-----------------------------------------------311// <true> tells AHRS to skip INS update as we have already done it in fast_loop()312ahrs.update(true);313ahrs_view.update();314}315316// read baro and rangefinder altitude at 10hz317void Sub::update_altitude()318{319// read in baro altitude320read_barometer();321322#if HAL_LOGGING_ENABLED323if (should_log(MASK_LOG_CTUN)) {324Log_Write_Control_Tuning();325#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED326AP::ins().write_notch_log_messages();327#endif328#if HAL_GYROFFT_ENABLED329gyro_fft.write_log_messages();330#endif331}332#endif // HAL_LOGGING_ENABLED333}334335bool Sub::control_check_barometer()336{337#if CONFIG_HAL_BOARD != HAL_BOARD_SITL338if (!ap.depth_sensor_present) { // can't hold depth without a depth sensor339gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor is not connected.");340return false;341} else if (failsafe.sensor_health) {342gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor error.");343return false;344}345#endif346return true;347}348349// vehicle specific waypoint info helpers350bool Sub::get_wp_distance_m(float &distance) const351{352// see GCS_MAVLINK_Sub::send_nav_controller_output()353distance = sub.wp_nav.get_wp_distance_to_destination() * 0.01;354return true;355}356357// vehicle specific waypoint info helpers358bool Sub::get_wp_bearing_deg(float &bearing) const359{360// see GCS_MAVLINK_Sub::send_nav_controller_output()361bearing = sub.wp_nav.get_wp_bearing_to_destination() * 0.01;362return true;363}364365// vehicle specific waypoint info helpers366bool Sub::get_wp_crosstrack_error_m(float &xtrack_error) const367{368// no crosstrack error reported, see GCS_MAVLINK_Sub::send_nav_controller_output()369xtrack_error = 0;370return true;371}372373#if AP_STATS_ENABLED374/*375update AP_Stats376*/377void Sub::stats_update(void)378{379AP::stats()->set_flying(motors.armed());380}381#endif382383// get the altitude relative to the home position or the ekf origin384float Sub::get_alt_rel() const385{386if (!ap.depth_sensor_present) {387return 0;388}389390// get relative position391float posD;392if (ahrs.get_relative_position_D_origin(posD)) {393if (ahrs.home_is_set()) {394// adjust to the home position395auto home = ahrs.get_home();396posD -= static_cast<float>(home.alt) * 0.01f;397}398} else {399// fall back to the barometer reading400posD = -AP::baro().get_altitude();401}402403// convert down to up404return -posD;405}406407// get the altitude above mean sea level408float Sub::get_alt_msl() const409{410if (!ap.depth_sensor_present) {411return 0;412}413414Location origin;415if (!ahrs.get_origin(origin)) {416return 0;417}418419// get relative position420float posD;421if (!ahrs.get_relative_position_D_origin(posD)) {422// fall back to the barometer reading423posD = -AP::baro().get_altitude();424}425426// add in the ekf origin altitude427posD -= static_cast<float>(origin.alt) * 0.01f;428429// convert down to up430return -posD;431}432433bool Sub::ensure_ekf_origin()434{435Location ekf_origin;436if (ahrs.get_origin(ekf_origin)) {437// ekf origin is set438return true;439}440441if (gps.num_sensors() > 0) {442// wait for the gps sensor to set the origin443// alert the pilot to poor compass performance444return false;445}446447auto backup_origin = Location(static_cast<int32_t>(sub.g2.backup_origin_lat * 1e7),448static_cast<int32_t>(sub.g2.backup_origin_lon * 1e7),449static_cast<int32_t>(sub.g2.backup_origin_alt * 100),450Location::AltFrame::ABSOLUTE);451452if (backup_origin.lat == 0 || backup_origin.lng == 0) {453gcs().send_text(MAV_SEVERITY_WARNING, "Backup location parameters are missing or zero");454return false;455}456457if (!check_latlng(backup_origin.lat, backup_origin.lng)) {458gcs().send_text(MAV_SEVERITY_WARNING, "Backup location parameters are not valid");459return false;460}461462if (!ahrs.set_origin(backup_origin)) {463// a possible problem is that ek3_srcn_posxy is set to 3 (gps)464gcs().send_text(MAV_SEVERITY_WARNING, "Failed to set origin, check EK3_SRC parameters");465return false;466}467468gcs().send_text(MAV_SEVERITY_INFO, "Using backup location");469470#if HAL_LOGGING_ENABLED471ahrs.Log_Write_Home_And_Origin();472#endif473474// send ekf origin to GCS475gcs().send_message(MSG_ORIGIN);476477return true;478}479480AP_HAL_MAIN_CALLBACKS(&sub);481482483