I’m running ArduPlane 4.6.2 on a CUAV X7+ carrier board. Attached is crash_dump.bin file.
The first time it was powered on, everything was fine(The firmware version used at that time was 4.3.7,and all other hardware plugged into the arupilot);
After updating the firmware to 4.6.2,When I use the MP “Preflight Reboot Shutdown” function, the IMU LED light does not light up after the flight controller enters “bootloader”;But it can start normally using USB;And then,the problem starting.“PreArm:CrashDump data detected”
I unplugged all other hardware plugged into the flight controller, restarted it repeatedly, and occasionally reproduced the "The LED light does not light up after entering bootloader "
I’ve had a look, and this seems to be an issue with the GPS driver:
#0 0x00000000 in ?? ()
#1 0x08059550 in AP_GPS::pre_arm_checks (this=0x30003708 <plane+856>, failure_msg=failure_msg@entry=0x30001cb4 "",
failure_msg_len=failure_msg_len@entry=100) at ../../libraries/AP_GPS/AP_GPS.cpp:1825
#2 0x080f75fa in AP_Arming::gps_checks (this=0x3000c614 <plane+37476>, report=<optimized out>)
at ../../libraries/AP_Arming/AP_Arming.cpp:640
#3 0x080f896c in AP_Arming::pre_arm_checks (this=0x3000c614 <plane+37476>, report=<optimized out>)
at ../../libraries/AP_Arming/AP_Arming.cpp:1611
#4 0x080f8b7c in AP_Arming::pre_arm_checks (this=this@entry=0x3000c614 <plane+37476>, report=report@entry=true)
at ../../libraries/AP_Arming/AP_Arming.cpp:1680
#5 0x08022180 in AP_Arming_Plane::pre_arm_checks (display_failure=true, this=0x3000c614 <plane+37476>)
at ../../ArduPlane/AP_Arming.cpp:67
#6 AP_Arming_Plane::pre_arm_checks (this=0x3000c614 <plane+37476>, display_failure=<optimized out>)
at ../../ArduPlane/AP_Arming.cpp:47
#7 0x080b8b9e in GCS_MAVLINK::handle_command_run_prearm_checks (this=0x30024680, packet=...)
at ../../libraries/GCS_MAVLink/GCS_Common.cpp:4781
#8 GCS_MAVLINK::handle_command_run_prearm_checks (packet=..., this=0x30024680) at ../../libraries/GCS_MAVLink/GCS_Common.cpp:4776
#9 GCS_MAVLINK::handle_command_int_packet (this=0x30024680, packet=..., msg=...)
at ../../libraries/GCS_MAVLink/GCS_Common.cpp:5592
#10 0x080b56b6 in GCS_MAVLINK::try_command_long_as_command_int (this=this@entry=0x30024680, packet=..., msg=...)
at ../../libraries/GCS_MAVLink/GCS_Common.cpp:5133
#11 0x080b5764 in GCS_MAVLINK::handle_command_long (this=0x30024680, msg=...) at ../../libraries/GCS_MAVLink/GCS_Common.cpp:5186
#12 0x080b50be in GCS_MAVLINK::update_receive (this=0x30024680, max_time_us=max_time_us@entry=1000)
at ../../libraries/GCS_MAVLink/GCS_Common.cpp:1885
#13 0x080b6f1a in GCS_MAVLINK::update_receive (max_time_us=1000, this=<optimized out>) at ../../libraries/GCS_MAVLink/GCS.h:420
#14 GCS::update_receive (this=0x300092c8 <plane+24344>) at ../../libraries/GCS_MAVLink/GCS_Common.cpp:2705
#15 0x080a6cf4 in AP_Vehicle::scheduler_delay_callback () at ../../libraries/AP_Vehicle/AP_Vehicle.cpp:719
#16 0x0806526c in AP_HAL::Scheduler::call_delay_cb (this=0x300175cc <schedulerInstance>) at ../../libraries/AP_HAL/Scheduler.cpp:26
#17 0x0816bb64 in ChibiOS::Scheduler::delay (this=0x300175cc <schedulerInstance>, ms=<optimized out>)
at ../../libraries/AP_HAL_ChibiOS/Scheduler.cpp:238
#18 0x08054664 in AP_Compass_IST8310::init (this=this@entry=0x300249f8) at ../../libraries/AP_Compass/AP_Compass_IST8310.cpp:130
#19 0x08054818 in AP_Compass_IST8310::probe (dev=..., force_external=<optimized out>, rotation=<optimized out>)
at ../../libraries/AP_Compass/AP_Compass_IST8310.cpp:90
#20 0x080501ee in Compass::_probe_external_i2c_compasses (this=this@entry=0x30003cec <plane+2364>)
at ../../libraries/AP_Compass/AP_Compass.cpp:1275
#21 0x08050d42 in Compass::_detect_backends (this=0x30003cec <plane+2364>) at ../../libraries/AP_Compass/AP_Compass.cpp:1404
#22 0x08051032 in Compass::init (this=0x30003cec <plane+2364>) at ../../libraries/AP_Compass/AP_Compass.cpp:845
#23 0x0803d346 in Plane::init_ardupilot (this=0x300033b0 <plane>) at ../../ArduPlane/system.cpp:66
#24 0x080a7258 in AP_Vehicle::setup (this=0x300033b0 <plane>) at ../../libraries/AP_Vehicle/AP_Vehicle.cpp:421
#25 0x08114658 in main_loop () at ../../libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp:256
#26 HAL_ChibiOS::run (this=<optimized out>, argc=<optimized out>, argv=<optimized out>, callbacks=0x300033b0 <plane>)
at ../../libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp:354
#27 0x08023818 in main (argc=<optimized out>, argv=<optimized out>) at ../../ArduPlane/ArduPlane.cpp:1075
I suspect the problem is that a pre-arm request came in over mavlink before the GPS was detected. I think there is a fix for this in 4.7.x
ping @peterbarker