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/ArduCopter/Copter.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/*16* ArduCopter (also known as APM, APM:Copter or just Copter)17* Wiki: copter.ardupilot.org18* Creator: Jason Short19* Lead Developer: Randy Mackay20* Lead Tester: Marco Robustini21* Based on code and ideas from the Arducopter team: Leonard Hall, Andrew Tridgell, Robert Lefebvre, Pat Hickey, Michael Oborne, Jani Hirvinen,22Olivier Adler, Kevin Hester, Arthur Benemann, Jonathan Challinger, John Arne Birkeland,23Jean-Louis Naudin, Mike Smith, and more24* Thanks to: Chris Anderson, Jordi Munoz, Jason Short, Doug Weibel, Jose Julio25*26* Special Thanks to contributors (in alphabetical order by first name):27*28* Adam M Rivera :Auto Compass Declination29* Amilcar Lucas :Camera mount library30* Andrew Tridgell :General development, Mavlink Support31* Andy Piper :Harmonic notch, In-flight FFT, Bi-directional DShot, various drivers32* Angel Fernandez :Alpha testing33* AndreasAntonopoulous:GeoFence34* Arthur Benemann :DroidPlanner GCS35* Benjamin Pelletier :Libraries36* Bill King :Single Copter37* Christof Schmid :Alpha testing38* Craig Elder :Release Management, Support39* Dani Saez :V Octo Support40* Doug Weibel :DCM, Libraries, Control law advice41* Emile Castelnuovo :VRBrain port, bug fixes42* Gregory Fletcher :Camera mount orientation math43* Guntars :Arming safety suggestion44* HappyKillmore :Mavlink GCS45* Hein Hollander :Octo Support, Heli Testing46* Igor van Airde :Control Law optimization47* Jack Dunkle :Alpha testing48* James Goppert :Mavlink Support49* Jani Hiriven :Testing feedback50* Jean-Louis Naudin :Auto Landing51* John Arne Birkeland :PPM Encoder52* Jose Julio :Stabilization Control laws, MPU6k driver53* Julien Dubois :PosHold flight mode54* Julian Oes :Pixhawk55* Jonathan Challinger :Inertial Navigation, CompassMot, Spin-When-Armed56* Kevin Hester :Andropilot GCS57* Max Levine :Tri Support, Graphics58* Leonard Hall :Flight Dynamics, Throttle, Loiter and Navigation Controllers59* Marco Robustini :Lead tester60* Michael Oborne :Mission Planner GCS61* Mike Smith :Pixhawk driver, coding support62* Olivier Adler :PPM Encoder, piezo buzzer63* Pat Hickey :Hardware Abstraction Layer (HAL)64* Robert Lefebvre :Heli Support, Copter LEDs65* Roberto Navoni :Library testing, Porting to VRBrain66* Sandro Benigno :Camera support, MinimOSD67* Sandro Tognana :PosHold flight mode68* Sebastian Quilter :SmartRTL69* ..and many more.70*71* Code commit statistics can be found here: https://github.com/ArduPilot/ardupilot/graphs/contributors72* Wiki: https://copter.ardupilot.org/73*74*/7576#include "Copter.h"77#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>7879#define FORCE_VERSION_H_INCLUDE80#include "version.h"81#undef FORCE_VERSION_H_INCLUDE8283const AP_HAL::HAL& hal = AP_HAL::get_HAL();8485#define SCHED_TASK(func, _interval_ticks, _max_time_micros, _prio) SCHED_TASK_CLASS(Copter, &copter, func, _interval_ticks, _max_time_micros, _prio)86#define FAST_TASK(func) FAST_TASK_CLASS(Copter, &copter, func)8788/*89scheduler table - all tasks should be listed here.9091All entries in this table must be ordered by priority.9293This table is interleaved with the table in AP_Vehicle to determine94the order in which tasks are run. Convenience methods SCHED_TASK95and SCHED_TASK_CLASS are provided to build entries in this structure:9697SCHED_TASK arguments:98- name of static function to call99- rate (in Hertz) at which the function should be called100- expected time (in MicroSeconds) that the function should take to run101- priority (0 through 255, lower number meaning higher priority)102103SCHED_TASK_CLASS arguments:104- class name of method to be called105- instance on which to call the method106- method to call on that instance107- rate (in Hertz) at which the method should be called108- expected time (in MicroSeconds) that the method should take to run109- priority (0 through 255, lower number meaning higher priority)110111*/112const AP_Scheduler::Task Copter::scheduler_tasks[] = {113// update INS immediately to get current gyro data populated114FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update),115// run low level rate controllers that only require IMU data116FAST_TASK(run_rate_controller_main),117#if AC_CUSTOMCONTROL_MULTI_ENABLED118FAST_TASK(run_custom_controller),119#endif120#if FRAME_CONFIG == HELI_FRAME121FAST_TASK(heli_update_autorotation),122#endif //HELI_FRAME123// send outputs to the motors library immediately124FAST_TASK(motors_output_main),125// run EKF state estimator (expensive)126FAST_TASK(read_AHRS),127#if FRAME_CONFIG == HELI_FRAME128FAST_TASK(update_heli_control_dynamics),129#endif //HELI_FRAME130// Inertial Nav131FAST_TASK(read_inertia),132// check if ekf has reset target heading or position133FAST_TASK(check_ekf_reset),134// run the attitude controllers135FAST_TASK(update_flight_mode),136// update home from EKF if necessary137FAST_TASK(update_home_from_EKF),138// check if we've landed or crashed139FAST_TASK(update_land_and_crash_detectors),140// surface tracking update141FAST_TASK(update_rangefinder_terrain_offset),142#if HAL_MOUNT_ENABLED143// camera mount's fast update144FAST_TASK_CLASS(AP_Mount, &copter.camera_mount, update_fast),145#endif146#if HAL_LOGGING_ENABLED147FAST_TASK(Log_Video_Stabilisation),148#endif149150SCHED_TASK(rc_loop, 250, 130, 3),151SCHED_TASK(throttle_loop, 50, 75, 6),152#if AP_FENCE_ENABLED153SCHED_TASK(fence_check, 25, 100, 7),154#endif155SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9),156#if AP_OPTICALFLOW_ENABLED157SCHED_TASK_CLASS(AP_OpticalFlow, &copter.optflow, update, 200, 160, 12),158#endif159SCHED_TASK(update_batt_compass, 10, 120, 15),160SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&copter.g2.rc_channels, read_aux_all, 10, 50, 18),161SCHED_TASK(arm_motors_check, 10, 50, 21),162#if TOY_MODE_ENABLED163SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50, 24),164#endif165SCHED_TASK(auto_disarm_check, 10, 50, 27),166SCHED_TASK(auto_trim, 10, 75, 30),167#if AP_RANGEFINDER_ENABLED168SCHED_TASK(read_rangefinder, 20, 100, 33),169#endif170#if HAL_PROXIMITY_ENABLED171SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50, 36),172#endif173#if AP_BEACON_ENABLED174SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50, 39),175#endif176SCHED_TASK(update_altitude, 10, 100, 42),177SCHED_TASK(run_nav_updates, 50, 100, 45),178SCHED_TASK(update_throttle_hover,100, 90, 48),179#if MODE_SMARTRTL_ENABLED180SCHED_TASK_CLASS(ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100, 51),181#endif182#if HAL_SPRAYER_ENABLED183SCHED_TASK_CLASS(AC_Sprayer, &copter.sprayer, update, 3, 90, 54),184#endif185SCHED_TASK(three_hz_loop, 3, 75, 57),186#if AP_SERVORELAYEVENTS_ENABLED187SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60),188#endif189#if AC_PRECLAND_ENABLED190SCHED_TASK(update_precland, 400, 50, 69),191#endif192#if FRAME_CONFIG == HELI_FRAME193SCHED_TASK(check_dynamic_flight, 50, 75, 72),194#endif195#if HAL_LOGGING_ENABLED196SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 75),197#endif198SCHED_TASK(one_hz_loop, 1, 100, 81),199SCHED_TASK(ekf_check, 10, 75, 84),200SCHED_TASK(check_vibration, 10, 50, 87),201SCHED_TASK(gpsglitch_check, 10, 50, 90),202SCHED_TASK(takeoff_check, 50, 50, 91),203#if AP_LANDINGGEAR_ENABLED204SCHED_TASK(landinggear_update, 10, 75, 93),205#endif206SCHED_TASK(standby_update, 100, 75, 96),207SCHED_TASK(lost_vehicle_check, 10, 50, 99),208SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_receive, 400, 180, 102),209SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_send, 400, 550, 105),210#if HAL_MOUNT_ENABLED211SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75, 108),212#endif213#if AP_CAMERA_ENABLED214SCHED_TASK_CLASS(AP_Camera, &copter.camera, update, 50, 75, 111),215#endif216#if HAL_LOGGING_ENABLED217SCHED_TASK(ten_hz_logging_loop, 10, 350, 114),218SCHED_TASK(twentyfive_hz_logging, 25, 110, 117),219SCHED_TASK_CLASS(AP_Logger, &copter.logger, periodic_tasks, 400, 300, 120),220#endif221SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50, 123),222223#if HAL_LOGGING_ENABLED224SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75, 126),225#endif226#if AP_RPM_ENABLED227SCHED_TASK_CLASS(AP_RPM, &copter.rpm_sensor, update, 40, 200, 129),228#endif229#if AP_TEMPCALIBRATION_ENABLED230SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100, 135),231#endif232#if HAL_ADSB_ENABLED233SCHED_TASK(avoidance_adsb_update, 10, 100, 138),234#endif235#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED236SCHED_TASK(afs_fs_check, 10, 100, 141),237#endif238#if AP_TERRAIN_AVAILABLE239SCHED_TASK(terrain_update, 10, 100, 144),240#endif241#if AP_WINCH_ENABLED242SCHED_TASK_CLASS(AP_Winch, &copter.g2.winch, update, 50, 50, 150),243#endif244#ifdef USERHOOK_FASTLOOP245SCHED_TASK(userhook_FastLoop, 100, 75, 153),246#endif247#ifdef USERHOOK_50HZLOOP248SCHED_TASK(userhook_50Hz, 50, 75, 156),249#endif250#ifdef USERHOOK_MEDIUMLOOP251SCHED_TASK(userhook_MediumLoop, 10, 75, 159),252#endif253#ifdef USERHOOK_SLOWLOOP254SCHED_TASK(userhook_SlowLoop, 3.3, 75, 162),255#endif256#ifdef USERHOOK_SUPERSLOWLOOP257SCHED_TASK(userhook_SuperSlowLoop, 1, 75, 165),258#endif259#if HAL_BUTTON_ENABLED260SCHED_TASK_CLASS(AP_Button, &copter.button, update, 5, 100, 168),261#endif262#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED263// don't delete this, there is an equivalent (virtual) in AP_Vehicle for the non-rate loop case264SCHED_TASK(update_dynamic_notch_at_specified_rate_main, LOOP_RATE, 200, 215),265#endif266};267268void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,269uint8_t &task_count,270uint32_t &log_bit)271{272tasks = &scheduler_tasks[0];273task_count = ARRAY_SIZE(scheduler_tasks);274log_bit = MASK_LOG_PM;275}276277constexpr int8_t Copter::_failsafe_priorities[7];278279280#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED281#if MODE_GUIDED_ENABLED282// set target location (for use by external control and scripting)283bool Copter::set_target_location(const Location& target_loc)284{285// exit if vehicle is not in Guided mode or Auto-Guided mode286if (!flightmode->in_guided_mode()) {287return false;288}289290return mode_guided.set_destination(target_loc);291}292293// start takeoff to given altitude (for use by scripting)294bool Copter::start_takeoff(const float alt)295{296// exit if vehicle is not in Guided mode or Auto-Guided mode297if (!flightmode->in_guided_mode()) {298return false;299}300301if (mode_guided.do_user_takeoff_start(alt * 100.0f)) {302copter.set_auto_armed(true);303return true;304}305return false;306}307#endif //MODE_GUIDED_ENABLED308#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED309310#if AP_SCRIPTING_ENABLED311#if MODE_GUIDED_ENABLED312// set target position (for use by scripting)313bool Copter::set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt)314{315// exit if vehicle is not in Guided mode or Auto-Guided mode316if (!flightmode->in_guided_mode()) {317return false;318}319320const Vector3f pos_neu_cm(target_pos.x * 100.0f, target_pos.y * 100.0f, -target_pos.z * 100.0f);321322return mode_guided.set_destination(pos_neu_cm, use_yaw, yaw_deg * 100.0, use_yaw_rate, yaw_rate_degs * 100.0, yaw_relative, terrain_alt);323}324325// set target position and velocity (for use by scripting)326bool Copter::set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel)327{328// exit if vehicle is not in Guided mode or Auto-Guided mode329if (!flightmode->in_guided_mode()) {330return false;331}332333const Vector3f pos_neu_cm(target_pos.x * 100.0f, target_pos.y * 100.0f, -target_pos.z * 100.0f);334const Vector3f vel_neu_cms(target_vel.x * 100.0f, target_vel.y * 100.0f, -target_vel.z * 100.0f);335336return mode_guided.set_destination_posvelaccel(pos_neu_cm, vel_neu_cms, Vector3f());337}338339// set target position, velocity and acceleration (for use by scripting)340bool Copter::set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative)341{342// exit if vehicle is not in Guided mode or Auto-Guided mode343if (!flightmode->in_guided_mode()) {344return false;345}346347const Vector3f pos_neu_cm(target_pos.x * 100.0f, target_pos.y * 100.0f, -target_pos.z * 100.0f);348const Vector3f vel_neu_cms(target_vel.x * 100.0f, target_vel.y * 100.0f, -target_vel.z * 100.0f);349const Vector3f accel_neu_cms(target_accel.x * 100.0f, target_accel.y * 100.0f, -target_accel.z * 100.0f);350351return mode_guided.set_destination_posvelaccel(pos_neu_cm, vel_neu_cms, accel_neu_cms, use_yaw, yaw_deg * 100.0, use_yaw_rate, yaw_rate_degs * 100.0, yaw_relative);352}353354bool Copter::set_target_velocity_NED(const Vector3f& vel_ned)355{356// exit if vehicle is not in Guided mode or Auto-Guided mode357if (!flightmode->in_guided_mode()) {358return false;359}360361// convert vector to neu in cm362const Vector3f vel_neu_cms(vel_ned.x * 100.0f, vel_ned.y * 100.0f, -vel_ned.z * 100.0f);363mode_guided.set_velocity(vel_neu_cms);364return true;365}366367// set target velocity and acceleration (for use by scripting)368bool Copter::set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool relative_yaw)369{370// exit if vehicle is not in Guided mode or Auto-Guided mode371if (!flightmode->in_guided_mode()) {372return false;373}374375// convert vector to neu in cm376const Vector3f vel_neu_cms(target_vel.x * 100.0f, target_vel.y * 100.0f, -target_vel.z * 100.0f);377const Vector3f accel_neu_cms(target_accel.x * 100.0f, target_accel.y * 100.0f, -target_accel.z * 100.0f);378379mode_guided.set_velaccel(vel_neu_cms, accel_neu_cms, use_yaw, yaw_deg * 100.0, use_yaw_rate, yaw_rate_degs * 100.0, relative_yaw);380return true;381}382383// set target roll pitch and yaw angles with throttle (for use by scripting)384bool Copter::set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs)385{386// exit if vehicle is not in Guided mode or Auto-Guided mode387if (!flightmode->in_guided_mode()) {388return false;389}390391Quaternion q;392q.from_euler(radians(roll_deg),radians(pitch_deg),radians(yaw_deg));393394mode_guided.set_angle(q, Vector3f{}, climb_rate_ms*100, false);395return true;396}397398// set target roll pitch and yaw rates with throttle (for use by scripting)399bool Copter::set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle)400{401// exit if vehicle is not in Guided mode or Auto-Guided mode402if (!flightmode->in_guided_mode()) {403return false;404}405406// Zero quaternion indicates rate control407Quaternion q;408q.zero();409410// Convert from degrees per second to radians per second411Vector3f ang_vel_body { roll_rate_dps, pitch_rate_dps, yaw_rate_dps };412ang_vel_body *= DEG_TO_RAD;413414// Pass to guided mode415mode_guided.set_angle(q, ang_vel_body, throttle, true);416return true;417}418419// Register a custom mode with given number and names420AP_Vehicle::custom_mode_state* Copter::register_custom_mode(const uint8_t num, const char* full_name, const char* short_name)421{422const Mode::Number number = (Mode::Number)num;423424// See if this mode has been registered already, if it has return the state for it425// This allows scripting restarts426for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {427if (mode_guided_custom[i] == nullptr) {428break;429}430if ((mode_guided_custom[i]->mode_number() == number) &&431(strcmp(mode_guided_custom[i]->name(), full_name) == 0) &&432(strncmp(mode_guided_custom[i]->name4(), short_name, 4) == 0)) {433return &mode_guided_custom[i]->state;434}435}436437// Number already registered to existing mode438if (mode_from_mode_num(number) != nullptr) {439return nullptr;440}441442// Find free slot443for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {444if (mode_guided_custom[i] == nullptr) {445// Duplicate strings so were not pointing to unknown memory446const char* full_name_copy = strdup(full_name);447const char* short_name_copy = strndup(short_name, 4);448if ((full_name_copy != nullptr) && (short_name_copy != nullptr)) {449mode_guided_custom[i] = NEW_NOTHROW ModeGuidedCustom(number, full_name_copy, short_name_copy);450}451if (mode_guided_custom[i] == nullptr) {452// Allocation failure453return nullptr;454}455456// Registration sucsessful, notify the GCS that it should re-request the avalable modes457gcs().available_modes_changed();458459return &mode_guided_custom[i]->state;460}461}462463// No free slots464return nullptr;465}466#endif // MODE_GUIDED_ENABLED467468#if MODE_CIRCLE_ENABLED469// circle mode controls470bool Copter::get_circle_radius(float &radius_m)471{472radius_m = circle_nav->get_radius() * 0.01f;473return true;474}475476bool Copter::set_circle_rate(float rate_dps)477{478circle_nav->set_rate(rate_dps);479return true;480}481#endif482483// set desired speed (m/s). Used for scripting.484bool Copter::set_desired_speed(float speed)485{486return flightmode->set_speed_xy(speed * 100.0f);487}488489#if MODE_AUTO_ENABLED490// returns true if mode supports NAV_SCRIPT_TIME mission commands491bool Copter::nav_scripting_enable(uint8_t mode)492{493return mode == (uint8_t)mode_auto.mode_number();494}495496// lua scripts use this to retrieve the contents of the active command497bool Copter::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)498{499if (flightmode != &mode_auto) {500return false;501}502503return mode_auto.nav_script_time(id, cmd, arg1, arg2, arg3, arg4);504}505506// lua scripts use this to indicate when they have complete the command507void Copter::nav_script_time_done(uint16_t id)508{509if (flightmode != &mode_auto) {510return;511}512513return mode_auto.nav_script_time_done(id);514}515#endif516517// returns true if the EKF failsafe has triggered. Only used by Lua scripts518bool Copter::has_ekf_failsafed() const519{520return failsafe.ekf;521}522523// get target location (for use by scripting)524bool Copter::get_target_location(Location& target_loc)525{526return flightmode->get_wp(target_loc);527}528529/*530update_target_location() acts as a wrapper for set_target_location531*/532bool Copter::update_target_location(const Location &old_loc, const Location &new_loc)533{534/*535by checking the caller has provided the correct old target536location we prevent a race condition where the user changes mode537or commands a different target in the controlling lua script538*/539Location next_WP_loc;540flightmode->get_wp(next_WP_loc);541if (!old_loc.same_loc_as(next_WP_loc) ||542old_loc.get_alt_frame() != new_loc.get_alt_frame()) {543return false;544}545546return set_target_location(new_loc);547}548549#endif // AP_SCRIPTING_ENABLED550551// returns true if vehicle is landing.552bool Copter::is_landing() const553{554return flightmode->is_landing();555}556557// returns true if vehicle is taking off.558bool Copter::is_taking_off() const559{560return flightmode->is_taking_off();561}562563bool Copter::current_mode_requires_mission() const564{565#if MODE_AUTO_ENABLED566return flightmode == &mode_auto;567#else568return false;569#endif570}571572// rc_loops - reads user input from transmitter/receiver573// called at 100hz574void Copter::rc_loop()575{576// Read radio and 3-position switch on radio577// -----------------------------------------578read_radio();579rc().read_mode_switch();580}581582// throttle_loop - should be run at 50 hz583// ---------------------------584void Copter::throttle_loop()585{586// update throttle_low_comp value (controls priority of throttle vs attitude control)587update_throttle_mix();588589// check auto_armed status590update_auto_armed();591592#if FRAME_CONFIG == HELI_FRAME593// update rotor speed594heli_update_rotor_speed_targets();595596// update trad heli swash plate movement597heli_update_landing_swash();598#endif599600// compensate for ground effect (if enabled)601update_ground_effect_detector();602update_ekf_terrain_height_stable();603}604605// update_batt_compass - read battery and compass606// should be called at 10hz607void Copter::update_batt_compass(void)608{609// read battery before compass because it may be used for motor interference compensation610battery.read();611612if(AP::compass().available()) {613// update compass with throttle value - used for compassmot614compass.set_throttle(motors->get_throttle());615compass.set_voltage(battery.voltage());616compass.read();617}618}619620#if HAL_LOGGING_ENABLED621// Full rate logging of attitude, rate and pid loops622// should be run at loop rate623void Copter::loop_rate_logging()624{625if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {626Log_Write_Attitude();627if (!using_rate_thread) {628Log_Write_Rate();629Log_Write_PIDS(); // only logs if PIDS bitmask is set630}631}632#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED633if (should_log(MASK_LOG_FTN_FAST) && !using_rate_thread) {634AP::ins().write_notch_log_messages();635}636#endif637if (should_log(MASK_LOG_IMU_FAST)) {638AP::ins().Write_IMU();639}640}641642// ten_hz_logging_loop643// should be run at 10hz644void Copter::ten_hz_logging_loop()645{646// always write AHRS attitude at 10Hz647ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);648// log attitude controller data if we're not already logging at the higher rate649if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {650Log_Write_Attitude();651if (!using_rate_thread) {652Log_Write_Rate();653}654}655if (!should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {656// log at 10Hz if PIDS bitmask is selected, even if no ATT bitmask is selected; logs at looprate if ATT_FAST and PIDS bitmask set657if (!using_rate_thread) {658Log_Write_PIDS();659}660}661// log EKF attitude data always at 10Hz unless ATTITUDE_FAST, then do it in the 25Hz loop662if (!should_log(MASK_LOG_ATTITUDE_FAST)) {663Log_Write_EKF_POS();664}665if ((FRAME_CONFIG == HELI_FRAME) || should_log(MASK_LOG_MOTBATT)) {666// always write motors log if we are a heli667motors->Log_Write();668}669if (should_log(MASK_LOG_RCIN)) {670logger.Write_RCIN();671#if AP_RSSI_ENABLED672if (rssi.enabled()) {673logger.Write_RSSI();674}675#endif676}677if (should_log(MASK_LOG_RCOUT)) {678logger.Write_RCOUT();679}680if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS() || !flightmode->has_manual_throttle())) {681pos_control->write_log();682}683if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {684AP::ins().Write_Vibration();685}686if (should_log(MASK_LOG_CTUN)) {687attitude_control->control_monitor_log();688#if HAL_PROXIMITY_ENABLED689g2.proximity.log(); // Write proximity sensor distances690#endif691#if AP_BEACON_ENABLED692g2.beacon.log();693#endif694}695#if AP_WINCH_ENABLED696if (should_log(MASK_LOG_ANY)) {697g2.winch.write_log();698}699#endif700#if HAL_MOUNT_ENABLED701if (should_log(MASK_LOG_CAMERA)) {702camera_mount.write_log();703}704#endif705}706707// twentyfive_hz_logging - should be run at 25hz708void Copter::twentyfive_hz_logging()709{710if (should_log(MASK_LOG_ATTITUDE_FAST)) {711Log_Write_EKF_POS();712}713714if (should_log(MASK_LOG_IMU) && !(should_log(MASK_LOG_IMU_FAST))) {715AP::ins().Write_IMU();716}717718#if MODE_AUTOROTATE_ENABLED719if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) {720//update autorotation log721g2.arot.Log_Write_Autorotation();722}723#endif724#if HAL_GYROFFT_ENABLED725if (should_log(MASK_LOG_FTN_FAST)) {726gyro_fft.write_log_messages();727}728#endif729}730#endif // HAL_LOGGING_ENABLED731732// three_hz_loop - 3hz loop733void Copter::three_hz_loop()734{735// check if we've lost contact with the ground station736failsafe_gcs_check();737738// check if we've lost terrain data739failsafe_terrain_check();740741// check for deadreckoning failsafe742failsafe_deadreckon_check();743744//update transmitter based in flight tuning745tuning();746747// check if avoidance should be enabled based on alt748low_alt_avoidance();749}750751// ap_value calculates a 32-bit bitmask representing various pieces of752// state about the Copter. It replaces a global variable which was753// used to track this state.754uint32_t Copter::ap_value() const755{756uint32_t ret = 0;757758const bool *b = (const bool *)≈759for (uint8_t i=0; i<sizeof(ap); i++) {760if (b[i]) {761ret |= 1U<<i;762}763}764765return ret;766}767768// one_hz_loop - runs at 1Hz769void Copter::one_hz_loop()770{771#if HAL_LOGGING_ENABLED772if (should_log(MASK_LOG_ANY)) {773Log_Write_Data(LogDataID::AP_STATE, ap_value());774}775#endif776777if (!motors->armed()) {778update_using_interlock();779780// check the user hasn't updated the frame class or type781motors->set_frame_class_and_type((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());782783#if FRAME_CONFIG != HELI_FRAME784// set all throttle channel settings785motors->update_throttle_range();786#endif787}788789// update assigned functions and enable auxiliary servos790AP::srv().enable_aux_servos();791792#if HAL_LOGGING_ENABLED793// log terrain data794terrain_logging();795#endif796797#if HAL_ADSB_ENABLED798adsb.set_is_flying(!ap.land_complete);799#endif800801AP_Notify::flags.flying = !ap.land_complete;802803// slowly update the PID notches with the average loop rate804if (!using_rate_thread) {805attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());806}807pos_control->get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());808#if AC_CUSTOMCONTROL_MULTI_ENABLED809custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());810#endif811812#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED813// see if we should have a separate rate thread814if (!started_rate_thread && get_fast_rate_type() != FastRateType::FAST_RATE_DISABLED) {815if (hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&Copter::rate_controller_thread, void),816"rate",8171536, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) {818started_rate_thread = true;819} else {820AP_BoardConfig::allocation_error("rate thread");821}822}823#endif824}825826void Copter::init_simple_bearing()827{828// capture current cos_yaw and sin_yaw values829simple_cos_yaw = ahrs.cos_yaw();830simple_sin_yaw = ahrs.sin_yaw();831832// initialise super simple heading (i.e. heading towards home) to be 180 deg from simple mode heading833super_simple_last_bearing = wrap_360_cd(ahrs.yaw_sensor+18000);834super_simple_cos_yaw = simple_cos_yaw;835super_simple_sin_yaw = simple_sin_yaw;836837#if HAL_LOGGING_ENABLED838// log the simple bearing839if (should_log(MASK_LOG_ANY)) {840Log_Write_Data(LogDataID::INIT_SIMPLE_BEARING, ahrs.yaw_sensor);841}842#endif843}844845// update_simple_mode - rotates pilot input if we are in simple mode846void Copter::update_simple_mode(void)847{848float rollx, pitchx;849850// exit immediately if no new radio frame or not in simple mode851if (simple_mode == SimpleMode::NONE || !ap.new_radio_frame) {852return;853}854855// mark radio frame as consumed856ap.new_radio_frame = false;857858if (simple_mode == SimpleMode::SIMPLE) {859// rotate roll, pitch input by -initial simple heading (i.e. north facing)860rollx = channel_roll->get_control_in()*simple_cos_yaw - channel_pitch->get_control_in()*simple_sin_yaw;861pitchx = channel_roll->get_control_in()*simple_sin_yaw + channel_pitch->get_control_in()*simple_cos_yaw;862}else{863// rotate roll, pitch input by -super simple heading (reverse of heading to home)864rollx = channel_roll->get_control_in()*super_simple_cos_yaw - channel_pitch->get_control_in()*super_simple_sin_yaw;865pitchx = channel_roll->get_control_in()*super_simple_sin_yaw + channel_pitch->get_control_in()*super_simple_cos_yaw;866}867868// rotate roll, pitch input from north facing to vehicle's perspective869channel_roll->set_control_in(rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw());870channel_pitch->set_control_in(-rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw());871}872873// update_super_simple_bearing - adjusts simple bearing based on location874// should be called after home_bearing has been updated875void Copter::update_super_simple_bearing(bool force_update)876{877if (!force_update) {878if (simple_mode != SimpleMode::SUPERSIMPLE) {879return;880}881if (home_distance() < SUPER_SIMPLE_RADIUS) {882return;883}884}885886const int32_t bearing = home_bearing();887888// check the bearing to home has changed by at least 5 degrees889if (labs(super_simple_last_bearing - bearing) < 500) {890return;891}892893super_simple_last_bearing = bearing;894const float angle_rad = radians((super_simple_last_bearing+18000)/100);895super_simple_cos_yaw = cosf(angle_rad);896super_simple_sin_yaw = sinf(angle_rad);897}898899void Copter::read_AHRS(void)900{901// we tell AHRS to skip INS update as we have already done it in FAST_TASK.902ahrs.update(true);903}904905// read baro and log control tuning906void Copter::update_altitude()907{908// read in baro altitude909read_barometer();910911#if HAL_LOGGING_ENABLED912if (should_log(MASK_LOG_CTUN)) {913Log_Write_Control_Tuning();914if (!should_log(MASK_LOG_FTN_FAST)) {915#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED916AP::ins().write_notch_log_messages();917#endif918#if HAL_GYROFFT_ENABLED919gyro_fft.write_log_messages();920#endif921}922}923#endif924}925926// vehicle specific waypoint info helpers927bool Copter::get_wp_distance_m(float &distance) const928{929// see GCS_MAVLINK_Copter::send_nav_controller_output()930distance = flightmode->wp_distance() * 0.01;931return true;932}933934// vehicle specific waypoint info helpers935bool Copter::get_wp_bearing_deg(float &bearing) const936{937// see GCS_MAVLINK_Copter::send_nav_controller_output()938bearing = flightmode->wp_bearing() * 0.01;939return true;940}941942// vehicle specific waypoint info helpers943bool Copter::get_wp_crosstrack_error_m(float &xtrack_error) const944{945// see GCS_MAVLINK_Copter::send_nav_controller_output()946xtrack_error = flightmode->crosstrack_error() * 0.01;947return true;948}949950// get the target earth-frame angular velocities in rad/s (Z-axis component used by some gimbals)951bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const952{953// always returns zero vector if landed or disarmed954if (copter.ap.land_complete) {955rate_ef_targets.zero();956} else {957rate_ef_targets = attitude_control->get_rate_ef_targets();958}959return true;960}961962/*963constructor for main Copter class964*/965Copter::Copter(void)966:967flight_modes(&g.flight_mode1),968pos_variance_filt(FS_EKF_FILT_DEFAULT),969vel_variance_filt(FS_EKF_FILT_DEFAULT),970hgt_variance_filt(FS_EKF_FILT_DEFAULT),971flightmode(&mode_stabilize),972simple_cos_yaw(1.0f),973super_simple_cos_yaw(1.0),974land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),975rc_throttle_control_in_filter(1.0f),976inertial_nav(ahrs),977param_loader(var_info)978{979}980981Copter copter;982AP_Vehicle& vehicle = copter;983984AP_HAL_MAIN_CALLBACKS(&copter);985986987