Skip to content

Commit

Permalink
Update for ue4.24. Add API call to spawn objects.
Browse files Browse the repository at this point in the history
  • Loading branch information
mitchellspryn committed Dec 17, 2019
1 parent 39e1b4f commit 8bf996d
Show file tree
Hide file tree
Showing 25 changed files with 246 additions and 56 deletions.
2 changes: 2 additions & 0 deletions AirLib/include/api/RpcLibClientBase.hpp
Expand Up @@ -40,6 +40,8 @@ class RpcLibClientBase {

Pose simGetObjectPose(const std::string& object_name) const;
bool simSetObjectPose(const std::string& object_name, const Pose& pose, bool teleport = true);
bool simSpawnStaticMeshObject(const std::string& object_class_name, const std::string& object_class, const Pose& pose);
bool simDeleteObject(const std::string& object_name);

//task management APIs
void cancelLastTask(const std::string& vehicle_name = "");
Expand Down
2 changes: 2 additions & 0 deletions AirLib/include/api/WorldSimApiBase.hpp
Expand Up @@ -26,6 +26,8 @@ class WorldSimApiBase {

virtual Pose getObjectPose(const std::string& object_name) const = 0;
virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) = 0;
virtual bool spawnStaticMeshObject(const std::string& object_class_name, const std::string& object_name, const Pose &pose) = 0;
virtual bool deleteObject(const std::string& object_name) = 0;

//----------- APIs to control ACharacter in scene ----------/
virtual void charSetFaceExpression(const std::string& expression_name, float value, const std::string& character_name) = 0;
Expand Down
2 changes: 1 addition & 1 deletion AirLib/include/common/common_utils/Utils.hpp
Expand Up @@ -593,7 +593,7 @@ class Utils {
//implements relative method - do not use for comparing with zero
//use this most of the time, tolerance needs to be meaningful in your context
template<typename TReal>
static bool isApproximatelyEqual(TReal a, TReal b, TReal tolerance = epsilon<TReal>())
static bool isApproximatelyEqual(TReal a, TReal b, TReal tolerance = std::numeric_limits<TReal>::epsilon())
{
TReal diff = std::fabs(a - b);
if (diff <= tolerance)
Expand Down
12 changes: 7 additions & 5 deletions AirLib/include/common/common_utils/type_utils.hpp
Expand Up @@ -44,12 +44,14 @@ namespace common_utils { namespace type_utils {

template <typename C> static no & f(...);

template <typename C>
// using template parameter symbol 'D' instead of 'C' as a workaround for
// VS2017 compiler issue (internal compiler error) starting 15.9.X releases.
template <typename D>
static yes & g(typename std::enable_if<
std::is_same<decltype(static_cast<typename C::const_iterator(C::*)() const>(&C::end)),
typename C::const_iterator(C::*)() const>::value, void>::type*);
std::is_same<decltype(static_cast<typename D::const_iterator(D::*)() const>(&D::end)),
typename D::const_iterator(D::*)() const>::value, void>::type*);

template <typename C> static no & g(...);
template <typename D> static no & g(...);

public:
static bool const beg_value = sizeof(f<T>(nullptr)) == sizeof(yes);
Expand Down Expand Up @@ -84,4 +86,4 @@ namespace common_utils { namespace type_utils {
struct is_container<std::tuple<Args...>> : std::true_type { };

}} //namespace
#endif
#endif
8 changes: 8 additions & 0 deletions AirLib/src/api/RpcLibClientBase.cpp
Expand Up @@ -373,6 +373,14 @@ bool RpcLibClientBase::simSetObjectPose(const std::string& object_name, const ms
{
return pimpl_->client.call("simSetObjectPose", object_name, RpcLibAdapatorsBase::Pose(pose), teleport).as<bool>();
}
bool RpcLibClientBase::simSpawnStaticMeshObject(const std::string& object_class_name, const std::string& object_name, const msr::airlib::Pose& pose)
{
return pimpl_->client.call("simSpawnStaticMeshObject", object_class_name, object_name, RpcLibAdapatorsBase::Pose(pose)).as<bool>();
}
bool RpcLibClientBase::simDeleteObject(const std::string& object_name)
{
return pimpl_->client.call("simDeleteObject", object_name).as<bool>();
}

CameraInfo RpcLibClientBase::simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name) const
{
Expand Down
6 changes: 6 additions & 0 deletions AirLib/src/api/RpcLibServerBase.cpp
Expand Up @@ -185,6 +185,12 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
pimpl_->server.bind("simSetObjectPose", [&](const std::string& object_name, const RpcLibAdapatorsBase::Pose& pose, bool teleport) -> bool {
return getWorldSimApi()->setObjectPose(object_name, pose.to(), teleport);
});
pimpl_->server.bind("simSpawnStaticMeshObject", [&](const std::string& object_class_name, const std::string& object_name, const RpcLibAdapatorsBase::Pose& pose) -> bool {
return getWorldSimApi()->spawnStaticMeshObject(object_class_name, object_name, pose.to());
});
pimpl_->server.bind("simDeleteObject", [&](const std::string& object_name) -> bool {
return getWorldSimApi()->deleteObject(object_name);
});

pimpl_->server.bind("simGetGroundTruthKinematics", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::KinematicsState {
const Kinematics::State& result = *getVehicleSimApi(vehicle_name)->getGroundTruthKinematics();
Expand Down
12 changes: 7 additions & 5 deletions MavLinkCom/common_utils/type_utils.hpp
Expand Up @@ -44,12 +44,14 @@ namespace mavlink_utils { namespace type_utils {

template <typename C> static no & f(...);

template <typename C>
// using template parameter symbol 'D' instead of 'C' as a workaround for
// VS2017 compiler issue (internal compiler error) starting 15.9.X releases.
template <typename D>
static yes & g(typename std::enable_if<
std::is_same<decltype(static_cast<typename C::const_iterator(C::*)() const>(&C::end)),
typename C::const_iterator(C::*)() const>::value, void>::type*);
std::is_same<decltype(static_cast<typename D::const_iterator(D::*)() const>(&D::end)),
typename D::const_iterator(D::*)() const>::value, void>::type*);

template <typename C> static no & g(...);
template <typename D> static no & g(...);

public:
static bool const beg_value = sizeof(f<T>(nullptr)) == sizeof(yes);
Expand Down Expand Up @@ -84,4 +86,4 @@ namespace mavlink_utils { namespace type_utils {
struct is_container<std::tuple<Args...>> : std::true_type { };

}} //namespace
#endif
#endif
8 changes: 4 additions & 4 deletions PythonClient/PythonClient.pyproj
Expand Up @@ -5,7 +5,7 @@
<SchemaVersion>2.0</SchemaVersion>
<ProjectGuid>e2049e20-b6dd-474e-8bca-1c8dc54725aa</ProjectGuid>
<ProjectHome>.</ProjectHome>
<StartupFile>urdfbot\GenerateImageTrainingSet.py</StartupFile>
<StartupFile>urdfbot\LunabotClientTest.py</StartupFile>
<SearchPath>
</SearchPath>
<WorkingDirectory>.</WorkingDirectory>
Expand Down Expand Up @@ -126,9 +126,6 @@
<Compile Include="urdfbot\ClientUtil.py">
<SubType>Code</SubType>
</Compile>
<Compile Include="urdfbot\GenerateImageTrainingSet.py">
<SubType>Code</SubType>
</Compile>
<Compile Include="urdfbot\LunabotClient.py">
<SubType>Code</SubType>
</Compile>
Expand All @@ -147,6 +144,9 @@
<Compile Include="urdfbot\ShapeDrawTest.py">
<SubType>Code</SubType>
</Compile>
<Compile Include="urdfbot\SpawnObjectTest.py">
<SubType>Code</SubType>
</Compile>
</ItemGroup>
<ItemGroup>
<Folder Include="airsim\" />
Expand Down
5 changes: 5 additions & 0 deletions PythonClient/airsim/client.py
Expand Up @@ -156,6 +156,11 @@ def simGetObjectPose(self, object_name):
def simSetObjectPose(self, object_name, pose, teleport = True):
return self.client.call('simSetObjectPose', object_name, pose, teleport)

def simSpawnStaticMeshObject(self, object_class_name, object_name, pose):
return self.client.call('simSpawnStaticMeshObject', object_class_name, object_name, pose)
def simDeleteObject(self, object_name):
return self.client.call('simDeleteObject', object_name)

def simSetSegmentationObjectID(self, mesh_name, object_id, is_name_regex = False):
return self.client.call('simSetSegmentationObjectID', mesh_name, object_id, is_name_regex)
def simGetSegmentationObjectID(self, mesh_name):
Expand Down
63 changes: 63 additions & 0 deletions PythonClient/urdfbot/SpawnObjectTest.py
@@ -0,0 +1,63 @@
import setup_path
import airsim
import airsim.airsim_types as at
import math
import time
import numpy as np
import pandas as pd
import random
import time

def main():
client = airsim.UrdfBotClient()

random.seed(42)


cone_class_name = "/Game/StarterContent/Props/SM_Couch.SM_Couch"

xs = [0, 0.1]
ys = [0, 0.1]
time_stamp = 0

for i in range(0, 3, 1):
xs.append(random.randint(0, 10))
ys.append(random.randint(0, 10))

for i in range(0, len(xs), 1):
x = xs[i]
y = ys[i]
random_position = at.Vector3r(x_val=x, y_val=y, z_val=5)
random_orientation = at.Quaternionr(x_val=0, y_val=0, z_val=0, w_val=1)
random_pose = at.Pose(position_val=random_position, orientation_val=random_orientation)

print('Spawning cone at ({0}, {1})...'.format(x, y))
client.simSpawnStaticMeshObject(cone_class_name, 'cone_{0}'.format(i), random_pose)

time.sleep(2)
ci = client.simGetCollisionInfo()
if (ci.has_collided and ci.time_stamp > time_stamp):
print('\tBot has collided with {0}.'.format(ci.object_name))
time_stamp = ci.time_stamp
else:
print('\tBot has not collided.')

time.sleep(3)

for i in range(0, len(xs), 1):
cone_name = 'cone_{0}'.format(i)
cone_pose = client.simGetObjectPose(cone_name)
print('Cone "{0}" is at position <{1}, {2}, {3}>'.format(cone_name, cone_pose.position.x_val, cone_pose.position.y_val, cone_pose.position.z_val))

time.sleep(3)

for i in range(0, len(xs), 1):
cone_name = 'cone_{0}'.format(i)
print('Deleting cone {0}...'.format(cone_name))
client.simDeleteObject(cone_name)

print('Graceful termination')

main()


3 changes: 1 addition & 2 deletions Unreal/Environments/Blocks/Config/DefaultEngine.ini
Expand Up @@ -12,7 +12,7 @@ GlobalDefaultGameMode=/Script/AirSim.AirSimGameMode
GlobalDefaultServerGameMode=None

[/Script/IOSRuntimeSettings.IOSRuntimeSettings]
MinimumiOSVersion=IOS_8
MinimumiOSVersion=IOS_11


[/Script/Engine.Engine]
Expand Down Expand Up @@ -67,4 +67,3 @@ SyncSceneSmoothingFactor=0.000000
AsyncSceneSmoothingFactor=0.990000
InitialAverageFrameRate=0.016667
PhysXTreeRebuildRate=10

8 changes: 4 additions & 4 deletions Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp
Expand Up @@ -124,15 +124,15 @@ void UAirBlueprintLib::enableViewportRendering(AActor* context, bool enable)
// Do this only if the main viewport is not being rendered anyway in case there are
// any adverse performance effects during main rendering.
//HACK: FViewPort doesn't expose this field so we are doing dirty work around by maintaining count by ourselves
if (flush_on_draw_count_ == 0)
viewport->GetGameViewport()->IncrementFlushOnDraw();
//if (flush_on_draw_count_ == 0)
// viewport->GetGameViewport()->IncrementFlushOnDraw();
}
else {
viewport->EngineShowFlags.SetRendering(true);

//HACK: FViewPort doesn't expose this field so we are doing dirty work around by maintaining count by ourselves
if (flush_on_draw_count_ > 0)
viewport->GetGameViewport()->DecrementFlushOnDraw();
//if (flush_on_draw_count_ > 0)
// viewport->GetGameViewport()->DecrementFlushOnDraw();
}
}

Expand Down
1 change: 1 addition & 0 deletions Unreal/Plugins/AirSim/Source/CameraDirector.h
Expand Up @@ -13,6 +13,7 @@
UENUM(BlueprintType)
enum class ECameraDirectorMode : uint8
{
CAMERA_DIRECTOR_MODE_UNUSED = 0 UMETA(Displayname = "Unused"),
CAMERA_DIRECTOR_MODE_FPV = 1 UMETA(DisplayName = "FPV"),
CAMERA_DIRECTOR_MODE_GROUND_OBSERVER = 2 UMETA(DisplayName = "GroundObserver"),
CAMERA_DIRECTOR_MODE_FLY_WITH_ME = 3 UMETA(DisplayName = "FlyWithMe"),
Expand Down
4 changes: 3 additions & 1 deletion Unreal/Plugins/AirSim/Source/PawnSimApi.cpp
Expand Up @@ -380,7 +380,9 @@ void PawnSimApi::serviceMoveCameraRequests()
AActor* cameraActor = matchedCamera->GetAttachParentActor();

FDetachmentTransformRules detatchRules(EDetachmentRule::KeepWorld, EDetachmentRule::KeepWorld, EDetachmentRule::KeepWorld, true);
matchedCamera->DetachSceneComponentsFromParent(cameraActor->GetRootComponent(), true);
matchedCamera->DetachAllSceneComponents(cameraActor->GetRootComponent(), detatchRules);
matchedCamera->DetachFromActor(detatchRules);
//matchedCamera->DetachSceneComponentsFromParent(cameraActor->GetRootComponent(), true);
auto a1 = cameraActor->GetActorLocation();
auto a2 = cameraActor->GetRootComponent()->GetComponentLocation();
matchedCamera->SetActorLocation(cameraActor->GetRootComponent()->GetComponentLocation() + request.transformVec);
Expand Down
2 changes: 2 additions & 0 deletions Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h
Expand Up @@ -79,6 +79,8 @@ class AIRSIM_API ASimModeBase : public AActor
return static_cast<PawnSimApi*>(api_provider_->getVehicleSimApi(vehicle_name));
}

virtual bool isUrdf() { return false; }

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

Expand Down
Expand Up @@ -95,7 +95,7 @@ void UnrealLidarSensor::getPointCloud(const msr::airlib::Pose& lidar_pose, const
FVector(start.x(), start.y(), start.z()),
5, //size
FColor::Blue,
true, //persistent (never goes away)
false, //persistent (never goes away)
0.1 //point leaves a trail on moving object
);
}
Expand Down Expand Up @@ -204,7 +204,7 @@ bool UnrealLidarSensor::shootLaser(const msr::airlib::Pose& lidar_pose, const ms
hit_result.ImpactPoint,
5, //size
FColor::Red,
true, //persistent (never goes away)
false, //persistent (never goes away)
0.1 //point leaves a trail on moving object
);
}
Expand Down Expand Up @@ -236,7 +236,7 @@ bool UnrealLidarSensor::shootLaser(const msr::airlib::Pose& lidar_pose, const ms
endVec,
5, //size
FColor::Green,
true, //persistent (never goes away)
false, //persistent (never goes away)
0.1 //point leaves a trail on moving object
);
}
Expand Down
Expand Up @@ -10,7 +10,7 @@ bool StaticMeshGenerator::Initialize(UStaticMesh* boxTemplateMesh, UStaticMesh*
return true;
}

bool StaticMeshGenerator::CreateUnscaledMeshForLink(FString linkName, UrdfGeometry* visualGeometry, UrdfGeometry* collisionGeometry, APawn* outer, AUrdfLink* link)
bool StaticMeshGenerator::CreateUnscaledMeshForLink(FString linkName, FString linkMaterialName, UrdfGeometry* visualGeometry, UrdfGeometry* collisionGeometry, APawn* outer, AUrdfLink* link, TMap<FString, UMaterialInterface*> materials)
{
FName collisionName = FName((linkName + TEXT("_collision")).GetCharArray().GetData());

Expand Down Expand Up @@ -58,6 +58,11 @@ bool StaticMeshGenerator::CreateUnscaledMeshForLink(FString linkName, UrdfGeomet
meshComponent->SetCollisionEnabled(ECollisionEnabled::Type::QueryAndPhysics);
meshComponent->SetNotifyRigidBodyCollision(true);

if (linkMaterialName.Len() > 0)
{
meshComponent->SetMaterial(0, materials[linkMaterialName]);
}

link->SetMeshFromStaticMeshComponent(meshComponent);
}
else if (geometryType == MESH)
Expand All @@ -82,6 +87,11 @@ bool StaticMeshGenerator::CreateUnscaledMeshForLink(FString linkName, UrdfGeomet
meshComponent->SetCollisionEnabled(ECollisionEnabled::Type::QueryAndPhysics);
meshComponent->SetNotifyRigidBodyCollision(true);

if (linkMaterialName.Len() > 0)
{
meshComponent->SetMaterial(0, materials[linkMaterialName]);
}

link->SetMeshFromStaticMeshComponent(meshComponent);
}
else
Expand Down Expand Up @@ -182,17 +192,32 @@ TArray<TArray<FVector>> StaticMeshGenerator::CreateCollisionVAHCD(TArray<FVector
VHACD_Params.m_oclAcceleration = false;
VHACD_Params.m_minVolumePerCH = minVolumePerCh; // this should be around 1 / (3 * m_resolution ^ (1/3))

const float* const verts = (float*)stlPoints.GetData();
double* verts = new double[3 * stlPoints.Num()];
double* vertPtr = verts;
for (int i = 0; i < stlPoints.Num(); i++)
{
FVector currentPoint = stlPoints[i];
*vertPtr = (double)currentPoint.X;
vertPtr++;
*vertPtr = (double)currentPoint.Y;
vertPtr++;
*vertPtr = (double)currentPoint.Z;
vertPtr++;
}

//const double* const verts = (double*)stlPoints.GetData();
const unsigned int numVerts = stlPoints.Num();
const int* const tris = (int*)stlIndices.GetData();
const unsigned int* const tris = (unsigned int*)stlIndices.GetData();
const unsigned int numTris = stlIndices.Num() / 3;

bool success = vhacdInterface->Compute(verts, 3, numVerts, tris, 3, numTris, VHACD_Params);

bool success = vhacdInterface->Compute(verts, numVerts, tris, numTris, VHACD_Params);
//bool success = vhacdInterface->Compute(verts, 3, numVerts, tris, 3, numTris, VHACD_Params);

if (!success)
{
vhacdInterface->Clean();
vhacdInterface->Release();
delete verts;
return TArray<TArray<FVector>>();
}

Expand Down Expand Up @@ -221,6 +246,7 @@ TArray<TArray<FVector>> StaticMeshGenerator::CreateCollisionVAHCD(TArray<FVector

vhacdInterface->Clean();
vhacdInterface->Release();
delete verts;

return output;
}
Expand Down
Expand Up @@ -30,7 +30,7 @@ class StaticMeshGenerator
{
public:
bool Initialize(UStaticMesh* boxTemplateMesh, UStaticMesh* cylinderTemplateMesh, UStaticMesh* sphereTemplateMesh, TMap<FString, UStaticMesh*> unrealMeshes);
bool CreateUnscaledMeshForLink(FString linkName, UrdfGeometry* visualGeometry, UrdfGeometry* collisionGeometry, APawn* outer, AUrdfLink* link);
bool CreateUnscaledMeshForLink(FString linkName, FString linkMaterialName, UrdfGeometry* visualGeometry, UrdfGeometry* collisionGeometry, APawn* outer, AUrdfLink* link, TMap<FString, UMaterialInterface*> materials);

private:
void ParseProceduralMeshSpecification(FString fileName, ProceduralMeshFileType fileType, bool reverseNormals, float scaleFactor, ProceduralMeshSpecification& meshSpecification);
Expand Down

0 comments on commit 8bf996d

Please sign in to comment.