Skip to content

Commit

Permalink
add plane pre-arms to table
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Jan 20, 2024
1 parent 942b5f7 commit 60bd743
Showing 1 changed file with 53 additions and 8 deletions.
61 changes: 53 additions & 8 deletions common/source/docs/common-prearm-safety-checks.rst
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ determine exactly which check has failed:

Pre-arm checks that are failing will also be sent as messages to the GCS while disarmed, about every 30 seconds. If you wish to disable this and have them sent only when an attempt arm fails, then set the :ref:`ARMING_OPTIONS<ARMING_OPTIONS>` bit 1 (value 1).

.. table:: Pre-Arm Failure Messages
.. table:: Pre-Arm Failure Messages (All vehicle types)
:widths: auto

======================================================= =================================================== ====================================================
Expand All @@ -42,13 +42,13 @@ Pre-arm checks that are failing will also be sent as messages to the GCS while d
3D Accel calibration needed Accelerometer calibration has not been done Complete the :ref:`accel calibration <common-accelerometer-calibration>`
Accels calibrated requires reboot Autopilot must be rebooted after accel calibration Reboot autopilot
Accels inconsistent Two accelerometers are inconsistent by 0.75 m/s/s Re-do the :ref:`accel calibration <common-accelerometer-calibration>`. Allow autopilot to warm-up and reboot. If failure continues replace autopilot
Accels not healthy At least one accelerometer is not providing data Reboot autopilot. If failure continues replace autopilot
ADSB out of memory Autopilot has run out of memory Disable features or replace with a higher powered autopilot
Accels not healthy At least one accelerometer is not providing data Reboot autopilot. If failure continues replace autopilot
AHRS: not using configured AHRS type EKF3 is not ready yet and vehicle is using DCM If indoors, go outside. Ensure good GPS lock. Check for misconfiguration of EKF (see :ref:`AHRS_EKF_TYPE<AHRS_EKF_TYPE>`)
AHRS: waiting for home GPS has not gotten a fix If indoors, go outside. Ensure compass and accelerometer calibrations have been completed. Eliminate radio-frequency sources that could interfere with the GPS
Airspeed 1 not healthy Autopilot is unable to retrieve data from sensor Check the physical connection and :ref:`configuration <airspeed>`
AP_Relay not available Parachute misconfigured Parachute is controlled via Relay but the relay feature is missing. `Custom build server <https://custom.ardupilot.org/>`__ was probably used, rebuild with relay enabled
Auxiliary authorisation refused External system has disallowed aurhorisation Check external authorisation system
Auxiliary authorization refused External system has disallowed authorization Check external authorisation system
Batch sampling requires reboot Batch sampling feature requires Autopilot reboot Reboot autopilot or check :ref:`Batch sampling<common-imu-batchsampling>` configuration
Battery below minimum arming capacity Battery capacity is below BATT_ARM_MAH Replace battery or adjust :ref:`BATT_ARM_MAH<BATT_ARM_MAH>`
Battery below minimum arming voltage Battery voltage is below BATT_ARM_VOLT Replace battery or adjust :ref:`BATT_ARM_VOLT<BATT_ARM_VOLT>`
Expand Down Expand Up @@ -87,7 +87,7 @@ Pre-arm checks that are failing will also be sent as messages to the GCS while d
EKF3 Roll/Pitch inconsistent by x degs Roll or Pitch lean angle estimates are inconsistent Normally due to EKF3 not getting good enough GPS accuracy, but could be due to other sensors producing errors. Go outdoors, wait or reboot autopilot.
EKF3 waiting for GPS config data automatic GPS configuration has not completed Check GPS connection and configuration especially if using DroneCAN GPS
EKF3 Yaw inconsistent by x degs Yaw angle estimates are inconsistent Wait or reboot autopilot
Failed to open mission.stg Failed to load mission from SD Card Check SD card. Try to resave mission to SD card
Failed to open mission.stg Failed to load mission from SD Card Check SD card. Try to re-save mission to SD card
Fence requires position If fences are enabled, position estimate required Wait or move vehicle to a location with a clear view of the sky. Reduce sources of radio-frequency interference
FENCE_ALT_MAX < FENCE_ALT_MIN FENCE_ALT_MAX must be greater than FENCE_ALT_MIN Increase :ref:`FENCE_ALT_MAX<FENCE_ALT_MAX>` or lower :ref:`FENCE_ALT_MIN<FENCE_ALT_MIN>`
FENCE_MARGIN is less than FENCE_RADIUS FENCE_MARGIN must be larger than FENCE_RADIUS Increase :ref:`FENCE_RADIUS<FENCE_RADIUS>` or reduce :ref:`FENCE_MARGIN<FENCE_MARGIN>`
Expand Down Expand Up @@ -203,12 +203,20 @@ Pre-arm checks that are failing will also be sent as messages to the GCS while d
VisOdom: not healthy VisualOdometry sensor is not providing data Check visual odometry physical connection and :ref:`configuration<common-non-gps-navigation-landing-page>`
VisOdom: out of memory Autopilot has run out of memory Disable features or replace with a higher powered autopilot
VTOL Fwd Throttle iz not zero RC transmitter's VTOL Fwd throttle stick is high Lower VTOL Fwd throttle stick or repeat :ref:`radio calibration <common-radio-control-calibration>`
Waiting for RC (Plane only) RC failsafe enabled but no RC signal Turn on RC transmitter or check RC transmitters connection to autopilot. If operating with only a GCS, see :ref:`common-gcs-only-operation`
waiting for terrain data Waiting for GCS to provide required terrain data Wait or move to location with better GPS reception
Yaw (RCx) is not neutral RC transmitter's yaw stick is not centered Move RC yaw stick to center or repeat :ref:`radio calibration <common-radio-control-calibration>`
Yaw radio max too low RC yaw channel max below 1700 Repeat the :ref:`radio calibration <common-radio-control-calibration>` procedure or increase :ref:`RC2_MAX<RC2_MAX>` above 1700
Yaw radio min too high RC yaw channel min above 1300 Repeat the :ref:`radio calibration <common-radio-control-calibration>` procedure or reduce :ref:`RC1_MIN<RC1_MIN>` below 1300
======================================================= =================================================== ====================================================

[site wiki="copter"]

.. table:: Pre-Arm Failure Messages (Copter/Heli Only)
:widths: auto

======================================================= =================================================== ====================================================
Message Cause Solution
======================================================= =================================================== ====================================================
ADSB threat detected ADSB failsafe. Manned vehicles nearby See :ref:`ADSB configuration<common-ads-b-receiver>`
AHRS not healthy AHRS/EKF is not yet ready Wait. Reboot autopilot
Altitude disparity Barometer and EKF altitudes differ by at least 1m Wait for EKF altitude to stabilise. Reboot autopilot
Expand All @@ -220,7 +228,7 @@ Pre-arm checks that are failing will also be sent as messages to the GCS while d
Check ANGLE_MAX ANGLE_MAX set too high Reduce :ref:`ANGLE_MAX<ANGLE_MAX>` to 8000 (e.g. 80 degrees) or lower
Check FS_THR_VALUE RC failsafe misconfiguration Set :ref:`FS_THR_VALUE<FS_THR_VALUE>` between 910 and RC throttle's min (e.g :ref:`RC3_MIN<RC3_MIN>`. See ref:`battery failsafe configuration <failsafe-battery>`
Check PILOT_SPEED_UP PILOT_SPEED_UP set too low Increase :ref:`PILOT_SPEED_UP<PILOT_SPEED_UP>` to a positive number (e.g. 100 = 1m/s). See :ref:`AltHold mode<altholdmode>`
Collective below failsafe (tradheli only) RC collective input is below FS_THR_VALUE Turn on RC transmitter or check :ref:`FS_THR_VALUE<FS_THR_VALUE>`. Check :ref:`RC failsafe setup<radio-failsafe>`
Collective below failsafe (TradHeli only) RC collective input is below FS_THR_VALUE Turn on RC transmitter or check :ref:`FS_THR_VALUE<FS_THR_VALUE>`. Check :ref:`RC failsafe setup<radio-failsafe>`
EKF attitude is bad EKF does not have a good attitude estimate Wait for EKF attitude to stabilize. Reboot autopilot. Replace autopilot
EKF compass variance Compass direction appears incorrect Relocate vehicle away from metal in the environment. Move compass away from metal in the frame. repeat :ref:`compass calibration <common-compass-calibration-in-mission-planner>`. Disable internal compass.
EKF height variance Barometer values are unstable or high vibration Wait. :ref:`Measure vibration <common-measuring-vibration>` and add :ref:`vibration isolation <common-vibration-damping>`
Expand All @@ -232,12 +240,13 @@ Pre-arm checks that are failing will also be sent as messages to the GCS while d
GPS glitching GPS position is unstable Wait. If indoors, go outside. Eliminate radio-frequency sources that could interfere with the GPS
High GPS HDOP GPS horizontal quality too low Wait or move to location with better GPS reception. You may raise :ref:`GPS_HDOP_GOOD<GPS_HDOP_GOOD>` but this is rarely a good idea
Home too far from EKF origin Home is more than 50km from EKF origin Reboot autopilot to reset EKF origin to current Location
Interlock/E-Stop Conflict (Copter only) Incompatible auxiliary function switch esconfigured Remove Interlock, E-Stop or Emergency Stop from :ref:`auxiliary function<common-auxiliary-functions>` setup
Interlock/E-Stop Conflict (TradHeli only) Incompatible auxiliary function switch configured Remove Interlock, E-Stop or Emergency Stop from :ref:`auxiliary function<common-auxiliary-functions>` setup
Invalid MultiCopter FRAME_CLASS FRAME_CLASS parameter misconfigured Multicopter firmware loaded but :ref:`FRAME_CLASS<FRAME_CLASS>` set to helicopter. Load helicopter firmware or change :ref:`FRAME_CLASS<FRAME_CLASS>`
Inverted flight option not supported Inverted flight auxiliary function not supported Remove :ref:`auxiliary function<common-auxiliary-functions>` switch for inverted flight
Leaning Vehicle is leaning more than ANGLE_MAX Level vehicle
Motor Interlock Enabled Motor Interlock in middle or high position Move motor interlock :ref:`auxiliary function<common-auxiliary-functions>` switch to low position
Motor Interlock not configured Helicopters require motor interlock be configured Enable the motor interlock :ref:`auxiliary function<common-auxiliary-functions>` switch
Motors: Check frame class and type Unknown or misconfigured frame class or type Enter valid frame class and/or type
Motors: Check MOT_PWM_MIN and MOT_PWM_MAX MOT_PWM_MIN or MOT_PWM_MAX misconfigured Set :ref:`MOT_PWM_MIN<MOT_PWM_MIN>` = 1000 and :ref:`MOT_PWM_MAX<MOT_PWM_MAX>` = 2000 and repeat the :ref:`ESC calibration <esc-calibration>`
Motors: MOT_SPIN_ARM > MOT_SPIN_MIN MOT_SPIN_ARM is too high or MOT_SPIN_MIN is too low Reducse :ref:`MOT_SPIN_ARM<MOT_SPIN_ARM>` to below :ref:`MOT_SPIN_MIN<MOT_SPIN_MIN>`. See :ref:`Seting motor range<set-motor-range>`
Motors: MOT_SPIN_MIN too high x > 0.3 MOT_SPIN_MIN parameter value is too high Reduce :ref:`MOT_SPIN_MIN<MOT_SPIN_MIN>` to below 0.3. See :ref:`Setting motor range<set-motor-range>`
Expand All @@ -253,9 +262,45 @@ Pre-arm checks that are failing will also be sent as messages to the GCS while d
Throttle below failsafe RC throttle input is below FS_THR_VALUE Turn on RC transmitter or check :ref:`FS_THR_VALUE<FS_THR_VALUE>`. Check :ref:`RC failsafe setup<radio-failsafe>`
Vehicle too far from EKF origin Vehicle is more than 50km from EKF origin Reboot autopilot to reset EKF origin to current Location
winch unhealthy Winch is not communicating with autopilot Check winch's physical connection and :ref:`configuration <common-daiwa-winch>`
[/site]
======================================================= =================================================== ====================================================
[/site]
[site wiki="plane"]

.. table:: Pre-Arm Failure Messages (Plane Only)
:widths: auto

======================================================= =================================================== ====================================================
Message Cause Solution
======================================================= =================================================== ====================================================
ADSB threat detected ADSB failsafe. Manned vehicles nearby See :ref:`ADSB configuration<common-ads-b-receiver>`
AHRS not healthy AHRS/EKF is not yet ready Wait. Reboot autopilotFS_LONG_TIMEOUT < FS_SHORT_TIMEOUT
LIM_ROLL_CD too small x Parameter set under 3 degrees Increase, 45 deg recommended minimum for adequate control
LIM_PITCH_MAX too small x Parameter set under 3 degrees Increase, 45 deg recommended minimum for adequate control
LIM_PITCH_MIN too large x Parameter set over 3 degrees Increase, 45 deg recommended minimum for adequate control
ARSPD_FBW_MIN too low x<5 m/s Parameter set too low, under 5m/s Raise to at least 20% above stall speed
Invalid THR_FS_VALUE for reversed throttle input THR_FS_VALUE pwm is not ABOVE the max throttle Set :ref:`THR_FS_VALUE<THR_FS_VALUE>` above throttle maximum pwm
Waiting for RC RC failsafe enabled but no RC signal Turn on RC transmitter or check RC transmitters connection to autopilot. If operating with only a GCS, see :ref:`common-gcs-only-operation`
Quadplane enabled but not running Q_ENABLE is set, but QuadPlane code has not started Reboot
quadplane needs SCHED_LOOP_RATE >= 100 Quadplane needs faster loop times for performance Increase :ref:`SCHED_LOOP_RATE<SCHED_LOOP_RATE>`; 300 is typical
Motors: Check frame class and type Unknown or misconfigured frame class or type Enter valid frame class and/or type
Motors: Check MOT_PWM_MIN and MOT_PWM_MAX MOT_PWM_MIN or MOT_PWM_MAX misconfigured Set :ref:`MOT_PWM_MIN<MOT_PWM_MIN>` = 1000 and :ref:`MOT_PWM_MAX<MOT_PWM_MAX>` = 2000 and repeat the :ref:`ESC calibration <esc-calibration>`
Motors: MOT_SPIN_ARM > MOT_SPIN_MIN MOT_SPIN_ARM is too high or MOT_SPIN_MIN is too low Reducse :ref:`MOT_SPIN_ARM<MOT_SPIN_ARM>` to below :ref:`MOT_SPIN_MIN<MOT_SPIN_MIN>`. See :ref:`Seting motor range<set-motor-range>`
Motors: MOT_SPIN_MIN too high x > 0.3 MOT_SPIN_MIN parameter value is too high Reduce :ref:`MOT_SPIN_MIN<MOT_SPIN_MIN>` to below 0.3. See :ref:`Setting motor range<set-motor-range>`
Motors: no SERVOx_FUNCTION set to MotorX At least one motor output has not been configured Check SERVOx_FUNCTION values for "Motor1", "Motor2", etc. Check :ref:`ESC and motor configuration <connect-escs-and-motors>`
Check Q_ANGLE_MAX Set above 80 degrees Reduce :ref:`Q_ANGLE_MAX<Q_ANGLE_MAX>` below 80; 30 degrees is typical
set TAILSIT_ENABLE 0 or TILT_ENABLE 0 Cannot have simultaneous tiltrotor and tailsitter Pick one to match your vehicle configuration and reboot
tailsitter setup not complete, reboot Enabled tiltrotor but have not rebooted yet Reboot
tiltrotor setup not complete, reboot Enabled tailsitter but have not rebooted yet Reboot
Bad parameter: ATC_ANG_PIT_P must be > 0 Attitude controller misconfiguration Increase specified parameter value to be above zero. See :ref:`Tuning Process Instructions<tuning-process-instructions>`
Bad parameter: PSC_POSXY_P must be > 0 Position controller misconfiguration Increase specified parameter value to be above zero. See :ref:`Tuning Process Instructions<tuning-process-instructions>`
Q_ASSIST_SPEED is not set Q_ASSIST_SPEED has not been set Set :ref:`Q_ASSIST_SPEED<Q_ASSIST_SPEED>` = -1 for no Assistance, See :ref:`assisted_fixed_wing_flight`
set Q_FWD_THR_USE to 0 Trying to use FWD Throttle on Tailsitter Set :ref:`Q_FWD_THR_USE<Q_FWD_THR_USE>` = 0 on tailsitters
Throttle trim not near center stick %x RC trim for centered throttle stick use incorrect Set throttle channels RC trim to center position (idle) if :ref:`FLIGHT_OPTIONS<FLIGHT_OPTIONS>` bit 10 is set.
In landing sequence Trying to arm while still in landing sequence Reset mission;change to mission item not in a landing sequence
Mode not armable Cannot arm from this mode Change Mode
Mode not QMODE Q_OPTION set to prevent arming except in QMODE/AUTO Change Mode or reset :ref:`Q_OPTIONS<Q_OPTIONS>` bit 18
======================================================= =================================================== ====================================================
[/site]
Other Failure messages
======================

Expand Down

0 comments on commit 60bd743

Please sign in to comment.