diff --git a/AirLib/include/api/RpcLibClientBase.hpp b/AirLib/include/api/RpcLibClientBase.hpp index 23bc36a754..ef1c043cb5 100644 --- a/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirLib/include/api/RpcLibClientBase.hpp @@ -60,6 +60,8 @@ namespace airlib void simSetWeatherParameter(WorldSimApiBase::WeatherParameter param, float val); vector simListSceneObjects(const string& name_regex = string(".*")) const; + vector simListSceneObjectsByTag(const string& tag_regex = string(".*")) const; + Pose simGetObjectPose(const std::string& object_name) const; bool simLoadLevel(const string& level_name); Vector3r simGetObjectScale(const std::string& object_name) const; @@ -163,6 +165,8 @@ namespace airlib void simSetWind(const Vector3r& wind) const; void simSetExtForce(const Vector3r& ext_force) const; + Vector3r simFindLookAtRotation(const std::string& vehicle_name, const std::string& object_name) const; + vector listVehicles(); std::string getSettingsString() const; diff --git a/AirLib/include/api/WorldSimApiBase.hpp b/AirLib/include/api/WorldSimApiBase.hpp index 3f2c27642b..538532e079 100644 --- a/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirLib/include/api/WorldSimApiBase.hpp @@ -67,6 +67,8 @@ namespace airlib virtual void simPlotTransformsWithNames(const vector& poses, const vector& names, float tf_scale, float tf_thickness, float text_scale, const vector& text_color_rgba, float duration) = 0; virtual std::vector listSceneObjects(const std::string& name_regex) const = 0; + virtual std::vector listSceneObjectsByTag(const std::string& tag_regex) const = 0; + virtual Pose getObjectPose(const std::string& object_name) const = 0; virtual Vector3r getObjectScale(const std::string& object_name) const = 0; virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) = 0; @@ -79,6 +81,7 @@ namespace airlib virtual vector getMeshPositionVertexBuffers() const = 0; virtual bool createVoxelGrid(const Vector3r& position, const int& x_size, const int& y_size, const int& z_size, const float& res, const std::string& output_file) = 0; + virtual Vector3r findLookAtRotation(const std::string& vehicle_name, const std::string& object_name) = 0; // Recording APIs virtual void startRecording() = 0; diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index 0cc4ed1cca..5a6ef95963 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -488,6 +488,11 @@ __pragma(warning(disable : 4239)) return pimpl_->client.call("simListSceneObjects", name_regex).as>(); } + vector RpcLibClientBase::simListSceneObjectsByTag(const string& tag_regex) const + { + return pimpl_->client.call("simListSceneObjectsByTag", tag_regex).as>(); + } + std::vector RpcLibClientBase::simSwapTextures(const std::string& tags, int tex_id, int component_id, int material_id) { return pimpl_->client.call("simSwapTextures", tags, tex_id, component_id, material_id).as>(); @@ -578,6 +583,11 @@ __pragma(warning(disable : 4239)) return pimpl_->client.call("simCreateVoxelGrid", RpcLibAdaptorsBase::Vector3r(position), x, y, z, res, output_file).as(); } + msr::airlib::Vector3r RpcLibClientBase::simFindLookAtRotation(const std::string& vehicle_name, const std::string& object_name) const + { + return pimpl_->client.call("simFindLookAtRotation", vehicle_name, object_name).as().to(); + } + void RpcLibClientBase::cancelLastTask(const std::string& vehicle_name) { pimpl_->client.call("cancelLastTask", vehicle_name); diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index 77d9cf324f..bc7f5b1844 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -364,6 +364,10 @@ namespace airlib return getWorldSimApi()->listSceneObjects(name_regex); }); + pimpl_->server.bind("simListSceneObjectsByTag", [&](const std::string& tag_regex) -> std::vector { + return getWorldSimApi()->listSceneObjectsByTag(tag_regex); + }); + pimpl_->server.bind("simLoadLevel", [&](const std::string& level_name) -> bool { return getWorldSimApi()->loadLevel(level_name); }); @@ -512,6 +516,11 @@ namespace airlib return getWorldSimApi()->getSettingsString(); }); + pimpl_->server.bind("simFindLookAtRotation", [&](const std::string& vehicle_name, const std::string& object_name) -> RpcLibAdaptorsBase::Vector3r { + const auto& rot = getWorldSimApi()->findLookAtRotation(vehicle_name, object_name); + return RpcLibAdaptorsBase::Vector3r(rot); + }); + //if we don't suppress then server will bomb out for exceptions raised by any method pimpl_->server.suppress_exceptions(true); } diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index f9cfd2256c..16c71ce2f2 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -555,6 +555,20 @@ def simListSceneObjects(self, name_regex = '.*'): """ return self.client.call('simListSceneObjects', name_regex) + def simListSceneObjectsByTag(self, tag_regex = '.*'): + """ + Lists the objects present in the environment by searching their tags + + Default behaviour is to list all objects, regex can be used to return smaller list of matching objects or actors + + Args: + tag_regex (str, optional): String to match actor tags against, e.g. "Tag.*" + + Returns: + list[str]: List containing all the names + """ + return self.client.call('simListSceneObjectsByTag', tag_regex) + def simLoadLevel(self, level_name): """ Loads a level specified by its name @@ -1123,6 +1137,9 @@ def simSetExtForce(self, ext_force): """ self.client.call('simSetExtForce', ext_force) + def simFindLookAtRotation(self, object_name, vehicle_name = ''): + return self.client.call('simFindLookAtRotation', vehicle_name, object_name) + # ----------------------------------- Multirotor APIs --------------------------------------------- class MultirotorClient(VehicleClient, object): def __init__(self, ip = "", port = 41451, timeout_value = 3600): diff --git a/PythonClient/multirotor/add_drone.py b/PythonClient/multirotor/add_drone.py index fd740dd5d5..ca53e91f4c 100644 --- a/PythonClient/multirotor/add_drone.py +++ b/PythonClient/multirotor/add_drone.py @@ -2,6 +2,7 @@ import airsim import tempfile import os +import random import numpy as np import cv2 import pprint @@ -11,7 +12,7 @@ client.confirmConnection() # add new vehicle -vehicle_name = "Drone2" +vehicle_name = "Drone2" + str(random.randrange(100)) pose = airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(0, 0, 0)) client.simAddVehicle(vehicle_name, "simpleflight", pose) diff --git a/PythonClient/multirotor/path.py b/PythonClient/multirotor/path.py index 6d34f13488..fb8d35d3d0 100644 --- a/PythonClient/multirotor/path.py +++ b/PythonClient/multirotor/path.py @@ -30,7 +30,7 @@ # AirSim uses NED coordinates so negative axis is up. # z of -5 is 5 meters above the original launch point. -z = -5 +z = -30 print("make sure we are hovering at {} meters...".format(-z)) client.moveToZAsync(z, 1).join() diff --git a/Unreal/Environments/Blocks/Blocks.uproject b/Unreal/Environments/Blocks/Blocks.uproject index 91c16a962a..6d803f0f0c 100644 --- a/Unreal/Environments/Blocks/Blocks.uproject +++ b/Unreal/Environments/Blocks/Blocks.uproject @@ -1,30 +1,30 @@ -{ - "FileVersion": 3, - "EngineAssociation": "5.1", - "Category": "", - "Description": "", - "Modules": [ - { - "Name": "Blocks", - "Type": "Runtime", - "LoadingPhase": "Default", - "AdditionalDependencies": [ - "AirSim" - ] - } - ], - "Plugins": [ - { - "Name": "AirSim", - "Enabled": true - }, - { - "Name": "SteamVR", - "Enabled": false - }, - { - "Name": "OculusVR", - "Enabled": false - } - ] +{ + "FileVersion": 3, + "EngineAssociation": "5.3", + "Category": "", + "Description": "", + "Modules": [ + { + "Name": "Blocks", + "Type": "Runtime", + "LoadingPhase": "Default", + "AdditionalDependencies": [ + "AirSim" + ] + } + ], + "Plugins": [ + { + "Name": "AirSim", + "Enabled": true + }, + { + "Name": "SteamVR", + "Enabled": false + }, + { + "Name": "OculusVR", + "Enabled": false + } + ] } \ No newline at end of file diff --git a/Unreal/Environments/Blocks/Config/DefaultEditor.ini b/Unreal/Environments/Blocks/Config/DefaultEditor.ini index d4e8232a87..f44257a4da 100644 --- a/Unreal/Environments/Blocks/Config/DefaultEditor.ini +++ b/Unreal/Environments/Blocks/Config/DefaultEditor.ini @@ -7,4 +7,5 @@ bReplaceBlueprintWithClass= true bDontLoadBlueprintOutsideEditor= true bBlueprintIsNotBlueprintType= true +[/Script/AdvancedPreviewScene.SharedProfiles] diff --git a/Unreal/Environments/Blocks/Config/DefaultEngine.ini b/Unreal/Environments/Blocks/Config/DefaultEngine.ini index 7fe1348403..bb71e75c2c 100644 --- a/Unreal/Environments/Blocks/Config/DefaultEngine.ini +++ b/Unreal/Environments/Blocks/Config/DefaultEngine.ini @@ -68,4 +68,17 @@ AsyncSceneSmoothingFactor=0.990000 InitialAverageFrameRate=0.016667 PhysXTreeRebuildRate=10 +[/Script/AndroidFileServerEditor.AndroidFileServerRuntimeSettings] +bEnablePlugin=True +bAllowNetworkConnection=True +SecurityToken=811F8F1C4E41692A119A55BE04E6DB61 +bIncludeInShipping=False +bAllowExternalStartInShipping=False +bCompileAFSProject=False +bUseCompression=False +bLogFiles=False +bReportStats=False +ConnectionType=USBOnly +bUseManualIPAddress=False +ManualIPAddress= diff --git a/Unreal/Environments/Blocks/Config/DefaultInput.ini b/Unreal/Environments/Blocks/Config/DefaultInput.ini index 78803ce4f1..c68d330fdd 100644 --- a/Unreal/Environments/Blocks/Config/DefaultInput.ini +++ b/Unreal/Environments/Blocks/Config/DefaultInput.ini @@ -1,20 +1,86 @@ [/Script/Engine.InputSettings] +-AxisConfig=(AxisKeyName="Gamepad_LeftX",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) +-AxisConfig=(AxisKeyName="Gamepad_LeftY",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) +-AxisConfig=(AxisKeyName="Gamepad_RightX",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) +-AxisConfig=(AxisKeyName="Gamepad_RightY",AxisProperties=(DeadZone=0.25,Exponent=1.f,Sensitivity=1.f)) +-AxisConfig=(AxisKeyName="MouseX",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) +-AxisConfig=(AxisKeyName="MouseY",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) +-AxisConfig=(AxisKeyName="Mouse2D",AxisProperties=(DeadZone=0.f,Exponent=1.f,Sensitivity=0.07f)) ++AxisConfig=(AxisKeyName="Gamepad_LeftX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_LeftY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_RightX",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_RightY",AxisProperties=(DeadZone=0.250000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MouseX",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MouseY",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Mouse2D",AxisProperties=(DeadZone=0.000000,Sensitivity=0.070000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MouseWheelAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_LeftTriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_RightTriggerAxis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_Special_Left_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Gamepad_Special_Left_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="Vive_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="MixedReality_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Left_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Right_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="OculusTouch_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Grip_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Left_Trackpad_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Grip_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Grip_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Trigger_Axis",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Thumbstick_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Thumbstick_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_X",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_Y",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) ++AxisConfig=(AxisKeyName="ValveIndex_Right_Trackpad_Force",AxisProperties=(DeadZone=0.000000,Sensitivity=1.000000,Exponent=1.000000,bInvert=False)) bAltEnterTogglesFullscreen=True bF11TogglesFullscreen=True bUseMouseForTouch=False bEnableMouseSmoothing=True bEnableFOVScaling=True -FOVScale=0.011110 -DoubleClickTime=0.200000 bCaptureMouseOnLaunch=False -DefaultViewportMouseCaptureMode=NoCapture -bDefaultViewportMouseLock=False -DefaultViewportMouseLockMode=DoNotLock +bEnableLegacyInputScales=True +bEnableMotionControls=True +bFilterInputByPlatformUser=False +bEnableInputDeviceSubsystem=True +bShouldFlushPressedKeysOnViewportFocusLost=True +bEnableDynamicComponentInputBinding=True bAlwaysShowTouchInterface=False bShowConsoleOnFourFingerTap=True +bEnableGestureRecognizer=False +bUseAutocorrect=False +DefaultViewportMouseCaptureMode=NoCapture +DefaultViewportMouseLockMode=DoNotLock +FOVScale=0.011110 +DoubleClickTime=0.200000 +DefaultPlayerInputClass=/Script/EnhancedInput.EnhancedPlayerInput +DefaultInputComponentClass=/Script/EnhancedInput.EnhancedInputComponent DefaultTouchInterface=/Engine/MobileResources/HUD/DefaultVirtualJoysticks.DefaultVirtualJoysticks -ConsoleKey=None -ConsoleKeys=Tilde +ConsoleKeys=Tilde - diff --git a/Unreal/Environments/Blocks/Source/Blocks.Target.cs b/Unreal/Environments/Blocks/Source/Blocks.Target.cs index d7c26bac5d..2a0f084779 100644 --- a/Unreal/Environments/Blocks/Source/Blocks.Target.cs +++ b/Unreal/Environments/Blocks/Source/Blocks.Target.cs @@ -9,7 +9,7 @@ public BlocksTarget(TargetInfo Target) : base(Target) { Type = TargetType.Game; ExtraModuleNames.AddRange(new string[] { "Blocks" }); - + DefaultBuildSettings = BuildSettingsVersion.V4; //bUseUnityBuild = false; if (Target.Platform == UnrealTargetPlatform.Linux) bUsePCHFiles = false; diff --git a/Unreal/Environments/Blocks/Source/BlocksEditor.Target.cs b/Unreal/Environments/Blocks/Source/BlocksEditor.Target.cs index 187daed546..a6e65043ae 100644 --- a/Unreal/Environments/Blocks/Source/BlocksEditor.Target.cs +++ b/Unreal/Environments/Blocks/Source/BlocksEditor.Target.cs @@ -9,7 +9,7 @@ public BlocksEditorTarget(TargetInfo Target) : base(Target) { Type = TargetType.Editor; ExtraModuleNames.AddRange(new string[] { "Blocks" }); - DefaultBuildSettings = BuildSettingsVersion.V2; + DefaultBuildSettings = BuildSettingsVersion.V4; //bUseUnityBuild = false; //bUsePCHFiles = false; } diff --git a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp index 46a123fde1..7f6f745779 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) @@ -346,8 +346,8 @@ std::string UAirBlueprintLib::GetMeshName(USkinnedMeshCom else return ""; // std::string(TCHAR_TO_UTF8(*(UKismetSystemLibrary::GetDisplayName(mesh)))); case msr::airlib::AirSimSettings::SegmentationSetting::MeshNamingMethodType::StaticMeshName: - if (mesh->SkeletalMesh) - return std::string(TCHAR_TO_UTF8(*(mesh->SkeletalMesh->GetName()))); + if (mesh->GetSkinnedAsset()) + return std::string(TCHAR_TO_UTF8(*(mesh->GetSkinnedAsset()->GetName()))); else return ""; default: @@ -445,6 +445,26 @@ std::vector UAirBlueprintLib::ListMatchingActors(const UObject* con return results; } +std::vector UAirBlueprintLib::ListMatchingActorsByTag(const UObject* context, const std::string& tag_regex) +{ + std::vector results; + auto world = context->GetWorld(); + std::regex compiledRegex(tag_regex, std::regex::optimize); + for (TActorIterator actorIterator(world); actorIterator; ++actorIterator) { + AActor* actor = *actorIterator; + auto name = std::string(TCHAR_TO_UTF8(*actor->GetName())); + for (auto& tag : actor->Tags) { + auto tag_ = std::string(TCHAR_TO_UTF8(*tag.ToString())); + bool match = std::regex_match(tag_, compiledRegex); + if (match) { + results.push_back(name); + break; // don't add the name twice + } + } + } + return results; +} + std::vector UAirBlueprintLib::GetStaticMeshComponents() { std::vector meshes; @@ -494,9 +514,9 @@ std::vector UAirBlueprintLib::Ge ENQUEUE_RENDER_COMMAND(GetVertexBuffer) ( [vertex_buffer, data](FRHICommandListImmediate& RHICmdList) { - FVector* indices = (FVector*)RHILockBuffer(vertex_buffer->VertexBufferRHI, 0, vertex_buffer->VertexBufferRHI->GetSize(), RLM_ReadOnly); + FVector* indices = (FVector*)RHICmdList.LockBuffer(vertex_buffer->VertexBufferRHI, 0, vertex_buffer->VertexBufferRHI->GetSize(), RLM_ReadOnly); memcpy(data, indices, vertex_buffer->VertexBufferRHI->GetSize()); - RHIUnlockBuffer(vertex_buffer->VertexBufferRHI); + RHICmdList.UnlockBuffer(vertex_buffer->VertexBufferRHI); }); #if ((ENGINE_MAJOR_VERSION > 4) || (ENGINE_MAJOR_VERSION == 4 && ENGINE_MINOR_VERSION >= 27)) @@ -516,9 +536,9 @@ std::vector UAirBlueprintLib::Ge ENQUEUE_RENDER_COMMAND(GetIndexBuffer) ( [IndexBuffer, data_ptr](FRHICommandListImmediate& RHICmdList) { - uint16_t* indices = (uint16_t*)RHILockBuffer(IndexBuffer->IndexBufferRHI, 0, IndexBuffer->IndexBufferRHI->GetSize(), RLM_ReadOnly); + uint16_t* indices = (uint16_t*)RHICmdList.LockBuffer(IndexBuffer->IndexBufferRHI, 0, IndexBuffer->IndexBufferRHI->GetSize(), RLM_ReadOnly); memcpy(data_ptr, indices, IndexBuffer->IndexBufferRHI->GetSize()); - RHIUnlockBuffer(IndexBuffer->IndexBufferRHI); + RHICmdList.UnlockBuffer(IndexBuffer->IndexBufferRHI); }); //Need to force the render command to go through cause on the next iteration the buffer no longer exists @@ -539,9 +559,9 @@ std::vector UAirBlueprintLib::Ge ENQUEUE_RENDER_COMMAND(GetIndexBuffer) ( [IndexBuffer, data_ptr](FRHICommandListImmediate& RHICmdList) { - uint32_t* indices = (uint32_t*)RHILockBuffer(IndexBuffer->IndexBufferRHI, 0, IndexBuffer->IndexBufferRHI->GetSize(), RLM_ReadOnly); + uint32_t* indices = (uint32_t*)RHICmdList.LockBuffer(IndexBuffer->IndexBufferRHI, 0, IndexBuffer->IndexBufferRHI->GetSize(), RLM_ReadOnly); memcpy(data_ptr, indices, IndexBuffer->IndexBufferRHI->GetSize()); - RHIUnlockBuffer(IndexBuffer->IndexBufferRHI); + RHICmdList.UnlockBuffer(IndexBuffer->IndexBufferRHI); }); FlushRenderingCommands(); @@ -576,7 +596,8 @@ std::vector UAirBlueprintLib::Ge TArray UAirBlueprintLib::ListWorldsInRegistry() { FARFilter Filter; - Filter.ClassNames.Add(UWorld::StaticClass()->GetFName()); + FTopLevelAssetPath UPath(UWorld::StaticClass()->GetPathName()); + Filter.ClassPaths.Add(UPath); Filter.bRecursivePaths = true; TArray AssetData; @@ -592,7 +613,8 @@ TArray UAirBlueprintLib::ListWorldsInRegistry() UObject* UAirBlueprintLib::GetMeshFromRegistry(const std::string& load_object) { FARFilter Filter; - Filter.ClassNames.Add(UStaticMesh::StaticClass()->GetFName()); + FTopLevelAssetPath MPath(UStaticMesh::StaticClass()->GetPathName()); + Filter.ClassPaths.Add(MPath); Filter.bRecursivePaths = true; TArray AssetData; @@ -806,3 +828,13 @@ bool UAirBlueprintLib::CompressUsingImageWrapper(const TArray& uncompress return bSucceeded; } + +void UAirBlueprintLib::FindAllActorByTag(const UObject* context, FName tag, TArray& foundActors) +{ + UGameplayStatics::GetAllActorsWithTag(context, tag, foundActors); +} + +FRotator UAirBlueprintLib::FindLookAtRotation(AActor* source, AActor* target) +{ + return UKismetMathLibrary::FindLookAtRotation(source->GetActorLocation(), target->GetActorLocation()); +} diff --git a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.h b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.h index d136a67997..53df307c7f 100644 --- a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.h +++ b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.h @@ -58,7 +58,7 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary FName name_n = FName(*name); for (TActorIterator It(context->GetWorld(), T::StaticClass()); It; ++It) { AActor* Actor = *It; - if (!Actor->IsPendingKill() && (Actor->ActorHasTag(name_n) || Actor->GetName().Compare(name) == 0)) { + if (IsValid(Actor) && (Actor->ActorHasTag(name_n) || Actor->GetName().Compare(name) == 0)) { return static_cast(Actor); } } @@ -71,7 +71,12 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary UGameplayStatics::GetAllActorsOfClass(context, T::StaticClass(), foundActors); } + static void FindAllActorByTag(const UObject* context, FName tag, TArray& foundActors); + static FRotator FindLookAtRotation(AActor* source, AActor* target); + static std::vector ListMatchingActors(const UObject* context, const std::string& name_regex); + static std::vector ListMatchingActorsByTag(const UObject* context, const std::string& tag_regex); + UFUNCTION(BlueprintCallable, Category = "AirSim|LevelAPI") static bool loadLevel(UObject* context, const FString& level_name); UFUNCTION(BlueprintCallable, Category = "AirSim|LevelAPI") @@ -123,7 +128,7 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary template static FInputActionBinding& BindActionToKey(const FName action_name, const FKey in_key, UserClass* actor, - typename FInputActionHandlerSignature::TUObjectMethodDelegate::FMethodPtr func, bool on_press_or_release = false, + typename FInputActionHandlerSignature::TMethodPtr func, bool on_press_or_release = false, bool shift_key = false, bool control_key = false, bool alt_key = false, bool command_key = false) { FInputActionKeyMapping action(action_name, in_key, shift_key, control_key, alt_key, command_key); @@ -136,7 +141,7 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary template static FInputAxisBinding& BindAxisToKey(const FName axis_name, const FKey in_key, AActor* actor, UserClass* obj, - typename FInputAxisHandlerSignature::TUObjectMethodDelegate::FMethodPtr func) + typename FInputAxisHandlerSignature::TMethodPtr func) { FInputAxisKeyMapping axis(axis_name, in_key); @@ -145,7 +150,7 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary template static FInputAxisBinding& BindAxisToKey(const FInputAxisKeyMapping& axis, AActor* actor, UserClass* obj, - typename FInputAxisHandlerSignature::TUObjectMethodDelegate::FMethodPtr func) + typename FInputAxisHandlerSignature::TMethodPtr func) { APlayerController* controller = actor->GetWorld()->GetFirstPlayerController(); diff --git a/Unreal/Plugins/AirSim/Source/AirSim.Build.cs b/Unreal/Plugins/AirSim/Source/AirSim.Build.cs index 9aa79c4743..de9041afe0 100644 --- a/Unreal/Plugins/AirSim/Source/AirSim.Build.cs +++ b/Unreal/Plugins/AirSim/Source/AirSim.Build.cs @@ -21,7 +21,9 @@ private string AirSimPluginPath } private string ProjectBinariesPath { - get { return Path.Combine( + get + { + return Path.Combine( Directory.GetParent(AirSimPluginPath).Parent.FullName, "Binaries"); } } @@ -90,7 +92,7 @@ public AirSim(ReadOnlyTargetRules Target) : base(Target) PublicIncludePaths.Add(Path.Combine(AirLibPath, "deps", "eigen3")); AddOSLibDependencies(Target); - SetupCompileMode(CompileMode.HeaderOnlyWithRpc, Target); + SetupCompileMode(CompileMode.CppCompileWithRpc, Target); } private void AddOSLibDependencies(ReadOnlyTargetRules Target) @@ -105,12 +107,12 @@ private void AddOSLibDependencies(ReadOnlyTargetRules Target) PublicAdditionalLibraries.Add("dxguid.lib"); } - if (Target.Platform == UnrealTargetPlatform.Linux) - { - // needed when packaging - PublicAdditionalLibraries.Add("stdc++"); - PublicAdditionalLibraries.Add("supc++"); - } + if (Target.Platform == UnrealTargetPlatform.Linux) + { + // needed when packaging + PublicAdditionalLibraries.Add("stdc++"); + PublicAdditionalLibraries.Add("supc++"); + } } static void CopyFileIfNewer(string srcFilePath, string destFolder) @@ -142,7 +144,9 @@ private bool AddLibDependency(string LibName, string LibPath, string LibFileName isLibrarySupported = true; PublicAdditionalLibraries.Add(Path.Combine(LibPath, PlatformString, ConfigurationString, LibFileName + ".lib")); - } else if (Target.Platform == UnrealTargetPlatform.Linux || Target.Platform == UnrealTargetPlatform.Mac) { + } + else if (Target.Platform == UnrealTargetPlatform.Linux || Target.Platform == UnrealTargetPlatform.Mac) + { isLibrarySupported = true; PublicAdditionalLibraries.Add(Path.Combine(LibPath, "lib" + LibFileName + ".a")); } diff --git a/Unreal/Plugins/AirSim/Source/CameraDirector.cpp b/Unreal/Plugins/AirSim/Source/AirSimCameraDirector.cpp similarity index 99% rename from Unreal/Plugins/AirSim/Source/CameraDirector.cpp rename to Unreal/Plugins/AirSim/Source/AirSimCameraDirector.cpp index 43f0a3f2ad..9cc9626692 100644 --- a/Unreal/Plugins/AirSim/Source/CameraDirector.cpp +++ b/Unreal/Plugins/AirSim/Source/AirSimCameraDirector.cpp @@ -1,4 +1,4 @@ -#include "CameraDirector.h" +#include "AirSimCameraDirector.h" #include "GameFramework/PlayerController.h" #include "AirBlueprintLib.h" diff --git a/Unreal/Plugins/AirSim/Source/CameraDirector.h b/Unreal/Plugins/AirSim/Source/AirSimCameraDirector.h similarity index 82% rename from Unreal/Plugins/AirSim/Source/CameraDirector.h rename to Unreal/Plugins/AirSim/Source/AirSimCameraDirector.h index 59f4557eda..6440e0f9de 100644 --- a/Unreal/Plugins/AirSim/Source/CameraDirector.h +++ b/Unreal/Plugins/AirSim/Source/AirSimCameraDirector.h @@ -7,7 +7,7 @@ #include "ManualPoseController.h" #include "common/common_utils/Utils.hpp" #include "GameFramework/SpringArmComponent.h" -#include "CameraDirector.generated.h" +#include "AirSimCameraDirector.generated.h" UENUM(BlueprintType) enum class ECameraDirectorMode : uint8 @@ -30,10 +30,10 @@ class AIRSIM_API ACameraDirector : public AActor public: /** Spring arm that will offset the camera */ UPROPERTY(Category = Camera, VisibleDefaultsOnly, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) - USpringArmComponent* SpringArm; + USpringArmComponent *SpringArm; UPROPERTY(Category = Camera, VisibleDefaultsOnly, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) - APIPCamera* ExternalCamera; + APIPCamera *ExternalCamera; public: void inputEventFpvView(); @@ -57,11 +57,11 @@ class AIRSIM_API ACameraDirector : public AActor void setMode(ECameraDirectorMode mode); void initializeForBeginPlay(ECameraDirectorMode view_mode, - AActor* follow_actor, APIPCamera* fpv_camera, APIPCamera* front_camera, APIPCamera* back_camera); + AActor *follow_actor, APIPCamera *fpv_camera, APIPCamera *front_camera, APIPCamera *back_camera); - APIPCamera* getFpvCamera() const; - APIPCamera* getExternalCamera() const; - APIPCamera* getBackupCamera() const; + APIPCamera *getFpvCamera() const; + APIPCamera *getExternalCamera() const; + APIPCamera *getBackupCamera() const; void setFollowDistance(const int follow_distance) { this->follow_distance_ = follow_distance; } void setCameraRotationLagEnabled(const bool lag_enabled) { this->camera_rotation_lag_enabled_ = lag_enabled; } @@ -74,16 +74,16 @@ class AIRSIM_API ACameraDirector : public AActor private: typedef common_utils::Utils Utils; - APIPCamera* fpv_camera_; - APIPCamera* backup_camera_; - APIPCamera* front_camera_; - AActor* follow_actor_; + APIPCamera *fpv_camera_; + APIPCamera *backup_camera_; + APIPCamera *front_camera_; + AActor *follow_actor_; - USceneComponent* last_parent_ = nullptr; + USceneComponent *last_parent_ = nullptr; ECameraDirectorMode mode_; UPROPERTY() - UManualPoseController* manual_pose_controller_; + UManualPoseController *manual_pose_controller_; FVector camera_start_location_; FVector initial_ground_obs_offset_; diff --git a/Unreal/Plugins/AirSim/Source/DetectionComponent.cpp b/Unreal/Plugins/AirSim/Source/DetectionComponent.cpp index a1fc1281fa..9498564e54 100644 --- a/Unreal/Plugins/AirSim/Source/DetectionComponent.cpp +++ b/Unreal/Plugins/AirSim/Source/DetectionComponent.cpp @@ -26,25 +26,34 @@ UDetectionComponent::UDetectionComponent() void UDetectionComponent::BeginPlay() { Super::BeginPlay(); - scene_capture_component_2D_ = CastChecked(GetAttachParent()); + scene_capture_component_2D_ = Cast(GetAttachParent()); + if (!scene_capture_component_2D_) + { + // we get re-parented to USceneComponent when saving Take Recorder videos + this->Deactivate(); + } object_filter_ = FObjectFilter(); } -void UDetectionComponent::TickComponent(float DeltaTime, ELevelTick TickType, FActorComponentTickFunction* ThisTickFunction) +void UDetectionComponent::TickComponent(float DeltaTime, ELevelTick TickType, FActorComponentTickFunction *ThisTickFunction) { Super::TickComponent(DeltaTime, TickType, ThisTickFunction); } -const TArray& UDetectionComponent::getDetections() +const TArray &UDetectionComponent::getDetections() { cached_detections_.Empty(); - for (TActorIterator actor_itr(GetWorld()); actor_itr; ++actor_itr) { - AActor* actor = *actor_itr; - if (object_filter_.matchesActor(actor)) { - if (FVector::Distance(actor->GetActorLocation(), GetComponentLocation()) <= max_distance_to_camera_) { + for (TActorIterator actor_itr(GetWorld()); actor_itr; ++actor_itr) + { + AActor *actor = *actor_itr; + if (object_filter_.matchesActor(actor)) + { + if (FVector::Distance(actor->GetActorLocation(), GetComponentLocation()) <= max_distance_to_camera_) + { FBox2D box_2D_out; - if (texture_target_ && calcBoundingFromViewInfo(actor, box_2D_out)) { + if (texture_target_ && calcBoundingFromViewInfo(actor, box_2D_out)) + { FDetectionInfo detection; detection.Actor = actor; detection.Box2D = box_2D_out; @@ -63,7 +72,7 @@ const TArray& UDetectionComponent::getDetections() return cached_detections_; } -bool UDetectionComponent::calcBoundingFromViewInfo(AActor* actor, FBox2D& box_out) +bool UDetectionComponent::calcBoundingFromViewInfo(AActor *actor, FBox2D &box_out) { FVector origin; FVector extend; @@ -74,7 +83,7 @@ bool UDetectionComponent::calcBoundingFromViewInfo(AActor* actor, FBox2D& box_ou bool is_in_camera_view = false; // get render target for texture size - FRenderTarget* render_target = texture_target_->GameThread_GetRenderTargetResource(); + FRenderTarget *render_target = texture_target_->GameThread_GetRenderTargetResource(); // initialize viewinfo for projection matrix FMinimalViewInfo info; @@ -113,16 +122,19 @@ bool UDetectionComponent::calcBoundingFromViewInfo(AActor* actor, FBox2D& box_ou FPlane(0, 1, 0, 0), FPlane(0, 0, 0, 1)); - if (scene_capture_component_2D_->bUseCustomProjectionMatrix) { + if (scene_capture_component_2D_->bUseCustomProjectionMatrix) + { projection_data.ProjectionMatrix = scene_capture_component_2D_->CustomProjectionMatrix; } - else { + else + { projection_data.ProjectionMatrix = info.CalculateProjectionMatrix(); } projection_data.SetConstrainedViewRectangle(screen_rect); // Project Points to pixels and get the corner pixels - for (FVector& point : points) { + for (FVector &point : points) + { FVector2D Pixel(0, 0); FSceneView::ProjectWorldToScreen((point), screen_rect, projection_data.ComputeViewProjectionMatrix(), Pixel); is_in_camera_view |= (Pixel != screen_rect.Min) && (Pixel != screen_rect.Max) && screen_rect.Contains(FIntPoint(Pixel.X, Pixel.Y)); @@ -136,13 +148,17 @@ bool UDetectionComponent::calcBoundingFromViewInfo(AActor* actor, FBox2D& box_ou // If actor in camera view - check if it's actually visible or hidden // Check against 8 extend points bool is_visible = false; - if (is_in_camera_view) { + if (is_in_camera_view) + { FHitResult result; bool is_world_hit; - for (FVector& point : points) { + for (FVector &point : points) + { is_world_hit = GetWorld()->LineTraceSingleByChannel(result, GetComponentLocation(), point, ECC_WorldStatic); - if (is_world_hit) { - if (result.GetActor() == actor) { + if (is_world_hit) + { + if (result.GetActor() == actor) + { is_visible = true; break; } @@ -151,12 +167,16 @@ bool UDetectionComponent::calcBoundingFromViewInfo(AActor* actor, FBox2D& box_ou // If actor in camera view but didn't hit any point out of 8 extend points, // check against 10 random points - if (!is_visible) { - for (int i = 0; i < 10; i++) { + if (!is_visible) + { + for (int i = 0; i < 10; i++) + { FVector point = UKismetMathLibrary::RandomPointInBoundingBox(origin, extend); is_world_hit = GetWorld()->LineTraceSingleByChannel(result, GetComponentLocation(), point, ECC_WorldStatic); - if (is_world_hit) { - if (result.GetActor() == actor) { + if (is_world_hit) + { + if (result.GetActor() == actor) + { is_visible = true; break; } @@ -187,11 +207,12 @@ FRotator UDetectionComponent::getRelativeRotation(FVector in_location, FRotator return relative_object_transform.Rotator(); } -void UDetectionComponent::addMeshName(const std::string& mesh_name) +void UDetectionComponent::addMeshName(const std::string &mesh_name) { FString name(mesh_name.c_str()); - if (!object_filter_.wildcard_mesh_names_.Contains(name)) { + if (!object_filter_.wildcard_mesh_names_.Contains(name)) + { object_filter_.wildcard_mesh_names_.Add(name); } } diff --git a/Unreal/Plugins/AirSim/Source/ObjectFilter.cpp b/Unreal/Plugins/AirSim/Source/ObjectFilter.cpp index 25c48b4f9a..905e7f0ce6 100644 --- a/Unreal/Plugins/AirSim/Source/ObjectFilter.cpp +++ b/Unreal/Plugins/AirSim/Source/ObjectFilter.cpp @@ -49,12 +49,12 @@ bool FObjectFilter::matchesActor(AActor* actor) const USkeletalMeshComponent* skeletal_mesh_component = Cast(actor_component); if (skeletal_mesh_component) { if (skeletal_mesh_ && - skeletal_mesh_component->SkeletalMesh == skeletal_mesh_) { + skeletal_mesh_component->GetSkeletalMeshAsset() == skeletal_mesh_) { return true; } if (wildcard_mesh_names_.Num() != 0 && - skeletal_mesh_component->SkeletalMesh && - isMatchAnyWildcard(skeletal_mesh_component->SkeletalMesh->GetName())) { + skeletal_mesh_component->GetSkeletalMeshAsset() && + isMatchAnyWildcard(skeletal_mesh_component->GetSkeletalMeshAsset()->GetName())) { return true; } } @@ -112,11 +112,11 @@ bool FObjectFilter::matchesComponent(UActorComponent* actor_component) const if (skeletal_mesh_ || wildcard_mesh_names_.Num() != 0) { USkeletalMeshComponent* SkeletalMeshComponent = Cast(actor_component); if (SkeletalMeshComponent) { - if (skeletal_mesh_ && SkeletalMeshComponent->SkeletalMesh == skeletal_mesh_) { + if (skeletal_mesh_ && SkeletalMeshComponent->GetSkeletalMeshAsset() == skeletal_mesh_) { bMatchesSkeletalMesh = true; } if (wildcard_mesh_names_.Num() != 0 && - isMatchAnyWildcard(SkeletalMeshComponent->SkeletalMesh->GetName())) { + isMatchAnyWildcard(SkeletalMeshComponent->GetSkeletalMeshAsset()->GetName())) { bMatchesWildcardMeshName = true; } } @@ -185,4 +185,4 @@ uint32 GetTypeHash(const FObjectFilter& key) // KeyHash = HashCombine(KeyHash, GetTypeHash(Key.WildcardMeshNames)); return key_hash; -} \ No newline at end of file +} diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp index bd815eebb5..0afae758ad 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp @@ -626,7 +626,7 @@ void APIPCamera::onViewModeChanged(bool nodisplay) std::vector APIPCamera::getPresetLensSettings() const { std::vector vector; - const TArray lens_presets = camera_->GetLensPresets(); + const TArray lens_presets = UCineCameraSettings::GetLensPresets(); for (const FNamedLensPreset& preset : lens_presets) { std::ostringstream current_lens_string; std::string name = (TCHAR_TO_UTF8(*preset.Name)); @@ -668,7 +668,7 @@ void APIPCamera::setPresetLensSettings(std::string preset_string) std::vector APIPCamera::getPresetFilmbackSettings() const { std::vector vector_all_presets; - TArray lens_presets = camera_->GetFilmbackPresets(); + TArray lens_presets = UCineCameraSettings::GetFilmbackPresets(); for (const FNamedFilmbackPreset& preset : lens_presets) { std::ostringstream preset_string; std::string name = (TCHAR_TO_UTF8(*preset.Name)); diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h index f21144a611..3e3e972bb1 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h @@ -7,7 +7,7 @@ #include "ParticleDefinitions.h" #include -#include "CameraDirector.h" +#include "AirSimCameraDirector.h" #include "common/AirSimSettings.hpp" #include "common/ClockFactory.hpp" #include "api/ApiServerBase.hpp" diff --git a/Unreal/Plugins/AirSim/Source/Weather/WeatherLib.cpp b/Unreal/Plugins/AirSim/Source/Weather/WeatherLib.cpp index a9f1f130a5..e0e4b63902 100644 --- a/Unreal/Plugins/AirSim/Source/Weather/WeatherLib.cpp +++ b/Unreal/Plugins/AirSim/Source/Weather/WeatherLib.cpp @@ -200,7 +200,6 @@ void UWeatherLib::hideWeatherMenu(UWorld* World) // hacky test to make sure we are getting the right class. for some reason cast above doesn't work, so we use this instead to test for class if (FoundWidgets[i] && FoundWidgets[i]->GetClass()->GetFName().ToString() == getWeatherMenuClassName()) { FoundWidgets[i]->RemoveFromParent(); - FoundWidgets[i]->RemoveFromViewport(); } } APlayerController* PC = UGameplayStatics::GetPlayerController(World, 0); diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index 8b8ec5223b..be836905c2 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -66,7 +66,7 @@ bool WorldSimApi::destroyObject(const std::string& object_name) AActor* actor = UAirBlueprintLib::FindActor(simmode_, FString(object_name.c_str())); if (actor) { actor->Destroy(); - result = actor->IsPendingKill(); + result = !IsValid(actor); } if (result) simmode_->scene_object_map.Remove(FString(object_name.c_str())); @@ -338,6 +338,16 @@ std::vector WorldSimApi::listSceneObjects(const std::string& name_r return result; } +std::vector WorldSimApi::listSceneObjectsByTag(const std::string& tag_regex) const +{ + std::vector result; + UAirBlueprintLib::RunCommandOnGameThread([this, &tag_regex, &result]() { + result = UAirBlueprintLib::ListMatchingActorsByTag(simmode_, tag_regex); + }, + true); + return result; +} + bool WorldSimApi::runConsoleCommand(const std::string& command) { bool succeeded = false; @@ -1063,3 +1073,23 @@ std::vector WorldSimApi::getDetections(ImageCaptureB return result; } + +Vector3r WorldSimApi::findLookAtRotation(const std::string& vehicle_name, const std::string& object_name) +{ + Vector3r result = Vector3r::Zero(); + PawnSimApi* pawn = simmode_->getVehicleSimApi(vehicle_name); + + if (pawn) { + AActor* source = pawn->getPawn(); + UAirBlueprintLib::RunCommandOnGameThread([this, object_name, &source, &result]() { + AActor* target = UAirBlueprintLib::FindActor(simmode_, FString(object_name.c_str())); + if (target) { + FRotator rot = UAirBlueprintLib::FindLookAtRotation(source, target); + result = Vector3r(rot.Pitch, rot.Roll, rot.Yaw); + } + }, + true); + } + + return result; +} diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.h b/Unreal/Plugins/AirSim/Source/WorldSimApi.h index 7bbbba3e8e..ce7e12647d 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.h +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.h @@ -52,6 +52,8 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase virtual bool setObjectMaterial(const std::string& object_name, const std::string& material_name, const int component_id = 0) override; virtual bool setObjectMaterialFromTexture(const std::string& object_name, const std::string& texture_path, const int component_id = 0) override; virtual std::vector listSceneObjects(const std::string& name_regex) const override; + virtual std::vector listSceneObjectsByTag(const std::string& tag_regex) const override; + virtual Pose getObjectPose(const std::string& object_name) const override; virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) override; virtual bool runConsoleCommand(const std::string& command) override; @@ -119,6 +121,8 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase virtual void clearDetectionMeshNames(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) override; virtual std::vector getDetections(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) override; + virtual Vector3r findLookAtRotation(const std::string& vehicle_name, const std::string& object_name); + private: AActor* createNewStaticMeshActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UStaticMesh* static_mesh); AActor* createNewBPActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UBlueprint* blueprint); diff --git a/UnrealPluginFiles.vcxproj b/UnrealPluginFiles.vcxproj index d6a2e80f8e..af6646ccdb 100644 --- a/UnrealPluginFiles.vcxproj +++ b/UnrealPluginFiles.vcxproj @@ -135,7 +135,7 @@ - + diff --git a/UnrealPluginFiles.vcxproj.filters b/UnrealPluginFiles.vcxproj.filters index b0516486ad..7d46ed4c27 100644 --- a/UnrealPluginFiles.vcxproj.filters +++ b/UnrealPluginFiles.vcxproj.filters @@ -122,7 +122,7 @@ Header Files - + Header Files diff --git a/build.sh b/build.sh index 9d9fb85cef..907b8d2b8f 100755 --- a/build.sh +++ b/build.sh @@ -94,12 +94,6 @@ if [[ ! -d $build_dir ]]; then mkdir -p $build_dir fi -# Fix for Unreal/Unity using x86_64 (Rosetta) on Apple Silicon hardware. -CMAKE_VARS= -if [ "$(uname)" == "Darwin" ]; then - CMAKE_VARS="-DCMAKE_APPLE_SILICON_PROCESSOR=x86_64" -fi - pushd $build_dir >/dev/null if $debug; then folder_name="Debug"