ArduCopter Faults appear on startup and remain while drone is operational

Hello,

My team is using a Pixhawk 4 running ArduCopter firmware to run a small quadrotor. Though the vehicle has successfully taken off and flown missions, there are a number of sensor faults that appear upon startup, and persist throughout operation.

The faults can be found below:

[01/01/70 00:00:03] INFO: Fault: SENSOR_3D_GYRO
[01/01/70 00:00:03] INFO: Fault: SENSOR_3D_ACCEL
[01/01/70 00:00:03] INFO: Fault: SENSOR_3D_MAG
[01/01/70 00:00:03] INFO: Fault: SENSOR_ABSOLUTE_PRESSURE
[01/01/70 00:00:03] INFO: Fault: SENSOR_GPS
[01/01/70 00:00:03] INFO: Fault: SENSOR_ANGULAR_RATE_CONTROL
[01/01/70 00:00:03] INFO: Fault: SENSOR_ATTITUDE_STABILIZATION
[01/01/70 00:00:03] INFO: Fault: SENSOR_YAW_POSITION
[01/01/70 00:00:03] INFO: Fault: SENSOR_MOTOR_OUTPUTS
[01/01/70 00:00:03] INFO: Fault: AHRS
[01/01/70 00:00:03] INFO: Fault: TERRAIN
[01/01/70 00:00:03] INFO: Fault: LOGGING
[01/01/70 00:00:03] INFO: Fault: SENSOR_BATTERY

fault: 2 healthy: 0 enabled: 1 present: 1 mask: 1
fault: 3 healthy: 0 enabled: 1 present: 1 mask: 2
fault: 4 healthy: 0 enabled: 1 present: 1 mask: 4
fault: 5 healthy: 0 enabled: 1 present: 1 mask: 8
fault: 7 healthy: 0 enabled: 1 present: 1 mask: 32
fault: 12 healthy: 0 enabled: 1 present: 1 mask: 1024
fault: 13 healthy: 0 enabled: 1 present: 1 mask: 2048
fault: 14 healthy: 0 enabled: 1 present: 1 mask: 4096
fault: 17 healthy: 0 enabled: 1 present: 1 mask: 32768
fault: 18 healthy: 0 enabled: 1 present: 1 mask: 65536
fault: 23 healthy: 0 enabled: 1 present: 1 mask: 2097152
fault: 24 healthy: 0 enabled: 1 present: 1 mask: 4194304
fault: 27 healthy: 0 enabled: 1 present: 1 mask: 33554432

Interestingly, each of these faults shows that each sensor seems to be enabled and present, but not healthy.

To clarify, the above bits correspond to the following:

/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. /
#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR
#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR
typedef enum MAV_SYS_STATUS_SENSOR
{
MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /
0x01 3D gyro | /
MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /
0x02 3D accelerometer | /
MAV_SYS_STATUS_SENSOR_3D_MAG=4, /
0x04 3D magnetometer | /
MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE=8, /
0x08 absolute pressure | /
MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE=16, /
0x10 differential pressure | /
MAV_SYS_STATUS_SENSOR_GPS=32, /
0x20 GPS | /
MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW=64, /
0x40 optical flow | /
MAV_SYS_STATUS_SENSOR_VISION_POSITION=128, /
0x80 computer vision position | /
MAV_SYS_STATUS_SENSOR_LASER_POSITION=256, /
0x100 laser based position | /
MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH=512, /
0x200 external ground truth (Vicon or Leica) | /
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL=1024, /
0x400 3D angular rate control | /
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION=2048, /
0x800 attitude stabilization | /
MAV_SYS_STATUS_SENSOR_YAW_POSITION=4096, /
0x1000 yaw position | /
MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /
0x2000 z/altitude control | /
MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /
0x4000 x/y position control | /
MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /
0x8000 motor outputs / control | /
MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /
0x10000 rc receiver | /
MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /
0x20000 2nd 3D gyro | /
MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /
0x40000 2nd 3D accelerometer | /
MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /
0x80000 2nd 3D magnetometer | /
MAV_SYS_STATUS_GEOFENCE=1048576, /
0x100000 geofence | /
MAV_SYS_STATUS_AHRS=2097152, /
0x200000 AHRS subsystem health | /
MAV_SYS_STATUS_TERRAIN=4194304, /
0x400000 Terrain subsystem health | /
MAV_SYS_STATUS_REVERSE_MOTOR=8388608, /
0x800000 Motors are reversed | /
MAV_SYS_STATUS_LOGGING=16777216, /
0x1000000 Logging | /
MAV_SYS_STATUS_SENSOR_BATTERY=33554432, /
0x2000000 Battery | /
MAV_SYS_STATUS_SENSOR_PROXIMITY=67108864, /
0x4000000 Proximity | /
MAV_SYS_STATUS_SENSOR_SATCOM=134217728, /
0x8000000 Satellite Communication | /
MAV_SYS_STATUS_SENSOR_ENUM_END=134217729, /
| */
} MAV_SYS_STATUS_SENSOR;
#endif

As I mentioned, the drone operated successfully despite these faults. So are these faults really occurring due to a hardware failure of the drone? Or could they be the result of a configuration option? Or are they not impactful enough and should be disabled if the drone is working?

Thank you for your time!
Jeremy

My team is using a Pixhawk 4 running ArduCopter firmware to run a small quadrotor. Though the vehicle has successfully taken off and flown missions, there
are a number of sensor faults that appear upon startup, and persist throughout operation.

Sorry, but at this point I suspect an analysis issue here. Copter’s
filling in of some of these flags looks like this:

 control_sensors_present |=
     MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
     MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
     MAV_SYS_STATUS_SENSOR_YAW_POSITION;

 control_sensors_enabled |=
     MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
     MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
     MAV_SYS_STATUS_SENSOR_YAW_POSITION;

 control_sensors_health |=
     MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
     MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
     MAV_SYS_STATUS_SENSOR_YAW_POSITION;

Note that I’m assuming you’re running master. Is that the case? If it
is, then I’ll have to work out what path can make those flags zero :slight_smile:
Come to think of it, perhaps we should make them unhealthy when disarmed -
you definitely don’t have yaw rate control in that case :wink:

These are always healthy, from when the vehicle is booted if I’m
thinking right.

The faults can be found below:

As I mentioned, the drone operated successfully despite these faults. So are these faults really occurring due to a hardware failure of the drone? Or
could they be the result of a configuration option? Or are they not impactful enough and should be disabled if the drone is working?

Some of them can definitely occur during runtime - sometimes be
persistent, sometimes go away. Being unable to get terrain data for a
while might send that bit unhealthy, for example. Having your battery go
low will set that bit… that sort of thing.

You should definitely look into what’s going on. Log analysis saves
vehicles - and you need to be able to trust your tools, which that output
appears to make difficult (from my perspective).

Jeremy

Yours,