Skip to content

Commit e692a6f

Browse files
authored
Merge pull request #3991 from saihv/PR/LightAPI
Ability to spawn/destroy lights and control light parameters
2 parents 1ba33b7 + fd322e3 commit e692a6f

File tree

11 files changed

+135
-46
lines changed

11 files changed

+135
-46
lines changed

AirLib/include/api/WorldSimApiBase.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,8 @@ namespace airlib
3232

3333
// ------ Level setting apis ----- //
3434
virtual bool loadLevel(const std::string& level_name) = 0;
35-
virtual string spawnObject(string& object_name, const string& load_component, const Pose& pose, const Vector3r& scale, bool physics_enabled) = 0;
36-
virtual bool destroyObject(const string& object_name) = 0;
35+
virtual string spawnObject(const std::string& object_name, const std::string& load_component, const Pose& pose, const Vector3r& scale, bool physics_enabled, bool is_blueprint) = 0;
36+
virtual bool destroyObject(const std::string& object_name) = 0;
3737

3838
virtual bool isPaused() const = 0;
3939
virtual void reset() = 0;
@@ -72,6 +72,7 @@ namespace airlib
7272
virtual bool runConsoleCommand(const std::string& command) = 0;
7373
virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) = 0;
7474
virtual std::unique_ptr<std::vector<std::string>> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) = 0;
75+
virtual bool setLightIntensity(const std::string& light_name, float intensity) = 0;
7576
virtual bool setObjectMaterial(const std::string& object_name, const std::string& material_name) = 0;
7677
virtual bool setObjectMaterialFromTexture(const std::string& object_name, const std::string& texture_path) = 0;
7778
virtual vector<MeshPositionVertexBuffersResponse> getMeshPositionVertexBuffers() const = 0;

AirLib/src/api/RpcLibServerBase.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -302,8 +302,8 @@ namespace airlib
302302
return getWorldSimApi()->loadLevel(level_name);
303303
});
304304

305-
pimpl_->server.bind("simSpawnObject", [&](string& object_name, const string& load_component, const RpcLibAdaptorsBase::Pose& pose, const RpcLibAdaptorsBase::Vector3r& scale, bool physics_enabled) -> string {
306-
return getWorldSimApi()->spawnObject(object_name, load_component, pose.to(), scale.to(), physics_enabled);
305+
pimpl_->server.bind("simSpawnObject", [&](string& object_name, const string& load_component, const RpcLibAdaptorsBase::Pose& pose, const RpcLibAdaptorsBase::Vector3r& scale, bool physics_enabled, bool is_blueprint) -> string {
306+
return getWorldSimApi()->spawnObject(object_name, load_component, pose.to(), scale.to(), physics_enabled, is_blueprint);
307307
});
308308

309309
pimpl_->server.bind("simDestroyObject", [&](const string& object_name) -> bool {
@@ -389,10 +389,15 @@ namespace airlib
389389
const Environment::State& result = (*getVehicleSimApi(vehicle_name)->getGroundTruthEnvironment()).getState();
390390
return RpcLibAdaptorsBase::EnvironmentState(result);
391391
});
392+
392393
pimpl_->server.bind("simCreateVoxelGrid", [&](const RpcLibAdaptorsBase::Vector3r& position, const int& x, const int& y, const int& z, const float& res, const std::string& output_file) -> bool {
393394
return getWorldSimApi()->createVoxelGrid(position.to(), x, y, z, res, output_file);
394395
});
395396

397+
pimpl_->server.bind("simSetLightIntensity", [&](const std::string& light_name, float intensity) -> bool {
398+
return getWorldSimApi()->setLightIntensity(light_name, intensity);
399+
});
400+
396401
pimpl_->server.bind("cancelLastTask", [&](const std::string& vehicle_name) -> void {
397402
getVehicleApi(vehicle_name)->cancelLastTask();
398403
});

PythonClient/airsim/client.py

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -158,6 +158,19 @@ def confirmConnection(self):
158158
print(ver_info)
159159
print('')
160160

161+
def simSetLightIntensity(self, light_name, intensity):
162+
"""
163+
Change intensity of named light
164+
165+
Args:
166+
light_name (str): Name of light to change
167+
intensity (float): New intensity value
168+
169+
Returns:
170+
bool: True if successful, otherwise False
171+
"""
172+
return self.client.call("simSetLightIntensity", light_name, intensity)
173+
161174
def simSwapTextures(self, tags, tex_id = 0, component_id = 0, material_id = 0):
162175
"""
163176
Runtime Swap Texture API
@@ -483,19 +496,21 @@ def simLoadLevel(self, level_name):
483496
"""
484497
return self.client.call('simLoadLevel', level_name)
485498

486-
def simSpawnObject(self, object_name, asset_name, pose, scale, physics_enabled=False):
499+
def simSpawnObject(self, object_name, asset_name, pose, scale, physics_enabled=False, is_blueprint=False):
487500
"""Spawned selected object in the world
488501
489502
Args:
490503
object_name (str): Desired name of new object
491504
asset_name (str): Name of asset(mesh) in the project database
492505
pose (airsim.Pose): Desired pose of object
493506
scale (airsim.Vector3r): Desired scale of object
507+
physics_enabled (bool, optional): Whether to enable physics for the object
508+
is_blueprint (bool, optional): Whether to spawn a blueprint or an actor
494509
495510
Returns:
496511
str: Name of spawned object, in case it had to be modified
497512
"""
498-
return self.client.call('simSpawnObject', object_name, asset_name, pose, scale, physics_enabled)
513+
return self.client.call('simSpawnObject', object_name, asset_name, pose, scale, physics_enabled, is_blueprint)
499514

500515
def simDestroyObject(self, object_name):
501516
"""Removes selected object from the world
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
import airsim
2+
import time
3+
4+
client = airsim.VehicleClient()
5+
client.confirmConnection()
6+
7+
# Access an existing light in the world
8+
lights = client.simListSceneObjects("PointLight.*")
9+
pose = client.simGetObjectPose(lights[0])
10+
scale = airsim.Vector3r(1, 1, 1)
11+
12+
# Destroy the light
13+
client.simDestroyObject(lights[0])
14+
time.sleep(1)
15+
16+
# Create a new light at the same pose
17+
new_light_name = client.simSpawnObject("PointLight", "PointLightBP", pose, scale, False, True)
18+
time.sleep(1)
19+
20+
# Change the light's intensity
21+
for i in range(20):
22+
client.simSetLightIntensity(new_light_name, i * 100)
23+
time.sleep(0.5)

Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,14 @@ void WorldSimApi::printLogMessage(const std::string& message, const std::string&
5858
PrintLogMessage(message.c_str(), message_param.c_str(), "", severity);
5959
}
6060

61+
bool WorldSimApi::setLightIntensity(const std::string& light_name, float intensity)
62+
{
63+
throw std::invalid_argument(common_utils::Utils::stringf(
64+
"setLightIntensity is not supported on unity")
65+
.c_str());
66+
return false;
67+
}
68+
6169
std::unique_ptr<std::vector<std::string>> WorldSimApi::swapTextures(const std::string& tag, int tex_id, int component_id, int material_id)
6270
{
6371
std::unique_ptr<std::vector<std::string>> result;

Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase
1818

1919
// ------ Level setting apis ----- //
2020
virtual bool loadLevel(const std::string& level_name) override { return false; };
21-
virtual std::string spawnObject(std::string& object_name, const std::string& load_component, const Pose& pose, const Vector3r& scale, bool physics_enabled) override { return ""; };
21+
virtual std::string spawnObject(const std::string& object_name, const std::string& load_component, const Pose& pose, const Vector3r& scale, bool physics_enabled, bool is_blueprint) override { return ""; };
2222
virtual bool destroyObject(const std::string& object_name) override { return false; };
2323

2424
virtual bool isPaused() const override;
@@ -37,6 +37,7 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase
3737
virtual void printLogMessage(const std::string& message,
3838
const std::string& message_param = "", unsigned char severity = 0) override;
3939

40+
virtual bool setLightIntensity(const std::string& light_name, float intensity) override;
4041
virtual std::unique_ptr<std::vector<std::string>> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) override;
4142
virtual bool setObjectMaterial(const std::string& object_name, const std::string& material_name) override;
4243
virtual bool setObjectMaterialFromTexture(const std::string& object_name, const std::string& texture_path) override;
Binary file not shown.
Binary file not shown.

Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -237,6 +237,7 @@ void UAirBlueprintLib::GenerateAssetRegistryMap(const UObject* context, TMap<FSt
237237
UAirBlueprintLib::RunCommandOnGameThread([context, &asset_map]() {
238238
FARFilter Filter;
239239
Filter.ClassNames.Add(UStaticMesh::StaticClass()->GetFName());
240+
Filter.ClassNames.Add(UBlueprint::StaticClass()->GetFName());
240241
Filter.bRecursivePaths = true;
241242

242243
auto world = context->GetWorld();

Unreal/Plugins/AirSim/Source/WorldSimApi.cpp

Lines changed: 70 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -7,9 +7,11 @@
77
#include "DrawDebugHelpers.h"
88
#include "Runtime/Engine/Classes/Components/LineBatchComponent.h"
99
#include "Runtime/Engine/Classes/Engine/Engine.h"
10+
#include "Misc/OutputDeviceNull.h"
1011
#include "ImageUtils.h"
1112
#include <cstdlib>
1213
#include <ctime>
14+
#include <algorithm>
1315

1416
WorldSimApi::WorldSimApi(ASimModeBase* simmode)
1517
: simmode_(simmode) {}
@@ -83,65 +85,69 @@ bool WorldSimApi::destroyObject(const std::string& object_name)
8385
return result;
8486
}
8587

86-
std::string WorldSimApi::spawnObject(std::string& object_name, const std::string& load_object, const WorldSimApi::Pose& pose, const WorldSimApi::Vector3r& scale, bool physics_enabled)
88+
std::string WorldSimApi::spawnObject(const std::string& object_name, const std::string& load_object, const WorldSimApi::Pose& pose, const WorldSimApi::Vector3r& scale, bool physics_enabled, bool is_blueprint)
8789
{
90+
FString asset_name(load_object.c_str());
91+
FAssetData* load_asset = simmode_->asset_map.Find(asset_name);
92+
93+
if (!load_asset->IsValid()) {
94+
throw std::invalid_argument("There were no objects with name " + load_object + " found in the Registry");
95+
}
96+
8897
// Create struct for Location and Rotation of actor in Unreal
8998
FTransform actor_transform = simmode_->getGlobalNedTransform().fromGlobalNed(pose);
9099

91-
bool found_object = false, spawned_object = false;
92-
UAirBlueprintLib::RunCommandOnGameThread([this, load_object, &object_name, &actor_transform, &found_object, &spawned_object, &scale, &physics_enabled]() {
93-
FString asset_name = FString(load_object.c_str());
94-
FAssetData* LoadAsset = simmode_->asset_map.Find(asset_name);
95-
96-
if (LoadAsset) {
97-
found_object = true;
98-
UStaticMesh* LoadObject = dynamic_cast<UStaticMesh*>(LoadAsset->GetAsset());
99-
std::vector<std::string> matching_names = UAirBlueprintLib::ListMatchingActors(simmode_->GetWorld(), ".*" + object_name + ".*");
100-
if (matching_names.size() > 0) {
101-
size_t greatest_num{ 0 }, result{ 0 };
102-
for (auto match : matching_names) {
103-
std::string number_extension = match.substr(match.find_last_not_of("0123456789") + 1);
104-
if (number_extension != "") {
105-
result = std::stoi(number_extension);
106-
greatest_num = greatest_num > result ? greatest_num : result;
107-
}
100+
bool spawned_object = false;
101+
std::string final_object_name = object_name;
102+
103+
UAirBlueprintLib::RunCommandOnGameThread([this, load_asset, &final_object_name, &spawned_object, &actor_transform, &scale, &physics_enabled, &is_blueprint]() {
104+
// Ensure new non-matching name for the object
105+
std::vector<std::string> matching_names = UAirBlueprintLib::ListMatchingActors(simmode_, ".*" + final_object_name + ".*");
106+
if (matching_names.size() > 0) {
107+
int greatest_num{ 0 };
108+
for (const auto& match : matching_names) {
109+
std::string number_extension = match.substr(match.find_last_not_of("0123456789") + 1);
110+
if (number_extension != "") {
111+
greatest_num = std::max(greatest_num, std::stoi(number_extension));
108112
}
109-
object_name += std::to_string(greatest_num + 1);
110-
}
111-
FActorSpawnParameters new_actor_spawn_params;
112-
new_actor_spawn_params.Name = FName(object_name.c_str());
113-
//new_actor_spawn_params.NameMode = FActorSpawnParameters::ESpawnActorNameMode::Required_ReturnNull;
114-
AActor* NewActor = this->createNewActor(new_actor_spawn_params, actor_transform, scale, LoadObject);
115-
116-
if (NewActor) {
117-
spawned_object = true;
118-
simmode_->scene_object_map.Add(FString(object_name.c_str()), NewActor);
119113
}
114+
final_object_name += std::to_string(greatest_num + 1);
115+
}
116+
117+
FActorSpawnParameters new_actor_spawn_params;
118+
new_actor_spawn_params.Name = FName(final_object_name.c_str());
120119

121-
UAirBlueprintLib::setSimulatePhysics(NewActor, physics_enabled);
120+
AActor* NewActor;
121+
if (is_blueprint) {
122+
UBlueprint* LoadObject = Cast<UBlueprint>(load_asset->GetAsset());
123+
NewActor = this->createNewBPActor(new_actor_spawn_params, actor_transform, scale, LoadObject);
122124
}
123125
else {
124-
found_object = false;
126+
UStaticMesh* LoadObject = dynamic_cast<UStaticMesh*>(load_asset->GetAsset());
127+
NewActor = this->createNewStaticMeshActor(new_actor_spawn_params, actor_transform, scale, LoadObject);
125128
}
129+
130+
if (IsValid(NewActor)) {
131+
spawned_object = true;
132+
simmode_->scene_object_map.Add(FString(final_object_name.c_str()), NewActor);
133+
}
134+
135+
UAirBlueprintLib::setSimulatePhysics(NewActor, physics_enabled);
126136
},
127137
true);
128138

129-
if (!found_object) {
130-
throw std::invalid_argument(
131-
"There were no objects with name " + load_object + " found in the Registry");
132-
}
133139
if (!spawned_object) {
134140
throw std::invalid_argument(
135141
"Engine could not spawn " + load_object + " because of a stale reference of same name");
136142
}
137-
return object_name;
143+
return final_object_name;
138144
}
139145

140-
AActor* WorldSimApi::createNewActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UStaticMesh* static_mesh)
146+
AActor* WorldSimApi::createNewStaticMeshActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UStaticMesh* static_mesh)
141147
{
142148
AActor* NewActor = simmode_->GetWorld()->SpawnActor<AActor>(AActor::StaticClass(), FVector::ZeroVector, FRotator::ZeroRotator, spawn_params);
143149

144-
if (NewActor) {
150+
if (IsValid(NewActor)) {
145151
UStaticMeshComponent* ObjectComponent = NewObject<UStaticMeshComponent>(NewActor);
146152
ObjectComponent->SetStaticMesh(static_mesh);
147153
ObjectComponent->SetRelativeLocation(FVector(0, 0, 0));
@@ -154,6 +160,33 @@ AActor* WorldSimApi::createNewActor(const FActorSpawnParameters& spawn_params, c
154160
return NewActor;
155161
}
156162

163+
AActor* WorldSimApi::createNewBPActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UBlueprint* blueprint)
164+
{
165+
UClass* new_bp = static_cast<UClass*>(blueprint->GeneratedClass);
166+
AActor* new_actor = simmode_->GetWorld()->SpawnActor<AActor>(new_bp, FVector::ZeroVector, FRotator::ZeroRotator, spawn_params);
167+
168+
if (new_actor) {
169+
new_actor->SetActorLocationAndRotation(actor_transform.GetLocation(), actor_transform.GetRotation(), false, nullptr, ETeleportType::TeleportPhysics);
170+
}
171+
return new_actor;
172+
}
173+
174+
bool WorldSimApi::setLightIntensity(const std::string& light_name, float intensity)
175+
{
176+
bool result = false;
177+
UAirBlueprintLib::RunCommandOnGameThread([this, &light_name, &intensity, &result]() {
178+
AActor* light_actor = simmode_->scene_object_map.FindRef(FString(light_name.c_str()));
179+
180+
if (light_actor) {
181+
const FString command = FString::Printf(TEXT("SetIntensity %f"), intensity);
182+
FOutputDeviceNull ar;
183+
result = light_actor->CallFunctionByNameWithArguments(*command, ar, nullptr, true);
184+
}
185+
},
186+
true);
187+
return result;
188+
}
189+
157190
bool WorldSimApi::createVoxelGrid(const Vector3r& position, const int& x_size, const int& y_size, const int& z_size, const float& res, const std::string& output_file)
158191
{
159192
bool success = false;

0 commit comments

Comments
 (0)