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/ArduPlane/Plane.cpp
Views: 1798
/*1Lead developer: Andrew Tridgell23Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler, Amilcar Lucas, Gregory Fletcher, Paul Riseborough, Brandon Jones, Jon Challinger, Tom Pittenger4Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier, Yury MonZon56Please contribute your ideas! See https://ardupilot.org/dev for details78This program is free software: you can redistribute it and/or modify9it under the terms of the GNU General Public License as published by10the Free Software Foundation, either version 3 of the License, or11(at your option) any later version.1213This program is distributed in the hope that it will be useful,14but WITHOUT ANY WARRANTY; without even the implied warranty of15MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the16GNU General Public License for more details.1718You should have received a copy of the GNU General Public License19along with this program. If not, see <http://www.gnu.org/licenses/>.20*/2122#include "Plane.h"2324#define FORCE_VERSION_H_INCLUDE25#include "version.h"26#undef FORCE_VERSION_H_INCLUDE2728const AP_HAL::HAL& hal = AP_HAL::get_HAL();2930#define SCHED_TASK(func, rate_hz, max_time_micros, priority) SCHED_TASK_CLASS(Plane, &plane, func, rate_hz, max_time_micros, priority)31#define FAST_TASK(func) FAST_TASK_CLASS(Plane, &plane, func)323334/*35scheduler table - all regular tasks should be listed here.3637All entries in this table must be ordered by priority.3839This table is interleaved with the table present in each of the40vehicles to determine the order in which tasks are run. Convenience41methods SCHED_TASK and SCHED_TASK_CLASS are provided to build42entries in this structure:4344SCHED_TASK arguments:45- name of static function to call46- rate (in Hertz) at which the function should be called47- expected time (in MicroSeconds) that the function should take to run48- priority (0 through 255, lower number meaning higher priority)4950SCHED_TASK_CLASS arguments:51- class name of method to be called52- instance on which to call the method53- method to call on that instance54- rate (in Hertz) at which the method should be called55- expected time (in MicroSeconds) that the method should take to run56- priority (0 through 255, lower number meaning higher priority)5758FAST_TASK entries are run on every loop even if that means the loop59overruns its allotted time60*/61const AP_Scheduler::Task Plane::scheduler_tasks[] = {62// Units: Hz us63FAST_TASK(ahrs_update),64FAST_TASK(update_control_mode),65FAST_TASK(stabilize),66FAST_TASK(set_servos),67SCHED_TASK(read_radio, 50, 100, 6),68SCHED_TASK(check_short_failsafe, 50, 100, 9),69SCHED_TASK(update_speed_height, 50, 200, 12),70SCHED_TASK(update_throttle_hover, 100, 90, 24),71SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&plane.g2.rc_channels, read_mode_switch, 7, 100, 27),72SCHED_TASK(update_GPS_50Hz, 50, 300, 30),73SCHED_TASK(update_GPS_10Hz, 10, 400, 33),74SCHED_TASK(navigate, 10, 150, 36),75SCHED_TASK(update_compass, 10, 200, 39),76SCHED_TASK(calc_airspeed_errors, 10, 100, 42),77SCHED_TASK(update_alt, 10, 200, 45),78SCHED_TASK(adjust_altitude_target, 10, 200, 48),79#if AP_ADVANCEDFAILSAFE_ENABLED80SCHED_TASK(afs_fs_check, 10, 100, 51),81#endif82SCHED_TASK(ekf_check, 10, 75, 54),83SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_receive, 300, 500, 57),84SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_send, 300, 750, 60),85#if AP_SERVORELAYEVENTS_ENABLED86SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150, 63),87#endif88SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300, 66),89#if AP_RANGEFINDER_ENABLED90SCHED_TASK(read_rangefinder, 50, 100, 78),91#endif92#if AP_ICENGINE_ENABLED93SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81),94#endif95#if AP_OPTICALFLOW_ENABLED96SCHED_TASK_CLASS(AP_OpticalFlow, &plane.optflow, update, 50, 50, 87),97#endif98SCHED_TASK(one_second_loop, 1, 400, 90),99SCHED_TASK(three_hz_loop, 3, 75, 93),100SCHED_TASK(check_long_failsafe, 3, 400, 96),101#if AP_RPM_ENABLED102SCHED_TASK_CLASS(AP_RPM, &plane.rpm_sensor, update, 10, 100, 99),103#endif104#if AP_AIRSPEED_AUTOCAL_ENABLE105SCHED_TASK(airspeed_ratio_update, 1, 100, 102),106#endif // AP_AIRSPEED_AUTOCAL_ENABLE107#if HAL_MOUNT_ENABLED108SCHED_TASK_CLASS(AP_Mount, &plane.camera_mount, update, 50, 100, 105),109#endif // HAL_MOUNT_ENABLED110#if AP_CAMERA_ENABLED111SCHED_TASK_CLASS(AP_Camera, &plane.camera, update, 50, 100, 108),112#endif // CAMERA == ENABLED113#if HAL_LOGGING_ENABLED114SCHED_TASK_CLASS(AP_Scheduler, &plane.scheduler, update_logging, 0.2, 100, 111),115#endif116SCHED_TASK(compass_save, 0.1, 200, 114),117#if HAL_LOGGING_ENABLED118SCHED_TASK(Log_Write_FullRate, 400, 300, 117),119SCHED_TASK(update_logging10, 10, 300, 120),120SCHED_TASK(update_logging25, 25, 300, 123),121#endif122#if HAL_SOARING_ENABLED123SCHED_TASK(update_soaring, 50, 400, 126),124#endif125SCHED_TASK(parachute_check, 10, 200, 129),126#if AP_TERRAIN_AVAILABLE127SCHED_TASK_CLASS(AP_Terrain, &plane.terrain, update, 10, 200, 132),128#endif // AP_TERRAIN_AVAILABLE129SCHED_TASK(update_is_flying_5Hz, 5, 100, 135),130#if HAL_LOGGING_ENABLED131SCHED_TASK_CLASS(AP_Logger, &plane.logger, periodic_tasks, 50, 400, 138),132#endif133SCHED_TASK_CLASS(AP_InertialSensor, &plane.ins, periodic, 50, 50, 141),134#if HAL_ADSB_ENABLED135SCHED_TASK(avoidance_adsb_update, 10, 100, 144),136#endif137SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&plane.g2.rc_channels, read_aux_all, 10, 200, 147),138#if HAL_BUTTON_ENABLED139SCHED_TASK_CLASS(AP_Button, &plane.button, update, 5, 100, 150),140#endif141#if AP_LANDINGGEAR_ENABLED142SCHED_TASK(landing_gear_update, 5, 50, 159),143#endif144#if AC_PRECLAND_ENABLED145SCHED_TASK(precland_update, 400, 50, 160),146#endif147#if AP_QUICKTUNE_ENABLED148SCHED_TASK(update_quicktune, 40, 100, 163),149#endif150};151152void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,153uint8_t &task_count,154uint32_t &log_bit)155{156tasks = &scheduler_tasks[0];157task_count = ARRAY_SIZE(scheduler_tasks);158log_bit = MASK_LOG_PM;159}160161#if HAL_QUADPLANE_ENABLED162constexpr int8_t Plane::_failsafe_priorities[7];163#else164constexpr int8_t Plane::_failsafe_priorities[6];165#endif166167// update AHRS system168void Plane::ahrs_update()169{170arming.update_soft_armed();171172ahrs.update();173174#if HAL_LOGGING_ENABLED175if (should_log(MASK_LOG_IMU)) {176AP::ins().Write_IMU();177}178#endif179180// calculate a scaled roll limit based on current pitch181roll_limit_cd = aparm.roll_limit*100;182pitch_limit_min = aparm.pitch_limit_min;183184bool rotate_limits = true;185#if HAL_QUADPLANE_ENABLED186if (quadplane.tailsitter.active()) {187rotate_limits = false;188}189#endif190if (rotate_limits) {191roll_limit_cd *= ahrs.cos_pitch();192pitch_limit_min *= fabsf(ahrs.cos_roll());193}194195// updated the summed gyro used for ground steering and196// auto-takeoff. Dot product of DCM.c with gyro vector gives earth197// frame yaw rate198steer_state.locked_course_err += ahrs.get_yaw_rate_earth() * G_Dt;199steer_state.locked_course_err = wrap_PI(steer_state.locked_course_err);200201#if HAL_QUADPLANE_ENABLED202// check if we have had a yaw reset from the EKF203quadplane.check_yaw_reset();204205// update inertial_nav for quadplane206quadplane.inertial_nav.update();207#endif208209#if HAL_LOGGING_ENABLED210if (should_log(MASK_LOG_VIDEO_STABILISATION)) {211ahrs.write_video_stabilisation();212}213#endif214}215216/*217update 50Hz speed/height controller218*/219void Plane::update_speed_height(void)220{221bool should_run_tecs = control_mode->does_auto_throttle();222#if HAL_QUADPLANE_ENABLED223if (quadplane.should_disable_TECS()) {224should_run_tecs = false;225}226#endif227228if (auto_state.idle_mode) {229should_run_tecs = false;230}231232#if AP_PLANE_GLIDER_PULLUP_ENABLED233if (mode_auto.in_pullup()) {234should_run_tecs = false;235}236#endif237238if (should_run_tecs) {239// Call TECS 50Hz update. Note that we call this regardless of240// throttle suppressed, as this needs to be running for241// takeoff detection242TECS_controller.update_50hz();243}244245#if HAL_QUADPLANE_ENABLED246if (quadplane.in_vtol_mode() ||247quadplane.in_assisted_flight()) {248quadplane.update_throttle_mix();249}250#endif251}252253254/*255read and update compass256*/257void Plane::update_compass(void)258{259compass.read();260}261262#if HAL_LOGGING_ENABLED263/*264do 10Hz logging265*/266void Plane::update_logging10(void)267{268bool log_faster = (should_log(MASK_LOG_ATTITUDE_FULLRATE) || should_log(MASK_LOG_ATTITUDE_FAST));269if (should_log(MASK_LOG_ATTITUDE_MED) && !log_faster) {270Log_Write_Attitude();271ahrs.Write_AOA_SSA();272} else if (log_faster) {273ahrs.Write_AOA_SSA();274}275#if HAL_MOUNT_ENABLED276if (should_log(MASK_LOG_CAMERA)) {277camera_mount.write_log();278}279#endif280}281282/*283do 25Hz logging284*/285void Plane::update_logging25(void)286{287// MASK_LOG_ATTITUDE_FULLRATE logs at 400Hz, MASK_LOG_ATTITUDE_FAST at 25Hz, MASK_LOG_ATTIUDE_MED logs at 10Hz288// highest rate selected wins289bool log_faster = should_log(MASK_LOG_ATTITUDE_FULLRATE);290if (should_log(MASK_LOG_ATTITUDE_FAST) && !log_faster) {291Log_Write_Attitude();292}293294if (should_log(MASK_LOG_CTUN)) {295Log_Write_Control_Tuning();296#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED297if (!should_log(MASK_LOG_NOTCH_FULLRATE)) {298AP::ins().write_notch_log_messages();299}300#endif301#if HAL_GYROFFT_ENABLED302gyro_fft.write_log_messages();303#endif304}305306if (should_log(MASK_LOG_NTUN)) {307Log_Write_Nav_Tuning();308Log_Write_Guided();309}310311if (should_log(MASK_LOG_RC))312Log_Write_RC();313314if (should_log(MASK_LOG_IMU))315AP::ins().Write_Vibration();316}317#endif // HAL_LOGGING_ENABLED318319/*320check for AFS failsafe check321*/322#if AP_ADVANCEDFAILSAFE_ENABLED323void Plane::afs_fs_check(void)324{325afs.check(failsafe.AFS_last_valid_rc_ms);326}327#endif328329#if HAL_WITH_IO_MCU330#include <AP_IOMCU/AP_IOMCU.h>331extern AP_IOMCU iomcu;332#endif333334void Plane::one_second_loop()335{336// make it possible to change control channel ordering at runtime337set_control_channels();338339#if HAL_WITH_IO_MCU340iomcu.setup_mixing(g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask);341#endif342343#if HAL_ADSB_ENABLED344adsb.set_stall_speed_cm(aparm.airspeed_min * 100); // convert m/s to cm/s345adsb.set_max_speed(aparm.airspeed_max);346#endif347348if (flight_option_enabled(FlightOptions::ENABLE_DEFAULT_AIRSPEED)) {349// use average of min and max airspeed as default airspeed fusion with high variance350ahrs.writeDefaultAirSpeed((float)((aparm.airspeed_min + aparm.airspeed_max)/2),351(float)((aparm.airspeed_max - aparm.airspeed_min)/2));352}353354// sync MAVLink system ID355mavlink_system.sysid = g.sysid_this_mav;356357AP::srv().enable_aux_servos();358359// update notify flags360AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);361AP_Notify::flags.pre_arm_gps_check = true;362AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::Required::NO;363364#if AP_TERRAIN_AVAILABLE && HAL_LOGGING_ENABLED365if (should_log(MASK_LOG_GPS)) {366terrain.log_terrain_data();367}368#endif369370// update home position if NOT armed and gps position has371// changed. Update every 5s at most372if (!arming.is_armed() &&373gps.last_message_time_ms() - last_home_update_ms > 5000 &&374gps.status() >= AP_GPS::GPS_OK_FIX_3D) {375last_home_update_ms = gps.last_message_time_ms();376update_home();377378// reset the landing altitude correction379landing.alt_offset = 0;380}381382// this ensures G_Dt is correct, catching startup issues with constructors383// calling the scheduler methods384if (!is_equal(1.0f/scheduler.get_loop_rate_hz(), scheduler.get_loop_period_s()) ||385!is_equal(G_Dt, scheduler.get_loop_period_s())) {386INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);387}388389const float loop_rate = AP::scheduler().get_filtered_loop_rate_hz();390#if HAL_QUADPLANE_ENABLED391if (quadplane.available()) {392quadplane.attitude_control->set_notch_sample_rate(loop_rate);393}394#endif395rollController.set_notch_sample_rate(loop_rate);396pitchController.set_notch_sample_rate(loop_rate);397yawController.set_notch_sample_rate(loop_rate);398}399400void Plane::three_hz_loop()401{402#if AP_FENCE_ENABLED403fence_check();404#endif405}406407void Plane::compass_save()408{409if (AP::compass().available() &&410compass.get_learn_type() >= Compass::LEARN_INTERNAL &&411!hal.util->get_soft_armed()) {412/*413only save offsets when disarmed414*/415compass.save_offsets();416}417}418419#if AP_AIRSPEED_AUTOCAL_ENABLE420/*421once a second update the airspeed calibration ratio422*/423void Plane::airspeed_ratio_update(void)424{425if (!airspeed.enabled() ||426gps.status() < AP_GPS::GPS_OK_FIX_3D ||427gps.ground_speed() < 4) {428// don't calibrate when not moving429return;430}431if (airspeed.get_airspeed() < aparm.airspeed_min &&432gps.ground_speed() < (uint32_t)aparm.airspeed_min) {433// don't calibrate when flying below the minimum airspeed. We434// check both airspeed and ground speed to catch cases where435// the airspeed ratio is way too low, which could lead to it436// never coming up again437return;438}439if (labs(ahrs.roll_sensor) > roll_limit_cd ||440ahrs.pitch_sensor > aparm.pitch_limit_max*100 ||441ahrs.pitch_sensor < pitch_limit_min*100) {442// don't calibrate when going beyond normal flight envelope443return;444}445const Vector3f &vg = gps.velocity();446airspeed.update_calibration(vg, aparm.airspeed_max);447}448#endif // AP_AIRSPEED_AUTOCAL_ENABLE449450/*451read the GPS and update position452*/453void Plane::update_GPS_50Hz(void)454{455gps.update();456457update_current_loc();458}459460/*461read update GPS position - 10Hz update462*/463void Plane::update_GPS_10Hz(void)464{465static uint32_t last_gps_msg_ms;466if (gps.last_message_time_ms() != last_gps_msg_ms && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {467last_gps_msg_ms = gps.last_message_time_ms();468469if (ground_start_count > 1) {470ground_start_count--;471} else if (ground_start_count == 1) {472// We countdown N number of good GPS fixes473// so that the altitude is more accurate474// -------------------------------------475if (current_loc.lat == 0 && current_loc.lng == 0) {476ground_start_count = 5;477478} else if (!hal.util->was_watchdog_reset()) {479if (!set_home_persistently(gps.location())) {480// silently ignore failure...481}482483next_WP_loc = prev_WP_loc = home;484485ground_start_count = 0;486}487}488489// update wind estimate490ahrs.estimate_wind();491} else if (gps.status() < AP_GPS::GPS_OK_FIX_3D && ground_start_count != 0) {492// lost 3D fix, start again493ground_start_count = 5;494}495496calc_gndspeed_undershoot();497}498499/*500main control mode dependent update code501*/502void Plane::update_control_mode(void)503{504if ((control_mode != &mode_auto) && (control_mode != &mode_takeoff)) {505// hold_course is only used in takeoff and landing506steer_state.hold_course_cd = -1;507}508// refresh the throttle limits, to avoid using stale values509// they will be updated once takeoff_calc_throttle is called510takeoff_state.throttle_lim_max = 100.0f;511takeoff_state.throttle_lim_min = -100.0f;512513update_fly_forward();514515control_mode->update();516}517518519void Plane::update_fly_forward(void)520{521// ensure we are fly-forward when we are flying as a pure fixed522// wing aircraft. This helps the EKF produce better state523// estimates as it can make stronger assumptions524#if HAL_QUADPLANE_ENABLED525if (quadplane.available()) {526if (quadplane.tailsitter.is_in_fw_flight()) {527ahrs.set_fly_forward(true);528return;529}530531if (quadplane.in_vtol_mode()) {532ahrs.set_fly_forward(false);533return;534}535536if (quadplane.in_assisted_flight()) {537ahrs.set_fly_forward(false);538return;539}540}541#endif542543if (auto_state.idle_mode) {544// don't fuse airspeed when in balloon lift545ahrs.set_fly_forward(false);546return;547}548549if (flight_stage == AP_FixedWing::FlightStage::LAND) {550ahrs.set_fly_forward(landing.is_flying_forward());551return;552}553554ahrs.set_fly_forward(true);555}556557/*558set the flight stage559*/560void Plane::set_flight_stage(AP_FixedWing::FlightStage fs)561{562if (fs == flight_stage) {563return;564}565566landing.handle_flight_stage_change(fs == AP_FixedWing::FlightStage::LAND);567568if (fs == AP_FixedWing::FlightStage::ABORT_LANDING) {569gcs().send_text(MAV_SEVERITY_NOTICE, "Landing aborted, climbing to %dm",570int(auto_state.takeoff_altitude_rel_cm/100));571}572573flight_stage = fs;574#if HAL_LOGGING_ENABLED575Log_Write_Status();576#endif577}578579void Plane::update_alt()580{581barometer.update();582583// calculate the sink rate.584float sink_rate;585Vector3f vel;586if (ahrs.get_velocity_NED(vel)) {587sink_rate = vel.z;588} else if (gps.status() >= AP_GPS::GPS_OK_FIX_3D && gps.have_vertical_velocity()) {589sink_rate = gps.velocity().z;590} else {591sink_rate = -barometer.get_climb_rate();592}593594// low pass the sink rate to take some of the noise out595auto_state.sink_rate = 0.8f * auto_state.sink_rate + 0.2f*sink_rate;596#if HAL_PARACHUTE_ENABLED597parachute.set_sink_rate(auto_state.sink_rate);598#endif599600update_flight_stage();601602#if AP_SCRIPTING_ENABLED603if (nav_scripting_active()) {604// don't call TECS while we are in a trick605return;606}607#endif608609bool should_run_tecs = control_mode->does_auto_throttle();610#if HAL_QUADPLANE_ENABLED611if (quadplane.should_disable_TECS()) {612should_run_tecs = false;613}614#endif615616if (auto_state.idle_mode) {617should_run_tecs = false;618}619620#if AP_PLANE_GLIDER_PULLUP_ENABLED621if (mode_auto.in_pullup()) {622should_run_tecs = false;623}624#endif625626if (should_run_tecs && !throttle_suppressed) {627628float distance_beyond_land_wp = 0;629if (flight_stage == AP_FixedWing::FlightStage::LAND &&630current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {631distance_beyond_land_wp = current_loc.get_distance(next_WP_loc);632}633634tecs_target_alt_cm = relative_target_altitude_cm();635636if (control_mode == &mode_rtl && !rtl.done_climb && (g2.rtl_climb_min > 0 || (plane.flight_option_enabled(FlightOptions::CLIMB_BEFORE_TURN)))) {637// ensure we do the initial climb in RTL. We add an extra638// 10m in the demanded height to push TECS to climb639// quickly640tecs_target_alt_cm = MAX(tecs_target_alt_cm, prev_WP_loc.alt - home.alt) + (g2.rtl_climb_min+10)*100;641}642643TECS_controller.update_pitch_throttle(tecs_target_alt_cm,644target_airspeed_cm,645flight_stage,646distance_beyond_land_wp,647get_takeoff_pitch_min_cd(),648throttle_nudge,649tecs_hgt_afe(),650aerodynamic_load_factor,651g.pitch_trim.get());652}653}654655/*656recalculate the flight_stage657*/658void Plane::update_flight_stage(void)659{660// Update the speed & height controller states661if (control_mode->does_auto_throttle() && !throttle_suppressed) {662if (control_mode == &mode_auto) {663#if HAL_QUADPLANE_ENABLED664if (quadplane.in_vtol_auto()) {665set_flight_stage(AP_FixedWing::FlightStage::VTOL);666return;667}668#endif669if (auto_state.takeoff_complete == false) {670set_flight_stage(AP_FixedWing::FlightStage::TAKEOFF);671return;672} else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND) {673if (landing.is_commanded_go_around() || flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {674// abort mode is sticky, it must complete while executing NAV_LAND675set_flight_stage(AP_FixedWing::FlightStage::ABORT_LANDING);676} else if (landing.get_abort_throttle_enable() && get_throttle_input() >= 90 &&677landing.request_go_around()) {678gcs().send_text(MAV_SEVERITY_INFO,"Landing aborted via throttle");679set_flight_stage(AP_FixedWing::FlightStage::ABORT_LANDING);680} else {681set_flight_stage(AP_FixedWing::FlightStage::LAND);682}683return;684}685#if HAL_QUADPLANE_ENABLED686if (quadplane.in_assisted_flight()) {687set_flight_stage(AP_FixedWing::FlightStage::VTOL);688return;689}690#endif691set_flight_stage(AP_FixedWing::FlightStage::NORMAL);692} else if ((control_mode != &mode_takeoff)693#if MODE_AUTOLAND_ENABLED694&& (control_mode != &mode_autoland)695#endif696) {697// If not in AUTO then assume normal operation for normal TECS operation.698// This prevents TECS from being stuck in the wrong stage if you switch from699// AUTO to, say, FBWB during a landing, an aborted landing or takeoff.700set_flight_stage(AP_FixedWing::FlightStage::NORMAL);701}702return;703}704#if HAL_QUADPLANE_ENABLED705if (quadplane.in_vtol_mode() ||706quadplane.in_assisted_flight()) {707set_flight_stage(AP_FixedWing::FlightStage::VTOL);708return;709}710#endif711set_flight_stage(AP_FixedWing::FlightStage::NORMAL);712}713714715716717/*718If land_DisarmDelay is enabled (non-zero), check for a landing then auto-disarm after time expires719720only called from AP_Landing, when the landing library is ready to disarm721*/722void Plane::disarm_if_autoland_complete()723{724if (landing.get_disarm_delay() > 0 &&725!is_flying() &&726arming.arming_required() != AP_Arming::Required::NO &&727arming.is_armed()) {728/* we have auto disarm enabled. See if enough time has passed */729if (millis() - auto_state.last_flying_ms >= landing.get_disarm_delay()*1000UL) {730if (arming.disarm(AP_Arming::Method::AUTOLANDED)) {731gcs().send_text(MAV_SEVERITY_INFO,"Auto disarmed");732}733}734}735}736737bool Plane::trigger_land_abort(const float climb_to_alt_m)738{739if (plane.control_mode != &plane.mode_auto) {740return false;741}742#if HAL_QUADPLANE_ENABLED743if (plane.quadplane.in_vtol_auto()) {744return quadplane.abort_landing();745}746#endif747748uint16_t mission_id = plane.mission.get_current_nav_cmd().id;749bool is_in_landing = (plane.flight_stage == AP_FixedWing::FlightStage::LAND) ||750plane.is_land_command(mission_id);751if (is_in_landing) {752// fly a user planned abort pattern if available753if (plane.have_position && plane.mission.jump_to_abort_landing_sequence(plane.current_loc)) {754return true;755}756757// only fly a fixed wing abort if we aren't doing quadplane stuff, or potentially758// shooting a quadplane approach759#if HAL_QUADPLANE_ENABLED760const bool attempt_go_around =761(!plane.quadplane.available()) ||762((!plane.quadplane.in_vtol_auto()) &&763(!plane.quadplane.landing_with_fixed_wing_spiral_approach()));764#else765const bool attempt_go_around = true;766#endif767if (attempt_go_around) {768// Initiate an aborted landing. This will trigger a pitch-up and769// climb-out to a safe altitude holding heading then one of the770// following actions will occur, check for in this order:771// - If MAV_CMD_CONTINUE_AND_CHANGE_ALT is next command in mission,772// increment mission index to execute it773// - else if DO_LAND_START is available, jump to it774// - else decrement the mission index to repeat the landing approach775776if (!is_zero(climb_to_alt_m)) {777plane.auto_state.takeoff_altitude_rel_cm = climb_to_alt_m * 100;778}779if (plane.landing.request_go_around()) {780plane.auto_state.next_wp_crosstrack = false;781return true;782}783}784}785return false;786}787788789/*790the height above field elevation that we pass to TECS791*/792float Plane::tecs_hgt_afe(void)793{794/*795pass the height above field elevation as the height above796the ground when in landing, which means that TECS gets the797rangefinder information and thus can know when the flare is798coming.799*/800float hgt_afe;801802if (flight_stage == AP_FixedWing::FlightStage::LAND) {803804#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED805// if external HAGL is active use that806if (get_external_HAGL(hgt_afe)) {807return hgt_afe;808}809#endif810811hgt_afe = height_above_target();812#if AP_RANGEFINDER_ENABLED813hgt_afe -= rangefinder_correction();814#endif815} else {816// when in normal flight we pass the hgt_afe as relative817// altitude to home818hgt_afe = relative_altitude;819}820return hgt_afe;821}822823// vehicle specific waypoint info helpers824bool Plane::get_wp_distance_m(float &distance) const825{826// see GCS_MAVLINK_Plane::send_nav_controller_output()827if (control_mode == &mode_manual) {828return false;829}830#if HAL_QUADPLANE_ENABLED831if (quadplane.in_vtol_mode()) {832distance = quadplane.using_wp_nav() ? quadplane.wp_nav->get_wp_distance_to_destination() * 0.01 : 0;833return true;834}835#endif836distance = auto_state.wp_distance;837return true;838}839840bool Plane::get_wp_bearing_deg(float &bearing) const841{842// see GCS_MAVLINK_Plane::send_nav_controller_output()843if (control_mode == &mode_manual) {844return false;845}846#if HAL_QUADPLANE_ENABLED847if (quadplane.in_vtol_mode()) {848bearing = quadplane.using_wp_nav() ? quadplane.wp_nav->get_wp_bearing_to_destination() : 0;849return true;850}851#endif852bearing = nav_controller->target_bearing_cd() * 0.01;853return true;854}855856bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const857{858// see GCS_MAVLINK_Plane::send_nav_controller_output()859if (control_mode == &mode_manual) {860return false;861}862#if HAL_QUADPLANE_ENABLED863if (quadplane.in_vtol_mode()) {864xtrack_error = quadplane.using_wp_nav() ? quadplane.wp_nav->crosstrack_error() : 0;865return true;866}867#endif868xtrack_error = nav_controller->crosstrack_error();869return true;870}871872#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED873// set target location (for use by external control and scripting)874bool Plane::set_target_location(const Location &target_loc)875{876Location loc{target_loc};877878if (plane.control_mode != &plane.mode_guided) {879// only accept position updates when in GUIDED mode880return false;881}882// add home alt if needed883if (loc.relative_alt) {884loc.alt += plane.home.alt;885loc.relative_alt = 0;886}887plane.set_guided_WP(loc);888return true;889}890#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED891892#if AP_SCRIPTING_ENABLED893// get target location (for use by scripting)894bool Plane::get_target_location(Location& target_loc)895{896switch (control_mode->mode_number()) {897case Mode::Number::RTL:898case Mode::Number::AVOID_ADSB:899case Mode::Number::GUIDED:900case Mode::Number::AUTO:901case Mode::Number::LOITER:902case Mode::Number::TAKEOFF:903#if HAL_QUADPLANE_ENABLED904case Mode::Number::QLOITER:905case Mode::Number::QLAND:906case Mode::Number::QRTL:907#endif908target_loc = next_WP_loc;909return true;910break;911default:912break;913}914return false;915}916917/*918update_target_location() works in all auto navigation modes919*/920bool Plane::update_target_location(const Location &old_loc, const Location &new_loc)921{922/*923by checking the caller has provided the correct old target924location we prevent a race condition where the user changes mode925or commands a different target in the controlling lua script926*/927if (!old_loc.same_loc_as(next_WP_loc) ||928old_loc.get_alt_frame() != new_loc.get_alt_frame()) {929return false;930}931next_WP_loc = new_loc;932933#if HAL_QUADPLANE_ENABLED934if (control_mode == &mode_qland || control_mode == &mode_qloiter) {935mode_qloiter.last_target_loc_set_ms = AP_HAL::millis();936}937#endif938939return true;940}941942// allow for velocity matching in VTOL943bool Plane::set_velocity_match(const Vector2f &velocity)944{945#if HAL_QUADPLANE_ENABLED946if (quadplane.in_vtol_mode() || quadplane.in_vtol_land_sequence()) {947quadplane.poscontrol.velocity_match = velocity;948quadplane.poscontrol.last_velocity_match_ms = AP_HAL::millis();949return true;950}951#endif952return false;953}954955// allow for override of land descent rate956bool Plane::set_land_descent_rate(float descent_rate)957{958#if HAL_QUADPLANE_ENABLED959if (quadplane.in_vtol_land_descent() ||960control_mode == &mode_qland) {961quadplane.poscontrol.override_descent_rate = descent_rate;962quadplane.poscontrol.last_override_descent_ms = AP_HAL::millis();963return true;964}965#endif966return false;967}968969// Allow for scripting to have control over the crosstracking when exiting and resuming missions or guided flight970// It's up to the Lua script to ensure the provided location makes sense971bool Plane::set_crosstrack_start(const Location &new_start_location)972{973prev_WP_loc = new_start_location;974auto_state.crosstrack = true;975return true;976}977978#endif // AP_SCRIPTING_ENABLED979980// returns true if vehicle is landing.981bool Plane::is_landing() const982{983#if HAL_QUADPLANE_ENABLED984if (plane.quadplane.in_vtol_land_descent()) {985return true;986}987#endif988return control_mode->is_landing();989}990991// returns true if vehicle is taking off.992bool Plane::is_taking_off() const993{994#if HAL_QUADPLANE_ENABLED995if (plane.quadplane.in_vtol_takeoff()) {996return true;997}998#endif999return control_mode->is_taking_off();1000}10011002// correct AHRS pitch for PTCH_TRIM_DEG in non-VTOL modes, and return VTOL view in VTOL1003void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const1004{1005#if HAL_QUADPLANE_ENABLED1006if (quadplane.show_vtol_view()) {1007pitch = quadplane.ahrs_view->pitch;1008roll = quadplane.ahrs_view->roll;1009return;1010}1011#endif1012pitch = ahrs.get_pitch();1013roll = ahrs.get_roll();1014if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for PTCH_TRIM_DEG1015pitch -= g.pitch_trim * DEG_TO_RAD;1016}1017}10181019/*1020update current_loc Location1021*/1022void Plane::update_current_loc(void)1023{1024have_position = plane.ahrs.get_location(plane.current_loc);10251026// re-calculate relative altitude1027ahrs.get_relative_position_D_home(plane.relative_altitude);1028relative_altitude *= -1.0f;1029}10301031// check if FLIGHT_OPTION is enabled1032bool Plane::flight_option_enabled(FlightOptions flight_option) const1033{1034return g2.flight_options & flight_option;1035}10361037#if AC_PRECLAND_ENABLED1038void Plane::precland_update(void)1039{1040// alt will be unused if we pass false through as the second parameter:1041#if AP_RANGEFINDER_ENABLED1042return g2.precland.update(rangefinder_state.height_estimate*100, rangefinder_state.in_range);1043#else1044return g2.precland.update(0, false);1045#endif1046}1047#endif10481049#if AP_QUICKTUNE_ENABLED1050/*1051update AP_Quicktune object. We pass the supports_quicktune() method1052in so that quicktune can detect if the user changes to a1053non-quicktune capable mode while tuning and the gains can be reverted1054*/1055void Plane::update_quicktune(void)1056{1057quicktune.update(control_mode->supports_quicktune());1058}1059#endif10601061/*1062constructor for main Plane class1063*/1064Plane::Plane(void)1065{1066// C++11 doesn't allow in-class initialisation of bitfields1067auto_state.takeoff_complete = true;1068}10691070Plane plane;1071AP_Vehicle& vehicle = plane;10721073AP_HAL_MAIN_CALLBACKS(&plane);107410751076