Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixes and improvements to world API #2898

Merged
merged 8 commits into from
Sep 2, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
40 changes: 40 additions & 0 deletions Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@
#include <exception>
#include "common/common_utils/Utils.hpp"
#include "Modules/ModuleManager.h"
#include "ARFilter.h"
#include "AssetRegistryModule.h"

/*
//TODO: change naming conventions to same as other files?
Expand Down Expand Up @@ -239,6 +241,44 @@ void UAirBlueprintLib::LogMessage(const FString &prefix, const FString &suffix,
//GEngine->AddOnScreenDebugMessage(key + 10, 60.0f, color, FString::FromInt(key));
}

void UAirBlueprintLib::GenerateAssetRegistryMap(const UObject* context, TMap<FString, FAssetData>& asset_map)
{
UAirBlueprintLib::RunCommandOnGameThread([context, &asset_map]() {
FARFilter Filter;
Filter.ClassNames.Add(UStaticMesh::StaticClass()->GetFName());
Filter.bRecursivePaths = true;

auto world = context->GetWorld();
TArray<FAssetData> AssetData;

// Find mesh in /Game and /AirSim asset registry. When more plugins are added this function will have to change
FAssetRegistryModule &AssetRegistryModule = FModuleManager::LoadModuleChecked<FAssetRegistryModule>("AssetRegistry");
AssetRegistryModule.Get().GetAssets(Filter, AssetData);

UObject *LoadObject = NULL;
for (auto asset : AssetData)
{
FString asset_name = asset.AssetName.ToString();
asset_map.Add(asset_name, asset);
}

LogMessageString("Asset database ready", "!", LogDebugLevel::Informational);
}, true);
}


void UAirBlueprintLib::GenerateActorMap(const UObject* context, TMap<FString, AActor*>& scene_object_map) {
auto world = context->GetWorld();
for (TActorIterator<AActor> actorIterator(world); actorIterator; ++actorIterator)
{
AActor* actor = *actorIterator;
FString name = *actor->GetName();

scene_object_map.Add(name, actor);
}
}


void UAirBlueprintLib::setUnrealClockSpeed(const AActor* context, float clock_speed)
{
UAirBlueprintLib::RunCommandOnGameThread([context, clock_speed]() {
Expand Down
3 changes: 3 additions & 0 deletions Unreal/Plugins/AirSim/Source/AirBlueprintLib.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary
return nullptr;
}


template<typename T>
static void FindAllActor(const UObject* context, TArray<AActor*>& foundActors)
{
Expand All @@ -85,6 +86,8 @@ class UAirBlueprintLib : public UBlueprintFunctionLibrary
UFUNCTION(BlueprintPure, Category = "AirSim|LevelAPI")
static TArray<FName> ListWorldsInRegistry();
static UObject* GetMeshFromRegistry(const std::string& load_object);
static void GenerateAssetRegistryMap(const UObject* context, TMap<FString, FAssetData>& asset_map);
static void GenerateActorMap(const UObject* context, TMap<FString, AActor*>& scene_object_map);

static bool HasObstacle(const AActor* actor, const FVector& start, const FVector& end,
const AActor* ignore_actor = nullptr, ECollisionChannel collision_channel = ECC_Visibility);
Expand Down
3 changes: 3 additions & 0 deletions Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,8 @@ void ASimModeBase::BeginPlay()
global_ned_transform_.reset(new NedTransform(player_start_transform,
UAirBlueprintLib::GetWorldToMetersScale(this)));

UAirBlueprintLib::GenerateAssetRegistryMap(this, asset_map);

world_sim_api_.reset(new WorldSimApi(this));
api_provider_.reset(new msr::airlib::ApiProvider(world_sim_api_.get()));

Expand Down Expand Up @@ -126,6 +128,7 @@ void ASimModeBase::BeginPlay()
UWeatherLib::initWeather(World, spawned_actors_);
//UWeatherLib::showWeatherMenu(World);
}
UAirBlueprintLib::GenerateActorMap(this, scene_object_map);

loading_screen_widget_->AddToViewport();
loading_screen_widget_->SetVisibility(ESlateVisibility::Hidden);
Expand Down
3 changes: 3 additions & 0 deletions Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,9 @@ class AIRSIM_API ASimModeBase : public AActor
return static_cast<PawnSimApi*>(api_provider_->getVehicleSimApi(vehicle_name));
}

TMap<FString, FAssetData> asset_map;
TMap<FString, AActor*> scene_object_map;

protected: //must overrides
typedef msr::airlib::AirSimSettings AirSimSettings;

Expand Down
65 changes: 46 additions & 19 deletions Unreal/Plugins/AirSim/Source/WorldSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include "common/common_utils/Utils.hpp"
#include "Weather/WeatherLib.h"
#include "DrawDebugHelpers.h"
#include "Runtime/Engine/Classes/Engine/Engine.h"
#include <cstdlib>
#include <ctime>

Expand Down Expand Up @@ -73,6 +74,10 @@ bool WorldSimApi::destroyObject(const std::string& object_name)
actor->Destroy();
result = actor->IsPendingKill();
}
if (result)
simmode_->scene_object_map.Remove(FString(object_name.c_str()));

GEngine->ForceGarbageCollection(true);
}, true);
return result;
}
Expand All @@ -81,12 +86,16 @@ std::string WorldSimApi::spawnObject(std::string& object_name, const std::string
{
// Create struct for Location and Rotation of actor in Unreal
FTransform actor_transform = simmode_->getGlobalNedTransform().fromGlobalNed(pose);
bool found_object;
UAirBlueprintLib::RunCommandOnGameThread([this, load_object, &object_name, &actor_transform, &found_object, &scale, &physics_enabled]() {
// Find mesh in /Game and /AirSim asset registry. When more plugins are added this function will have to change
UStaticMesh* LoadObject = dynamic_cast<UStaticMesh*>(UAirBlueprintLib::GetMeshFromRegistry(load_object));
if (LoadObject)

bool found_object = false, spawned_object = false;
UAirBlueprintLib::RunCommandOnGameThread([this, load_object, &object_name, &actor_transform, &found_object, &spawned_object, &scale, &physics_enabled]() {
FString asset_name = FString(load_object.c_str());
FAssetData *LoadAsset = simmode_->asset_map.Find(asset_name);

if (LoadAsset)
{
found_object = true;
UStaticMesh* LoadObject = dynamic_cast<UStaticMesh*>(LoadAsset->GetAsset());
std::vector<std::string> matching_names = UAirBlueprintLib::ListMatchingActors(simmode_->GetWorld(), ".*"+object_name+".*");
if (matching_names.size() > 0)
{
Expand All @@ -104,8 +113,14 @@ std::string WorldSimApi::spawnObject(std::string& object_name, const std::string
}
FActorSpawnParameters new_actor_spawn_params;
new_actor_spawn_params.Name = FName(object_name.c_str());
new_actor_spawn_params.NameMode = FActorSpawnParameters::ESpawnActorNameMode::Required_ReturnNull;
AActor* NewActor = this->createNewActor(new_actor_spawn_params, actor_transform, scale, LoadObject);
found_object = true;

if (NewActor)
{
spawned_object = true;
simmode_->scene_object_map.Add(FString(object_name.c_str()), NewActor);
}

UAirBlueprintLib::setSimulatePhysics(NewActor, physics_enabled);
}
Expand All @@ -120,21 +135,29 @@ std::string WorldSimApi::spawnObject(std::string& object_name, const std::string
throw std::invalid_argument(
"There were no objects with name " + load_object + " found in the Registry");
}
if (!spawned_object)
{
throw std::invalid_argument(
"Engine could not spawn " + load_object + " because of a stale reference of same name");
}
return object_name;
}

AActor* WorldSimApi::createNewActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UStaticMesh* static_mesh)
{
AActor* NewActor = simmode_->GetWorld()->SpawnActor<AActor>(AActor::StaticClass(), FVector::ZeroVector, FRotator::ZeroRotator, spawn_params); // new
UStaticMeshComponent* ObjectComponent = NewObject<UStaticMeshComponent>(NewActor);
ObjectComponent->SetStaticMesh(static_mesh);
ObjectComponent->SetRelativeLocation(FVector(0, 0, 0));
ObjectComponent->SetWorldScale3D(FVector(scale[0], scale[1], scale[2]));
ObjectComponent->SetHiddenInGame(false, true);
ObjectComponent->RegisterComponent();
NewActor->SetRootComponent(ObjectComponent);
NewActor->SetActorLocationAndRotation(actor_transform.GetLocation(), actor_transform.GetRotation(), false, nullptr, ETeleportType::TeleportPhysics);
AActor* NewActor = simmode_->GetWorld()->SpawnActor<AActor>(AActor::StaticClass(), FVector::ZeroVector, FRotator::ZeroRotator, spawn_params);

if (NewActor)
{
UStaticMeshComponent* ObjectComponent = NewObject<UStaticMeshComponent>(NewActor);
ObjectComponent->SetStaticMesh(static_mesh);
ObjectComponent->SetRelativeLocation(FVector(0, 0, 0));
ObjectComponent->SetWorldScale3D(FVector(scale[0], scale[1], scale[2]));
ObjectComponent->SetHiddenInGame(false, true);
ObjectComponent->RegisterComponent();
NewActor->SetRootComponent(ObjectComponent);
NewActor->SetActorLocationAndRotation(actor_transform.GetLocation(), actor_transform.GetRotation(), false, nullptr, ETeleportType::TeleportPhysics);
}
return NewActor;
}

Expand Down Expand Up @@ -204,7 +227,8 @@ WorldSimApi::Pose WorldSimApi::getObjectPose(const std::string& object_name) con
{
Pose result;
UAirBlueprintLib::RunCommandOnGameThread([this, &object_name, &result]() {
AActor* actor = UAirBlueprintLib::FindActor<AActor>(simmode_, FString(object_name.c_str()));
// AActor* actor = UAirBlueprintLib::FindActor<AActor>(simmode_, FString(object_name.c_str()));
AActor* actor = simmode_->scene_object_map.FindRef(FString(object_name.c_str()));
result = actor ? simmode_->getGlobalNedTransform().toGlobalNed(FTransform(actor->GetActorRotation(), actor->GetActorLocation()))
: Pose::nanPose();
}, true);
Expand All @@ -216,7 +240,8 @@ WorldSimApi::Vector3r WorldSimApi::getObjectScale(const std::string& object_name
{
Vector3r result;
UAirBlueprintLib::RunCommandOnGameThread([this, &object_name, &result]() {
AActor* actor = UAirBlueprintLib::FindActor<AActor>(simmode_, FString(object_name.c_str()));
// AActor* actor = UAirBlueprintLib::FindActor<AActor>(simmode_, FString(object_name.c_str()));
AActor* actor = simmode_->scene_object_map.FindRef(FString(object_name.c_str()));
result = actor ? Vector3r(actor->GetActorScale().X, actor->GetActorScale().Y, actor->GetActorScale().Z)
: Vector3r::Zero();
}, true);
Expand All @@ -228,7 +253,8 @@ bool WorldSimApi::setObjectPose(const std::string& object_name, const WorldSimAp
bool result;
UAirBlueprintLib::RunCommandOnGameThread([this, &object_name, &pose, teleport, &result]() {
FTransform actor_transform = simmode_->getGlobalNedTransform().fromGlobalNed(pose);
AActor* actor = UAirBlueprintLib::FindActor<AActor>(simmode_, FString(object_name.c_str()));
// AActor* actor = UAirBlueprintLib::FindActor<AActor>(simmode_, FString(object_name.c_str()));
AActor* actor = simmode_->scene_object_map.FindRef(FString(object_name.c_str()));
if (actor) {
if (teleport)
result = actor->SetActorLocationAndRotation(actor_transform.GetLocation(), actor_transform.GetRotation(), false, nullptr, ETeleportType::TeleportPhysics);
Expand All @@ -245,7 +271,8 @@ bool WorldSimApi::setObjectScale(const std::string& object_name, const Vector3r&
{
bool result;
UAirBlueprintLib::RunCommandOnGameThread([this, &object_name, &scale, &result]() {
AActor* actor = UAirBlueprintLib::FindActor<AActor>(simmode_, FString(object_name.c_str()));
// AActor* actor = UAirBlueprintLib::FindActor<AActor>(simmode_, FString(object_name.c_str()));
AActor* actor = simmode_->scene_object_map.FindRef(FString(object_name.c_str()));
if (actor) {
actor->SetActorScale3D(FVector(scale[0], scale[1], scale[2]));
result = true;
Expand Down