Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Floating Point Exception in the position controller #28969

Closed
peterbarker opened this issue Dec 30, 2024 · 2 comments
Closed

Floating Point Exception in the position controller #28969

peterbarker opened this issue Dec 30, 2024 · 2 comments

Comments

@peterbarker
Copy link
Contributor

CI run produced an FPE while running test.Plane.FlyEachFrame. I've never seen this before.

The PR in question is going absolutely nowhere near the relevant code (should actually be a no-compiler-output change in SITL?). #28966

Link to output is below, also excerpted below.

Seems to be something wrong with the maths in limit_accel_xy - we're taking the square root of a negative number; something wrong with taking the cross product, perhaps?! Thankfully the output below contains values for all of the variables required...

https://productionresultssa10.blob.core.windows.net/actions-results/4e63b159-021f-4b97-a167-86fc7dcf4f13/workflow-job-run-6b0240de-2d48-582d-e68b-9616ef328464/logs/job/job-logs.txt?rsct=text%2Fplain&se=2024-12-30T07%3A30%3A15Z&sig=CO5BGQOMT4%2FEO2n%2F2x77s%2FBvK54kxyiUgE7qSlhKxUs%3D&ske=2024-12-30T19%3A10%3A12Z&skoid=ca7593d4-ee42-46cd-af88-8b886a2f84eb&sks=b&skt=2024-12-30T07%3A10%3A12Z&sktid=398a6654-997b-47e9-b12b-9515b896b4de&skv=2024-11-04&sp=r&spr=https&sr=b&st=2024-12-30T07%3A20%3A10Z&sv=2024-11-04

2024-12-30T06:13:01.8519750Z AT-0413.1: AP: VTOL position1 v=21.3 d=169.1 h=49.8 dc=19.6
2024-12-30T06:13:01.8520094Z arduplane: ERROR: Floating point exception - aborting
2024-12-30T06:13:01.8520719Z arduplane: Running: sh Tools/scripts/dumpstack.sh 8040 >dumpstack.sh_arduplane.8040.out 2>&1
2024-12-30T06:13:01.8521189Z arduplane: dumpstack.sh has been run.  Output was:
2024-12-30T06:13:01.8521547Z arduplane: -------------- begin dumpstack.sh output ----------------
2024-12-30T06:13:01.8521872Z arduplane: [New LWP 8041]
2024-12-30T06:13:01.8522144Z arduplane: [Thread debugging using libthread_db enabled]
2024-12-30T06:13:01.8522575Z arduplane: Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
2024-12-30T06:13:01.8523073Z arduplane: 0x00007fe61ddfb42f in wait4 () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8523543Z arduplane: #0  0x00007fe61ddfb42f in wait4 () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8523926Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8524278Z arduplane: #1  0x00007fe61dd61bdb in ?? () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8524638Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8533257Z arduplane: #2  0x000055788a89e19f in AP_HAL::run_command_on_ownpid (commandname=0x55788aa1a1af "dumpstack.sh") at ../../libraries/AP_HAL_SITL/system.cpp:127
2024-12-30T06:13:01.8534641Z arduplane:         command_filepath = 0x7ffdaf31f660 "Tools/scripts/dumpstack.sh"
2024-12-30T06:13:01.8535865Z arduplane:         statbuf = {st_dev = 2065, st_ino = 527244, st_nlink = 1, st_mode = 33261, st_uid = 0, st_gid = 0, __pad0 = 0, st_rdev = 0, st_size = 265, st_blksize = 4096, st_blocks = 8, st_atim = {tv_sec = 1735538476, tv_nsec = 968517313}, st_mtim = {tv_sec = 1735538476, tv_nsec = 968517313}, st_ctim = {tv_sec = 1735538476, tv_nsec = 968517313}, __glibc_reserved = {0, 0, 0}}
2024-12-30T06:13:01.8537613Z arduplane:         custom_scripts_dir_path = 0x0
2024-12-30T06:13:01.8538484Z arduplane:         custom_scripts_dir_path_pattern = 0x0
2024-12-30T06:13:01.8539517Z arduplane:         paths = {0x0, 0x55788aa1a06b "Tools/scripts/%s", 0x55788aa1a07c "APM/Tools/scripts/%s", 0x55788aa1a091 "../Tools/scripts/%s"}
2024-12-30T06:13:01.8541241Z arduplane:         buffer = "Tools/scripts/dumpstack.sh\000\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"
2024-12-30T06:13:01.8543296Z arduplane:         progname = "/__w/ardupilot/ardupilot/build/sitl/bin\000arduplane\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"
2024-12-30T06:13:01.8544682Z arduplane:         n = 49
2024-12-30T06:13:01.8545053Z arduplane:         p = 0x7ffdaf31f717 ""
2024-12-30T06:13:01.8546307Z arduplane:         output_filepath = "dumpstack.sh_arduplane.8040.out\000\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"
2024-12-30T06:13:01.8549709Z arduplane:         cmd = "sh Tools/scripts/dumpstack.sh 8040 >dumpstack.sh_arduplane.8040.out 2>&1\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"
2024-12-30T06:13:01.8552083Z arduplane:         fd = 2141192192
2024-12-30T06:13:01.8555083Z arduplane:         buf = "\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"...
2024-12-30T06:13:01.8558307Z arduplane: #3  0x000055788a89e34d in AP_HAL::dump_stack_trace () at ../../libraries/AP_HAL_SITL/system.cpp:159
2024-12-30T06:13:01.8559065Z arduplane: No locals.
2024-12-30T06:13:01.8559724Z arduplane: #4  0x000055788a89ef34 in _sig_fpe (signum=8) at ../../libraries/AP_HAL_SITL/SITL_cmdline.cpp:65
2024-12-30T06:13:01.8560456Z arduplane: No locals.
2024-12-30T06:13:01.8560811Z arduplane: #5  <signal handler called>
2024-12-30T06:13:01.8561274Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8561893Z arduplane: #6  0x00007fe61df6c49c in ?? () from /lib/x86_64-linux-gnu/libm.so.6
2024-12-30T06:13:01.8562662Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8563291Z arduplane: #7  0x00007fe61df6e6e5 in ?? () from /lib/x86_64-linux-gnu/libm.so.6
2024-12-30T06:13:01.8563913Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8564666Z arduplane: #8  0x000055788a6d8822 in safe_sqrt<float> (v=-0.03125) at ../../libraries/AP_Math/AP_Math.cpp:73
2024-12-30T06:13:01.8565405Z arduplane:         ret = 566.187256
2024-12-30T06:13:01.8566232Z arduplane: #9  0x000055788a6daa7e in limit_accel_xy (vel=..., accel=..., accel_max=566.187256) at ../../libraries/AP_Math/control.cpp:390
2024-12-30T06:13:01.8567133Z arduplane:         accel_max_dir = 4.59135442e-41
2024-12-30T06:13:01.8567835Z arduplane:         vel_input_unit = {x = 0.984285712, y = 0.176583186}
2024-12-30T06:13:01.8568392Z arduplane:         accel_dir = -0.0795593262
2024-12-30T06:13:01.8568938Z arduplane:         accel_cross = {x = 99.9791489, y = -557.290039}
2024-12-30T06:13:01.8570050Z arduplane: #10 0x000055788a8577ca in AC_PosControl::update_xy_controller (this=0x55788b15f850) at ../../libraries/AC_AttitudeControl/AC_PosControl.cpp:706
2024-12-30T06:13:01.8571094Z arduplane:         ahrsGndSpdLimit = 400
2024-12-30T06:13:01.8571545Z arduplane:         ahrsControlScaleXY = 1
2024-12-30T06:13:01.8572195Z arduplane:         curr_pos = @0x55788ab23238: {x = -17819.6914, y = 3957.76709, z = 4968.15088}
2024-12-30T06:13:01.8572950Z arduplane:         comb_pos = {x = -17819.6914, y = 3957.76709, z = 4968.15088}
2024-12-30T06:13:01.8573522Z arduplane:         vel_target = {x = 0, y = 0}
2024-12-30T06:13:01.8574094Z arduplane:         curr_vel = @0x55788ab23244: {x = 2097.99463, y = 376.385193}
2024-12-30T06:13:01.8574725Z arduplane:         comb_vel = {x = 2097.99463, y = 376.385193}
2024-12-30T06:13:01.8575307Z arduplane:         accel_target = {x = 99.9008408, y = -557.304077}
2024-12-30T06:13:01.8575829Z arduplane:         angle_max = 3000
2024-12-30T06:13:01.8576244Z arduplane:         accel_max = 566.187256
2024-12-30T06:13:01.8577379Z arduplane: #11 0x000055788a6595fe in QuadPlane::run_xy_controller (this=0x55788ab23220 <plane+54528>, accel_limit=3) at ../../ArduPlane/quadplane.cpp:2169
2024-12-30T06:13:01.8578422Z arduplane:         accel_cmss = 300
2024-12-30T06:13:01.8578826Z arduplane:         speed_cms = 500
2024-12-30T06:13:01.8579781Z arduplane: #12 0x000055788a65b287 in QuadPlane::vtol_position_controller (this=0x55788ab23220 <plane+54528>) at ../../ArduPlane/quadplane.cpp:2621
2024-12-30T06:13:01.8581098Z arduplane:         rel_groundspeed_vector = {x = 20.9799461, y = 3.76385188}
2024-12-30T06:13:01.8581693Z arduplane:         stopping_speed = 28.2293301
2024-12-30T06:13:01.8582271Z arduplane:         target_speed_xy_cms = {x = 2104.06812, y = -341.523285}
2024-12-30T06:13:01.8582909Z arduplane:         target_accel_cms = {x = -117.963844, y = 19.1473846}
2024-12-30T06:13:01.8583616Z arduplane:         target_yaw_deg = -9.219594
2024-12-30T06:13:01.8584082Z arduplane:         distance = 169.129776
2024-12-30T06:13:01.8584563Z arduplane:         closing_groundspeed = 20.105875
2024-12-30T06:13:01.8585058Z arduplane:         target_speed = 21.320034
2024-12-30T06:13:01.8585465Z arduplane:         wp_speed = 5
2024-12-30T06:13:01.8585893Z arduplane:         scaled_wp_speed = 4.73900986
2024-12-30T06:13:01.8586425Z arduplane:         diff_wp = {x = 166.94487, y = -27.0977764}
2024-12-30T06:13:01.8586940Z arduplane:         target_accel = 1.19507706
2024-12-30T06:13:01.8587423Z arduplane:         rel_groundspeed_sq = 454.324738
2024-12-30T06:13:01.8587902Z arduplane:         have_target_yaw = false
2024-12-30T06:13:01.8588373Z arduplane:         target_speed_ms = 21.320034
2024-12-30T06:13:01.8589911Z arduplane:         loc = @0x55788ab23068: {relative_alt = 0 '\000', loiter_ccw = 0 '\000', terrain_alt = 0 '\000', origin_alt = 0 '\000', loiter_xtrack = 0 '\000', alt = 63825, lat = -353630410, lng = 1491652220, static LOCATION_SCALING_FACTOR = 0.0111318845, static LOCATION_SCALING_FACTOR_INV = 89.8320465}
2024-12-30T06:13:01.8591506Z arduplane:         now_ms = 184369
2024-12-30T06:13:01.8591950Z arduplane:         position2_dist_threshold = 10
2024-12-30T06:13:01.8592448Z arduplane:         position2_target_speed = 3
2024-12-30T06:13:01.8592947Z arduplane:         suppress_z_controller = false
2024-12-30T06:13:01.8593469Z arduplane:         landing_velocity = {x = 0, y = 0}
2024-12-30T06:13:01.8594419Z arduplane: #13 0x000055788a65d6aa in QuadPlane::control_auto (this=0x55788ab23220 <plane+54528>) at ../../ArduPlane/quadplane.cpp:3250
2024-12-30T06:13:01.8595325Z arduplane:         id = 85
2024-12-30T06:13:01.8596121Z arduplane: #14 0x000055788a648ec9 in ModeAuto::update (this=0x55788ab21378 <plane+46680>) at ../../ArduPlane/mode_auto.cpp:77
2024-12-30T06:13:01.8597086Z arduplane:         nav_cmd_id = 85
2024-12-30T06:13:01.8597925Z arduplane: #15 0x000055788a6368ed in Plane::update_control_mode (this=0x55788ab15d20 <plane>) at ../../ArduPlane/Plane.cpp:516
2024-12-30T06:13:01.8598772Z arduplane: No locals.
2024-12-30T06:13:01.8599817Z arduplane: #16 0x000055788a639dbc in Functor<void>::method_wrapper<Plane, &Plane::update_control_mode> (obj=0x55788ab15d20 <plane>) at ../../libraries/AP_HAL/utility/functor.h:88
2024-12-30T06:13:01.8600920Z arduplane:         t = 0x55788ab15d20 <plane>
2024-12-30T06:13:01.8601927Z arduplane: #17 0x000055788a6efeb0 in Functor<void>::operator() (this=0x55788aae6160 <Plane::scheduler_tasks+32>) at ../../libraries/AP_HAL/utility/functor.h:54
2024-12-30T06:13:01.8602930Z arduplane: No locals.
2024-12-30T06:13:01.8603839Z arduplane: #18 0x000055788a7533c1 in AP_Scheduler::run (this=0x55788ab15ee8 <plane+456>, time_available=3333) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:264
2024-12-30T06:13:01.8604867Z arduplane:         run_vehicle_task = true
2024-12-30T06:13:01.8606514Z arduplane:         task = @0x55788aae6160: {function = {_obj = 0x55788ab15d20 <plane>, _method = 0x55788a639d98 <Functor<void>::method_wrapper<Plane, &Plane::update_control_mode>(void*)>}, name = 0x55788a9e97f9 "Plane::update_control_mode*", rate_hz = 0, max_time_micros = 0, priority = 0 '\000'}
2024-12-30T06:13:01.8608158Z arduplane:         time_taken = 0
2024-12-30T06:13:01.8608653Z arduplane:         overrun = false
2024-12-30T06:13:01.8609046Z arduplane:         i = 1 '\001'
2024-12-30T06:13:01.8609457Z arduplane:         run_started_usec = 184369556
2024-12-30T06:13:01.8609904Z arduplane:         now = 184369556
2024-12-30T06:13:01.8610337Z arduplane:         vehicle_tasks_offset = 2 '\002'
2024-12-30T06:13:01.8610832Z arduplane:         common_tasks_offset = 0 '\000'
2024-12-30T06:13:01.8611795Z arduplane: #19 0x000055788a753870 in AP_Scheduler::loop (this=0x55788ab15ee8 <plane+456>) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:393
2024-12-30T06:13:01.8612748Z arduplane:         sample_time_us = 184369556
2024-12-30T06:13:01.8613179Z arduplane:         loop_us = 3333
2024-12-30T06:13:01.8613639Z arduplane:         now = 184369556
2024-12-30T06:13:01.8614030Z arduplane:         time_available = 3333
2024-12-30T06:13:01.8614433Z arduplane:         loop_tick_us = 0
2024-12-30T06:13:01.8615279Z arduplane: #20 0x000055788a759779 in AP_Vehicle::loop (this=0x55788ab15d20 <plane>) at ../../libraries/AP_Vehicle/AP_Vehicle.cpp:539
2024-12-30T06:13:01.8616181Z arduplane:         new_internal_errors = 0
2024-12-30T06:13:01.8617421Z arduplane: #21 0x000055788a893418 in HAL_SITL::run (this=0x55788ab319e0 <hal_sitl_inst>, argc=10, argv=0x7ffdaf3208c8, callbacks=0x55788ab15d20 <plane>) at ../../libraries/AP_HAL_SITL/HAL_SITL_Class.cpp:289
2024-12-30T06:13:01.8618648Z arduplane:         now = 184367
2024-12-30T06:13:01.8619378Z arduplane:         __PRETTY_FUNCTION__ = "virtual void HAL_SITL::run(int, char* const*, AP_HAL::HAL::Callbacks*) const"
2024-12-30T06:13:01.8620168Z arduplane:         new_argv_offset = 9 '\t'
2024-12-30T06:13:01.8620808Z arduplane:         using_watchdog = false
2024-12-30T06:13:01.8621272Z arduplane:         last_watchdog_save = 1754
2024-12-30T06:13:01.8621845Z arduplane:         fill_count = 3 '\003'
2024-12-30T06:13:01.8622579Z arduplane: #22 0x000055788a63974b in main (argc=10, argv=0x7ffdaf3208c8) at ../../ArduPlane/Plane.cpp:1070
2024-12-30T06:13:01.8623316Z arduplane: No locals.
2024-12-30T06:13:01.8623646Z arduplane: 
2024-12-30T06:13:01.8624075Z arduplane: Thread 2 (Thread 0x7fe61dcd9640 (LWP 8041) "log_io"):
2024-12-30T06:13:01.8624871Z arduplane: #0  0x00007fe61ddf67f8 in clock_nanosleep () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8625589Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8626246Z arduplane: #1  0x00007fe61ddfb677 in nanosleep () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8626968Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8627757Z arduplane: #2  0x00007fe61de2d11f in usleep () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8628420Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8629544Z arduplane: #3  0x000055788a895e47 in HALSITL::SITL_State::wait_clock (this=0x55788ab30160 <sitlState>, wait_time_usec=184370556) at ../../libraries/AP_HAL_SITL/SITL_State.cpp:179
2024-12-30T06:13:01.8630641Z arduplane:         speedup = 100
2024-12-30T06:13:01.8631712Z arduplane: #4  0x000055788a89beaa in HALSITL::Scheduler::delay_microseconds (this=0x55788ab30660 <sitlScheduler>, usec=1000) at ../../libraries/AP_HAL_SITL/Scheduler.cpp:142
2024-12-30T06:13:01.8632830Z arduplane:         dtime = 0
2024-12-30T06:13:01.8633207Z arduplane:         start = 184369556
2024-12-30T06:13:01.8634092Z arduplane: #5  0x000055788a761a40 in AP_Logger::io_thread (this=0x55788ab180a0 <plane+9088>) at ../../libraries/AP_Logger/AP_Logger.cpp:1430
2024-12-30T06:13:01.8634999Z arduplane:         now = 184369556
2024-12-30T06:13:01.8635388Z arduplane:         delay = 1000
2024-12-30T06:13:01.8635780Z arduplane:         last_run_us = 184369556
2024-12-30T06:13:01.8636223Z arduplane:         last_stack_us = 184326240
2024-12-30T06:13:01.8636685Z arduplane:         last_crash_check_us = 5031320
2024-12-30T06:13:01.8637178Z arduplane:         done_crash_dump_save = true
2024-12-30T06:13:01.8638431Z arduplane: #6  0x000055788a7627bd in Functor<void>::method_wrapper<AP_Logger, &AP_Logger::io_thread> (obj=0x55788ab180a0 <plane+9088>) at ../../libraries/AP_HAL/utility/functor.h:88
2024-12-30T06:13:01.8639595Z arduplane:         t = 0x55788ab180a0 <plane+9088>
2024-12-30T06:13:01.8640509Z arduplane: #7  0x000055788a6efeb0 in Functor<void>::operator() (this=0x55788b158a10) at ../../libraries/AP_HAL/utility/functor.h:54
2024-12-30T06:13:01.8641353Z arduplane: No locals.
2024-12-30T06:13:01.8642252Z arduplane: #8  0x000055788a89c485 in HALSITL::Scheduler::thread_create_trampoline (ctx=0x55788b158a30) at ../../libraries/AP_HAL_SITL/Scheduler.cpp:317
2024-12-30T06:13:01.8643238Z arduplane:         a = 0x55788b158a30
2024-12-30T06:13:01.8643653Z arduplane:         _getsem17 = {_mtx = @0x0}
2024-12-30T06:13:01.8644396Z arduplane: #9  0x00007fe61dda5ac3 in ?? () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8645024Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8645623Z arduplane: #10 0x00007fe61de37a40 in ?? () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8646242Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8646647Z arduplane: 
2024-12-30T06:13:01.8647100Z arduplane: Thread 1 (Thread 0x7fe61dd103c0 (LWP 8040) "arduplane"):
2024-12-30T06:13:01.8647859Z arduplane: #0  0x00007fe61ddfb42f in wait4 () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8648484Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8649073Z arduplane: #1  0x00007fe61dd61bdb in ?? () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:01.8649673Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8650707Z arduplane: #2  0x000055788a89e19f in AP_HAL::run_command_on_ownpid (commandname=0x55788aa1a1af "dumpstack.sh") at ../../libraries/AP_HAL_SITL/system.cpp:127
2024-12-30T06:13:01.8651871Z arduplane:         command_filepath = 0x7ffdaf31f660 "Tools/scripts/dumpstack.sh"
2024-12-30T06:13:01.8653801Z arduplane:         statbuf = {st_dev = 2065, st_ino = 527244, st_nlink = 1, st_mode = 33261, st_uid = 0, st_gid = 0, __pad0 = 0, st_rdev = 0, st_size = 265, st_blksize = 4096, st_blocks = 8, st_atim = {tv_sec = 1735538476, tv_nsec = 968517313}, st_mtim = {tv_sec = 1735538476, tv_nsec = 968517313}, st_ctim = {tv_sec = 1735538476, tv_nsec = 968517313}, __glibc_reserved = {0, 0, 0}}
2024-12-30T06:13:01.8655412Z arduplane:         custom_scripts_dir_path = 0x0
2024-12-30T06:13:01.8655944Z arduplane:         custom_scripts_dir_path_pattern = 0x0
2024-12-30T06:13:01.8656908Z arduplane:         paths = {0x0, 0x55788aa1a06b "Tools/scripts/%s", 0x55788aa1a07c "APM/Tools/scripts/%s", 0x55788aa1a091 "../Tools/scripts/%s"}
2024-12-30T06:13:01.8658517Z arduplane:         buffer = "Tools/scripts/dumpstack.sh\000\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"
2024-12-30T06:13:01.8660457Z arduplane:         progname = "/__w/ardupilot/ardupilot/build/sitl/bin\000arduplane\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"
2024-12-30T06:13:01.8663394Z arduplane:         n = 49
2024-12-30T06:13:01.8663768Z arduplane:         p = 0x7ffdaf31f717 ""
2024-12-30T06:13:01.8664995Z arduplane:         output_filepath = "dumpstack.sh_arduplane.8040.out\000\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"
2024-12-30T06:13:01.8668304Z arduplane:         cmd = "sh Tools/scripts/dumpstack.sh 8040 >dumpstack.sh_arduplane.8040.out 2>&1\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"
2024-12-30T06:13:01.8670729Z arduplane:         fd = 2141192192
2024-12-30T06:13:01.8673861Z arduplane:         buf = "\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177\000\000\240\177"...
2024-12-30T06:13:01.8677064Z arduplane: #3  0x000055788a89e34d in AP_HAL::dump_stack_trace () at ../../libraries/AP_HAL_SITL/system.cpp:159
2024-12-30T06:13:01.8677817Z arduplane: No locals.
2024-12-30T06:13:01.8678472Z arduplane: #4  0x000055788a89ef34 in _sig_fpe (signum=8) at ../../libraries/AP_HAL_SITL/SITL_cmdline.cpp:65
2024-12-30T06:13:01.8679200Z arduplane: No locals.
2024-12-30T06:13:01.8679547Z arduplane: #5  <signal handler called>
2024-12-30T06:13:01.8679992Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8680609Z arduplane: #6  0x00007fe61df6c49c in ?? () from /lib/x86_64-linux-gnu/libm.so.6
2024-12-30T06:13:01.8681246Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8681869Z arduplane: #7  0x00007fe61df6e6e5 in ?? () from /lib/x86_64-linux-gnu/libm.so.6
2024-12-30T06:13:01.8682627Z arduplane: No symbol table info available.
2024-12-30T06:13:01.8683066Z arduplane: #8  0x000055788a6d8822 in safe_sqrt<float> (v=-0.03125) at ../../libraries/AP_Math/AP_Math.cpp:73
2024-12-30T06:13:01.8683502Z arduplane:         ret = 566.187256
2024-12-30T06:13:01.8683984Z arduplane: #9  0x000055788a6daa7e in limit_accel_xy (vel=..., accel=..., accel_max=566.187256) at ../../libraries/AP_Math/control.cpp:390
2024-12-30T06:13:01.8684496Z arduplane:         accel_max_dir = 4.59135442e-41
2024-12-30T06:13:01.8684829Z arduplane:         vel_input_unit = {x = 0.984285712, y = 0.176583186}
2024-12-30T06:13:01.8685169Z arduplane:         accel_dir = -0.0795593262
2024-12-30T06:13:01.8685479Z arduplane:         accel_cross = {x = 99.9791489, y = -557.290039}
2024-12-30T06:13:01.8686232Z arduplane: #10 0x000055788a8577ca in AC_PosControl::update_xy_controller (this=0x55788b15f850) at ../../libraries/AC_AttitudeControl/AC_PosControl.cpp:706
2024-12-30T06:13:01.8686956Z arduplane:         ahrsGndSpdLimit = 400
2024-12-30T06:13:01.8687224Z arduplane:         ahrsControlScaleXY = 1
2024-12-30T06:13:01.8687601Z arduplane:         curr_pos = @0x55788ab23238: {x = -17819.6914, y = 3957.76709, z = 4968.15088}
2024-12-30T06:13:01.8688284Z arduplane:         comb_pos = {x = -17819.6914, y = 3957.76709, z = 4968.15088}
2024-12-30T06:13:01.8688760Z arduplane:         vel_target = {x = 0, y = 0}
2024-12-30T06:13:01.8689097Z arduplane:         curr_vel = @0x55788ab23244: {x = 2097.99463, y = 376.385193}
2024-12-30T06:13:01.8689458Z arduplane:         comb_vel = {x = 2097.99463, y = 376.385193}
2024-12-30T06:13:01.8689804Z arduplane:         accel_target = {x = 99.9008408, y = -557.304077}
2024-12-30T06:13:01.8690110Z arduplane:         angle_max = 3000
2024-12-30T06:13:01.8690348Z arduplane:         accel_max = 566.187256
2024-12-30T06:13:01.8690933Z arduplane: #11 0x000055788a6595fe in QuadPlane::run_xy_controller (this=0x55788ab23220 <plane+54528>, accel_limit=3) at ../../ArduPlane/quadplane.cpp:2169
2024-12-30T06:13:01.8691508Z arduplane:         accel_cmss = 300
2024-12-30T06:13:01.8691739Z arduplane:         speed_cms = 500
2024-12-30T06:13:01.8692448Z arduplane: #12 0x000055788a65b287 in QuadPlane::vtol_position_controller (this=0x55788ab23220 <plane+54528>) at ../../ArduPlane/quadplane.cpp:2621
2024-12-30T06:13:01.8693604Z arduplane:         rel_groundspeed_vector = {x = 20.9799461, y = 3.76385188}
2024-12-30T06:13:01.8694218Z arduplane:         stopping_speed = 28.2293301
2024-12-30T06:13:01.8694799Z arduplane:         target_speed_xy_cms = {x = 2104.06812, y = -341.523285}
2024-12-30T06:13:01.8695453Z arduplane:         target_accel_cms = {x = -117.963844, y = 19.1473846}
2024-12-30T06:13:01.8695787Z arduplane:         target_yaw_deg = -9.219594
2024-12-30T06:13:01.8696050Z arduplane:         distance = 169.129776
2024-12-30T06:13:01.8696321Z arduplane:         closing_groundspeed = 20.105875
2024-12-30T06:13:01.8696709Z arduplane:         target_speed = 21.320034
2024-12-30T06:13:01.8696983Z arduplane:         wp_speed = 5
2024-12-30T06:13:01.8697324Z arduplane:         scaled_wp_speed = 4.73900986
2024-12-30T06:13:01.8697643Z arduplane:         diff_wp = {x = 166.94487, y = -27.0977764}
2024-12-30T06:13:01.8697947Z arduplane:         target_accel = 1.19507706
2024-12-30T06:13:01.8698222Z arduplane:         rel_groundspeed_sq = 454.324738
2024-12-30T06:13:01.8698521Z arduplane:         have_target_yaw = false
2024-12-30T06:13:01.8698792Z arduplane:         target_speed_ms = 21.320034
2024-12-30T06:13:01.8699650Z arduplane:         loc = @0x55788ab23068: {relative_alt = 0 '\000', loiter_ccw = 0 '\000', terrain_alt = 0 '\000', origin_alt = 0 '\000', loiter_xtrack = 0 '\000', alt = 63825, lat = -353630410, lng = 1491652220, static LOCATION_SCALING_FACTOR = 0.0111318845, static LOCATION_SCALING_FACTOR_INV = 89.8320465}
2024-12-30T06:13:01.8700491Z arduplane:         now_ms = 184369
2024-12-30T06:13:01.8701004Z arduplane:         position2_dist_threshold = 10
2024-12-30T06:13:01.8701419Z arduplane:         position2_target_speed = 3
2024-12-30T06:13:01.8701704Z arduplane:         suppress_z_controller = false
2024-12-30T06:13:01.8702007Z arduplane:         landing_velocity = {x = 0, y = 0}
2024-12-30T06:13:01.8702566Z arduplane: #13 0x000055788a65d6aa in QuadPlane::control_auto (this=0x55788ab23220 <plane+54528>) at ../../ArduPlane/quadplane.cpp:3250
2024-12-30T06:13:01.8703078Z arduplane:         id = 85
2024-12-30T06:13:01.8703534Z arduplane: #14 0x000055788a648ec9 in ModeAuto::update (this=0x55788ab21378 <plane+46680>) at ../../ArduPlane/mode_auto.cpp:77
2024-12-30T06:13:01.8704017Z arduplane:         nav_cmd_id = 85
2024-12-30T06:13:01.8704493Z arduplane: #15 0x000055788a6368ed in Plane::update_control_mode (this=0x55788ab15d20 <plane>) at ../../ArduPlane/Plane.cpp:516
2024-12-30T06:13:01.8705049Z arduplane: No locals.
2024-12-30T06:13:01.8705639Z arduplane: #16 0x000055788a639dbc in Functor<void>::method_wrapper<Plane, &Plane::update_control_mode> (obj=0x55788ab15d20 <plane>) at ../../libraries/AP_HAL/utility/functor.h:88
2024-12-30T06:13:01.8706302Z arduplane:         t = 0x55788ab15d20 <plane>
2024-12-30T06:13:01.8706893Z arduplane: #17 0x000055788a6efeb0 in Functor<void>::operator() (this=0x55788aae6160 <Plane::scheduler_tasks+32>) at ../../libraries/AP_HAL/utility/functor.h:54
2024-12-30T06:13:01.8707464Z arduplane: No locals.
2024-12-30T06:13:01.8708100Z arduplane: #18 0x000055788a7533c1 in AP_Scheduler::run (this=0x55788ab15ee8 <plane+456>, time_available=3333) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:264
2024-12-30T06:13:01.8708683Z arduplane:         run_vehicle_task = true
2024-12-30T06:13:01.8709953Z arduplane:         task = @0x55788aae6160: {function = {_obj = 0x55788ab15d20 <plane>, _method = 0x55788a639d98 <Functor<void>::method_wrapper<Plane, &Plane::update_control_mode>(void*)>}, name = 0x55788a9e97f9 "Plane::update_control_mode*", rate_hz = 0, max_time_micros = 0, priority = 0 '\000'}
2024-12-30T06:13:01.8710897Z arduplane:         time_taken = 0
2024-12-30T06:13:01.8711138Z arduplane:         overrun = false
2024-12-30T06:13:01.8711366Z arduplane:         i = 1 '\001'
2024-12-30T06:13:01.8711608Z arduplane:         run_started_usec = 184369556
2024-12-30T06:13:01.8711972Z arduplane:         now = 184369556
2024-12-30T06:13:01.8712229Z arduplane:         vehicle_tasks_offset = 2 '\002'
2024-12-30T06:13:01.8712522Z arduplane:         common_tasks_offset = 0 '\000'
2024-12-30T06:13:01.8713075Z arduplane: #19 0x000055788a753870 in AP_Scheduler::loop (this=0x55788ab15ee8 <plane+456>) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:393
2024-12-30T06:13:01.8713613Z arduplane:         sample_time_us = 184369556
2024-12-30T06:13:01.8713861Z arduplane:         loop_us = 3333
2024-12-30T06:13:01.8714085Z arduplane:         now = 184369556
2024-12-30T06:13:01.8714320Z arduplane:         time_available = 3333
2024-12-30T06:13:01.8714571Z arduplane:         loop_tick_us = 0
2024-12-30T06:13:01.8715128Z arduplane: #20 0x000055788a759779 in AP_Vehicle::loop (this=0x55788ab15d20 <plane>) at ../../libraries/AP_Vehicle/AP_Vehicle.cpp:539
2024-12-30T06:13:01.8715640Z arduplane:         new_internal_errors = 0
2024-12-30T06:13:01.8716340Z arduplane: #21 0x000055788a893418 in HAL_SITL::run (this=0x55788ab319e0 <hal_sitl_inst>, argc=10, argv=0x7ffdaf3208c8, callbacks=0x55788ab15d20 <plane>) at ../../libraries/AP_HAL_SITL/HAL_SITL_Class.cpp:289
2024-12-30T06:13:01.8717022Z arduplane:         now = 184367
2024-12-30T06:13:01.8717441Z arduplane:         __PRETTY_FUNCTION__ = "virtual void HAL_SITL::run(int, char* const*, AP_HAL::HAL::Callbacks*) const"
2024-12-30T06:13:01.8717888Z arduplane:         new_argv_offset = 9 '\t'
2024-12-30T06:13:01.8718143Z arduplane:         using_watchdog = false
2024-12-30T06:13:01.8718407Z arduplane:         last_watchdog_save = 1754
2024-12-30T06:13:01.8718779Z arduplane:         fill_count = 3 '\003'
2024-12-30T06:13:01.8719199Z arduplane: #22 0x000055788a63974b in main (argc=10, argv=0x7ffdaf3208c8) at ../../ArduPlane/Plane.cpp:1070
2024-12-30T06:13:01.8719618Z arduplane: No locals.
2024-12-30T06:13:01.8719930Z arduplane: A debugging session is active.
2024-12-30T06:13:01.8720172Z arduplane: 
2024-12-30T06:13:01.8720395Z arduplane: 	Inferior 1 [process 8040] will be detached.
2024-12-30T06:13:01.8720674Z arduplane: 
2024-12-30T06:13:01.8720935Z arduplane: Quit anyway? (y or n) [answered Y; input not from terminal]
2024-12-30T06:13:22.0834109Z arduplane: [Inferior 1 (process 8040) detached]
2024-12-30T06:13:22.0834686Z arduplane: -------------- end dumpstack.sh output ----------------
2024-12-30T06:13:22.0835237Z arduplane: Running: sh Tools/scripts/dumpcore.sh 8040 >dumpcore.sh_arduplane.8040.out 2>&1
2024-12-30T06:13:22.0835997Z arduplane: dumpcore.sh has been run.  Output was:
2024-12-30T06:13:22.0837175Z arduplane: -------------- begin dumpcore.sh output ----------------
2024-12-30T06:13:22.0837544Z arduplane: [New LWP 8041]
2024-12-30T06:13:22.0837844Z arduplane: [Thread debugging using libthread_db enabled]
2024-12-30T06:13:22.0838342Z arduplane: Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
2024-12-30T06:13:22.0838926Z arduplane: 0x00007fe61ddfb42f in wait4 () from /lib/x86_64-linux-gnu/libc.so.6
2024-12-30T06:13:22.0839502Z arduplane: warning: target file /proc/8040/cmdline contained unexpected null characters
2024-12-30T06:13:22.0840130Z arduplane: warning: Memory read failed for corefile section, 4096 bytes at 0xffffffffff600000.
2024-12-30T06:13:22.0840603Z arduplane: Saved corefile ap-8055.core
2024-12-30T06:13:22.0840895Z arduplane: A debugging session is active.
2024-12-30T06:13:22.0841167Z arduplane: 
2024-12-30T06:13:22.0841408Z arduplane: 	Inferior 1 [process 8040] will be detached.
2024-12-30T06:13:22.0841716Z arduplane: 
2024-12-30T06:13:22.0842002Z arduplane: Quit anyway? (y or n) [answered Y; input not from terminal]
2024-12-30T06:13:22.0842401Z arduplane: [Inferior 1 (process 8040) detached]
2024-12-30T06:13:22.0842770Z arduplane: -------------- end dumpcore.sh output ----------------
2024-12-30T06:13:22.0843102Z EOF on TCP socket
2024-12-30T06:13:22.0843313Z Attempting reconnect
2024-12-30T06:13:22.0843540Z [Errno 111] Connection refused sleeping
2024-12-30T06:13:22.0843818Z [Errno 111] Connection refused sleeping
2024-12-30T06:13:22.0844228Z [Errno 111] Connection refused sleeping
2024-12-30T06:13:22.0844498Z [Errno 111] Connection refused sleeping
2024-12-30T06:13:22.0844770Z [Errno 111] Connection refused sleeping
@lthall
Copy link
Contributor

lthall commented Jan 1, 2025

It is safe to limit the answer to positve values.
float accel_max_dir = safe_sqrt(MAX(0, sq(accel_max) - accel_cross.length_squared()));

@tpwrules
Copy link
Contributor

tpwrules commented Jan 1, 2025

It's happened again here: https://github.com/ArduPilot/ardupilot/actions/runs/12572260649/job/35044375709?pr=28857

Numbers are identical.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
Status: Pending
Development

No branches or pull requests

3 participants