ArduPilot / ardupilot

ArduPlane, ArduCopter, ArduRover, ArduSub source
http://ardupilot.org/
GNU General Public License v3.0
10.85k stars 17.3k forks source link

SIGFPE in ADSB avoid #15028

Open samuelctabor opened 4 years ago

samuelctabor commented 4 years ago

Came across this while testing in SITL. Not sure if it can occur in real life but I guess worth investigating.

Thread 1 "arduplane" received signal SIGFPE, Arithmetic exception. 0x0000000000450860 in Location::get_bearing_to (this=0x909bc0 <plane+24416>, loc2=...) at ../../libraries/AP_Common/Location.cpp:312 312 const int32_t off_y = (loc2.lat - lat) / loc2.longitude_scale(); (gdb) bt

0 0x0000000000450860 in Location::get_bearing_to (

this=0x909bc0 <plane+24416>, loc2=...)
at ../../libraries/AP_Common/Location.cpp:312

1 0x0000000000423480 in Plane::setup_turn_angle (this=0x903c60 )

at ../../ArduPlane/navigation.cpp:341

2 0x0000000000417fb4 in Plane::set_guided_WP (this=0x903c60 )

at ../../ArduPlane/commands.cpp:90

3 0x0000000000417889 in AP_Avoidance_Plane::handle_avoidance (

this=0x909aa0 <plane+24128>, obstacle=0x9829a0, 
requested_action=MAV_COLLISION_ACTION_MOVE_HORIZONTALLY)
at ../../ArduPlane/avoidance_adsb.cpp:65

4 0x00000000005153f7 in AP_Avoidance::handle_avoidance_local (

this=0x909aa0 <plane+24128>, threat=0x9829a0)
at ../../libraries/AP_Avoidance/AP_Avoidance.cpp:569

5 0x000000000051520d in AP_Avoidance::update (this=0x909aa0 <plane+24128>)

at ../../libraries/AP_Avoidance/AP_Avoidance.cpp:526

6 0x00000000004176ee in Plane::avoidance_adsb_update (this=0x903c60 )

at ../../ArduPlane/avoidance_adsb.cpp:8

7 0x0000000000406cec in Functor::method_wrapper<Plane, &Plane::avoidance_adsb_update> (obj=0x903c60 )

at ../../libraries/AP_HAL/utility/functor.h:88

8 0x000000000048691e in Functor::operator() (

this=0x650b40 <Plane::scheduler_tasks+1472>)

--Type for more, q to quit, c to continue without paging-- at ../../libraries/AP_HAL/utility/functor.h:54

9 0x00000000004a070f in AP_Scheduler::run (this=0x903cd8 <plane+120>,

time_available=20000) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:206

10 0x00000000004a0bd5 in AP_Scheduler::loop (this=0x903cd8 <plane+120>)

at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:327

11 0x00000000004a6264 in AP_Vehicle::loop (this=0x903c60 )

at ../../libraries/AP_Vehicle/AP_Vehicle.cpp:118

12 0x0000000000545014 in HAL_SITL::run (

this=0x9149e0 <AP_HAL::get_HAL()::hal>, argc=9, argv=0x7fffffffdaf8, 
callbacks=0x903c60 <plane>)
at ../../libraries/AP_HAL_SITL/HAL_SITL_Class.cpp:219

13 0x000000000040666d in main (argc=9, argv=0x7fffffffdaf8)

at ../../ArduPlane/ArduPlane.cpp:660
peterbarker commented 4 years ago

On Tue, 11 Aug 2020, Samuel Tabor wrote:

Came across this while testing in SITL. Not sure if it can occur in real life but I guess worth investigating.

Thread 1 "arduplane" received signal SIGFPE, Arithmetic exception.

How do you know this wasa divide-by-zero exception? I'm only seeing evidence of it being an FPE, nothing more specific.

Any steps to reproduce?

peterbarker commented 4 years ago

@samuelctabor nudge

samuelctabor commented 4 years ago

You're right, it's not necessarily divide by zero. I've updated the title accordingly.

I can reproduce reliably using the following parameters. I provoke a conflict and AVOID_ADSB mode is entered. I get the messages:

APM: Avoid: Resuming with action: 3 APM: Avoid: Performing action: 3

But LOITER is not entered as I expected, it continues in a straight line in AVOID_ADSB mode. Some time later it reliably hits the SIGFPE.

AVD_ENABLE 1.000000 AVD_F_ACTION 3.000000 AVD_F_ALT_MIN 0.000000 AVD_F_DIST_XY 5000.000000 AVD_F_DIST_Z 500.000000 AVD_F_RCVRY 3.000000 AVD_F_TIME 30.000000 AVD_OBS_MAX 20.000000 AVD_W_ACTION 1.000000 AVD_W_DIST_XY 1000.000000 AVD_W_DIST_Z 300.000000 AVD_W_TIME 30.000000

samuelctabor commented 4 years ago

Related to https://github.com/ArduPilot/ardupilot/issues/15043

samuelctabor commented 4 years ago

It looks like the avoidance behaviour selects an extremely distant waypoint and this causes the SIGFPE when the result is too large to fit in an int32.

peterbarker commented 4 years ago

@samuelctabor correct on the waypoint thing; the avoidance behaviour offsets the waypoint 10km every call:

image

So that's relatively easily fixed - we can just set that waypoint from an offset of the vehicle's current location rather than offset the guided waypoint. However, that still leaves the vehicle travelling 10km before entering loiter, which will probably be sub-optimal for most users. We can either use a lower multiplier for the unit vector we're using - perhaps 10 seconds of travel at current speed - or we could simply drop straight into loiter mode and circle where we are.

It's also worth noting that the failsafe action to fly horizontally away from the threat is not doing so with terrain in mind - at least by default.

I've created a PR to address the issues I've reproduced so far here: https://github.com/ArduPilot/ardupilot/pull/15063

I have not yet managed to reproduce the FPE.