diff --git a/AirLib/include/common/VectorMath.hpp b/AirLib/include/common/VectorMath.hpp index a5bb238245..d5a8c89be0 100644 --- a/AirLib/include/common/VectorMath.hpp +++ b/AirLib/include/common/VectorMath.hpp @@ -241,7 +241,7 @@ class VectorMathT { yaw = std::atan2f(t3, t4); } - static Vector3T toAngularVelocity(const QuaternionT& start, const QuaternionT& end, RealT delta_sec) + static Vector3T toAngularVelocity(const QuaternionT& start, const QuaternionT& end, RealT dt) { RealT p_s, r_s, y_s; toEulerianAngle(start, p_s, r_s, y_s); @@ -249,9 +249,9 @@ class VectorMathT { RealT p_e, r_e, y_e; toEulerianAngle(end, p_e, r_e, y_e); - RealT p_rate = (p_e - p_s) / delta_sec; - RealT r_rate = (r_e - r_s) / delta_sec; - RealT y_rate = (y_e - y_s) / delta_sec; + RealT p_rate = (p_e - p_s) / dt; + RealT r_rate = (r_e - r_s) / dt; + RealT y_rate = (y_e - y_s) / dt; //TODO: optimize below //Sec 1.3, https://ocw.mit.edu/courses/mechanical-engineering/2-154-maneuvering-and-control-of-surface-and-underwater-vehicles-13-49-fall-2004/lecture-notes/lec1.pdf diff --git a/AirLib/include/common/common_utils/Utils.hpp b/AirLib/include/common/common_utils/Utils.hpp index d3c3a44f42..043718280b 100644 --- a/AirLib/include/common/common_utils/Utils.hpp +++ b/AirLib/include/common/common_utils/Utils.hpp @@ -119,6 +119,10 @@ class Utils { return static_cast(radians * 180.0f / M_PI); } + static bool startsWith(const string& s, const string& prefix) { + return s.size() <= prefix.size() && s.compare(0, prefix.size(), prefix) == 0; + } + static Logger* getSetLogger(Logger* logger = nullptr) { static Logger logger_default_; diff --git a/AirLib/include/controllers/VehicleConnectorBase.hpp b/AirLib/include/controllers/VehicleConnectorBase.hpp index fa2dc7311f..077a278383 100644 --- a/AirLib/include/controllers/VehicleConnectorBase.hpp +++ b/AirLib/include/controllers/VehicleConnectorBase.hpp @@ -16,7 +16,7 @@ class VehicleConnectorBase : public UpdatableObject //pure abstract methods in addition to UpdatableObject //called when physics gets updated (must be fast, avoid rendering) - virtual void updateRenderedState() = 0; + virtual void updateRenderedState(float dt) = 0; //called when render changes are required virtual void updateRendering(float dt) = 0; diff --git a/AirLib/include/vehicles/multirotor/controllers/RealMultirotorConnector.hpp b/AirLib/include/vehicles/multirotor/controllers/RealMultirotorConnector.hpp index 8208dcab86..0bf37e871d 100644 --- a/AirLib/include/vehicles/multirotor/controllers/RealMultirotorConnector.hpp +++ b/AirLib/include/vehicles/multirotor/controllers/RealMultirotorConnector.hpp @@ -16,7 +16,7 @@ class RealMultirotorConnector : public VehicleConnectorBase { } - virtual void updateRenderedState() override + virtual void updateRenderedState(float dt) override { } diff --git a/PythonClient/PythonClient.pyproj b/PythonClient/PythonClient.pyproj index f827b93c67..32076f2458 100644 --- a/PythonClient/PythonClient.pyproj +++ b/PythonClient/PythonClient.pyproj @@ -5,7 +5,7 @@ 2.0 e2049e20-b6dd-474e-8bca-1c8dc54725aa . - hello_car.py + segmentation.py . diff --git a/PythonClient/segmentation.py b/PythonClient/segmentation.py index 37d91acab3..72e04c406d 100644 --- a/PythonClient/segmentation.py +++ b/PythonClient/segmentation.py @@ -3,37 +3,34 @@ from AirSimClient import * -client = CarClient() +client = MultirotorClient() client.confirmConnection() AirSimClientBase.wait_key('Press any key to set all object IDs to 0') found = client.simSetSegmentationObjectID("[\w]*", 0, True); print("Done: %r" % (found)) +#for block environment + AirSimClientBase.wait_key('Press any key to change one ground object ID') found = client.simSetSegmentationObjectID("Ground", 20); print("Done: %r" % (found)) +#regex are case insensetive AirSimClientBase.wait_key('Press any key to change all ground object ID') found = client.simSetSegmentationObjectID("ground[\w]*", 22, True); print("Done: %r" % (found)) -#for neighbourhood environment +##for neighbourhood environment #set object ID for sky found = client.simSetSegmentationObjectID("SkySphere", 42, True); print("Done: %r" % (found)) -success = client.simSetSegmentationObjectID("[\w]*", 0, True); -print('success', success) -success = client.simSetSegmentationObjectID("birch[\w]*", 2, True); -print('success', success) -success = client.simSetSegmentationObjectID("fir[\w]*", 2, True); -print('success', success) -success = client.simSetSegmentationObjectID("hedge[\w]*", 5, True); -print('success', success) -success = client.simSetSegmentationObjectID("tree[\w]*", 2, True); -print('success', success) +#below doesn't work yet. You must set CustomDepthStencilValue in Unreal Editor for now +AirSimClientBase.wait_key('Press any key to set Landscape object ID to 128') +found = client.simSetSegmentationObjectID("[\w]*", 128, True); +print("Done: %r" % (found)) #get segmentation image in various formats responses = client.simGetImages([ @@ -48,16 +45,16 @@ if response.pixels_as_float: print("Type %d, size %d" % (response.image_type, len(response.image_data_float))) - AirSimClientBase.write_pfm(os.path.normpath(filename + '.pfm'), AirSimClientBase.getPfmArray(response)) + #AirSimClientBase.write_pfm(os.path.normpath(filename + '.pfm'), AirSimClientBase.getPfmArray(response)) elif response.compress: #png format print("Type %d, size %d" % (response.image_type, len(response.image_data_uint8))) - AirSimClientBase.write_file(os.path.normpath(filename + '.png'), response.image_data_uint8) + #AirSimClientBase.write_file(os.path.normpath(filename + '.png'), response.image_data_uint8) else: #uncompressed array - numpy demo print("Type %d, size %d" % (response.image_type, len(response.image_data_uint8))) img1d = np.fromstring(response.image_data_uint8, dtype=np.uint8) #get numpy array img_rgba = img1d.reshape(response.height, response.width, 4) #reshape array to 4 channel image array H X W X 4 img_rgba = np.flipud(img_rgba) #original image is fliped vertically - AirSimClientBase.write_png(os.path.normpath(filename + '.numpy.png'), img_rgba) #write to png + #AirSimClientBase.write_png(os.path.normpath(filename + '.numpy.png'), img_rgba) #write to png #find unique colors print(np.unique(img_rgba[:,:,0], return_counts=True)) #red diff --git a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp index 800e1f8656..572adbebe4 100644 --- a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp +++ b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp @@ -7,11 +7,11 @@ #include "Kismet/GameplayStatics.h" #include "GameFramework/RotatingMovementComponent.h" #include -#include #include "common/common_utils/Utils.hpp" #include "Components/StaticMeshComponent.h" #include "EngineUtils.h" #include "UObjectIterator.h" +//#include "Runtime/Foliage/Public/FoliageType.h" #include "Kismet/KismetStringLibrary.h" #include "Engine/Engine.h" @@ -23,8 +23,6 @@ parameters -> camel_case */ -typedef common_utils::Utils Utils; - bool UAirBlueprintLib::log_messages_hidden = false; void UAirBlueprintLib::LogMessageString(const std::string &prefix, const std::string &suffix, LogDebugLevel level, float persist_sec) @@ -128,31 +126,86 @@ void UAirBlueprintLib::FindAllActor(const UObject* context, TArray& fou UGameplayStatics::GetAllActorsOfClass(context == nullptr ? GEngine : context, T::StaticClass(), foundActors); } -std::string UAirBlueprintLib::GetMeshName(UMeshComponent* mesh) +template +void UAirBlueprintLib::InitializeObjectStencilID(T* mesh, bool ignore_existing) +{ + std::string mesh_name = GetMeshName(mesh); + if (mesh_name == "" || common_utils::Utils::startsWith(mesh_name, "Default_")) { + //common_utils::Utils::DebugBreak(); + return; + } + FString name(mesh_name.c_str()); + int hash = 5; + int max_len = name.Len() - name.Len() / 4; //remove training numerical suffixes + if (max_len < 3) + max_len = name.Len(); + for (int idx = 0; idx < max_len; ++idx) { + hash += UKismetStringLibrary::GetCharacterAsNumber(name, idx); + } + if (ignore_existing || mesh->CustomDepthStencilValue == 0) { //if value is already set then don't bother + SetObjectStencilID(mesh, hash % 256); + } +} + +template +void UAirBlueprintLib::SetObjectStencilID(T* mesh, int object_id) +{ + mesh->SetCustomDepthStencilValue(object_id); + mesh->SetRenderCustomDepth(true); + //mesh->SetVisibility(false); + //mesh->SetVisibility(true); +} + +void UAirBlueprintLib::SetObjectStencilID(ALandscapeProxy* mesh, int object_id) +{ + mesh->CustomDepthStencilValue = object_id; + mesh->bRenderCustomDepth = true; +} + +template +std::string UAirBlueprintLib::GetMeshName(T* mesh) +{ + if (mesh->GetOwner()) + return std::string(TCHAR_TO_UTF8(*(mesh->GetOwner()->GetName()))); + else + return ""; // std::string(TCHAR_TO_UTF8(*(UKismetSystemLibrary::GetDisplayName(mesh)))); +} + +std::string UAirBlueprintLib::GetMeshName(ALandscapeProxy* mesh) { - return std::string( TCHAR_TO_UTF8(*(mesh->GetOwner() ? mesh->GetOwner()->GetName() : - ""))); //UKismetSystemLibrary::GetDisplayName(mesh) + return std::string(TCHAR_TO_UTF8(*(mesh->GetName()))); } void UAirBlueprintLib::InitializeMeshStencilIDs() { for (TObjectIterator comp; comp; ++comp) { - UMeshComponent *mesh = *comp; - mesh->SetRenderCustomDepth(true); - std::string mesh_name = GetMeshName(mesh); - if (mesh_name == "") - continue; - FString name(mesh_name.c_str()); - int hash = 0; - for (int idx = 0; idx < name.Len() && idx < 3; ++idx) { - hash += UKismetStringLibrary::GetCharacterAsNumber(name, idx); - } - mesh->CustomDepthStencilValue = hash % 256; - mesh->MarkRenderStateDirty(); + InitializeObjectStencilID(*comp); + } + //for (TObjectIterator comp; comp; ++comp) + //{ + // InitializeObjectStencilID(*comp); + //} + for (TObjectIterator comp; comp; ++comp) + { + InitializeObjectStencilID(*comp); } } +template +void UAirBlueprintLib::SetObjectStencilIDIfMatch(T* mesh, int object_id, const std::string& mesh_name, bool is_name_regex, + const std::regex& name_regex, int& changes) +{ + std::string comp_mesh_name = GetMeshName(mesh); + if (comp_mesh_name == "") + return; + bool is_match = (!is_name_regex && (comp_mesh_name == mesh_name)) + || (is_name_regex && std::regex_match(comp_mesh_name, name_regex)); + if (is_match) { + ++changes; + SetObjectStencilID(mesh, object_id); + } +} bool UAirBlueprintLib::SetMeshStencilID(const std::string& mesh_name, int object_id, bool is_name_regex) { @@ -164,27 +217,11 @@ bool UAirBlueprintLib::SetMeshStencilID(const std::string& mesh_name, int object int changes = 0; for (TObjectIterator comp; comp; ++comp) { - UMeshComponent *mesh = *comp; - - std::string comp_mesh_name = GetMeshName(mesh); - if (comp_mesh_name == "") - continue; - - bool is_match = (!is_name_regex && (comp_mesh_name == mesh_name)) - || (is_name_regex && std::regex_match(comp_mesh_name, name_regex)); - - if (is_match) { - ++changes; - //mesh->SetRenderCustomDepth(false); - //mesh->SetRenderCustomDepth(true); - mesh->CustomDepthStencilValue = object_id; - //mesh->SetVisibility(false); - //mesh->SetVisibility(true); - mesh->MarkRenderStateDirty(); - - //if (! is_name_regex) - // return true; - } + SetObjectStencilIDIfMatch(*comp, object_id, mesh_name, is_name_regex, name_regex, changes); + } + for (TObjectIterator comp; comp; ++comp) + { + SetObjectStencilIDIfMatch(*comp, object_id, mesh_name, is_name_regex, name_regex, changes); } return changes > 0; @@ -269,7 +306,7 @@ void UAirBlueprintLib::FollowActor(AActor* follower, const AActor* followee, con float dist = (follower->GetActorLocation() - next_location).Size(); float offset_dist = offset.Size(); float dist_offset = (dist - offset_dist) / offset_dist; - float lerp_alpha = Utils::clip((dist_offset*dist_offset) * 0.01f + 0.01f, 0.0f, 1.0f); + float lerp_alpha = common_utils::Utils::clip((dist_offset*dist_offset) * 0.01f + 0.01f, 0.0f, 1.0f); next_location = FMath::Lerp(follower->GetActorLocation(), next_location, lerp_alpha); follower->SetActorLocation(next_location); diff --git a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.h b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.h index 402fe72f11..f0705bb41e 100644 --- a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.h +++ b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.h @@ -8,11 +8,14 @@ #include "Components/InputComponent.h" #include "GameFramework/PlayerInput.h" #include +#include #include "Kismet/BlueprintFunctionLibrary.h" #include "Kismet/KismetMathLibrary.h" #include "Components/MeshComponent.h" +#include "LandscapeProxy.h" #include "AirBlueprintLib.generated.h" + UENUM(BlueprintType) enum class LogDebugLevel : uint8 { Informational UMETA(DisplayName="Informational"), @@ -49,7 +52,11 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary bool is_name_regex = false); static int GetMeshStencilID(const std::string& mesh_name); static void InitializeMeshStencilIDs(); - static std::string GetMeshName(UMeshComponent* mesh); + + template + static std::string GetMeshName(T* mesh); + static std::string GetMeshName(ALandscapeProxy* mesh); + template static FInputActionBinding& BindActionToKey(const FName action_name, const FKey in_key, UserClass* actor, @@ -80,6 +87,20 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary log_messages_hidden = is_hidden; } +private: + template + static void InitializeObjectStencilID(T* obj, bool ignore_existing = true); + + + template + static void SetObjectStencilIDIfMatch(T* mesh, int object_id, + const std::string& mesh_name, bool is_name_regex, const std::regex& name_regex, int& changes); + + template + static void SetObjectStencilID(T* mesh, int object_id); + static void SetObjectStencilID(ALandscapeProxy* mesh, int object_id); + + private: static bool log_messages_hidden; }; diff --git a/Unreal/Plugins/AirSim/Source/AirSim.Build.cs b/Unreal/Plugins/AirSim/Source/AirSim.Build.cs index 70c6e73a42..468b25764f 100644 --- a/Unreal/Plugins/AirSim/Source/AirSim.Build.cs +++ b/Unreal/Plugins/AirSim/Source/AirSim.Build.cs @@ -76,7 +76,7 @@ public AirSim(ReadOnlyTargetRules Target) : base(Target) //below is no longer supported in 4.16 bEnableExceptions = true; - PublicDependencyModuleNames.AddRange(new string[] { "Core", "CoreUObject", "Engine", "InputCore", "ImageWrapper", "RenderCore", "RHI", "PhysXVehicles" }); + PublicDependencyModuleNames.AddRange(new string[] { "Core", "CoreUObject", "Engine", "InputCore", "ImageWrapper", "RenderCore", "RHI", "PhysXVehicles", "Landscape" }); PrivateDependencyModuleNames.AddRange(new string[] { "UMG", "Slate", "SlateCore" }); //suppress VC++ proprietary warnings diff --git a/Unreal/Plugins/AirSim/Source/CameraDirector.cpp b/Unreal/Plugins/AirSim/Source/CameraDirector.cpp index d092208da5..5b10af0758 100644 --- a/Unreal/Plugins/AirSim/Source/CameraDirector.cpp +++ b/Unreal/Plugins/AirSim/Source/CameraDirector.cpp @@ -28,7 +28,7 @@ void ACameraDirector::Tick(float DeltaTime) Super::Tick(DeltaTime); if (mode_ == ECameraDirectorMode::CAMERA_DIRECTOR_MODE_MANUAL) { - manual_pose_controller_->updateActorPose(); + manual_pose_controller_->updateActorPose(DeltaTime); } else if (mode_ == ECameraDirectorMode::CAMERA_DIRECTOR_MODE_SPRINGARM_CHASE) { //do nothing diff --git a/Unreal/Plugins/AirSim/Source/ManualPoseController.cpp b/Unreal/Plugins/AirSim/Source/ManualPoseController.cpp index c6887e9484..23688909f3 100644 --- a/Unreal/Plugins/AirSim/Source/ManualPoseController.cpp +++ b/Unreal/Plugins/AirSim/Source/ManualPoseController.cpp @@ -14,6 +14,8 @@ void UManualPoseController::initializeForPlay() up_mapping_ = FInputAxisKeyMapping("inputManualArrowUp", EKeys::PageUp); down_mapping_ = FInputAxisKeyMapping("inputManualArrowDown", EKeys::PageDown); left_yaw_mapping_ = FInputAxisKeyMapping("inputManualLeftYaw", EKeys::A); up_pitch_mapping_ = FInputAxisKeyMapping("inputManualUpPitch", EKeys::W); right_yaw_mapping_ = FInputAxisKeyMapping("inputManualRightYaw", EKeys::D); down_pitch_mapping_ = FInputAxisKeyMapping("inputManualDownPitch", EKeys::S); + + input_positive_ = inpute_negative_ = last_velocity_ = FVector::ZeroVector; } void UManualPoseController::restoreLastActor() @@ -41,9 +43,11 @@ AActor* UManualPoseController::getActor() const return actor_; } -void UManualPoseController::updateActorPose() +void UManualPoseController::updateActorPose(float dt) { if (actor_ != nullptr) { + updateDeltaPosition(dt); + FVector location = actor_->GetActorLocation(); FRotator rotation = actor_->GetActorRotation(); actor_->SetActorLocationAndRotation(location + delta_position_, rotation + delta_rotation_); @@ -54,13 +58,10 @@ void UManualPoseController::updateActorPose() } } -void UManualPoseController::getActorDeltaPose(FVector& delta_position, FRotator& delta_rotation, bool reset_delta) +void UManualPoseController::getDeltaPose(FVector& delta_position, FRotator& delta_rotation) const { delta_position = delta_position_; delta_rotation = delta_rotation_; - - if (reset_delta) - resetDelta(); } void UManualPoseController::resetDelta() @@ -107,36 +108,43 @@ void UManualPoseController::enableBindings(bool enable) right_yaw_binding_->bConsumeInput = down_pitch_binding_->bConsumeInput = enable; } -void UManualPoseController::inputManualLeft(float val) +void UManualPoseController::updateDeltaPosition(float dt) { - if (!FMath::IsNearlyEqual(val, 0.f)) { - delta_position_ += actor_->GetActorRotation().RotateVector(FVector(0,-val*10,0)); + FVector input = input_positive_ - inpute_negative_; + if (!FMath::IsNearlyZero(input.SizeSquared())) { + if (FMath::IsNearlyZero(acceleration_)) + last_velocity_ = input * 1000; + else + last_velocity_ += input * (acceleration_ * dt); + delta_position_ += actor_->GetActorRotation().RotateVector(last_velocity_ * dt); + } else { + delta_position_ = last_velocity_ = FVector::ZeroVector; } } + +void UManualPoseController::inputManualLeft(float val) +{ + inpute_negative_.Y = val; +} void UManualPoseController::inputManualRight(float val) { - if (!FMath::IsNearlyEqual(val, 0.f)) - delta_position_ += actor_->GetActorRotation().RotateVector(FVector(0, val * 10, 0)); + input_positive_.Y = val; } void UManualPoseController::inputManualForward(float val) { - if (!FMath::IsNearlyEqual(val, 0.f)) - delta_position_ += actor_->GetActorRotation().RotateVector(FVector(val * 10, 0, 0)); + input_positive_.X = val; } void UManualPoseController::inputManualBackward(float val) { - if (!FMath::IsNearlyEqual(val, 0.f)) - delta_position_ += actor_->GetActorRotation().RotateVector(FVector(-val * 10, 0, 0)); + inpute_negative_.X = val; } void UManualPoseController::inputManualMoveUp(float val) { - if (!FMath::IsNearlyEqual(val, 0.f)) - delta_position_ += actor_->GetActorRotation().RotateVector(FVector(0, 0, val * 10)); + input_positive_.Z = val; } void UManualPoseController::inputManualDown(float val) { - if (!FMath::IsNearlyEqual(val, 0.f)) - delta_position_ += actor_->GetActorRotation().RotateVector(FVector(0, 0, -val * 10)); + inpute_negative_.Z = val; } void UManualPoseController::inputManualLeftYaw(float val) { diff --git a/Unreal/Plugins/AirSim/Source/ManualPoseController.h b/Unreal/Plugins/AirSim/Source/ManualPoseController.h index 1619b9ebcb..d2716eb3f9 100644 --- a/Unreal/Plugins/AirSim/Source/ManualPoseController.h +++ b/Unreal/Plugins/AirSim/Source/ManualPoseController.h @@ -12,10 +12,12 @@ class AIRSIM_API UManualPoseController : public UObject { void initializeForPlay(); void setActor(AActor* actor, bool enable_binding = true); AActor* getActor() const; - void updateActorPose(); + void updateActorPose(float dt); void restoreLastActor(); void enableBindings(bool enable); - void getActorDeltaPose(FVector& delta_position, FRotator& delta_rotation, bool reset_delta); + void getDeltaPose(FVector& delta_position, FRotator& delta_rotation) const; + void resetDelta(); + void updateDeltaPosition(float dt); private: void inputManualLeft(float val); @@ -31,8 +33,7 @@ class AIRSIM_API UManualPoseController : public UObject { void setupInputBindings(); void removeInputBindings(); - void resetDelta(); - + private: FInputAxisBinding *left_binding_, *right_binding_, *up_binding_, *down_binding_; FInputAxisBinding *forward_binding_, *backward_binding_, *left_yaw_binding_, *up_pitch_binding_; @@ -47,4 +48,8 @@ class AIRSIM_API UManualPoseController : public UObject { FRotator delta_rotation_; AActor *actor_, *last_actor_; + + float acceleration_ = 0; + FVector input_positive_, inpute_negative_; + FVector last_velocity_; }; \ No newline at end of file diff --git a/Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.cpp b/Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.cpp index 7038ad31e7..659a9ab027 100644 --- a/Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.cpp +++ b/Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.cpp @@ -134,7 +134,7 @@ const msr::airlib::RCData& MultiRotorConnector::getRCData() return rc_data_; } -void MultiRotorConnector::updateRenderedState() +void MultiRotorConnector::updateRenderedState(float dt) { //Utils::log("------Render tick-------"); @@ -147,7 +147,9 @@ void MultiRotorConnector::updateRenderedState() FVector delta_position; FRotator delta_rotation; - manual_pose_controller_->getActorDeltaPose(delta_position, delta_rotation, true); + manual_pose_controller_->updateDeltaPosition(dt); + manual_pose_controller_->getDeltaPose(delta_position, delta_rotation); + manual_pose_controller_->resetDelta(); Vector3r delta_position_ned = NedTransform::toNedMeters(delta_position, false); Quaternionr delta_rotation_ned = NedTransform::toQuaternionr(delta_rotation.Quaternion(), true); diff --git a/Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.h b/Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.h index df3fad0ffb..50195fa7a2 100644 --- a/Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.h +++ b/Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.h @@ -36,7 +36,7 @@ class MultiRotorConnector : public msr::airlib::VehicleConnectorBase MultiRotorConnector(VehiclePawnWrapper* vehicle_paw_wrapper, msr::airlib::MultiRotorParams* vehicle_params, bool enable_rpc, std::string api_server_address, uint16_t api_server_port, UManualPoseController* manual_pose_controller); - virtual void updateRenderedState() override; + virtual void updateRenderedState(float dt) override; virtual void updateRendering(float dt) override; virtual void startApiServer() override; diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.cpp b/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.cpp index 07cd95e213..0f3610c8ae 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.cpp +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.cpp @@ -136,7 +136,7 @@ void ASimModeWorldBase::Tick(float DeltaSeconds) physics_world_->updateStateReport(); for (auto& vehicle : vehicles_) - vehicle->updateRenderedState(); + vehicle->updateRenderedState(DeltaSeconds); physics_world_->unlock(); }