Open Eraz1997 opened 4 years ago
I wonder if you could try it out on Copter or Plane (in AirSim)? This is a new feature that we are planning to release with Plane-4.0.6 and Copter-4.0.4 so I'm just a little worried that we have a bug that could get out.
@Eraz1997 I'm unable to reproduce this with the latest AirSim release as well as master. My testing was mostly just moving in manual, a bit in guided and then RTL. Could you post the script or some more details on how to reproduce this? Logs would also be helpful, you could comment out the #if 0
and #endif
around this code, that should provide more info about the data Airsim is sending
There hasn't been any such change in master which would affect Rover, so I think using a release should also work in trying to reproduce. Releases can be downloaded from here - https://github.com/microsoft/AirSim/releases This doesn't require any Unreal Engine setup, building, etc. Just unzip and run the env.
Side note, Airsim rover needs some serious tuning, will try to give it a shot over the weekend, but haven't done that before, so any suggestions, etc. would be great!
Thank you for the support guys! @rmackay9 No way to reproduce the bug with Copter, it works fine! @rajat2004 I'm using latest AirSim realease and this is the code I used to control the Rover:
from __future__ import print_function
import time
from dronekit import connect, VehicleMode, LocationGlobalRelative
# Parse connection string
import argparse
parser = argparse.ArgumentParser()
parser.add_argument('--connect')
args = parser.parse_args()
connectionString = args.connect
if not connectionString:
quit();
# Connect to vehicle
print('Connecting to vehicle on: %s' % connectionString)
vehicle = connect(connectionString, wait_ready=False)
vehicle.initialize(8, 30)
vehicle.wait_ready('autopilot_version')
vehicle.parameters['avoid_enable'] = 0
vehicle.parameters['PRX_TYPE'] = 0
# Arm
print("Basic pre-arm checks")
while not vehicle.is_armable:
print(" Waiting for vehicle to initialise...")
time.sleep(1)
print("Arming motors")
vehicle.armed = True
while not vehicle.armed:
print(" Waiting for arming...")
time.sleep(1)
print("Armed")
angle = 1500
throttle = 1500
pitch = 1500 # (only for copter)
yaw = 1500 # (only for copter)
@vehicle.on_message('RC_CHANNELS')
def chin_listener(self, name, message):
angle = message.chan1_raw
throttle = message.chan3_raw
pitch = message.chan2_raw
yaw = message.chan4_raw
# Manual control through RC channels
vehicle.channels.overrides['1'] = 1500 # angle
vehicle.channels.overrides['3'] = 1500 # throttle
vehicle.channels.overrides['2'] = 1500 # pitch (only for copter)
vehicle.channels.overrides['4'] = 1500 # yaw (only for copter)
import keyboard # using module keyboard
while True: # making a loop
if keyboard.is_pressed('q'): # if key 'q' is pressed
print('Exit!')
break # finishing the loop
if keyboard.is_pressed('w'):
throttle += 50
if(throttle > 2000):
throttle = 2000
vehicle.channels.overrides['3'] = throttle
if keyboard.is_pressed('s'):
throttle -= 50
if(throttle < 1000):
throttle = 1000
vehicle.channels.overrides['3'] = throttle
if keyboard.is_pressed('d'):
angle += 50
if(angle > 2000):
angle = 2000
vehicle.channels.overrides['1'] = angle
if keyboard.is_pressed('a'):
angle -= 50
if(angle < 1000):
angle = 1000
vehicle.channels.overrides['1'] = angle
# only for Copter
if keyboard.is_pressed('i'):
pitch += 50
if(pitch > 2000):
pitch = 2000
vehicle.channels.overrides['2'] = pitch
if keyboard.is_pressed('k'):
pitch -= 50
if(pitch < 1000):
pitch = 1000
vehicle.channels.overrides['2'] = pitch
if keyboard.is_pressed('l'):
yaw += 50
if(yaw > 2000):
yaw = 2000
vehicle.channels.overrides['4'] = yaw
if keyboard.is_pressed('j'):
yaw -= 50
if(yaw < 1000):
yaw = 1000
vehicle.channels.overrides['4'] = yaw
time.sleep(0.2)
print("Angle: ", angle, " - Throttle: ", throttle, " | Pitch: ", pitch, " - Yaw: ", yaw, end="\r")
# Exit
print("Close vehicle object")
vehicle.close()
Here there is my log file, I removed the #if 0
and #endif
in the code as you suggested
The settings.json configuration file of AirSim is the same described in the official documentation of Ardupilot
@Eraz1997 Thanks for the script! After having a brief look at the log you provided to see the RC values, became quite clear as to what to do to trigger the exception.
The main thing required was extreme RC input, so my method was to use manual mode with rc 3 1700
and rc 1 1300
first to turn the vehicle to the left so that there's a straight free path ahead. Then increase Throttle to 2000, wait for a few seconds so that it picks up speed and then apply slight Roll of say 1300 and see what happens! I hadn't tested such high values before so wasn't aware of this.
I was unable to reproduce this with AP built with debugging enabled, with both being 2000 also. But with the default build happened fairly quickly
See Update at the end, has the backtrace
There are 2 log files, 5 is the one with debugging enabled, as you can see, pushed it fairly hard but no exception. 8 is without debugging and has the exception.
Maybe a GCC optimisation problem? Do let me know if I can provide more info or testing. Ping @rmackay9 @tridge
BTW, I reproduced this with the latest AirSim release, so there shouldn't be any need to build AirSim from source, for those trying to reproduce this
Update: I'm actually able to reproduce with AP's default SITL also following the method I described above to increase Throttle to 2000 and then add Roll In SITL, it's happening with debugging also, maybe I didn't push it enough when trying with AirSim. Backtrace -
Program received signal SIGFPE, Arithmetic exception.
0x000055555576b1ca in EKFGSF_yaw::correct (this=0x555555a96420,
mdl_idx=1 '\001') at ../../libraries/AP_NavEKF/EKFGSF_yaw.cpp:458
458 K[1][0] = -P10*P11*t7+P10*t7*t8;
(gdb) bt
#0 0x000055555576b1ca in EKFGSF_yaw::correct (this=0x555555a96420,
mdl_idx=1 '\001') at ../../libraries/AP_NavEKF/EKFGSF_yaw.cpp:458
#1 0x000055555576a09f in EKFGSF_yaw::update (this=0x555555a96420, delAng=...,
delVel=..., delAngDT=-1.35348309e+17, delVelDT=1.35348309e+17, runEKF=247,
TAS=-14798104) at ../../libraries/AP_NavEKF/EKFGSF_yaw.cpp:120
#2 0x00005555557099ab in NavEKF2_core::UpdateFilter (this=0x555555a9675c,
predict=true) at ../../libraries/AP_NavEKF2/AP_NavEKF2_core.cpp:594
#3 0x00005555555e52ab in NavEKF2::UpdateFilter (
this=0x555555a1ab48 <rover+8744>)
at ../../libraries/AP_NavEKF2/AP_NavEKF2.cpp:782
#4 0x000055555559f4d7 in AP_AHRS_NavEKF::update_EKF2 (
this=0x555555a1a830 <rover+7952>)
at ../../libraries/AP_AHRS/AP_AHRS_NavEKF.cpp:204
#5 0x000055555559f24a in AP_AHRS_NavEKF::update (
this=0x555555a1a830 <rover+7952>, skip_ins_update=false)
at ../../libraries/AP_AHRS/AP_AHRS_NavEKF.cpp:135
#6 0x000055555558cbf4 in Rover::ahrs_update (this=0x555555a18920 <rover>)
at ../../Rover/Rover.cpp:195
#7 0x000055555558d507 in Functor<void>::method_wrapper<Rover, &Rover::ahrs_update> (obj=0x555555a18920 <rover>) at ../../libraries/AP_HAL/utility/functor.h:88
#8 0x00005555555e342a in Functor<void>::operator() (
this=0x555555a01660 <Rover::scheduler_tasks+32>)
at ../../libraries/AP_HAL/utility/functor.h:54
---Type <return> to continue, or q <return> to quit---
#9 0x00005555555fc909 in AP_Scheduler::run (this=0x555555a18998 <rover+120>, time_available=20000) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:206
#10 0x00005555555fcdd1 in AP_Scheduler::loop (this=0x555555a18998 <rover+120>) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:327
#11 0x00005555555ffae6 in AP_Vehicle::loop (this=0x555555a18920 <rover>) at ../../libraries/AP_Vehicle/AP_Vehicle.cpp:112
#12 0x0000555555679877 in HAL_SITL::run (this=0x555555a285e0 <AP_HAL::get_HAL()::hal>, argc=9, argv=0x7fffffffdcd8, callbacks=0x555555a18920 <rover>)
at ../../libraries/AP_HAL_SITL/HAL_SITL_Class.cpp:219
#13 0x000055555558d23f in main (argc=9, argv=0x7fffffffdcd8) at ../../Rover/Rover.cpp:372
Log - sitl_exception.zip
I've opened https://github.com/ArduPilot/ardupilot/pull/14476 which adds an autotest to reproduce this
PR has been merged, use ./Tools/autotest/autotest.py --gdb --debug build.Rover test.Rover.DriveMaxRCIN
to run the test since it's currently disabled. Also. I think the title can be changed since it's not specific to Airsim
its probably worth noting that to get the error your rotating at 450 deg/second. The SITL copter will only do about 200 max, so I suspect this could be reproduced on any vehicle. I think its fair to say that this is outside the expected operating range, so the fix is probably just to check the yaw rate is less than some number before doing the EKFGSF_yaw::updateRotMat()
Hi!
I was running into this issue as well, and not just when doing high speed turns. I looked into it and I think I found the problem. For me, it was crashing or behaving strangely when turning 180 degrees around. I think the issue is that AirSim calculates the angular velocity from the delta of euler angles, but it was not accounting for the case where the angle wraps from 180 degrees to -180 degrees, so when this happened it causes a very large delta, making the angular velocity very high, causing the floating point exception. I created a pull request for AirSim here: https://github.com/microsoft/AirSim/pull/2956
This still doesn't help with the MaxRCInput test, but it is a related problem, so I thought I would mention it. I haven't run into the EKF floating point exception "in the wild" since making this change.
Hopefully that will be helpful to someone. Thanks!
Bug report
Issue details
When running SITL with rover simulation linked to AirSim (-f airsim-rover), it often happens that EKF (both 2 and 3) gets a Floating point exception. The problem is in function EKFGSF_yaw::updateRotMat(...) located in libraries/EKFGSF_yaw.cpp. The values of P matrix in EKF get huge apparently at random, then a floating point exception is thrown.
To reproduce the bug you have to simply connect AirSim with ardurover simulation in SITL and control the rover (I used dronekit library in Python).
Version master - updated to May 23, 2020
Platform [ ] All [ ] AntennaTracker [ ] Copter [ ] Plane [X] Rover [ ] Submarine
Airframe type airsim-rover
Hardware type SITL (ardurover)
Logs Logs of the exception dumped with dumpstack.sh