Closed victoryzy closed 3 years ago
Please try my latest PR which fixes a lot of issues in PX4 SITL support: https://github.com/microsoft/AirSim/pull/2310
@lovettchris The PR does not solve this issue for the following environment: OS : Ubuntu 18.04 LTS UE version : 4.18 AirSim : master + your PR PX4 version : 1.9
The TCP connection works fine but the simulation still freezes on stopping it.
Are you running any python scripts? I have found that if you CTRL+C a python script that is controlling the drone then AirSim crashes or freezes... and this appears to be a bug in the rpclib code.
Not at all. I run the blocks environment and just press play without even running anything externally (python scripts or px4). As soon as I press stop, the engine freezes. Also, I tried to run the blocks environment externally by making a package so that I could try to trace the error. I ran the environment in gdb and shut it down using Alt+F4. It froze just like in the engine with the following output:
[2019.12.13-05.37.18:171][425]LogSlate: Request Window 'Blocks Environment for AirSim Blocks Environment for AirSim' being destroyed
[Thread 0x7fffe0190700 (LWP 19119) exited]
[Thread 0x7fffe0cf6700 (LWP 19118) exited]
[New Thread 0x7fffe0cf6700 (LWP 19121)]
[New Thread 0x7fffe0190700 (LWP 19122)]
[2019.12.13-05.37.18:200][425]LogSlate: Window 'Blocks Environment for AirSim Blocks Environment for AirSim' being destroyed
[Thread 0x7fff82ffd700 (LWP 19117) exited]
[Thread 0x7fff837fe700 (LWP 19116) exited]
[Thread 0x7fff83fff700 (LWP 19115) exited]
[Thread 0x7fff98d93700 (LWP 19114) exited]
[Thread 0x7fff99594700 (LWP 19113) exited]
[Thread 0x7fff99d95700 (LWP 19112) exited]
[2019.12.13-05.37.18:202][425]LogTemp: Disconnecting mavlink vehicle
Disconnecting mavlink vehicle
Then I pressed ctrl+c to shut the program down with the following backtrace:
Thread 1 "Blocks" received signal SIGINT, Interrupt.
0x00007ffff7bbed2d in __GI___pthread_timedjoin_ex (threadid=140735782938368,
thread_return=0x0, abstime=0x0, block=<optimized out>)
at pthread_join_common.c:89
89 pthread_join_common.c: No such file or directory.
(gdb) backtrace
#0 0x00007ffff7bbed2d in __GI___pthread_timedjoin_ex (
threadid=140735782938368, thread_return=0x0, abstime=0x0,
block=<optimized out>) at pthread_join_common.c:89
#1 0x0000000006635a8b in std::__1::thread::join() ()
#2 0x0000000005d3b640 in msr::airlib::MavLinkMultirotorApi::~MavLinkMultirotorApi (this=0x7fffe42ccae0)
at /home/sai/air_sim/AirSim/Unreal/Environments/Blocks/Plugins/AirSim/Source/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp:50
#3 0x0000000005d3b999 in msr::airlib::MavLinkMultirotorApi::~MavLinkMultirotorApi (this=0x7fffe42ccae0)
at /home/sai/air_sim/AirSim/Unreal/Environments/Blocks/Plugins/AirSim/Source/AirLib/include/vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp:46
#4 0x0000000005d158e9 in std::__1::default_delete<msr::airlib::MultirotorApiBase>::operator() (__ptr=0x7fff9a5969d0, this=<optimized out>)
at ThirdParty/Linux/LibCxx/include/c++/v1/memory:2541
#5 std::__1::unique_ptr<msr::airlib::MultirotorApiBase, std::__1::default_delete<msr::airlib::MultirotorApiBase> >::reset (this=<optimized out>,
__p=<optimized out>) at ThirdParty/Linux/LibCxx/include/c++/v1/memory:2747
#6 std::__1::unique_ptr<msr::airlib::MultirotorApiBase, std::__1::default_delete<msr::airlib::MultirotorApiBase> >::~unique_ptr (this=<optimized out>)
at ThirdParty/Linux/LibCxx/include/c++/v1/memory:2715
---Type <return> to continue, or q <return> to quit---
#7 MultirotorPawnSimApi::~MultirotorPawnSimApi (this=0x7fffd85840c0) at ../../../AirSim/Unreal/Environments/Blocks/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.h:31
#8 0x0000000005d15909 in MultirotorPawnSimApi::~MultirotorPawnSimApi (this=0x7fffd85840c0)
at ../../../AirSim/Unreal/Environments/Blocks/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.h:31
#9 0x0000000005cde706 in std::__1::default_delete<msr::airlib::VehicleSimApiBase>::operator() (__ptr=0x7fff9a5969d0, this=<optimized out>) at ThirdParty/Linux/LibCxx/include/c++/v1/memory:2541
#10 std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> >::reset (this=0x7ffff7bbed2d <__GI___pthread_timedjoin_ex+381>, __p=<optimized out>)
at ThirdParty/Linux/LibCxx/include/c++/v1/memory:2747
#11 std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> >::~unique_ptr (this=0x7ffff7bbed2d <__GI___pthread_timedjoin_ex+381>)
at ThirdParty/Linux/LibCxx/include/c++/v1/memory:2715
#12 std::__1::allocator<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> > >::destroy (__p=0x7ffff7bbed2d <__GI___pthread_timedjoin_ex+381>,
this=<optimized out>) at ThirdParty/Linux/LibCxx/include/c++/v1/memory:1802
#13 std::__1::allocator_traits<std::__1::allocator<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> > > >::__destroy<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> > > (__p=0x7ffff7bbed2d <__GI___pthread_timedjoin_ex+381>, __a=...)
at ThirdParty/Linux/LibCxx/include/c++/v1/memory:1670
#14 std::__1::allocator_traits<std::__1::allocator<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> > > >::destroy<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> > > (__p=0x7ffff7bbed2d <__GI___pthread_timedjoin_ex+381>, __a=...) at ThirdParty/Linux/LibCxx/include/c++/v1/memory:1538
#15 std::__1::__vector_base<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> >, std::__1::allocator<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> > > >::__destruct_at_end (this=<optimized out>, __new_last=0x7fffe2a90290) at ThirdParty/Linux/LibCxx/include/c++/v1/vector:425
#16 std::__1::__vector_base<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> >, std::__1::allocator<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> > > >::clear (this=<optimized out>) at ThirdParty/Linux/LibCxx/include/c++/v1/vector:369
#17 std::__1::vector<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> >, std::__1::allocator<std::__1::unique_ptr<msr::airlib::VehicleSimApiBase, std::__1::default_delete<msr::airlib::VehicleSimApiBase> > > >::clear (this=<optimized out>) at ThirdParty/Linux/LibCxx/include/c++/v1/vector:739
#18 ASimModeBase::EndPlay (this=0x7ffff4fa9a00, EndPlayReason=EEndPlayReason::Destroyed) at /home/sai/air_sim/AirSim/Unreal/Environments/Blocks/Plugins/AirSim/Source/SimMode/SimModeBase.cpp:143
#19 0x0000000003f8933c in AActor::RouteEndPlay (this=0x7ffff4fa9a00, EndPlayReason=EEndPlayReason::Destroyed) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/Actor.cpp:1959
#20 AActor::Destroyed (this=0x7ffff4fa9a00) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/Actor.cpp:2037
#21 0x00000000045a6f72 in UWorld::DestroyActor (this=0x7fffea15eac0, ThisActor=0x7ffff4fa9a00, bNetForce=<optimized out>, bShouldModifyLevel=true)
at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/LevelActor.cpp:577
#22 0x0000000003f82c41 in AActor::Destroy (this=0x7ffff4fa9a00, bNetForce=false, bShouldModifyLevel=true) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/Actor.cpp:3615
#23 0x0000000005cda629 in ASimHUD::EndPlay (this=0x7fffc06fa4c0, EndPlayReason=EEndPlayReason::Destroyed) at /home/sai/air_sim/AirSim/Unreal/Environments/Blocks/Plugins/AirSim/Source/SimHUD/SimHUD.cpp:58
#24 0x0000000003f8933c in AActor::RouteEndPlay (this=0x7fffc06fa4c0, EndPlayReason=EEndPlayReason::Destroyed) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/Actor.cpp:1959
#25 AActor::Destroyed (this=0x7fffc06fa4c0) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/Actor.cpp:2037
#26 0x00000000045a6f72 in UWorld::DestroyActor (this=0x7fffea15eac0, ThisActor=0x7fffc06fa4c0, bNetForce=<optimized out>, bShouldModifyLevel=true)
at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/LevelActor.cpp:577
#27 0x0000000003f82c41 in AActor::Destroy (this=0x7fffc06fa4c0, bNetForce=false, bShouldModifyLevel=true) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/Actor.cpp:3615
#28 0x000000000489fe03 in APlayerController::Destroyed (this=0x7fffd3dbd850) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/PlayerController.cpp:1509
#29 0x00000000045a6f72 in UWorld::DestroyActor (this=0x7fffea15eac0, ThisActor=0x7fffd3dbd850, bNetForce=<optimized out>, bShouldModifyLevel=true)
at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/LevelActor.cpp:577
#30 0x0000000003f82c41 in AActor::Destroy (this=0x7fffd3dbd850, bNetForce=false, bShouldModifyLevel=true) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/Actor.cpp:3615
#31 0x0000000004472cbc in UGameInstance::RemoveLocalPlayer (this=0x7fffe2f19d00, ExistingPlayer=0x7fffe6fad800) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/GameInstance.cpp:609
#32 0x0000000004475053 in UGameInstance::CleanupGameViewport (this=0x7fffe2f19d00) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/GameInstance.cpp:807
#33 0x0000000004ba3c20 in UEngine::CleanupGameViewport (this=0x7fffe4320100) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/UnrealEngine.cpp:2198
#34 0x000000000444d61e in UGameEngine::Tick (this=0x7fffe4320100, DeltaSeconds=<optimized out>, bIdleMode=<optimized out>)
at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Engine/Private/GameEngine.cpp:1151
#35 0x00000000022c28fb in FEngineLoop::Tick (this=<optimized out>) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Launch/Private/LaunchEngineLoop.cpp:3292
#36 0x00000000022c706a in EngineTick () at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Launch/Private/Launch.cpp:62
#37 GuardedMain (CmdLine=<optimized out>) at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Launch/Private/Launch.cpp:168
#38 0x0000000004f6d430 in CommonLinuxMain (argc=<optimized out>, argv=0x7fffffffd6d8, RealMain=0x22c6dd0 <GuardedMain(wchar_t const*)>)
at /home/sai/air_sim/UnrealEngine/Engine/Source/Runtime/Linux/LinuxCommonStartup/Private/LinuxCommonStartup.cpp:236
#39 0x00007ffff6822b97 in __libc_start_main (main=0x22cca70 <main(int, char**)>, argc=1, argv=0x7fffffffd6d8, init=<optimized out>, fini=<optimized out>, rtld_fini=<optimized out>,
stack_end=0x7fffffffd6c8) at ../csu/libc-start.c:310
#40 0x00000000022b9e3a in _start () at Runtime/Core/Public/Containers/ContainerAllocationPolicies.h:356
I don't quite understand the log but maybe you can make some sense of it?
I've tried to debug the code a bit and I see it getting stuck at the following line of code:
virtual ~MavLinkMultirotorApi()
{
closeAllConnection();
if (this->connect_thread_.joinable())
{
This Line --> this->connect_thread_.join();
}
}
Is there a particular reason why the thread isn't able to join?
Thanks that's very helpful. Looking at connect_thread, presumably createMavConnection completed because you did connect in your scenario, right? So that leaves connectToLogViewer and connectToQGC. If those are stuck on a blocked "connect" call then that might explain it. Try setting these empty strings in your settings.json:
"Vehicles": {
"PX4": {
"VehicleType": "PX4Multirotor",
...
"LogViewerHostIp": "",
"QgcHostIp": ""
}
}
@lovettchris I understand the problem now. I was actually just trying to press play and immedietly stop without connecting the simulator to PX4. The UE4 freezes whenever I press stop without connecting to PX4 but it works if the PX4 is connected. Since the call to tcp connection is blocking it waits at the createMavConnection() function and keeps waiting for PX4... even if the program is shut down.
I think the better way to solve this would be to make the TCP connection call non-blocking which keeps waiting for the PX4 connection until the exit signal is received in which case it should stop waiting there. That's just my suggestion. In any case, it would be better to make sure the connection stops waiting for PX4 if an exit call is received first which it doesn't making the client freeze.
Also, I believe the original problem mentioned in this issue might have been resolved by your PR after all. Since this one is actually a different problem.
Cheers!
@lovettchris Hi, I am not sure why but the freeze has risen up again? Maybe I was lucky before or what, I am not sure. I do seem to have narrowed down the problem about it though. As far as I have debugged the problem occurs on the udp socket. During the cleanup on pressing stop or escape, the mav_vehicle disconnects from gcs udp connection. On disconnection, it closes the udp socket before making sure the read() call in read_thread of MavLinkConnection has finished. This causes the recvfrom() defined in UdpClientPortImpl to get blocked indefinitely on read. The code gets stuck here on cleanup:
void MavLinkConnectionImpl::close()
{
closed = true;
if (port != nullptr) {
port->close();
port = nullptr;
}
if (read_thread.joinable()) {
Stuck on -> read_thread.join();
}
if (publish_thread_.joinable()) {
msg_available_.post();
publish_thread_.join();
}
sendLog_ = nullptr;
}
I think an easy way to fix this is to add a simple timeout of a few seconds on the udp socket. I just ran it and it worked. I just added the timeout in connect() in UdpClientPort.cpp.
int connect(const std::string& localHost, int localPort, const std::string& remoteHost, int remotePort)
{
sock = socket(AF_INET, SOCK_DGRAM, 0);
resolveAddress(localHost, localPort, localaddr);
if (remoteHost != "") {
hasRemote = true;
resolveAddress(remoteHost, remotePort, remoteaddr);
}
else
{
remoteaddr.sin_port = 0;
}
// Update
> struct timeval tv;
> tv.tv_sec = 1.0;
> tv.tv_usec = 0;
> setsockopt(sock, SOL_SOCKET, SO_RCVTIMEO, (const char*)&tv, sizeof tv);
Using this the thread just waits for 1.0 second and does not freeze the simulator.
Hi Harnix, As I have mentioned in the comment, the connect() function is located in UdpClientPort.cpp file. I don't have the directory to check right now but you can just search the file in airsim unreal engine api.
On Tue, Mar 31, 2020 at 9:46 PM Harnix notifications@github.com wrote:
@saifullah3396 https://github.com/saifullah3396 How do I locate this block of code that you modified?
— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/microsoft/AirSim/issues/2112#issuecomment-606744031, or unsubscribe https://github.com/notifications/unsubscribe-auth/AEYYBTPWEN5OGWW5LVTMIGDRKIM5XANCNFSM4II3QSCA .
-- Saifullah Research Associate Intelligent Robotics Lab (IRL) National Center of Artificial Intelligence (NCAI) National University of Sciences and Technology (NUST) Pakistan +923159236454
@saifullah3396 Thanks, I found the file directory by searching on GitHub. I've also modified the code and will test it out when I can.
@Harnix You might still be getting a freeze for another reason as I have tested this on my system before. Try setting the empty strings for log viewer and QGC as well (mentioned by @lovettchris) as that can also cause freeze if they are not connected.
On Wed, Apr 1, 2020 at 10:07 PM Harnix notifications@github.com wrote:
"Disconnecting mavlink vehicle.... Disconnecting mavlink vehicle... " I get these exact 2 messages when Unreal Engine freezes.
— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/microsoft/AirSim/issues/2112#issuecomment-607374685, or unsubscribe https://github.com/notifications/unsubscribe-auth/AEYYBTLO54GBLVDTVRP4BE3RKNYE5ANCNFSM4II3QSCA .
-- Saifullah Research Associate Intelligent Robotics Lab (IRL) National Center of Artificial Intelligence (NCAI) National University of Sciences and Technology (NUST) Pakistan +923159236454
I am experiencing the same issue and @saifullah3396's fix works on my system. Can an AirSim developer incorporate this into master?
i'm running to the same problem in UE4 4.22 and ubuntu 18.04. i will try @saifullah339's to have a timeout
I added this timeout to this PR since I was also fixing a related issue in the same code: https://github.com/microsoft/AirSim/pull/3757 Thanks to @saifullah3396 for the proposed fix!
This has been fixed by #3757
OS : Ubuntu 16.04 LTS UE version : 4.18 AirSim : master (cloned on 2019/7/30) PX4 version : 1.8.2
After building UE and AirSim as document saids, I try to use Blocks environment to check if everything is fine. Here's how I run the program
$ ~/UnrealEngin/Engine/Binaries/Linux/UE4Editor
and chooseBlocks.uproject
$ cd Firmware
and$ make posix_sitl_ekf2 none_iris
Play
in UE.I can control drone from PX4 with commands like
commander arm
andcommander takeoff
. But UE freezes after I pressESC
on my keyboard or clickStop
in UE.The
~/Documents/AirSim/settings.json
file and error messages are as follow :I have found other similar issues like #415 , #634 , #2041 but didn't found solution. I also tried this with UE version 4.22 but still fails.
Other system information
Besides asking how to solve the problem, I still have some questions.
settings.json
but it seems that AirSim(or UE?) tries to send message to them and error occurs. Does it mean AirSim by default connects to QGroundControl and LogViewer?settings.json
?LandscapeMountains
after download the file. I previously launched it by$ ./LandscapeMountains.sh
. Is it that simple? I found few tutorials that teach people to run AirSim on Ubuntu.Hope anyone who had ever successfully run it share his or her experience. Any advice or experience sharing will be appreciated. Thanks a lot!