HQW3a^%lkOOBF+c6CON5%#XfWWzl_zo2B|s+N
zBsZU5fgCAm!<`>5wpfsPtoVT*PW@62J=y=C6K6Ojb~-QrocKzQT=8W{zl(+mFwBPm
z91W+rutw1T^AV3D@$a6%=1-I&Q9C4nYFw3J_?C@tG$>2-ivMz?{NM%1ke=|dlhX=T
z)P_7OA-)1~AlS{v0~OAi>S2kIlW-J|VkOSiLHrkUnx_inLKOK893MJStQ~LGL0lrf
zQJ_FN?31NT0&rmq#oDP<2k}mzlLbP!jq(ewwUb*=p@X#(u2`Ydx4ReZIY~8R*Y7&H
ziZ}H8=AtQ0*mbM4?Q^RJv6rJ7yW_>Olhk+JgZ{0VRNHK*cB@d@I{JJF@G0b`;gA>r
zTu4K~RmhaW9ZL|aPvvLQv_5qgIJKAl{jleI4;?Q`KC@<(bQ|X?znKnE5OHj!l(#z|
zLK5TaB#JG6i4g-BMii(i?*DNdo?$t+-sEikFi%*PGj2Eg8%@3&@j%5IAy##;Y}3X@
zFH#>oasF@`rV9#oBPig6o6sm|Tce!&^m>kBd`E!h8u5&ZTbg#kT#4PHrO1!$Lv;F-
ztimT`lp%wHgBANb_x|eoHTT?|y$<<8ls*u;FRaRPU%)|7cH|U(
zOuP5XYk#(<{>W|KvJZa0u{=fL1!>G*Az*{Y$_w~%fwU^l4f-GQvb=y`O^n38>@?UR0u=hV!OGe-WJyGDYcW+yA@~ek-cpe$I^tk`p#PoEq
zTR64;!|zv-=DfDq1;)xh$?2Mi|UDJE@!na9MM!e_BZxKT=m-nVS72O4r#}+gn#Xs)xxH+i;Dq;$6i%0K(dV#+
z3r{;n02T_}=23mgf4If(0HDL*JT=)G7o1}XfbTvCJY-fP%VYC}G6adKIfbJbTPtc*
zJSXybiwGQidl?A1zLbNUO4jrEqYa1q8YZsreEs&RoBs6u=^x^i2W3dckSkn@nYcQG
xGQ<+>7*i-y9te4g{=MNtA0OP6yXNOFVM@s*hnl?fy){{?#_$cO*{
diff --git a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp
index 7f6f745779..3931456d63 100644
--- a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp
+++ b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp
@@ -51,7 +51,7 @@ EAppReturnType::Type UAirBlueprintLib::ShowMessage(EAppMsgType::Type message_typ
return FMessageDialog::Open(message_type,
FText::FromString(message.c_str()),
- title_text);
+ &title_text);
}
void UAirBlueprintLib::enableWorldRendering(AActor* context, bool enable)
diff --git a/Unreal/Plugins/AirSim/Source/AirSim.Build.cs b/Unreal/Plugins/AirSim/Source/AirSim.Build.cs
index de9041afe0..11397360fa 100644
--- a/Unreal/Plugins/AirSim/Source/AirSim.Build.cs
+++ b/Unreal/Plugins/AirSim/Source/AirSim.Build.cs
@@ -91,8 +91,13 @@ public AirSim(ReadOnlyTargetRules Target) : base(Target)
PublicIncludePaths.Add(Path.Combine(AirLibPath, "include"));
PublicIncludePaths.Add(Path.Combine(AirLibPath, "deps", "eigen3"));
AddOSLibDependencies(Target);
+
+ CompileMode cmplMode = CompileMode.CppCompileWithRpc;
+
+ if (Target.Platform == UnrealTargetPlatform.Linux)
+ cmplMode = CompileMode.HeaderOnlyWithRpc;
- SetupCompileMode(CompileMode.CppCompileWithRpc, Target);
+ SetupCompileMode(cmplMode, Target);
}
private void AddOSLibDependencies(ReadOnlyTargetRules Target)
diff --git a/setup.sh b/setup.sh
index 47cc03e81b..9bb41adf26 100755
--- a/setup.sh
+++ b/setup.sh
@@ -49,8 +49,7 @@ else #linux
rsync \
software-properties-common \
wget \
- libvulkan1 \
- vulkan-utils
+ libvulkan1
#install clang and build tools
VERSION=$(lsb_release -rs | cut -d. -f1)
@@ -61,6 +60,13 @@ else #linux
sudo apt-get update
fi
sudo apt-get install -y clang-12 clang++-12 libc++-12-dev libc++abi-12-dev
+
+
+ if [ "$VERSION" -gt "20" ]; then
+ sudo apt-get -y install --no-install-recommends vulkan-tools libunwind-dev
+ else
+ sudo apt-get -y install --no-install-recommends vulkan-utils
+ fi
fi
if ! which cmake; then
From 34cd497d72e8f49557466126d5820a72df2425cc Mon Sep 17 00:00:00 2001
From: Simple Max <62309109+simple-max-2001@users.noreply.github.com>
Date: Thu, 17 Oct 2024 17:45:51 +0300
Subject: [PATCH 4/4] Added checking if SITL is connected using armDisarm
---
.../firmwares/betaflight/BetaflightApi.hpp | 21 ++++---------------
1 file changed, 4 insertions(+), 17 deletions(-)
diff --git a/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp
index 7775394412..19bf6224ba 100644
--- a/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp
+++ b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp
@@ -63,6 +63,7 @@ namespace airlib
if (recvControl()) {
failed_pkts = 0;
+ if (!is_connected_) is_connected_ = true;
}
else {
@@ -71,6 +72,7 @@ namespace airlib
if (failed_pkts >= max_failed_pkts) {
failed_pkts = 0;
+ is_connected_ = false;
start_timestamp = timestamp + wait_time;
resetRotors();
Utils::log(Utils::stringf("Rotors data not recieved. Retry in %.0f sec", wait_time), Utils::kLogLevelWarn);
@@ -92,7 +94,7 @@ namespace airlib
virtual bool armDisarm(bool arm) override
{
unused(arm);
- return true;
+ return is_connected_;
}
virtual GeoPoint getHomeGeoPoint() const override
{
@@ -150,21 +152,6 @@ namespace airlib
return physics_->getKinematics();
}
- virtual Vector3r getPosition() const override
- {
- return physics_->getKinematics().pose.position;
- }
-
- virtual Vector3r getVelocity() const override
- {
- return physics_->getKinematics().twist.linear;
- }
-
- virtual Quaternionr getOrientation() const override
- {
- return physics_->getKinematics().pose.orientation;
- }
-
virtual LandedState getLandedState() const override
{
return physics_->isGrounded() ? LandedState::Landed : LandedState::Flying;
@@ -476,7 +463,7 @@ namespace airlib
MultirotorApiParams safety_params_;
AirSimSettings::MavLinkConnectionInfo connection_info_;
const MultiRotorParams* vehicle_params_;
- MultiRotorPhysicsBody* physics_;
+ const MultiRotorPhysicsBody* physics_ = nullptr;
const SensorCollection* sensors_;
std::string ip_;