Skip to content

Commit 1dd5956

Browse files
committed
Merge branch 'landscape_bug'
2 parents 2a30997 + 3c219bd commit 1dd5956

File tree

15 files changed

+165
-91
lines changed

15 files changed

+165
-91
lines changed

AirLib/include/common/VectorMath.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -241,17 +241,17 @@ class VectorMathT {
241241
yaw = std::atan2f(t3, t4);
242242
}
243243

244-
static Vector3T toAngularVelocity(const QuaternionT& start, const QuaternionT& end, RealT delta_sec)
244+
static Vector3T toAngularVelocity(const QuaternionT& start, const QuaternionT& end, RealT dt)
245245
{
246246
RealT p_s, r_s, y_s;
247247
toEulerianAngle(start, p_s, r_s, y_s);
248248

249249
RealT p_e, r_e, y_e;
250250
toEulerianAngle(end, p_e, r_e, y_e);
251251

252-
RealT p_rate = (p_e - p_s) / delta_sec;
253-
RealT r_rate = (r_e - r_s) / delta_sec;
254-
RealT y_rate = (y_e - y_s) / delta_sec;
252+
RealT p_rate = (p_e - p_s) / dt;
253+
RealT r_rate = (r_e - r_s) / dt;
254+
RealT y_rate = (y_e - y_s) / dt;
255255

256256
//TODO: optimize below
257257
//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

AirLib/include/common/common_utils/Utils.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -119,6 +119,10 @@ class Utils {
119119
return static_cast<float>(radians * 180.0f / M_PI);
120120
}
121121

122+
static bool startsWith(const string& s, const string& prefix) {
123+
return s.size() <= prefix.size() && s.compare(0, prefix.size(), prefix) == 0;
124+
}
125+
122126
static Logger* getSetLogger(Logger* logger = nullptr)
123127
{
124128
static Logger logger_default_;

AirLib/include/controllers/VehicleConnectorBase.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ class VehicleConnectorBase : public UpdatableObject
1616
//pure abstract methods in addition to UpdatableObject
1717

1818
//called when physics gets updated (must be fast, avoid rendering)
19-
virtual void updateRenderedState() = 0;
19+
virtual void updateRenderedState(float dt) = 0;
2020
//called when render changes are required
2121
virtual void updateRendering(float dt) = 0;
2222

AirLib/include/vehicles/multirotor/controllers/RealMultirotorConnector.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ class RealMultirotorConnector : public VehicleConnectorBase
1616
{
1717
}
1818

19-
virtual void updateRenderedState() override
19+
virtual void updateRenderedState(float dt) override
2020
{
2121
}
2222

PythonClient/PythonClient.pyproj

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
<SchemaVersion>2.0</SchemaVersion>
66
<ProjectGuid>e2049e20-b6dd-474e-8bca-1c8dc54725aa</ProjectGuid>
77
<ProjectHome>.</ProjectHome>
8-
<StartupFile>hello_car.py</StartupFile>
8+
<StartupFile>segmentation.py</StartupFile>
99
<SearchPath>
1010
</SearchPath>
1111
<WorkingDirectory>.</WorkingDirectory>

PythonClient/segmentation.py

Lines changed: 12 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -3,37 +3,34 @@
33

44
from AirSimClient import *
55

6-
client = CarClient()
6+
client = MultirotorClient()
77
client.confirmConnection()
88

99
AirSimClientBase.wait_key('Press any key to set all object IDs to 0')
1010
found = client.simSetSegmentationObjectID("[\w]*", 0, True);
1111
print("Done: %r" % (found))
1212

13+
#for block environment
14+
1315
AirSimClientBase.wait_key('Press any key to change one ground object ID')
1416
found = client.simSetSegmentationObjectID("Ground", 20);
1517
print("Done: %r" % (found))
1618

19+
#regex are case insensetive
1720
AirSimClientBase.wait_key('Press any key to change all ground object ID')
1821
found = client.simSetSegmentationObjectID("ground[\w]*", 22, True);
1922
print("Done: %r" % (found))
2023

21-
#for neighbourhood environment
24+
##for neighbourhood environment
2225

2326
#set object ID for sky
2427
found = client.simSetSegmentationObjectID("SkySphere", 42, True);
2528
print("Done: %r" % (found))
2629

27-
success = client.simSetSegmentationObjectID("[\w]*", 0, True);
28-
print('success', success)
29-
success = client.simSetSegmentationObjectID("birch[\w]*", 2, True);
30-
print('success', success)
31-
success = client.simSetSegmentationObjectID("fir[\w]*", 2, True);
32-
print('success', success)
33-
success = client.simSetSegmentationObjectID("hedge[\w]*", 5, True);
34-
print('success', success)
35-
success = client.simSetSegmentationObjectID("tree[\w]*", 2, True);
36-
print('success', success)
30+
#below doesn't work yet. You must set CustomDepthStencilValue in Unreal Editor for now
31+
AirSimClientBase.wait_key('Press any key to set Landscape object ID to 128')
32+
found = client.simSetSegmentationObjectID("[\w]*", 128, True);
33+
print("Done: %r" % (found))
3734

3835
#get segmentation image in various formats
3936
responses = client.simGetImages([
@@ -48,16 +45,16 @@
4845

4946
if response.pixels_as_float:
5047
print("Type %d, size %d" % (response.image_type, len(response.image_data_float)))
51-
AirSimClientBase.write_pfm(os.path.normpath(filename + '.pfm'), AirSimClientBase.getPfmArray(response))
48+
#AirSimClientBase.write_pfm(os.path.normpath(filename + '.pfm'), AirSimClientBase.getPfmArray(response))
5249
elif response.compress: #png format
5350
print("Type %d, size %d" % (response.image_type, len(response.image_data_uint8)))
54-
AirSimClientBase.write_file(os.path.normpath(filename + '.png'), response.image_data_uint8)
51+
#AirSimClientBase.write_file(os.path.normpath(filename + '.png'), response.image_data_uint8)
5552
else: #uncompressed array - numpy demo
5653
print("Type %d, size %d" % (response.image_type, len(response.image_data_uint8)))
5754
img1d = np.fromstring(response.image_data_uint8, dtype=np.uint8) #get numpy array
5855
img_rgba = img1d.reshape(response.height, response.width, 4) #reshape array to 4 channel image array H X W X 4
5956
img_rgba = np.flipud(img_rgba) #original image is fliped vertically
60-
AirSimClientBase.write_png(os.path.normpath(filename + '.numpy.png'), img_rgba) #write to png
57+
#AirSimClientBase.write_png(os.path.normpath(filename + '.numpy.png'), img_rgba) #write to png
6158

6259
#find unique colors
6360
print(np.unique(img_rgba[:,:,0], return_counts=True)) #red

Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp

Lines changed: 77 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -7,11 +7,11 @@
77
#include "Kismet/GameplayStatics.h"
88
#include "GameFramework/RotatingMovementComponent.h"
99
#include <exception>
10-
#include <regex>
1110
#include "common/common_utils/Utils.hpp"
1211
#include "Components/StaticMeshComponent.h"
1312
#include "EngineUtils.h"
1413
#include "UObjectIterator.h"
14+
//#include "Runtime/Foliage/Public/FoliageType.h"
1515
#include "Kismet/KismetStringLibrary.h"
1616
#include "Engine/Engine.h"
1717

@@ -23,8 +23,6 @@ parameters -> camel_case
2323
*/
2424

2525

26-
typedef common_utils::Utils Utils;
27-
2826
bool UAirBlueprintLib::log_messages_hidden = false;
2927

3028
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<AActor*>& fou
128126
UGameplayStatics::GetAllActorsOfClass(context == nullptr ? GEngine : context, T::StaticClass(), foundActors);
129127
}
130128

131-
std::string UAirBlueprintLib::GetMeshName(UMeshComponent* mesh)
129+
template<typename T>
130+
void UAirBlueprintLib::InitializeObjectStencilID(T* mesh, bool ignore_existing)
131+
{
132+
std::string mesh_name = GetMeshName(mesh);
133+
if (mesh_name == "" || common_utils::Utils::startsWith(mesh_name, "Default_")) {
134+
//common_utils::Utils::DebugBreak();
135+
return;
136+
}
137+
FString name(mesh_name.c_str());
138+
int hash = 5;
139+
int max_len = name.Len() - name.Len() / 4; //remove training numerical suffixes
140+
if (max_len < 3)
141+
max_len = name.Len();
142+
for (int idx = 0; idx < max_len; ++idx) {
143+
hash += UKismetStringLibrary::GetCharacterAsNumber(name, idx);
144+
}
145+
if (ignore_existing || mesh->CustomDepthStencilValue == 0) { //if value is already set then don't bother
146+
SetObjectStencilID(mesh, hash % 256);
147+
}
148+
}
149+
150+
template<typename T>
151+
void UAirBlueprintLib::SetObjectStencilID(T* mesh, int object_id)
152+
{
153+
mesh->SetCustomDepthStencilValue(object_id);
154+
mesh->SetRenderCustomDepth(true);
155+
//mesh->SetVisibility(false);
156+
//mesh->SetVisibility(true);
157+
}
158+
159+
void UAirBlueprintLib::SetObjectStencilID(ALandscapeProxy* mesh, int object_id)
160+
{
161+
mesh->CustomDepthStencilValue = object_id;
162+
mesh->bRenderCustomDepth = true;
163+
}
164+
165+
template<class T>
166+
std::string UAirBlueprintLib::GetMeshName(T* mesh)
167+
{
168+
if (mesh->GetOwner())
169+
return std::string(TCHAR_TO_UTF8(*(mesh->GetOwner()->GetName())));
170+
else
171+
return ""; // std::string(TCHAR_TO_UTF8(*(UKismetSystemLibrary::GetDisplayName(mesh))));
172+
}
173+
174+
std::string UAirBlueprintLib::GetMeshName(ALandscapeProxy* mesh)
132175
{
133-
return std::string( TCHAR_TO_UTF8(*(mesh->GetOwner() ? mesh->GetOwner()->GetName() :
134-
""))); //UKismetSystemLibrary::GetDisplayName(mesh)
176+
return std::string(TCHAR_TO_UTF8(*(mesh->GetName())));
135177
}
136178

137179
void UAirBlueprintLib::InitializeMeshStencilIDs()
138180
{
139181
for (TObjectIterator<UMeshComponent> comp; comp; ++comp)
140182
{
141-
UMeshComponent *mesh = *comp;
142-
mesh->SetRenderCustomDepth(true);
143-
std::string mesh_name = GetMeshName(mesh);
144-
if (mesh_name == "")
145-
continue;
146-
FString name(mesh_name.c_str());
147-
int hash = 0;
148-
for (int idx = 0; idx < name.Len() && idx < 3; ++idx) {
149-
hash += UKismetStringLibrary::GetCharacterAsNumber(name, idx);
150-
}
151-
mesh->CustomDepthStencilValue = hash % 256;
152-
mesh->MarkRenderStateDirty();
183+
InitializeObjectStencilID(*comp);
184+
}
185+
//for (TObjectIterator<UFoliageType> comp; comp; ++comp)
186+
//{
187+
// InitializeObjectStencilID(*comp);
188+
//}
189+
for (TObjectIterator<ALandscapeProxy> comp; comp; ++comp)
190+
{
191+
InitializeObjectStencilID(*comp);
153192
}
154193
}
155194

195+
template<typename T>
196+
void UAirBlueprintLib::SetObjectStencilIDIfMatch(T* mesh, int object_id, const std::string& mesh_name, bool is_name_regex,
197+
const std::regex& name_regex, int& changes)
198+
{
199+
std::string comp_mesh_name = GetMeshName(mesh);
200+
if (comp_mesh_name == "")
201+
return;
202+
bool is_match = (!is_name_regex && (comp_mesh_name == mesh_name))
203+
|| (is_name_regex && std::regex_match(comp_mesh_name, name_regex));
204+
if (is_match) {
205+
++changes;
206+
SetObjectStencilID(mesh, object_id);
207+
}
208+
}
156209
bool UAirBlueprintLib::SetMeshStencilID(const std::string& mesh_name, int object_id,
157210
bool is_name_regex)
158211
{
@@ -164,27 +217,11 @@ bool UAirBlueprintLib::SetMeshStencilID(const std::string& mesh_name, int object
164217
int changes = 0;
165218
for (TObjectIterator<UMeshComponent> comp; comp; ++comp)
166219
{
167-
UMeshComponent *mesh = *comp;
168-
169-
std::string comp_mesh_name = GetMeshName(mesh);
170-
if (comp_mesh_name == "")
171-
continue;
172-
173-
bool is_match = (!is_name_regex && (comp_mesh_name == mesh_name))
174-
|| (is_name_regex && std::regex_match(comp_mesh_name, name_regex));
175-
176-
if (is_match) {
177-
++changes;
178-
//mesh->SetRenderCustomDepth(false);
179-
//mesh->SetRenderCustomDepth(true);
180-
mesh->CustomDepthStencilValue = object_id;
181-
//mesh->SetVisibility(false);
182-
//mesh->SetVisibility(true);
183-
mesh->MarkRenderStateDirty();
184-
185-
//if (! is_name_regex)
186-
// return true;
187-
}
220+
SetObjectStencilIDIfMatch(*comp, object_id, mesh_name, is_name_regex, name_regex, changes);
221+
}
222+
for (TObjectIterator<ALandscapeProxy> comp; comp; ++comp)
223+
{
224+
SetObjectStencilIDIfMatch(*comp, object_id, mesh_name, is_name_regex, name_regex, changes);
188225
}
189226

190227
return changes > 0;
@@ -269,7 +306,7 @@ void UAirBlueprintLib::FollowActor(AActor* follower, const AActor* followee, con
269306
float dist = (follower->GetActorLocation() - next_location).Size();
270307
float offset_dist = offset.Size();
271308
float dist_offset = (dist - offset_dist) / offset_dist;
272-
float lerp_alpha = Utils::clip((dist_offset*dist_offset) * 0.01f + 0.01f, 0.0f, 1.0f);
309+
float lerp_alpha = common_utils::Utils::clip((dist_offset*dist_offset) * 0.01f + 0.01f, 0.0f, 1.0f);
273310
next_location = FMath::Lerp(follower->GetActorLocation(), next_location, lerp_alpha);
274311
follower->SetActorLocation(next_location);
275312

Unreal/Plugins/AirSim/Source/AirBlueprintLib.h

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,11 +8,14 @@
88
#include "Components/InputComponent.h"
99
#include "GameFramework/PlayerInput.h"
1010
#include <string>
11+
#include <regex>
1112
#include "Kismet/BlueprintFunctionLibrary.h"
1213
#include "Kismet/KismetMathLibrary.h"
1314
#include "Components/MeshComponent.h"
15+
#include "LandscapeProxy.h"
1416
#include "AirBlueprintLib.generated.h"
1517

18+
1619
UENUM(BlueprintType)
1720
enum class LogDebugLevel : uint8 {
1821
Informational UMETA(DisplayName="Informational"),
@@ -49,7 +52,11 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary
4952
bool is_name_regex = false);
5053
static int GetMeshStencilID(const std::string& mesh_name);
5154
static void InitializeMeshStencilIDs();
52-
static std::string GetMeshName(UMeshComponent* mesh);
55+
56+
template<class T>
57+
static std::string GetMeshName(T* mesh);
58+
static std::string GetMeshName(ALandscapeProxy* mesh);
59+
5360

5461
template<class UserClass>
5562
static FInputActionBinding& BindActionToKey(const FName action_name, const FKey in_key, UserClass* actor,
@@ -80,6 +87,20 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary
8087
log_messages_hidden = is_hidden;
8188
}
8289

90+
private:
91+
template<typename T>
92+
static void InitializeObjectStencilID(T* obj, bool ignore_existing = true);
93+
94+
95+
template<typename T>
96+
static void SetObjectStencilIDIfMatch(T* mesh, int object_id,
97+
const std::string& mesh_name, bool is_name_regex, const std::regex& name_regex, int& changes);
98+
99+
template<typename T>
100+
static void SetObjectStencilID(T* mesh, int object_id);
101+
static void SetObjectStencilID(ALandscapeProxy* mesh, int object_id);
102+
103+
83104
private:
84105
static bool log_messages_hidden;
85106
};

Unreal/Plugins/AirSim/Source/AirSim.Build.cs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ public AirSim(ReadOnlyTargetRules Target) : base(Target)
7676
//below is no longer supported in 4.16
7777
bEnableExceptions = true;
7878

79-
PublicDependencyModuleNames.AddRange(new string[] { "Core", "CoreUObject", "Engine", "InputCore", "ImageWrapper", "RenderCore", "RHI", "PhysXVehicles" });
79+
PublicDependencyModuleNames.AddRange(new string[] { "Core", "CoreUObject", "Engine", "InputCore", "ImageWrapper", "RenderCore", "RHI", "PhysXVehicles", "Landscape" });
8080
PrivateDependencyModuleNames.AddRange(new string[] { "UMG", "Slate", "SlateCore" });
8181

8282
//suppress VC++ proprietary warnings

Unreal/Plugins/AirSim/Source/CameraDirector.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ void ACameraDirector::Tick(float DeltaTime)
2828
Super::Tick(DeltaTime);
2929

3030
if (mode_ == ECameraDirectorMode::CAMERA_DIRECTOR_MODE_MANUAL) {
31-
manual_pose_controller_->updateActorPose();
31+
manual_pose_controller_->updateActorPose(DeltaTime);
3232
}
3333
else if (mode_ == ECameraDirectorMode::CAMERA_DIRECTOR_MODE_SPRINGARM_CHASE) {
3434
//do nothing

0 commit comments

Comments
 (0)