Skip to content

AP_Terrain: Fix SIGFPE crash on invalid TERRAIN_CHECK command#32366

Closed
Ttl wants to merge 2 commits intoArduPilot:masterfrom
Ttl:terrain_crash_fix
Closed

AP_Terrain: Fix SIGFPE crash on invalid TERRAIN_CHECK command#32366
Ttl wants to merge 2 commits intoArduPilot:masterfrom
Ttl:terrain_crash_fix

Conversation

@Ttl
Copy link

@Ttl Ttl commented Mar 4, 2026

Summary

Sending TERRAIN_CHECK Mavlink command with out of range latitude leads to SIGFPE crash.

Testing (more checks increases chance of being merged)

  • Checked by a human programmer
  • Tested in SITL
  • Tested on hardware
  • Logs attached
  • Logs available on request
  • Autotest included

Description

Can be reproduced in Mission Planner 1.3.83 (latest stable as of now) with mission that has single DO_DIGICAM_CONFIG command with param5=138, param6=218.

Reproduction mission
QGC WPL 110
0	1	0	16	0	0	0	0	60	24	0.080000	1
1	0	0	202	0.00000000	0.00000000	0.00000000	0.00000000	138.00000000	218.00000000	110.000000	1
Backtrace
#5  0x0000602de7f2e3be in _sig_fpe (signum=8) at ../../libraries/AP_HAL_SITL/SITL_cmdline.cpp:65
No locals.
#6  <signal handler called>
No locals.
#7  Location::offset_latlng (lat=@0x7ffdf8f9fba8: -1180000000, lng=@0x7ffdf8f9fbac: -2120000000, ofs_north=85543200, ofs_east=53200) at ../../libraries/AP_Common/Location.cpp:482
        dlat = 32765
        dlng = 105750279017247
#8  0x0000602de7d0dbc7 in Location::offset (this=0x7ffdf8f9fba0, ofs_north=85543200, ofs_east=53200) at ../../libraries/AP_Common/Location.cpp:492
No locals.
#9  0x0000602de803ad78 in AP_Terrain::calculate_grid_info (this=0x602de81d61d0 <copter+49296>, loc=..., info=...) at ../../libraries/AP_Terrain/TerrainUtil.cpp:92
        ref = {relative_alt = 0 '\000', loiter_ccw = 0 '\000', terrain_alt = 0 '\000', origin_alt = 0 '\000', loiter_xtrack = 0 '\000', alt = 0, lat = -1180000000, lng = -2120000000, static LOCATION_SCALING_FACTOR = 0.0111318845, static LOCATION_SCALING_FACTOR_INV = 89.8320465}
        offset = {x = -19313456, y = 55172.3555}
        idx_x = 4294774162
        idx_y = 551
#10 0x0000602de7dcec12 in AP_Terrain::height_amsl (this=0x602de81d61d0 <copter+49296>, loc=..., height=@0x7ffdf8f9fc98: 0, corrected=true) at ../../libraries/AP_Terrain/AP_Terrain.cpp:135
        ahrs = @0x602de81ccce0: {EKF2 = {num_cores = 0 '\000', primary = 0 '\000', core = 0x0, core_malloc_failed = false, _frameTimeUsec = 0, _framesPerPrediction = 0 '\000', _enable = {...}
        info = {lat_degrees = -118 '\212', lon_degrees = -212, grid_lat = 8192, grid_lon = 227556032, grid_idx_x = 35643, grid_idx_y = 19, idx_x = 10 '\n', idx_y = 19 '\023', frac_x = -42949672, frac_y = 0.723554671, file_offset = 24621}
        grid = <error reading variable: Cannot access memory at address 0x60000d903ac0>
        h00 = 24622
        h01 = 0
        h10 = -976
        h11 = -1799
        avg1 = 4.59135442e-41
        avg2 = -2.10066939e+24
        avg = 3.45013695e-41
#11 0x0000602de8039159 in AP_Terrain::send_terrain_report (this=0x602de81d61d0 <copter+49296>, link=..., loc=..., extrapolate=false) at ../../libraries/AP_Terrain/TerrainGCS.cpp:238
        terrain_height = 0
        spacing = 0
        pending = 63737
        loaded = 32765
        current_height = 3.45013695e-41
        packet = {lat = -117834544, lon = 32765, terrain_height = -4.05629573e+34, current_height = 4.59135442e-41, spacing = 64720, pending = 63737, loaded = 32765}
#12 0x0000602de80392b7 in AP_Terrain::handle_terrain_check (this=0x602de81d61d0 <copter+49296>, link=..., msg=...) at ../../libraries/AP_Terrain/TerrainGCS.cpp:276
        packet = {lat = 1380000000, lon = -2114967296}
        loc = {relative_alt = 0 '\000', loiter_ccw = 0 '\000', terrain_alt = 0 '\000', origin_alt = 0 '\000', loiter_xtrack = 0 '\000', alt = 0, lat = 1380000000, lng = -2114967296, static LOCATION_SCALING_FACTOR = 0.0111318845, static LOCATION_SCALING_FACTOR_INV = 89.8320465}
#13 0x0000602de803900c in AP_Terrain::handle_message (this=0x602de81d61d0 <copter+49296>, link=..., msg=...) at ../../libraries/AP_Terrain/TerrainGCS.cpp:207
No locals.
#14 0x0000602de7df8fc7 in GCS_MAVLINK::handle_message (this=0x602e0d903ac0, msg=...) at ../../libraries/GCS_MAVLink/GCS_Common.cpp:4454
        terrain = 0x602de81d61d0 <copter+49296>
#15 0x0000602de7cb2f2c in GCS_MAVLINK_Copter::handle_message (this=0x602e0d903ac0, msg=...) at ../../ArduCopter/GCS_MAVLink_Copter.cpp:1231
No locals.
#16 0x0000602de7df2d9f in GCS_MAVLINK::raw_packetReceived (this=0x602e0d903ac0, framing_status=1 '\001', status=..., msg=...) at ../../libraries/GCS_MAVLink/GCS_Common.cpp:1921
No locals.

In the first place there shouldn't be a reason for mission planner to send TERRAIN_CHECK for this command. However, if TERRAIN_CHECK with out of range lat or lon is given it first overflows lat_degrees int8_t in AP_Terrain. This ends up calling Location::offset_latlng with very large float input. Line const int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV; in Location.cpp:482 causes the crash as the multiplication output is too large to fit in int32_t.

This PR adds guard in height_asml to reject inputs that are out of valid range.

@Ttl
Copy link
Author

Ttl commented Mar 4, 2026

Just found ArduPilot/ardupilot_wiki#7359. This is probably not critical on real hardware and should instead be fixed in Mission Planner.

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We have a check_latlng method to do this.

.... but I think you're correct, we can simply say GIGO in this case; it's on the client to make correct requests.

@Ttl Ttl closed this Mar 5, 2026
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants