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/AP_Arming.cpp
Views: 1798
/*1additional arming checks for plane2*/3#include "AP_Arming.h"4#include "Plane.h"56#include "qautotune.h"78constexpr uint32_t AP_ARMING_DELAY_MS = 2000; // delay from arming to start of motor spoolup910const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = {11// variables from parent vehicle12AP_NESTEDGROUPINFO(AP_Arming, 0),1314// index 3 was RUDDER and should not be used1516#if AP_PLANE_BLACKBOX_LOGGING17// @Param: BBOX_SPD18// @DisplayName: Blackbox speed19// @Description: This is a 3D GPS speed threshold above which we will force arm the vehicle to start logging. WARNING: This should only be used on a vehicle with no propellers attached to the flight controller and when the flight controller is not in control of the vehicle.20// @Units: m/s21// @Increment: 122// @Range: 1 2023// @User: Advanced24AP_GROUPINFO("BBOX_SPD", 4, AP_Arming_Plane, blackbox_speed, 5),25#endif // AP_PLANE_BLACKBOX_LOGGING2627AP_GROUPEND28};2930// expected to return true if the terrain database is required to have31// all data loaded32bool AP_Arming_Plane::terrain_database_required() const33{34#if AP_TERRAIN_AVAILABLE35if (plane.g.terrain_follow) {36return true;37}38#endif39return AP_Arming::terrain_database_required();40}4142/*43additional arming checks for plane4445*/46bool AP_Arming_Plane::pre_arm_checks(bool display_failure)47{48if (armed || require == (uint8_t)Required::NO) {49// if we are already armed or don't need any arming checks50// then skip the checks51return true;52}53//are arming checks disabled?54if (checks_to_perform == 0) {55return mandatory_checks(display_failure);56}57if (hal.util->was_watchdog_armed()) {58// on watchdog reset bypass arming checks to allow for59// in-flight arming if we were armed before the reset. This60// allows a reset on a BVLOS flight to return home if the61// operator can command arming over telemetry62return true;63}6465// call parent class checks66bool ret = AP_Arming::pre_arm_checks(display_failure);6768#if AP_AIRSPEED_ENABLED69// Check airspeed sensor70ret &= AP_Arming::airspeed_checks(display_failure);71#endif7273if (plane.g.fs_timeout_long < plane.g.fs_timeout_short && plane.g.fs_action_short != FS_ACTION_SHORT_DISABLED) {74check_failed(display_failure, "FS_LONG_TIMEOUT < FS_SHORT_TIMEOUT");75ret = false;76}7778if (plane.aparm.roll_limit < 3) {79check_failed(display_failure, "ROLL_LIMIT_DEG too small (%.1f)", plane.aparm.roll_limit.get());80ret = false;81}8283if (plane.aparm.pitch_limit_max < 3) {84check_failed(display_failure, "PTCH_LIM_MAX_DEG too small (%.1f)", plane.aparm.pitch_limit_max.get());85ret = false;86}8788if (plane.aparm.pitch_limit_min > -3) {89check_failed(display_failure, "PTCH_LIM_MIN_DEG too large (%.1f)", plane.aparm.pitch_limit_min.get());90ret = false;91}9293if (plane.aparm.airspeed_min < MIN_AIRSPEED_MIN) {94check_failed(display_failure, "AIRSPEED_MIN too low (%i < %i)", plane.aparm.airspeed_min.get(), MIN_AIRSPEED_MIN);95ret = false;96}9798if (plane.channel_throttle->get_reverse() &&99Plane::ThrFailsafe(plane.g.throttle_fs_enabled.get()) != Plane::ThrFailsafe::Disabled &&100plane.g.throttle_fs_value <101plane.channel_throttle->get_radio_max()) {102check_failed(display_failure, "Invalid THR_FS_VALUE for rev throttle");103ret = false;104}105106ret &= rc_received_if_enabled_check(display_failure);107108#if HAL_QUADPLANE_ENABLED109ret &= quadplane_checks(display_failure);110#endif111112// check adsb avoidance failsafe113if (plane.failsafe.adsb) {114check_failed(display_failure, "ADSB threat detected");115ret = false;116}117118if (plane.flight_option_enabled(FlightOptions::CENTER_THROTTLE_TRIM)){119int16_t trim = plane.channel_throttle->get_radio_trim();120if (trim < 1250 || trim > 1750) {121check_failed(display_failure, "Throttle trim not near center stick(%u)",trim );122ret = false;123}124}125126if (plane.mission.get_in_landing_sequence_flag() &&127!plane.mission.starts_with_takeoff_cmd()) {128check_failed(display_failure,"In landing sequence");129ret = false;130}131132char failure_msg[50] {};133if (!plane.control_mode->pre_arm_checks(ARRAY_SIZE(failure_msg), failure_msg)) {134check_failed(display_failure, "%s %s", plane.control_mode->name(), failure_msg);135return false;136}137138return ret;139}140141bool AP_Arming_Plane::mandatory_checks(bool display_failure)142{143bool ret = true;144145ret &= rc_received_if_enabled_check(display_failure);146147// Call parent class checks148ret &= AP_Arming::mandatory_checks(display_failure);149150return ret;151}152153154#if HAL_QUADPLANE_ENABLED155bool AP_Arming_Plane::quadplane_checks(bool display_failure)156{157if (!plane.quadplane.enabled()) {158return true;159}160161if (!plane.quadplane.available()) {162check_failed(display_failure, "Quadplane enabled but not running");163return false;164}165166bool ret = true;167168if (plane.scheduler.get_loop_rate_hz() < 100) {169check_failed(display_failure, "quadplane needs SCHED_LOOP_RATE >= 100");170ret = false;171}172173char failure_msg[50] {};174if (!plane.quadplane.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {175check_failed(display_failure, "Motors: %s", failure_msg);176ret = false;177}178179// lean angle parameter check180if (plane.quadplane.aparm.angle_max < 1000 || plane.quadplane.aparm.angle_max > 8000) {181check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check Q_ANGLE_MAX");182ret = false;183}184185if ((plane.quadplane.tailsitter.enable > 0) && (plane.quadplane.tiltrotor.enable > 0)) {186check_failed(ARMING_CHECK_PARAMETERS, display_failure, "set TAILSIT_ENABLE 0 or TILT_ENABLE 0");187ret = false;188189} else {190191if ((plane.quadplane.tailsitter.enable > 0) && !plane.quadplane.tailsitter.enabled()) {192check_failed(ARMING_CHECK_PARAMETERS, display_failure, "tailsitter setup not complete, reboot");193ret = false;194}195196if ((plane.quadplane.tiltrotor.enable > 0) && !plane.quadplane.tiltrotor.enabled()) {197check_failed(ARMING_CHECK_PARAMETERS, display_failure, "tiltrotor setup not complete, reboot");198ret = false;199}200}201202// ensure controllers are OK with us arming:203if (!plane.quadplane.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {204check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);205ret = false;206}207if (!plane.quadplane.attitude_control->pre_arm_checks("ATC", failure_msg, ARRAY_SIZE(failure_msg))) {208check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);209ret = false;210}211212/*213Q_ASSIST_SPEED really should be enabled for all quadplanes except tailsitters214*/215if (check_enabled(ARMING_CHECK_PARAMETERS) &&216is_zero(plane.quadplane.assist.speed) &&217!plane.quadplane.tailsitter.enabled()) {218check_failed(display_failure,"Q_ASSIST_SPEED is not set");219ret = false;220}221222if ((plane.quadplane.tailsitter.enable > 0) && (plane.quadplane.q_fwd_thr_use != QuadPlane::FwdThrUse::OFF)) {223check_failed(ARMING_CHECK_PARAMETERS, display_failure, "set Q_FWD_THR_USE to 0");224ret = false;225}226227return ret;228}229#endif // HAL_QUADPLANE_ENABLED230231bool AP_Arming_Plane::ins_checks(bool display_failure)232{233// call parent class checks234if (!AP_Arming::ins_checks(display_failure)) {235return false;236}237238// additional plane specific checks239if (check_enabled(ARMING_CHECK_INS)) {240char failure_msg[50] = {};241if (!AP::ahrs().pre_arm_check(true, failure_msg, sizeof(failure_msg))) {242check_failed(ARMING_CHECK_INS, display_failure, "AHRS: %s", failure_msg);243return false;244}245}246247return true;248}249250bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)251{252if (method == AP_Arming::Method::RUDDER) {253const AP_Arming::RudderArming arming_rudder = get_rudder_arming_type();254255if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {256//parameter disallows rudder arming/disabling257258// if we emit a message here then someone doing surface259// checks may be bothered by the message being emitted.260// check_failed(true, "Rudder arming disabled");261return false;262}263264// if throttle is not down, then pilot cannot rudder arm/disarm265if (!is_zero(plane.get_throttle_input())){266check_failed(true, "Non-zero throttle");267return false;268}269}270271//are arming checks disabled?272if (checks_to_perform == 0) {273return true;274}275276if (hal.util->was_watchdog_armed()) {277// on watchdog reset bypass arming checks to allow for278// in-flight arming if we were armed before the reset. This279// allows a reset on a BVLOS flight to return home if the280// operator can command arming over telemetry281gcs().send_text(MAV_SEVERITY_WARNING, "watchdog: Bypassing arming checks");282return true;283}284285// call parent class checks286return AP_Arming::arm_checks(method);287}288289/*290update HAL soft arm state291*/292void AP_Arming_Plane::change_arm_state(void)293{294update_soft_armed();295#if HAL_QUADPLANE_ENABLED296plane.quadplane.set_armed(hal.util->get_soft_armed());297#endif298}299300bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_checks)301{302if (!AP_Arming::arm(method, do_arming_checks)) {303return false;304}305306if (plane.update_home()) {307// after update_home the home position could still be308// different from the current_loc if the EKF refused the309// resetHeightDatum call. If we are updating home then we want310// to force the home to be the current_loc so relative alt311// takeoffs work correctly312if (plane.ahrs.set_home(plane.current_loc)) {313// update current_loc314plane.update_current_loc();315}316}317318change_arm_state();319320// rising edge of delay_arming oneshot321delay_arming = true;322323send_arm_disarm_statustext("Throttle armed");324325return true;326}327328/*329disarm motors330*/331bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks)332{333if (do_disarm_checks &&334(AP_Arming::method_is_GCS(method) ||335method == AP_Arming::Method::RUDDER)) {336if (plane.is_flying()) {337// don't allow mavlink or rudder disarm while flying338return false;339}340}341342if (do_disarm_checks && method == AP_Arming::Method::RUDDER) {343// option must be enabled:344if (get_rudder_arming_type() != AP_Arming::RudderArming::ARMDISARM) {345gcs().send_text(MAV_SEVERITY_INFO, "Rudder disarm: disabled");346return false;347}348}349350if (!AP_Arming::disarm(method, do_disarm_checks)) {351return false;352}353if (plane.control_mode != &plane.mode_auto) {354// reset the mission on disarm if we are not in auto355plane.mission.reset();356}357358// suppress the throttle in auto-throttle modes359plane.throttle_suppressed = plane.control_mode->does_auto_throttle();360361// if no airmode switch assigned, ensure airmode is off:362#if HAL_QUADPLANE_ENABLED363if ((plane.quadplane.air_mode == AirMode::ON) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr)) {364plane.quadplane.air_mode = AirMode::OFF;365}366#endif367368//only log if disarming was successful369change_arm_state();370371#if QAUTOTUNE_ENABLED372// Possibly save auto tuned parameters373plane.quadplane.qautotune.disarmed(plane.control_mode == &plane.mode_qautotune);374#endif375376// re-initialize speed variable used in AUTO and GUIDED for377// DO_CHANGE_SPEED commands378plane.new_airspeed_cm = -1;379380#if MODE_AUTOLAND_ENABLED381// takeoff direction always cleared on disarm382plane.takeoff_state.initial_direction.initialized = false;383#endif384send_arm_disarm_statustext("Throttle disarmed");385return true;386}387388void AP_Arming_Plane::update_soft_armed()389{390bool _armed = is_armed();391#if HAL_QUADPLANE_ENABLED392if (plane.quadplane.motor_test.running){393_armed = true;394}395#endif396397hal.util->set_soft_armed(_armed);398#if HAL_LOGGING_ENABLED399AP::logger().set_vehicle_armed(hal.util->get_soft_armed());400#endif401402// update delay_arming oneshot403if (delay_arming &&404(AP_HAL::millis() - hal.util->get_last_armed_change() >= AP_ARMING_DELAY_MS)) {405406delay_arming = false;407}408409#if AP_PLANE_BLACKBOX_LOGGING410if (blackbox_speed > 0) {411const float speed3d = plane.gps.status() >= AP_GPS::GPS_OK_FIX_3D?plane.gps.velocity().length():0;412const uint32_t now = AP_HAL::millis();413if (speed3d > blackbox_speed) {414last_over_3dspeed_ms = now;415}416if (!_armed && speed3d > blackbox_speed) {417// force safety on so we don't run motors418hal.rcout->force_safety_on();419AP_Param::set_by_name("RC_PROTOCOLS", 0);420arm(Method::BLACKBOX, false);421gcs().send_text(MAV_SEVERITY_WARNING, "BlackBox: arming at %.1f m/s", speed3d);422}423if (_armed && now - last_over_3dspeed_ms > 20000U) {424gcs().send_text(MAV_SEVERITY_WARNING, "BlackBox: disarming at %.1f m/s", speed3d);425disarm(Method::BLACKBOX, false);426}427}428#endif429}430431/*432extra plane mission checks433*/434bool AP_Arming_Plane::mission_checks(bool report)435{436// base checks437bool ret = AP_Arming::mission_checks(report);438if (plane.g.rtl_autoland == RtlAutoland::RTL_DISABLE) {439if (plane.mission.contains_item(MAV_CMD_DO_LAND_START)) {440ret = false;441check_failed(ARMING_CHECK_MISSION, report, "DO_LAND_START set and RTL_AUTOLAND disabled");442}443if (plane.mission.contains_item(MAV_CMD_DO_RETURN_PATH_START)) {444ret = false;445check_failed(ARMING_CHECK_MISSION, report, "DO_RETURN_PATH_START set and RTL_AUTOLAND disabled");446}447}448#if HAL_QUADPLANE_ENABLED449if (plane.quadplane.available()) {450const uint16_t num_commands = plane.mission.num_commands();451AP_Mission::Mission_Command prev_cmd {};452for (uint16_t i=1; i<num_commands; i++) {453AP_Mission::Mission_Command cmd;454if (!plane.mission.read_cmd_from_storage(i, cmd)) {455break;456}457if (plane.is_land_command(cmd.id) &&458prev_cmd.id == MAV_CMD_NAV_WAYPOINT) {459const float dist = cmd.content.location.get_distance(prev_cmd.content.location);460const float tecs_land_speed = plane.TECS_controller.get_land_airspeed();461const float landing_speed = is_positive(tecs_land_speed)?tecs_land_speed:plane.aparm.airspeed_cruise;462const float min_dist = 0.75 * plane.quadplane.stopping_distance(sq(landing_speed));463if (dist < min_dist) {464ret = false;465check_failed(ARMING_CHECK_MISSION, report, "VTOL land too short, min %.0fm", min_dist);466}467}468prev_cmd = cmd;469}470}471#endif472return ret;473}474475// Checks rc has been received if it is configured to be used476bool AP_Arming_Plane::rc_received_if_enabled_check(bool display_failure)477{478if (rc().enabled_protocols() == 0) {479// No protocols enabled, will never get RC, don't block arming480return true;481}482483// If RC failsafe is enabled we must receive RC before arming484if ((Plane::ThrFailsafe(plane.g.throttle_fs_enabled.get()) == Plane::ThrFailsafe::Enabled) &&485!(rc().has_had_rc_receiver() || rc().has_had_rc_override())) {486check_failed(display_failure, "Waiting for RC");487return false;488}489490return true;491}492493494