Lazy loaded image
电机解锁/上锁(Arm/Disarm)源码分析
Words 2965Read Time 8 min
2024-8-11
2024-12-11
type
date
slug
category
icon
password
 

一、简介

为了防止设备在未准备好或不安全的情况下意外启动,造成潜在的危险或损坏。电机需要具备上锁解锁功能。常见的方法包括物理开关、软件命令方法。在特定条件下(如失去信号、低电压等)也会自动上锁。
针对软件命令上锁/解锁,可通过地面控制站(QGC)或者RC遥控器操作。
  • RC遥控器发出各通道控制信号,接收机通过 PPM、PWM、SBUS 等协议直接接收,转化为自驾仪器各通道具体输出。解锁步骤参考这里,乐迪 T8FB 手柄操作方式可参考这里
  • 地面控制站通过 Mavlink 协议控制解锁。解锁上锁命令如下,详细可以参考【
    一、简介
    】。
 
了解上锁/解锁命令使用场景,命令下发方式,接下来我们分析 ArduPilot 源码,对接收到命令后,自驾仪底层控制流程和逻辑做分析。

二、框架和功能接口

首先,来熟悉水下机器人Ardusub 解锁/上锁功能框架和主要接口。
AP_Arming_Sub类继承自库中 AP_Arming类,构造方法也直接继承过来,在此基础上,重写了rc_calibration_checkspre_arm_checks、disarm等接口。
各接口功能如下:
  1. has_disarm_function 电机解锁前需检测已经指定了解锁按钮;
  1. pre_arm_checks 执行解锁前安全检查;
  1. rc_calibration_checks 检查RC控制4个通道的最小值和最大值是否标定成功;
  1. disarm/arm 电机解锁和上锁接口,传入操作方法,设置是否需要检查。
 

三、函数调用链

3.1 解锁前检查

void Sub::one_hz_loop()bool AP_Arming_Sub::pre_arm_checks(bool display_failure) bool AP_Arming::pre_arm_checks(bool report)
在 Sub类中调用 AP_Arming_Sub 类方法,实例化对象。
1Hz周期调用 AP_Arming_Sub::pre_arm_checks,进行解锁前检查。
AP_Arming_Sub::pre_arm_checks 检测方法首先检测是否解锁,若解锁直接跳出。未解锁则继续运行。判断是否有上锁 disarm 功能,确保解锁后可以上锁。只有存在上锁功能,才执行解锁前检查。
真正解锁前检查功能在AP_Arming库中的pre_arm_checks执行。

3.2 执行解锁/上锁

通过搜索arming.arm,获取具体应用时何处调用解锁方法。ArduSub 中在遥控手柄joystick.cpp中使用,同时我们关注一下多旋翼在motors.cppGCS_MAVLINK.cpp中调用。
为啥在 ArduSub 和 ArduCopter下位于不同的函数?
这和通讯控制硬件架构有关。水下机器人通过电力载波有线通讯,通过PC 上地面控制站外接 joystick 进行控制。而多旋翼机器人通过RC遥控器和接收机无线通讯,通过遥控器方向舵Rudder进行控制。
notion image
 
首先分析ArduSub/joystick.cpp源码。transform_manual_control_to_rc_override将人工控制输入转化为rc输出。循环判断是否有按钮按下,不同按钮操作在handle_jsbutton_press中switch:case分支。下面源码列出了解锁/上锁操作,第一种是单个按钮控制解锁/上锁,第二种是单独解锁按钮,第三种是单独上锁按钮。这三种方法都是通过AP_Arming::Method::MAVLINK方法控制。而transform_manual_control_to_rc_override调用过程参考
总体来说,解锁/上锁整个调用链如下:
GCS::update_receive() GCS_MAVLINK::update_receive()void GCS_MAVLINK::packetReceived()void GCS_MAVLINK_Sub::handle_message() void Sub::transform_manual_control_to_rc_override() void Sub::handle_jsbutton_press()arming.arm()/arming.disarm()
 
再来分析ArduCopter/motors.cpp,首需要打开方向舵解锁功能,根据偏航角输入,右满舵则解锁,左满舵上锁。为了避免误触发,控制在计数器超过ARM_DELAY 后才执行,防抖动。解锁/上锁调用链如下: SCHED_TASK(arm_motors_check, 10, 50, 21)arming.arm()/arming.disarm()

四、解锁前检查详细说明

4.1 源码分析

真正的检查工作在AP_Arming库中pre_arm_checks中执行,下面详细分析一下检查项目
ArduPilot includes a suite of Pre-arm Safety Checks which will prevent the vehicle from arming its propulsion system if any of a fairly large number of issues are discovered before movement including missed calibration, configuration or bad sensor data. These checks help prevent crashes or fly-aways but some can also be disabled if necessary.
  1. 已经解锁或者解锁无需检测(应该始终不要关闭ARMING_CHECK);
    1. ⚠️
      Never disable the arming checks (ie ARMING_CHECK not = “1”, except for bench testing. Always resolve any prearm or arming failures BEFORE attempting to fly. Doing otherwise may result in the loss of the vehicle.
  1. checks_result 检查结果综合不同检查项目结果(逻辑与),不同检查项目检测与否绝对于宏定义是否打开;
  1. 检测项目包括气压计、惯导、罗盘、GPS、电池、日志记录功能、遥控器检测、任务检测、板载电压、测距仪等。

4.2 通过QGC识别检测信息

  1. a pre-arm check failure will be unable to arm the vehicle and the notification LED
  1. The first cause of the Pre-Arm Check failure will be displayed in red on the HUD window
  1. 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 ARMING_OPTIONS bit 1 (value 1).
Pre-Arm Failure Messages (All vehicle types)
Message
Cause
Solution
3D Accel calibration needed
Accelerometer calibration has not been done
Complete the accel 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 accel calibration. Allow autopilot to warm-up and reboot. 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 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 configuration
AP_Relay not available
Parachute misconfigured
Parachute is controlled via Relay but the relay feature is missing. Custom build server was probably used, rebuild with relay enabled
Auxiliary authorisation refused
External system has disallowed authorisation
Check external authorisation system
Batch sampling requires reboot
Batch sampling feature requires Autopilot reboot
Reboot autopilot or check Batch sampling configuration
Battery below minimum arming capacity
Battery capacity is below BATT_ARM_MAH
Replace battery or adjust BATT_ARM_MAH
Battery below minimum arming voltage
Battery voltage is below BATT_ARM_VOLT
Replace battery or adjust BATT_ARM_VOLT
Battery capacity failsafe critical >= low
Battery failsafe misconfiguration
Check BATT_LOW_MAH is higher than BATT_CRT_MAH
Battery critical capacity failsafe
Battery capacity is below BATT_CRT_MAH
Replace battery or adjust BATT_CRT_MAH
Battery critical voltage failsafe
Battery voltage is below BATT_CRT_VOLT
Replace battery or adjust BATT_CRT_VOLT
Battery low capacity failsafe
Battery capacity is below BATT_LOW_MAH
Replace battery or adjust BATT_LOW_MAH
Battery low voltage failsafe
Battery voltage is below BATT_LOW_VOLT
Replace battery or adjust BATT_LOW_VOLT
Battery unhealthy
Battery is not providing data
Check battery monitors physical connect and configuration
Battery voltage failsafe critical >= low
Battery failsafe misconfiguration
Check BATT_LOW_VOLT is higher than BATT_CRT_VOLT
BendyRuler OA requires reboot
Object avoidance config change requires reboot
Reboot autopilot. See Object Avoidance configuration
Board (Xv) out of range 4.3-5.8v
Board voltage below BRD_VBUS_MIN or too high
Check power supply. If powering via USB plug in a battery or replace USB cable
BTN_PINx=y invalid
Button misconfigured
BTNx_PIN is set to an invalid value. Check Button setup instructions
BTN_PINx=y, set SERVOz_FUNCTION=-1
Button misconfigured
Set SERVOz_FUNCTION to -1
Can’t check rally without position
EKF does not have a position estimate yet
Wait or move to location with better GPS reception
Check fence
Fence feature has failed to be initialised
Reboot autopilot
Check mag field (xy diff:x>875)
Compass horiz field strength is too large or small
Relocate vehicle away from metal in the environment. Move compass away from metal in the frame. repeat compass calibration. Disable internal compass.
Check mag field (z diff:x>875)
Compass vert field strength is too large or small
Relocate vehicle away from metal in the environment. Move compass away from metal in the frame. repeat compass calibration. Disable internal compass.
Check mag field: x, max y, min z
Compass field strength is too large or small
Relocate vehicle away from metal in the environment. Move compass away from metal in the frame. repeat compass calibration. Disable internal compass.
Chute has no channel
Parachute misconfigured
Parachute is controlled using PWM but no servo output function has been configured (e.g. need SERVOx_FUNCTION = 27). see Parachute setup instructions
Chute has no relay
Parachute misconfigured
Parachute is controlled via Relay but no relay output has been configured. see Parachute setup instructions
Chute is released
Parachute has been released
Reboot autopilot
Compass calibrated requires reboot
Autopilot must be rebooted after compass cal
Reboot autopilot
Compass calibration running
Compass calibration is running
Complete or cancel the compass calibration
Compass not healthy
At least one compass is not providing data
Check compass’s connection to autopilot and configuration
Compass offsets too high
Compass offset params are too large
Relocate compass away from metal in the frame and repeat compass calibration. Disable internal compass. Increase COMPASS_OFFS_MAX.
Compasses inconsistent
Two compasses angles or field strength disagree
Check compass orientations (e.g. COMPASS_ORIENT). Move compass away from metal in the frame. repeat compass calibration. Disable internal compass.
Dijkstra OA requires reboot
Object avoidance config change requires reboot
Reboot autopilot. See Object Avoidance configuration
Disarm Switch on
Disarm auxiliary switch is in the high position
Move Disarm switch to the low position or check auxiliary functions setup
Downloading logs
Vehicle cannot be armed while logs are downloading
Wait until logs are downloaded, cancel download or reboot autopilot
DroneCAN: Duplicate Node x../y!
DroneCAN sees same node ids used by two devices
Clear DroneCAN DNS server by setting CAN_D1_UC_OPTION = 1 and reboot
DroneCAN: Failed to access storage!
Possible hardware issue
Reboot autopilot
DroneCAN: Failed to add Node x!
DroneCAN could not init connection to a device
Check sensor’s physical connection and power supply
DroneCAN: Node x unhealthy!
A DroneCAN device is not providing data
Check sensor’s physical connection and power supply
Duplicate Aux Switch Options
Two auxiliary function switches for same feature
Check auxiliary function setup. Check for RCx_OPTION parameters with same values
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 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 FENCE_ALT_MAX or lower FENCE_ALT_MIN
FENCE_MARGIN is less than FENCE_RADIUS
FENCE_MARGIN must be larger than FENCE_RADIUS
Increase FENCE_RADIUS or reduce FENCE_MARGIN
FENCE_MARGIN too big
FENCE_ALT_MAX - FENCE_ALT_MIN < 2x FENCE_MARGIN
Decrease FENCE_MARGIN or increase difference between FENCE_ALT_MAX and FENCE_ALT_MIN
Fences enabled, but none selected
Fences are enabled but none are defined
Disable some or all fences using FENCE_ENABLE or FENCE_TYPE or define the missing fences
Fences invalid
Polygon fence is invalid
Check polygon fence does not have overlapping lines
FETtec: Invalid motor mask
FETtec misconfiguration
FETtec: Invalid pole count x
FETtec misconfiguration
FETtec: No uart
FETtec misconfiguration
FETtec: Not initialised
FETtec ESCs are not communicating with autopilot
FETtec: x of y ESCs are not running
FETtec ESCs are not spinning
FETtec: x of y ESCs are not sending telem
FETtec ESCs are not communicating with autopilot
FFT calibrating noise
FFT Harmonic Notch analysis has not completed
Wait until In-Flight FFT analysis completes
FFT config MAXHZ xHz > yHz
FFT Harmonic Notch misconfiguration
FFT self-test failed, max error Hz
FFT Harmonic Notch failed
FFT still analyzing
FFT Harmonic Notch analysis has not completed
Wait until In-Flight FFT analysis completes
FFT: calibrated xHz/xHz/xHz
FFT Harmonic Notch issue
FFT: resolution is xHz, increase length
FFT Harmonic Notch misconfiguration
Generator: Not healthy
Generator is not communicating with autopilot
Generator: No backend driver
Firmware does not include seelected generator
Build version of firmware with desired generator using custom.ardupilot.org
GPS and AHRS differ by Xm
GPS and EKF positions differ by at least 10m
Wait until GPS quality improves. Move vehicle to a location with a clear view of the sky. Reduce sources of radio-frequency interference
GPS blending unhealthy
At least one GPS is not providing good data
Move vehicle to a location with a clear view of the sky. Reduce sources of radio-frequency interference. Check GPS blending configuration
GPS Node x not set as instance y
DroneCan GPS configuration error
GPS positions differ by Xm
Two GPSs reported positions differ by 50m or more
Wait until GPS quality improves. Move vehicle to a location with a clear view of the sky. Reduce sources of radio-frequency interference
GPS x still configuring this GPS
Automatic GPS configuration has not completed
Wait until configuration completes. Check GPS connection and configuration especially if using DroneCAN GPS
GPS x: Bad fix
GPS does not have a good lock
Move vehicle to a location with a clear view of the sky. Reduce sources of radio-frequency interference
GPS x: not healthy
GPS is not providing data
Check GPSs physical connection to autopilot and configuration
GPS x: primary but TYPE 0
Primary GPS has not been configured
Check GPS_PRIMARY and confirm corresponding GPS1_TYPE or GPS2_TYPE matches type of GPS used
GPS x: was not found
GPS disconnected or incorrectly configured
Check GPSs physical connection to autopilot and configuration
GPSx yaw not available
GPS-for-yaw configured but not working
Move to location with better GPS reception. Check GPS-for-yaw configuration
Gyros inconsistent
Two gyros are inconsistent by at least 5 deg/sec
Reboot autopilot and hold vehicle still until gyro calibration completes. Allow autopilot to warm-up and reboot. If failure continues replace autopilot
Gyros not calibrated
Gyro calibration normally run at startup failed
Reboot autopilot and hold vehicle still until gyro calibration completes
Gyros not healthy
At least one gyro is not providing data
Reboot autopilot. If failure continues replace autopilot
Hardware safety switch
Hardware safety switch has not been pushed
Push safety switch (normally on top of GPS) or disable by setting BRD_SAFETY_DEFLT to zero and reboot autopilot
heater temp low (x < 45)
Board heater temp is below BRD_HEAT_TARG
Wait for board to heat up. Target temperature can be adjust using BRD_HEAT_TARG
In OSD menu
OSD is being configured
Complete OSD configuration. Check OSD configuration
Internal errors 0x%x l:%u %s
An internal error has occurred
Reboot the autopilot. Report error to the development team
Invalid FENCE_ALT_MAX value
FENCE_ALT_MAX must be positive
Increase FENCE_ALT_MAX
Invalid FENCE_ALT_MIN value
FENCE_ALT_MIN must be higher than -100
Increase FENCE_ALT_MIN
Invalid FENCE_MARGIN value
FENCE_MARGIN must be positive
Increase FENCE_MARGIN
Invalid FENCE_RADIUS value
FENCE_RADIUS must be positive
Increase FENCE_RADIUS
Logging failed
Logs could not be written. Maybe hardware failure
Reboot autopilot. Replace autopilot
Logging not started
Logs could not be written. Maybe hardware failure
Reboot autopilot. Replace autopilot
Main loop slow (xHz < 400Hz)
Autopilot’s CPU is overloaded
Wait to see if the error is temporary. Disable features or replace with a higher powered autopilot. Reduce SCHED_LOOP_RATE
Margin is less than inclusion circle radius
A circular fence has radius below FENCE_MARGIN
Increase the size of the circular fence involved or decrease FENCE_MARGIN
memory low for auxiliary authorisation
Autopilot has run out of memory
Disable features or replace with a higher powered autopilot
Missing mission item: do land start
Auto mission needs a DO_LAND_START command
Add a DO_LAND_START command to the mission or adjust the ARMING_MIS_ITEMS parameter
Missing mission item: land
Auto mission needs a LAND command
Add a LAND command to the mission or adjust the ARMING_MIS_ITEMS parameter
Missing mission item: RTL
Auto mission needs an RTL command
Add an RTL command to the mission or adjust the ARMING_MIS_ITEMS parameter
Missing mission item: takeoff
Auto mission needs a TAKEOFF command
Add a TAKEOFF command to the mission or adjust the ARMING_MIS_ITEMS parameter
Missing mission item: vtol land
Auto mission needs a VTOL_LAND command
Add a VTOL_LAND command to the mission or adjust the ARMING_MIS_ITEMS parameter
Missing mission item: vtol takeoff
Auto mission needs a VTOL_TAKEOFF command
Add a VTOL_TAKEOFF command to the mission or adjust the ARMING_MIS_ITEMS parameter
Mode channel and RCx_OPTION conflict
RC flight mode switch also used for an aux function
Change FLTMODE_CH (or MODE_CH for Rover) or RCx_OPTION to remove conflict
Mode requires mission
Attempting to arm in Auto mode but no mission
Arm in an other mode or create and upload an Auto mission
Motors Emergency Stopped
Motors emergency stopped
Release emergency stop. See auxiliary functions
Mount: check TYPE
Mount (aka camera gimbal) misconfiguration
Check MNT1_TYPE is valid. Check Gimbal configuration
Mount: not healthy
Mount is not communicating with autopilot
Check physical connection between autopilot and gimbal and check Gimbal configuration
Multiple SERIAL ports configured for RC input
RC misconfiguration
No mission library present
Auto mission feature has been disabled
Custom build server was probably used to produce the firmware without auto missions. Rebuild with auto missions enabled
No rally library present
Rally point feature has been disabled
Custom build server was probably used to produce the firmware without rally point. Rebuild with Rally points included
No SD card
SD card is corrupted or missing
Format or replace SD card
No sufficiently close rally point located
Rally points are further than RALLY_LIMIT_KM
Move rally points closer to vehicle’s current location or increase RALLY_LIMIT_KM
OA requires reboot
Object avoidance config change requires reboot
Reboot autopilot. See Object Avoidance configuration
OpenDroneID: ARM_STATUS not available
OpenDroneID misconfiguration
OpenDroneID: operator location must be set
Operator location is not available
OpenDroneID: SYSTEM not available
OpenDroneID misconfiguration
OpenDroneID: UA_TYPE required in BasicID
OpenDroneID misconfiguration
OSD_TYPE2 not compatible with first OSD
OSD1 and OSD2 configurations are incompatible
Disable 2nd OSD (set OSD_TYPE2 to zero) or check OSD configuration
Param storage failed
Eeprom hardware failure
Check power supply or replace autopilot
parameter storage full
Eeprom storage full
Save params. Reset to defaults. Reload saved parameters.
PiccoloCAN: Servo x not detected
PiccoloCAN misconfiguration or servo issue
Pin x disabled (ISR flood)
Sensor connected to GPIO pin is rapidly changing
Check sensor attached to specified pin
Pitch (RCx) is not neutral
RC transmitter’s pitch stick is not centered
Move RC pitch stick to center or repeat radio calibration
Pitch radio max too low
RC pitch channel max below 1700
Repeat the radio calibration procedure or increase RC2_MAX above 1700
Pitch radio min too high
RC pitch channel min above 1300
Repeat the radio calibration procedure or reduce RC2_MIN below 1300
PRXx: No Data
Proximity sensor is not providing data
Check proximity sensor physical connection and configuration
PRXx: Not Connected
Proximity sensor is not providing data
Check proximity sensor physical connection and configuration
Radio failsafe on
RC failsafe has triggered
Turn on RC transmitter or check RC failsafe configuration
Rangefinder x: Not Connected
Rangefinder is not providing data
Check rangefinder’s physical connection to autopilot and configuration
Rangefinder x: Not Detected
Rangefinder is not providing data
Check rangefinder’s physical connection to autopilot and configuration
RC calibrating
RC calibration is in progress
Complete the radio calibration procedure
RC not calibrated
RC calibration has not been done
Complete the radio calibrationRC3_MIN and RC3_MAX must have been changed from their default values (1100 and 1900), and for channels 1 to 4, MIN value must be 1300 or less, and MAX value 1700 or more.
RC not found
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 Operation Using Only a Ground Control Station (GCS)
RCx_MAX is less than RCx_TRIM
RC misconfiguration
Adjust RCx_TRIM to be lower than RCx_MAX or repeat radio calibration
RCx_MIN is greater than RCx_TRIM
RC misconfiguration
Adjust RCx_TRIM to be higher than RCx_MIN or repeat radio calibration
RELAYx_PIN=y invalid
Relay misconfigured
RELAYx_PIN is set to an invalid value. Check Relay setup instructions
RELAYx_PIN=y, set SERVx_FUNCTION=-1
Relay misconfigured
Set SERVOx_FUNCTION to -1
RNGFNDx_PIN not set
Rangefinder misconfigured
Set RNGFNDx_PIN to a non-zero value. See rangefinder configuration
RNGFNDx_PIN=y invalid
Rangefinder misconfigured
RNGFNDx_PIN is set to an invalid value. Check rangefinder configuration
RNGFNDx_PIN=y, set SERVOx_FUNCTION=-1
Rangefinder misconfigured
Set SERVOx_FUNCTION to -1
Roll (RCx) is not neutral
RC transmitter’s roll stick is not centered
Move RC roll stick to center or repeat radio calibration
Roll radio max too low
RC roll channel max below 1700
Repeat the radio calibration procedure or increase RC1_MAX above 1700
Roll radio min too high
RC roll channel min above 1300
Repeat the radio calibration procedure or reduce RC1_MIN below 1300
RPMx_PIN not set
RPM sensor misconfigured
Check RPMx_PIN value. Check RPM setup instructions
RPMx_PIN=y invalid
RPM sensor misconfigured
RPMx_PIN is set to an invalid value. Check RPM setup instructions
RPMx_PIN=y, set SERVOx_FUNCTION=-1
RPM sensor misconfigured
Set SERVOz_FUNCTION to -1
Same Node Id x set for multiple GPS
DroneCan GPS configuration error
Check GPS1_CAN_NODEID and GPS2_CAN_NODEID are different. Set one to zero and reboot autopilot
Same rfnd on different CAN ports
Two rangefinders appearing on different CAN ports
Check USD1, TOFSensP, NanoRadar or Benewake setup instructions
Scripting: loaded CRC incorrect want: x
Script has incorrect CRC
Replace Lua script with expected version
Scripting: running CRC incorrect want: x
Script has incorrect CRC
Replace Lua script with expected version
Scripting: xxx failed to start
A Lua script failed to start
Autopilot out of memory or Lua script misconfiguration. See Lua scripts
Scripting: xxx out of memory
A Lua script ran out of memory
Servo voltage to low (Xv < 4.3v)
Servo rail voltage below 4.3V
Check power supply to rear servo rail
SERVOx_FUNCTION=y on disabled channel
PWM output misconfigured
SERVOx_FUNCTION is set for a servo output that has been disabled. See BLHeli setup
SERVOx_MAX is less than SERVOx_TRIM
PWM output misconfigured
Set SERVOx_TRIM to be lower than SERVOx_MAX
SERVOx_MIN is greater than SERVOx_TRIM
PWM output misconfigured
Set SERVOx_TRIM to be higher than SERVOx_MIN
temperature cal running
Temperature calibration is running
Wait until temp calibration completes or reboot autopilot
terrain disabled
Auto mission uses terrain but terrain disabled
Enable the terrain database (set TERRAIN_ENABLE = 1) or remove auto mission items that use terrain altitudes. For Copters also check RTL_ALT_TYPE.
Terrain out of memory
Autopilot has run out of memory
Disable features or replace with a higher powered autopilot
Throttle (RCx) is not neutral
RC transmitter’s throttle stick is too high
Lower throttle stick or repeat radio calibration
Throttle radio max too low
RC throttle channel max below 1700
Repeat the radio calibration procedure or increase RC2_MAX above 1700
Throttle radio min too high
RC throttle channel min above 1300
Repeat the radio calibration procedure or reduce RC1_MIN below 1300
Too many auxiliary authorisers
More than 3 external systems controlling arming
Check external authorisation system
vehicle outside fence
Vehicle is outside the fence
Move vehicle within the fence
VisOdom: not healthy
VisualOdometry sensor is not providing data
Check visual odometry physical connection and configuration
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 radio calibration
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 radio calibration
Yaw radio max too low
RC yaw channel max below 1700
Repeat the radio calibration procedure or increase RC2_MAX above 1700
Yaw radio min too high
RC yaw channel min above 1300
Repeat the radio calibration procedure or reduce RC1_MIN below 1300
Message
Cause
Solution
ADSB threat detected
ADSB failsafe. Manned vehicles nearby
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
Auto mode not armable
Vehicle cannot be armed in Auto mode
Switch to another mode (like Loiter) or set RTL_OPTIONS = 3. See Auto mode
Bad parameter: ATC_ANG_PIT_P must be > 0
Attitude controller misconfiguration
Increase specified parameter value to be above zero. See Tuning Process Instructions
Bad parameter: PSC_POSXY_P must be > 0
Position controller misconfiguration
Increase specified parameter value to be above zero. See Tuning Process Instructions
Battery failsafe
Battery failsafe has triggered
Plug in battery and check its voltage and capacity. See ref:battery failsafe configuration <failsafe-battery>
Check ACRO_BAL_ROLL/PITCH
ACRO_BAL_ROLL or ACRO_BAL_PITCH too high
Reduce ACRO_BAL_ROLL below ATC_ANG_RLL_P and/or ACRO_BAL_PITCH below ATC_ANG_PIT_P. See Acro mode
Check ANGLE_MAX
ANGLE_MAX set too high
Reduce ANGLE_MAX to 8000 (e.g. 80 degrees) or lower
Check FS_THR_VALUE
RC failsafe misconfiguration
Set FS_THR_VALUE between 910 and RC throttle’s min (e.g RC3_MIN. See ref:battery failsafe configuration <failsafe-battery>
Check PILOT_SPEED_UP
PILOT_SPEED_UP set too low
Increase PILOT_SPEED_UP to a positive number (e.g. 100 = 1m/s). See AltHold mode
Collective below failsafe (TradHeli only)
RC collective input is below FS_THR_VALUE
Turn on RC transmitter or check FS_THR_VALUE. Check RC failsafe setup
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 compass calibration. Disable internal compass.
EKF height variance
Barometer values are unstable or high vibration
EKF position variance
GPS position is unstable
Wait. If indoors, go outside. Eliminate radio-frequency sources that could interfere with the GPS
EKF velocity variance
GPS or optical flow velocities are unstable
Wait. If indoors, go outside. Eliminate radio-frequency sources that could interfere with the GPS. Check optical flow calibration
Fence enabled, need position estimate
Fence is enabled so need a position estimate
Wait. If indoors, go outside. Ensure compass and accelerometer calibrations have been completed. Eliminate radio-frequency sources that could interfere with the GPS. See Fence configuration
FS_GCS_ENABLE=2 removed, see FS_OPTIONS
GCS failsafe misconfiguration
Set FS_GCS_ENABLE = 1 and check FS_OPTIONS parameter. See ref:GCS Failsafe configuration<gcs-failsafe>
GCS failsafe on
GCS failsafe has triggered
Check telemetry connection. See ref:GCS Failsafe configuration<gcs-failsafe>
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 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 (TradHeli only)
Incompatible auxiliary function switch configured
Remove Interlock, E-Stop or Emergency Stop from auxiliary function setup
Invalid MultiCopter FRAME_CLASS
FRAME_CLASS parameter misconfigured
Multicopter firmware loaded but FRAME_CLASS set to helicopter. Load helicopter firmware or change FRAME_CLASS
Inverted flight option not supported
Inverted flight auxiliary function not supported
Remove auxiliary function 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 auxiliary function switch to low position
Motor Interlock not configured
Helicopters require motor interlock be configured
Enable the motor interlock auxiliary function 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 MOT_PWM_MIN = 1000 and MOT_PWM_MAX = 2000 and repeat the ESC calibration
Motors: MOT_SPIN_ARM > MOT_SPIN_MIN
MOT_SPIN_ARM is too high or MOT_SPIN_MIN is too low
Reducse MOT_SPIN_ARM to below MOT_SPIN_MIN. See Seting motor range
Motors: MOT_SPIN_MIN too high x > 0.3
MOT_SPIN_MIN parameter value is too high
Reduce MOT_SPIN_MIN to below 0.3. See Setting 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 ESC and motor configuration
Need Alt Estimate
EKF has not yet calculated the altitude
Wait. Allow autopilot to heat up. Ensure accelerometer calibration has been done.
Need Position Estimate
EKF does not have a position estimate
Wait. If indoors, go outside. Ensure compass and accelerometer calibrations have been completed. Eliminate radio-frequency sources that could interfere with the GPS
Proximity x deg, ym (want > Zm)
Obstacles too close to vehicle
Move obstacles away from vehicle or check sensor. See proximity sensor configuration
RTL mode not armable
Vehicle cannot be armed in RTL mode
Switch to another flight mode
RTL_ALT_TYPE is above-terrain but no rangefinder
RTL uses rangefinder but rangefinder unavailable
Check rangefinder configuration including RNGFNDx_ORIENT=251
RTL_ALT_TYPE is above-terrain but no terrain data
RTL uses terrain but Terrain database unavailable
RTL_ALT_TYPE is above-terrain but RTL_ALT>RNGFND_MAX_CM
RTL return altitude above rangefinder range
Reduce RTL_ALT to less than RNGFNDx_MAX_CM. See Terrain Following
Safety Switch
Hardware safety switch has not been pushed
Push safety switch (normally on top of GPS) or disable by setting BRD_SAFETY_DEFLT to zero and reboot autopilot
Throttle below failsafe
RC throttle input is below FS_THR_VALUE
Turn on RC transmitter or check FS_THR_VALUE. Check RC failsafe setup
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 configuration

举例:PreArm总线电压异常(4.2V,不在4.3-4.8之间)

排查发现,Pixhawk供电电压5.0V时,Vcc采集为4.67V。采集电压不准确。
notion image
排查供电若无异常,可以通过修改总线电压报警低限值,取消该报警。
notion image

五、解锁/上锁详细说明

5.1 解锁源码分析

  1. 由于解锁命令会周期调用,为了防止多次进入,解锁函数被多次执行并发问题。首先在函数开始处,判断是否在此函数中,在此函数中,程序会直接跳出;
  1. 调用AP_Arming::arm方法,做解锁检测,若检测不通过,设置标志,直接跳出;
  1. 日志记录解锁成功事件(event);
  1. 发出解锁成功提醒;
  1. 获取姿态航向参考系统 ahrs 航向作为解锁初始航向;
  1. hal库设置软件解锁功能主要设置解锁时间;
  1. enable_motor_output() 电机输出最小值。
 

5.2 上锁源码分析

上锁主要保存罗盘偏移、向电机发送上锁命令,重置任务和清除输入保持。
 

 
 
上一篇
电机库源码分析
下一篇
定深模式日志分析

Comments
Loading...