class
#include <esp/sim/Simulator.h>
Simulator
Constructors, destructors, conversion operators
-
Simulator(const SimulatorConfiguration& cfg,
std::
shared_ptr<metadata:: MetadataMediator> _metadataMediator = nullptr) explicit - ~Simulator() virtual
- Simulator() protected defaulted
Public functions
- void close(bool destroy = true)
- Closes the simulator and frees all loaded assets and GPU contexts.
- void reconfigure(const SimulatorConfiguration& cfg)
- void reset(bool calledAfterSceneCreate = false)
- Reset the simulation state including the state of all physics objects and the default light setup. Sets the worldTime_ to 0.0, changes the physical state of all objects back to their initial states. Does not invalidate existing ManagedObject wrappers. Does not add or remove object instances. Only changes motion_type when scene_instance specified a motion type.
-
void seed(uint32_
t newSeed) -
auto getRenderer() -> std::
shared_ptr<gfx:: Renderer> - void getRenderGLContext()
-
auto getGfxReplayManager() -> std::
shared_ptr<gfx:: replay:: ReplayManager> - auto gpuDevice() const -> int
- The ID of the CUDA device of the OpenGL context owned by the simulator. This will only be nonzero if the simulator is built in –headless mode on linux.
-
auto getAOAttributesManager() const -> const std::
shared_ptr<metadata:: managers:: AOAttributesManager>& - Return manager for construction and access to articulated object attributes for the current dataset.
-
auto getAssetAttributesManager() const -> const std::
shared_ptr<metadata:: managers:: AssetAttributesManager>& - Return manager for construction and access to asset attributes for the current dataset.
-
auto getLightLayoutAttributesManager() const -> const std::
shared_ptr<metadata:: managers:: LightLayoutAttributesManager>& - Return manager for construction and access to light attributes and layouts for the current dataset.
-
auto getObjectAttributesManager() const -> const std::
shared_ptr<metadata:: managers:: ObjectAttributesManager>& - Return manager for construction and access to object attributes and layouts for the current dataset.
-
auto getPhysicsAttributesManager() const -> const std::
shared_ptr<metadata:: managers:: PhysicsAttributesManager>& - Return manager for construction and access to physics world attributes.
-
auto getStageAttributesManager() const -> const std::
shared_ptr<metadata:: managers:: StageAttributesManager>& - Return manager for construction and access to scene attributes for the current dataset.
-
auto getActiveSceneDatasetName() -> std::
string - Get current active dataset name from metadataMediator_
. -
void setActiveSceneDatasetName(const std::
string& _dsHandle) - Set current active dataset name from metadataMediator_
. -
auto getPhysicsSimulationLibrary() const -> const esp::
physics:: PhysicsManager:: PhysicsSimulationLibrary& - Return the library implementation type for the simulator currently in use. Use to check for a particular implementation.
-
void physicsDebugDraw(const Magnum::
Matrix4& projTrans) const - Render any debugging visualizations provided by the underlying physics simulator implementation. By default does nothing. See BulletPhysicsManager::debugDraw.
- auto getStageInitializationTemplate() const -> metadata::attributes::StageAttributes::cptr
- Get a copy of a stage's template when the stage was instanced.
-
auto getActiveSceneGraph() -> scene::
SceneGraph& - get the current active scene graph
-
auto getSemanticScene() -> std::
shared_ptr<scene:: SemanticScene> -
auto getSemanticSceneColormap() const -> const std::
vector<Mn:: Vector3ub>& - Return a view of the currently set Semantic scene colormap.
- auto semanticSceneExists() const -> bool
- check if the semantic scene exists.
- auto semanticSceneGraphExists() const -> bool
- Check to see if there is a SemanticSceneGraph for rendering.
-
auto getActiveSemanticSceneGraph() -> scene::
SceneGraph& - get the semantic scene's SceneGraph for rendering
-
auto buildSemanticCCObjects() const -> std::
unordered_map<uint32_ t, std:: vector<scene::CCSemanticObject::ptr>> - Build a map keyed by semantic color/id referencing a list of connected component-based Semantic objects.
-
auto buildVertexColorMapReport() const -> std::
vector<std:: string> - Build a report on vertex color mappings to semantic scene descriptor object colors, to show whether any verts have unknown colors and whether any semantic object colors are not present in the mesh.
-
auto saveCurrentSceneInstance(const std::
string& saveFilename) const -> bool - Builds a esp::
metadata:: attributes:: SceneInstanceAttributes describing the current scene configuration, and saves it to a JSON file, using saveFileName
. - auto saveCurrentSceneInstance(bool overwrite = false) const -> bool
- Builds a esp::
metadata:: attributes:: SceneInstanceAttributes describing the current scene configuration, and saves it to a JSON file, using the current scene attributes' filename, or an incremented version if overwrite
== false. -
auto getExistingObjectIDs() -> std::
vector<int> - Get the IDs of the physics objects instanced in a physical scene. See esp::
physics:: PhysicsManager:: getExistingObjectIDs. -
auto getSceneAabb() -> const Mn::
Range3D& - Get the axis-aligned bounding box (AABB) of the scene in global space.
- void performDiscreteCollisionDetection()
- Perform discrete collision detection for the scene.
-
auto getPhysicsContactPoints() -> std::
vector<esp:: physics:: ContactPointData> - Query physics simulation implementation for contact point data from the most recent collision detection cache.
- auto getPhysicsNumActiveContactPoints() -> int
- Query the number of contact points that were active during the collision detection check.
- auto getPhysicsNumActiveOverlappingPairs() -> int
- See BulletPhysicsManager.h getNumActiveOverlappingPairs.
-
auto getPhysicsStepCollisionSummary() -> std::
string - See BulletPhysicsManager.h getStepCollisionSummary.
- void setStageIsCollidable(bool collidable)
- Set the stage to collidable or not.
- auto getStageIsCollidable() -> bool
- Get whether or not the stage is collision active.
-
auto getRigidObjectManager() const -> std::
shared_ptr<esp:: physics:: RigidObjectManager> - returns the wrapper manager for the currently created rigid objects.
-
auto getArticulatedObjectManager() const -> std::
shared_ptr<esp:: physics:: ArticulatedObjectManager> - returns the wrapper manager for the currently created articulated objects.
-
auto castRay(const esp::
geo:: Ray& ray, double maxDistance = 100.0, double bufferDistance = 0.08) -> esp:: physics:: RaycastResults - Raycast into the collision world of a scene.
- auto stepWorld(double dt = 1.0/60.0) -> double
- the physical world has a notion of time which passes during animation/simulation/action/etc... Step the physical world forward in time by a desired duration. Note that the actual duration of time passed by this step will depend on simulation time stepping mode (todo). See esp::
physics:: PhysicsManager:: stepPhysics. - auto getWorldTime() -> double
- Get the current time in the simulated world. This is always 0 if no esp::
physics:: PhysicsManager is initialized. See stepWorld. See esp:: physics:: PhysicsManager:: getWorldTime. - auto getPhysicsTimeStep() -> double
- Get the last physics timestep in seconds.
-
auto getCurSceneInstanceName() const -> std::
string - Get the simplified name of the esp::
metadata:: attributes:: SceneInstanceAttributes used to create the scene currently being simulated/displayed. - auto getCurSceneDefaultCOMHandling() const -> bool
- Return whether the esp::
metadata:: attributes:: SceneInstanceAttributes used to create the scene currently being simulated/displayed specifies a default COM handling for rigid objects. -
void setGravity(const Magnum::
Vector3& gravity) - Set the gravity in a physical scene.
-
auto getGravity() const -> Magnum::
Vector3 - Get the gravity in a physical scene.
-
auto getDebugLineRender() -> std::
shared_ptr<esp:: gfx:: DebugLineRender> -
auto recomputeNavMesh(nav::
PathFinder& pathfinder, const nav:: NavMeshSettings& navMeshSettings) -> bool - Compute the navmesh for the simulator's current active scene and assign it to the referenced nav::
PathFinder. - auto getJoinedMesh(bool includeStaticObjects = false) -> assets::MeshData::ptr
- Get the joined mesh data for all objects in the scene.
-
auto getJoinedSemanticMesh(std::
vector<std:: uint16_t>& objectIds) -> assets::MeshData::ptr - Get the joined semantic mesh data for all objects in the scene.
- auto setNavMeshVisualization(bool visualize) -> bool
- Set visualization of the current NavMesh pathfinder_ on or off.
- auto isNavMeshVisualizationActive() -> bool
- Query active state of the current NavMesh pathfinder_ visualization.
-
auto getDrawableGroup() -> esp::
gfx:: DrawableGroup& - Return a ref to a new drawables in the currently active scene, for object creation.
-
auto addTrajectoryObject(const std::
string& trajVisName, const std:: vector<Mn:: Vector3>& pts, const std:: vector<Mn:: Color3>& colorVec, int numSegments = 3, float radius = .001, bool smooth = false, int numInterp = 10) -> int - Compute a trajectory visualization for the passed points.
-
auto removeTrajVisByName(const std::
string& trajVisName) -> bool - Remove a trajectory visualization by name.
- auto removeTrajVisByID(int trajVisObjID) -> bool
- Remove a trajectory visualization by object ID.
-
auto addSensorToObject(int objectId,
const esp::sensor::SensorSpec::ptr& sensorSpec) -> esp::
sensor:: Sensor& - Initialize a sensor from its spec and attach it to the SceneNode of a particular object or link.
-
auto displayObservation(const std::
string& sensorUuid) -> bool - Displays observations on default frame buffer for a particular sensor.
-
auto getRenderTarget(const std::
string& sensorUuid) -> gfx:: RenderTarget* - get the render target of a particular sensor
-
auto drawObservation(const std::
string& sensorUuid) -> bool - draw observations to the frame buffer stored in that particular sensor. Unlike the @displayObservation, it will not display the observation on the default frame buffer
-
auto visualizeObservation(const std::
string& sensorUuid, float colorMapOffset, float colorMapScale) -> bool - visualize the undisplayable observations such as depth, semantic, to the frame buffer stored in the SensorInfoVisualizer Note: it will not display the observation on the default frame buffer
-
auto visualizeObservation(const std::
string& sensorUuid) -> bool -
auto getSensorObservation(const std::
string& sensorUuid, sensor:: Observation& observation) -> bool -
auto getSensorObservationSpace(const std::
string& sensorUuid, sensor:: ObservationSpace& space) -> bool - auto getPathFinder() -> nav::PathFinder::ptr
- void setPathFinder(nav::PathFinder::ptr pf)
- void setFrustumCullingEnabled(bool val)
- Enable or disable frustum culling (enabled by default)
- auto isFrustumCullingEnabled() const -> bool
- Get status, whether frustum culling is enabled or not.
-
auto getLightSetup(const std::
string& key = DEFAULT_ LIGHTING_ KEY) -> gfx:: LightSetup - Get a copy of an existing gfx::
LightSetup by its key. -
auto getCurrentLightSetup() -> gfx::
LightSetup - Get a copy of the currently set existing gfx::
LightSetup. -
auto getCurrentLightSetupKey() const -> std::
string - retrieve Current lightsetup key
-
void setLightSetup(gfx::
LightSetup lightSetup, const std:: string& key = DEFAULT_ LIGHTING_ KEY) - Register a gfx::
LightSetup with a key name. -
auto createRigidConstraint(const physics::
RigidConstraintSettings& settings) -> int - Create a rigid constraint between two objects or an object and the world.
-
void updateRigidConstraint(int constraintId,
const physics::
RigidConstraintSettings& settings) - Update the settings of a rigid constraint.
- void removeRigidConstraint(int constraintId)
- Remove a rigid constraint by id.
-
auto getRigidConstraintSettings(int constraintId) const -> physics::
RigidConstraintSettings - Get a copy of the settings for an existing rigid constraint.
-
auto random() -> core::
Random:: ptr - Getter for PRNG.
-
auto getMetadataMediator() const -> std::
shared_ptr<metadata:: MetadataMediator> - Get this simulator's MetadataMediator.
-
void setMetadataMediator(std::
shared_ptr<metadata:: MetadataMediator> _metadataMediator) - Set this simulator's MetadataMediator.
-
auto loadAndCreateRenderAssetInstance(const assets::
AssetInfo& assetInfo, const assets:: RenderAssetInstanceCreationInfo& creation) -> scene:: SceneNode* - Load and add a render asset instance to the current scene graph(s).
-
auto getRuntimePerfStatNames() -> std::
vector<std:: string> - Runtime perf stats are various scalars helpful for troubleshooting runtime perf.
-
auto getRuntimePerfStatValues() -> std::
vector<float> - Runtime perf stats are various scalars helpful for troubleshooting runtime perf.
Protected functions
- void resetNavMeshVisIfActive()
- if Navmesh visualization is active, reset the visualization.
-
auto createSceneInstance(const std::
string& activeSceneName) -> bool - Builds a scene instance and populates it with initial object layout, if appropriate, based on esp::
metadata:: attributes:: SceneInstanceAttributes referenced by activeSceneName
. -
auto instanceStageForSceneAttributes(const metadata::attributes::SceneInstanceAttributes::cptr& curSceneInstanceAttributes,
const std::
shared_ptr<esp:: metadata:: attributes:: SemanticAttributes>& semanticAttr) -> bool - Instance the stage for the current scene based on curSceneInstanceAttributes_, the currently active scene's esp::
metadata:: attributes:: SceneInstanceAttributes. - auto instanceObjectsForSceneAttributes(const metadata::attributes::SceneInstanceAttributes::cptr& curSceneInstanceAttributes) -> bool
- Instance all the objects in the scene based on curSceneInstanceAttributes_, the currently active scene's esp::
metadata:: attributes:: SceneInstanceAttributes. - auto instanceArticulatedObjectsForSceneAttributes(const metadata::attributes::SceneInstanceAttributes::cptr& curSceneInstanceAttributes) -> bool
- Instance all the articulated objects in the scene based on curSceneInstanceAttributes_, the currently active scene's esp::
metadata:: attributes:: SceneInstanceAttributes. - auto buildCurrentStateSceneAttributes() const -> metadata::attributes::SceneInstanceAttributes::ptr
- Build a metadata::
attributes:: SceneInstanceAttributes describing the current scene's present state. - auto sceneHasPhysics() const -> bool
- void reconfigureReplayManager(bool enableGfxReplaySave)
Protected variables
- gfx::WindowlessContext::uptr context_
-
std::
shared_ptr<gfx:: Renderer> renderer_ -
std::
unique_ptr<assets:: ResourceManager> resourceManager_ -
std::
shared_ptr<metadata:: MetadataMediator> metadataMediator_ - Owns and manages the metadata/attributes managers.
- metadata::attributes::SceneInstanceAttributes::cptr curSceneInstanceAttributes_
- Configuration describing currently active scene.
- scene::SceneManager::uptr sceneManager_
- int activeSceneID_
- int activeSemanticSceneID_
- bool semanticSceneMeshLoaded_
- Whether or not the loaded scene has a semantic scene mesh loaded.
-
std::
vector<int> sceneID_ -
std::
shared_ptr<physics:: PhysicsManager> physicsManager_ -
std::
shared_ptr<esp:: gfx:: replay:: ReplayManager> gfxReplayMgr_ -
core::
Random:: ptr random_ - SimulatorConfiguration config_
- nav::PathFinder::ptr pathfinder_
- bool frustumCulling_
- int navMeshVisPrimID_
- NavMesh visualization variables.
-
esp::
scene:: SceneNode* navMeshVisNode_ -
Corrade::
Containers:: Optional<bool> requiresTextures_ - Tracks whether or not the simulator was initialized to load textures. Because we cache mesh loading, this should not be changed without calling close() first.
-
std::
shared_ptr<esp:: gfx:: DebugLineRender> debugLineRender_ -
std::
vector<float> runtimePerfStatValues_
Function documentation
void esp:: sim:: Simulator:: close(bool destroy = true)
Closes the simulator and frees all loaded assets and GPU contexts.
Parameters | |
---|---|
destroy | When set, destroy the background rendering thread and gl context also. Otherwise these persist if the background rendering thread was used. This is done because the OpenGL driver leaks memory on thread destroy on some systems. |
void esp:: sim:: Simulator:: reset(bool calledAfterSceneCreate = false)
Reset the simulation state including the state of all physics objects and the default light setup. Sets the worldTime_ to 0.0, changes the physical state of all objects back to their initial states. Does not invalidate existing ManagedObject wrappers. Does not add or remove object instances. Only changes motion_type when scene_instance specified a motion type.
Parameters | |
---|---|
calledAfterSceneCreate | Whether this reset is being called after a new scene has been created in reconfigure. If so we con't want to redundantly re-place the newly-placed object positions. |
void esp:: sim:: Simulator:: setActiveSceneDatasetName(const std:: string& _dsHandle)
Set current active dataset name from metadataMediator_
Parameters | |
---|---|
_dsHandle | The desired dataset to switch to. If has not been loaded, an attempt will be made to load it. |
const esp:: physics:: PhysicsManager:: PhysicsSimulationLibrary& esp:: sim:: Simulator:: getPhysicsSimulationLibrary() const
Return the library implementation type for the simulator currently in use. Use to check for a particular implementation.
Returns | The implementation type of this simulator. |
---|
void esp:: sim:: Simulator:: physicsDebugDraw(const Magnum:: Matrix4& projTrans) const
Render any debugging visualizations provided by the underlying physics simulator implementation. By default does nothing. See BulletPhysicsManager::debugDraw.
Parameters | |
---|---|
projTrans | The composed projection and transformation matrix for the render camera. |
metadata::attributes::StageAttributes::cptr esp:: sim:: Simulator:: getStageInitializationTemplate() const
Get a copy of a stage's template when the stage was instanced.
Use this to query the stage's properties when it was initialized.
bool esp:: sim:: Simulator:: saveCurrentSceneInstance(const std:: string& saveFilename) const
Builds a esp::saveFileName
.
Parameters | |
---|---|
saveFilename | The name to use to save the current scene instance. |
Returns | whether successful or not. |
bool esp:: sim:: Simulator:: saveCurrentSceneInstance(bool overwrite = false) const
Builds a esp::overwrite
== false.
Parameters | |
---|---|
overwrite | Whether to overwrite an existing file with the same name, should one exist. |
Returns | whether successful or not. |
std:: vector<int> esp:: sim:: Simulator:: getExistingObjectIDs()
Get the IDs of the physics objects instanced in a physical scene. See esp::
Returns | A vector of ID keys into esp:: |
---|
std:: vector<esp:: physics:: ContactPointData> esp:: sim:: Simulator:: getPhysicsContactPoints()
Query physics simulation implementation for contact point data from the most recent collision detection cache.
Returns | a vector with each entry corresponding to a single contact point. |
---|
int esp:: sim:: Simulator:: getPhysicsNumActiveContactPoints()
Query the number of contact points that were active during the collision detection check.
Returns | the number of active contact points. |
---|
std:: shared_ptr<esp:: physics:: RigidObjectManager> esp:: sim:: Simulator:: getRigidObjectManager() const
returns the wrapper manager for the currently created rigid objects.
Returns | RigidObject wrapper manager. |
---|
std:: shared_ptr<esp:: physics:: ArticulatedObjectManager> esp:: sim:: Simulator:: getArticulatedObjectManager() const
returns the wrapper manager for the currently created articulated objects.
Returns | ArticulatedObject wrapper manager |
---|
esp:: physics:: RaycastResults esp:: sim:: Simulator:: castRay(const esp:: geo:: Ray& ray,
double maxDistance = 100.0,
double bufferDistance = 0.08)
Raycast into the collision world of a scene.
Parameters | |
---|---|
ray | The ray to cast. Need not be unit length, but returned hit distances will be in units of ray length. |
maxDistance | The maximum distance along the ray direction to search. In units of ray length. |
bufferDistance | The casts the ray from this distance behind the origin in the inverted ray direction to avoid errors related to casting rays inside a collision shape's margin. |
Returns | Raycast results sorted by distance. |
Note: A default physics::
double esp:: sim:: Simulator:: stepWorld(double dt = 1.0/60.0)
the physical world has a notion of time which passes during animation/simulation/action/etc... Step the physical world forward in time by a desired duration. Note that the actual duration of time passed by this step will depend on simulation time stepping mode (todo). See esp::
Parameters | |
---|---|
dt | The desired amount of time to advance the physical world. |
Returns | The new world time after stepping. See esp:: |
double esp:: sim:: Simulator:: getWorldTime()
Get the current time in the simulated world. This is always 0 if no esp::
Returns | The amount of time, esp:: |
---|
double esp:: sim:: Simulator:: getPhysicsTimeStep()
Get the last physics timestep in seconds.
Returns | The timestep. |
---|
bool esp:: sim:: Simulator:: recomputeNavMesh(nav:: PathFinder& pathfinder,
const nav:: NavMeshSettings& navMeshSettings)
Compute the navmesh for the simulator's current active scene and assign it to the referenced nav::
Parameters | |
---|---|
pathfinder | The pathfinder object to which the recomputed navmesh will be assigned. |
navMeshSettings | The nav:: |
Returns | Whether or not the navmesh recomputation succeeded. |
assets::MeshData::ptr esp:: sim:: Simulator:: getJoinedMesh(bool includeStaticObjects = false)
Get the joined mesh data for all objects in the scene.
Parameters | |
---|---|
includeStaticObjects | flag to include static objects |
Returns | A shared ptr assets::MeshData with required mesh |
assets::MeshData::ptr esp:: sim:: Simulator:: getJoinedSemanticMesh(std:: vector<std:: uint16_t>& objectIds)
Get the joined semantic mesh data for all objects in the scene.
Parameters | |
---|---|
objectIds out | will be populated with the object ids for the semantic mesh |
Returns | A shared ptr assets::MeshData with required mesh and populate the objectIds |
bool esp:: sim:: Simulator:: setNavMeshVisualization(bool visualize)
Set visualization of the current NavMesh pathfinder_ on or off.
Parameters | |
---|---|
visualize | Whether or not to visualize the navmesh. |
Returns | Whether or not the NavMesh visualization is active. |
int esp:: sim:: Simulator:: addTrajectoryObject(const std:: string& trajVisName,
const std:: vector<Mn:: Vector3>& pts,
const std:: vector<Mn:: Color3>& colorVec,
int numSegments = 3,
float radius = .001,
bool smooth = false,
int numInterp = 10)
Compute a trajectory visualization for the passed points.
Parameters | |
---|---|
trajVisName | The name to use for the trajectory visualization |
pts | The points of a trajectory, in order |
colorVec | Array of colors for trajectory tube. |
numSegments | The number of the segments around the circumference of the tube. Must be greater than or equal to 3. |
radius | The radius of the tube. |
smooth | Whether to smooth the points in the trajectory or not. Will build a much bigger mesh |
numInterp | The number of interpolations between each trajectory point, if smoothed |
Returns | The ID of the object created for the visualization |
bool esp:: sim:: Simulator:: removeTrajVisByName(const std:: string& trajVisName)
Remove a trajectory visualization by name.
Parameters | |
---|---|
trajVisName | The name of the trajectory visualization to remove. |
Returns | whether successful or not. |
bool esp:: sim:: Simulator:: removeTrajVisByID(int trajVisObjID)
Remove a trajectory visualization by object ID.
Parameters | |
---|---|
trajVisObjID | The object ID of the trajectory visualization to remove. |
Returns | whether successful or not. |
esp:: sensor:: Sensor& esp:: sim:: Simulator:: addSensorToObject(int objectId,
const esp::sensor::SensorSpec::ptr& sensorSpec)
Initialize a sensor from its spec and attach it to the SceneNode of a particular object or link.
Parameters | |
---|---|
objectId | Id of the object to which a sensor will be initialized at its node |
sensorSpec | SensorSpec of sensor to be initialized |
Returns | handle to sensor initialized |
bool esp:: sim:: Simulator:: displayObservation(const std:: string& sensorUuid)
Displays observations on default frame buffer for a particular sensor.
Parameters | |
---|---|
sensorUuid | Unique Id of the sensor for which the observation is to be returned |
gfx:: RenderTarget* esp:: sim:: Simulator:: getRenderTarget(const std:: string& sensorUuid)
get the render target of a particular sensor
Parameters | |
---|---|
sensorUuid | Id of the sensor for which the observation is to be returned |
Returns | pointer to the render target if it is a valid visual sensor, otherwise nullptr |
bool esp:: sim:: Simulator:: drawObservation(const std:: string& sensorUuid)
draw observations to the frame buffer stored in that particular sensor. Unlike the @displayObservation, it will not display the observation on the default frame buffer
Parameters | |
---|---|
sensorUuid | Id of the sensor for which the observation is to be returned |
bool esp:: sim:: Simulator:: visualizeObservation(const std:: string& sensorUuid,
float colorMapOffset,
float colorMapScale)
visualize the undisplayable observations such as depth, semantic, to the frame buffer stored in the SensorInfoVisualizer Note: it will not display the observation on the default frame buffer
Parameters | |
---|---|
sensorUuid in | Id of the sensor for which the observation is to be returned |
colorMapOffset in | the offset of the color map |
colorMapScale in | the scale of the color map See details in TextureVisualizerShader::setColorMapTransformation for more info. |
Returns | false if the sensor's observation cannot be visualized. |
NOTE: it assumes: -) it is a non-rgb sensor (such as a depth or semantic sensor); -) the drawObservation is called; -) when the render target is bound to the sensor, "VisualizeTexture" is enabled. See Renderer::bindRenderTarget and Renderer::RenderTargetBindingFlag for more info
void esp:: sim:: Simulator:: setFrustumCullingEnabled(bool val)
Enable or disable frustum culling (enabled by default)
Parameters | |
---|---|
val | true = enable, false = disable |
bool esp:: sim:: Simulator:: isFrustumCullingEnabled() const
Get status, whether frustum culling is enabled or not.
Returns | true if enabled, otherwise false |
---|
gfx:: LightSetup esp:: sim:: Simulator:: getLightSetup(const std:: string& key = DEFAULT_ LIGHTING_ KEY)
Get a copy of an existing gfx::
Parameters | |
---|---|
key | The string key of the gfx:: |
void esp:: sim:: Simulator:: setLightSetup(gfx:: LightSetup lightSetup,
const std:: string& key = DEFAULT_ LIGHTING_ KEY)
Register a gfx::
Parameters | |
---|---|
lightSetup | The gfx:: |
key | Key to identify this gfx:: |
If this name already exists, the gfx::
int esp:: sim:: Simulator:: createRigidConstraint(const physics:: RigidConstraintSettings& settings)
Create a rigid constraint between two objects or an object and the world.
Parameters | |
---|---|
settings | The datastructure defining the constraint parameters. |
Returns | The id of the newly created constraint or ID_UNDEFINED if failed. |
Note: requires Bullet physics to be enabled.
void esp:: sim:: Simulator:: updateRigidConstraint(int constraintId,
const physics:: RigidConstraintSettings& settings)
Update the settings of a rigid constraint.
Parameters | |
---|---|
constraintId | The id of the constraint to update. |
settings | The new settings of the constraint. |
Note: requires Bullet physics to be enabled.
void esp:: sim:: Simulator:: removeRigidConstraint(int constraintId)
Remove a rigid constraint by id.
Parameters | |
---|---|
constraintId | The id of the constraint to remove. |
Note: requires Bullet physics to be enabled.
physics:: RigidConstraintSettings esp:: sim:: Simulator:: getRigidConstraintSettings(int constraintId) const
Get a copy of the settings for an existing rigid constraint.
Parameters | |
---|---|
constraintId | The id of the constraint. |
Returns | The settings of the constraint. |
Note: requires Bullet physics to be enabled.
core:: Random:: ptr esp:: sim:: Simulator:: random()
Getter for PRNG.
Use this where-ever possible so that habitat won't be effected by python random or numpy.random modules.
scene:: SceneNode* esp:: sim:: Simulator:: loadAndCreateRenderAssetInstance(const assets:: AssetInfo& assetInfo,
const assets:: RenderAssetInstanceCreationInfo& creation)
Load and add a render asset instance to the current scene graph(s).
Parameters | |
---|---|
assetInfo | the asset to load |
creation | how to create the instance |
std:: vector<std:: string> esp:: sim:: Simulator:: getRuntimePerfStatNames()
Runtime perf stats are various scalars helpful for troubleshooting runtime perf.
Returns | A vector of stat names; currently, this is constant so it can be called once at startup. See also getRuntimePerfStatValues. |
---|
std:: vector<float> esp:: sim:: Simulator:: getRuntimePerfStatValues()
Runtime perf stats are various scalars helpful for troubleshooting runtime perf.
Returns | a vector of stat values. Stat values generally change after every physics step. See also getRuntimePerfStatNames. |
---|
bool esp:: sim:: Simulator:: createSceneInstance(const std:: string& activeSceneName) protected
Builds a scene instance and populates it with initial object layout, if appropriate, based on esp::activeSceneName
.
Parameters | |
---|---|
activeSceneName | The name of the desired SceneInstanceAttributes to use to instantiate a scene. |
Returns | Whether successful or not. |
bool esp:: sim:: Simulator:: instanceStageForSceneAttributes(const metadata::attributes::SceneInstanceAttributes::cptr& curSceneInstanceAttributes,
const std:: shared_ptr<esp:: metadata:: attributes:: SemanticAttributes>& semanticAttr) protected
Instance the stage for the current scene based on curSceneInstanceAttributes_, the currently active scene's esp::
Parameters | |
---|---|
curSceneInstanceAttributes | The attributes describing the current scene instance. |
semanticAttr | |
Returns | whether stage creation is completed successfully |
bool esp:: sim:: Simulator:: instanceObjectsForSceneAttributes(const metadata::attributes::SceneInstanceAttributes::cptr& curSceneInstanceAttributes) protected
Instance all the objects in the scene based on curSceneInstanceAttributes_, the currently active scene's esp::
Parameters | |
---|---|
curSceneInstanceAttributes | The attributes describing the current scene instance. |
Returns | whether object creation and placement is completed successfully |
bool esp:: sim:: Simulator:: instanceArticulatedObjectsForSceneAttributes(const metadata::attributes::SceneInstanceAttributes::cptr& curSceneInstanceAttributes) protected
Instance all the articulated objects in the scene based on curSceneInstanceAttributes_, the currently active scene's esp::
Parameters | |
---|---|
curSceneInstanceAttributes | The attributes describing the current scene instance. |
Returns | whether articulated object creation and placement is completed successfully |