Classes
- namespace Eigen
-
namespace esp Root namespace.
- namespace agent Agent library.
-
namespace assets Assets library.
- struct Asset Wrapper for all valid asset types.
- struct AssetInfo AssetInfo stores information necessary to identify and load an Asset.
- class BaseMesh Base class for storing mesh asset data including geometry and topology.
- struct CollisionMeshData Provides references to geometry and topology for an individual component of an asset for use in generating collision shapes for simulation.
-
class GenericMeshData Mesh data storage and loading for gltf format assets. See ResourceManager::
loadMeshes. - struct RenderingBuffer Stores render data for the mesh necessary for gltf format.
-
class GenericSemanticMeshData Mesh data storage and loading for ply format assets used primarily for Semantic Scene meshes, including manage vertex colors and vertex IDs for semantic visualization and rendering.
- class PerPartitionIdMeshBuilder This class is intended to provide a concise interface to build the appropriate mesh data.
- struct RenderingBuffer Stores render data for the mesh.
- struct MeshData Raw mesh data storage.
- struct MeshMetaData Stores meta data for an asset possibly containing multiple meshes, materials, textures, and a hierarchy of component transform relationships.
- struct MeshTransformNode Stores meta data for objects with a multi-component transformation hierarchy.
- struct PhongMaterialColor stores basic Phong compatible color properties for procedural override material construction
- struct RenderAssetInstanceCreationInfo
-
class ResourceManager Singleton class responsible for loading and managing common simulator assets such as meshes, textures, and materials.
- struct LoadedAssetData Data for a loaded asset.
- struct StaticDrawableInfo
- class RigManager Tracks the rig instances in a simulator (skinned articulated objects).
-
namespace core Core Habitat functionality.
-
namespace config Configuration functionality.
- class Configuration This class holds Configuration data in a map of ConfigValues, and also supports nested Configurations via a map of smart pointers to this type.
- class ConfigValue This class uses an anonymous tagged union to store values of different types, as well as providing access to the values in a type safe manner.
-
namespace managedContainers
- class AbstractFileBasedManagedObject
- class AbstractManagedObject This abstract base class provides the interface of expected functionality for an object to be manageable by esp::
core:: managedContainers:: ManagedContainer class template specializations. Any class that inherits from this class properly can be managed by a esp:: core:: managedContainers:: ManagedContainer specialization. - class ManagedContainer Class template defining responsibilities and functionality for managing esp::
core:: managedContainers:: AbstractManagedObject constructs. - class ManagedContainerBase Base class of Managed Container, holding template-type-independent functionality.
- class ManagedFileBasedContainer Class template defining file-io-based responsibilities and functionality for managing esp::
core:: managedContainers:: AbstractFileBasedManagedObject constructs.
- class Buffer A class act as a data buffer.
- class Random
- struct RigidState describes the state of a rigid object as a composition of rotation (quaternion) and translation.
-
namespace config Configuration functionality.
-
namespace geo
- class CoordinateFrame
- class OBB
- struct Ray
-
namespace gfx GFX library.
- namespace CubeMapShaderBaseTexUnitSpace
- namespace pbrTextureUnitSpace
-
namespace replay
- class AbstractPlayerImplementation Backend implementation for Player.
- class AbstractSceneGraphPlayerImplementation Classic scene graph backend implementation for Player.
- struct CreationRecord
- struct InstanceMetadata Metadata associated with an instance.
- struct Keyframe A serialization/replay-friendly render keyframe class. See Recorder.
- class Player Playback for "render replay".
-
class Recorder Recording for "render replay".
- struct InstanceRecord
- struct RenderAssetInstanceState The dynamic state of a render instance that is tracked by the replay system every frame.
- class ReplayManager Helper class for the replay python bindings (GfxReplayBindings.cpp)
- struct RigCreation Definition of a rigged articulated object.
- struct RigUpdate The dynamic state of a rigged articulated object that is tracked by the replay system every frame.
- struct Transform serialization/replay-friendly Transform class
- class CubeMap
- class CubeMapCamera
- class CubeMapShaderBase
-
class DebugLineRender Singleton utility class for on-the-fly rendering of lines (e.g. every frame). This is intended for debugging or simple UX for prototype apps. The API prioritizes ease-of-use over maximum runtime performance.
- struct GLResourceSet
- struct VertexRecord
- class DoubleSphereCameraShader
- class Drawable Drawable for use with DrawableGroup.
- class DrawableConfiguration
- class DrawableGroup Group of drawables, and shared group parameters.
- class EquirectangularShader
- class GaussianFilterShader A shader to visualize the depth buffer information.
-
class GenericDrawable
- struct GenericMaterialCache
- struct InstanceSkinData Stores skinning data for an instance. Contains association information of graphics bones and articulated object links.
- struct LightInfo Contains a single light's information.
- class MeshVisualizerDrawable
-
class PbrDrawable
-
struct PBRMaterialCache
- struct AnisotropyLayer
- struct ClearCoat
- struct SpecularLayer
- struct TransmissionLayer
- struct VolumeLayer
- struct PBRShaderConfig
-
struct PBRMaterialCache
- class PbrEquiRectangularToCubeMapShader a shader to convert a HDRi image (the environment map in equirectangular form) to a cubemap
- class PbrIBLHelper This class performs 2 functions. It derives the Irradiance and Precomputed Cubemaps based on an Enironment map texture, and it provides references to all the assets that are then consumed by the PBR shader for IBL functionality.
- class PbrPrecomputedMapShader A shader to output the irradiance map, applied in the IBL diffuse part, or the prefiltered environment map, applied in the IBL specular part, based on the user setting.
-
class PbrShader
- class Configuration PBR Shader configuration.
- struct PbrEquationScales
- class RenderCamera
- class Renderer
- class RenderTarget
- struct Rig Contains the nodes that control the articulations of a skinned model instance.
- struct SkinData Stores skinning data for an asset.
- class TextureVisualizerShader A shader to visualize the depth buffer information.
- class WindowlessContext
-
namespace gfx_batch Batch renderer.
- class DepthShader Depth-only shader.
- class Hbao
- class HbaoConfiguration
- class Renderer Batch renderer.
- struct RendererConfiguration Global renderer configuration.
- class RendererStandalone Standalone batch renderer.
- struct RendererStandaloneConfiguration Global standalone renderer configuration.
- struct SceneStats Statistics for a single renderer scene.
- namespace io
-
namespace logging logging library
-
namespace impl
- class LogMessageVoidify
- class LoggingContext Logging context that tracks which logging statements are enabled.
-
namespace impl
-
namespace metadata Metadata management.
-
namespace attributes Metadata Attributes library.
- class AbstractAttributes Base class for all implemented attributes. Inherits from esp::
core:: managedContainers:: AbstractFileBasedManagedObject so the attributes can be managed by a esp:: core:: managedContainers:: ManagedContainer. - class AbstractObjectAttributes base attributes object holding attributes shared by all esp::
metadata:: attributes:: ObjectAttributes and esp:: metadata:: attributes:: StageAttributes objects; Should be treated as abstract - should never be instanced directly - class AbstractPrimitiveAttributes
- class ArticulatedObjectAttributes attributes class describing essential and default quantities used to instantiate an Articulated object
- class CapsulePrimitiveAttributes attributes describing primitive capsule objects
- class ConePrimitiveAttributes
- class CubePrimitiveAttributes
- class CylinderPrimitiveAttributes
- class IcospherePrimitiveAttributes
- class LightInstanceAttributes This class describes an instance of a light - its template name, location/direction, color, intensity, type and other parameters if appropriate.
- class LightLayoutAttributes This class describes a lighting layout, consisting of a series of lights.
- class LinkSet This class provides an alias for the nested Configuration tree used for a single link's 1 or more MarkerSets that should be attached to the named link.
- class MarkerSet This class provides an alias for a single Configuration holding 1 or more marker points within a particular LinkSet.
- class MarkerSets This class provides an alias for the nested Configuration tree used to hold multiple TaskSets.
- class ObjectAttributes Specific Attributes instance describing a rigid object, constructed with a default set of object-specific required attributes.
- class PbrShaderAttributes attributes class describing essential and default quantities and settings for configuring PBR shader calculations.
- class PhysicsManagerAttributes attributes class describing essential and default quantities used to instantiate a physics manager.
- class SceneAOInstanceAttributes This class describes an instance of an articulated object in a scene.
- class SceneDatasetAttributes
- class SceneInstanceAttributes
- class SceneObjectInstanceAttributes This class describes an instance of a stage, object or articulated object in a scene - its template name, translation from the origin, rotation, motiontype, and other values required to instantiate the construct described.
- class SemanticAttributes This class describes the semantic attributes for a specific scene. This includes semantic region description and annotation.
- class SemanticVolumeAttributes This class describes the attributes describing some Semantic Volume. Currently only used for region annotations.
- class StageAttributes Specific Attributes instance describing a rigid stage, constructed with a default set of stage-specific required attributes.
- class TaskSet This class provides an alias for the nested Configuration tree used for a single TaskSet, holding 1 or more LinkSets.
- class UVSpherePrimitiveAttributes
- class AbstractAttributes Base class for all implemented attributes. Inherits from esp::
-
namespace managers Metadata Attribute Managers library.
- class AbstractAttributesManager Class template defining responsibilities and functionality for managing esp::
metadata:: attributes:: AbstractAttributes constructs. - class AbstractObjectAttributesManager Class template defining responsibilities and functionality for managing esp::
metadata:: attributes:: AbstractObjectAttributes constructs. - class AOAttributesManager
- class AssetAttributesManager
- class LightLayoutAttributesManager
- class ObjectAttributesManager single instance class managing templates describing physical objects
- class PbrShaderAttributesManager
- class PhysicsAttributesManager
- class SceneDatasetAttributesManager
- class SceneInstanceAttributesManager
- class SemanticAttributesManager
- class StageAttributesManager
- class AbstractAttributesManager Class template defining responsibilities and functionality for managing esp::
-
namespace URDF URDF parsing library.
- struct CollisionShape Parsed from a URDF link collision shape (<collision>)
- struct Geometry
- struct Inertia
- struct Joint Parsed from a URDF joint (<joint>), connects two links.
- struct Link
- struct LinkContactInfo
- struct Material Storage for metadata defining override materials for visual shapes.
- struct MaterialColor
- class Model
- class Parser Functional class for parsing URDF files into a URDF::Model representation.
- struct Shape Stores general properties of any shape.
- struct VisualShape Parsed from a URDF link visual shape (<visual>)
- class MetadataMediator
-
namespace attributes Metadata Attributes library.
-
namespace nav NavMesh namespace.
-
class GreedyGeodesicFollowerImpl Generates actions to take to reach a goal.
- struct TryStepResult
- struct HitRecord Struct for recording closest obstacle information.
- struct MultiGoalShortestPath Struct for multi-goal shortest path finding. Used in conjunction with PathFinder::
findPath. - struct NavMeshSettings Configuration structure for NavMesh generation with recast.
- class PathFinder Loads and/or builds a navigation mesh and then allows point sampling, path finding, collision, and island queries on that navmesh.
- struct ShortestPath Struct for shortest path finding. Used in conjunction with PathFinder::
findPath.
-
class GreedyGeodesicFollowerImpl Generates actions to take to reach a goal.
-
namespace physics Physics library.
- class AbstractManagedPhysicsObject Base class template for wrapper for physics objects of all kinds to enable Managed Container access.
- class AbstractManagedRigidBase Class template describing wrapper for RigidBase constructions. Provides bindings for all RigidBase functionality.
- class ArticulatedLink A single rigid link in a kinematic chain. Abstract class. Feature attaches to a SceneNode.
- class ArticulatedObject An articulated rigid object (i.e. kinematic chain). Abstract class to be derived by physics simulator specific implementations.
- class ArticulatedObjectManager Class template defining responsibilities and functionality shared for managing all esp::
physics:: ManagedArticulatedObject wrappers. - class BulletArticulatedLink
- class BulletArticulatedObject
- class BulletBase This class is intended to implement bullet-specific.
- class BulletCollisionHelper
- class BulletPhysicsManager Dynamic stage and object manager interfacing with Bullet physics engine: https:/
/ github.com/ bulletphysics/ bullet3. - class BulletRigidObject An individual rigid object instance implementing an interface with Bullet physics to enable dynamic objects. See btRigidBody.
- class BulletRigidStage An individual rigid stage instance implementing an interface with Bullet physics to enable dynamics. See btCollisionObject.
- class BulletURDFImporter Derived importer class for loading URDF into Bullet physics.
- struct childParentIndex struct to encapsulate mapping between child and parent links ids.
- class CollisionGroupHelper A convenience class with all static functions providing an interface for customizing collision masking behavior for simulated objects.
- struct ContactPointData based on Bullet b3ContactPointData
- struct JointLimitConstraintInfo Structure to hold joint limit constraint info during construction.
- struct JointMotor A general wrapper class for JointMotor (e.g. PD control) implementation.
- struct JointMotorSettings Stores JointMotor (i.e. per-DoF PD control) parameters for creation and updates.
- class ManagedArticulatedObject Class describing wrapper for ArticulatedObject constructions. Provides bindings for all ArticulatedObject-specific functionality.
- class ManagedBulletArticulatedObject Class describing wrapper for dynamic ArticulatedObject constructions using the Bullet library. Provides bindings for all ArticulatedObject-specific functionality.
- class ManagedBulletRigidObject Class describing wrapper for RigidObject constructions. Provides bindings for all RigidObject-specific functionality.
- class ManagedRigidObject Class describing wrapper for RigidObject constructions. Provides bindings for all RigidObject-specific functionality.
- class PhysicsManager Kinematic and dynamic scene and object manager. Responsible for tracking, updating, and synchronizing the state of the physical world and all non-static geometry in the scene as well as interfacing with specific physical simulation implementations.
- class PhysicsObjectBase
- class PhysicsObjectBaseManager Class template defining responsibilities and functionality for managineg object wrappers specializing esp::
physics:: AbstractManagedPhysicsObject template. - struct RaycastResults Holds information about all ray hit instances from a ray cast.
- struct RayHitInfo Holds information about one ray hit instance.
- class RigidBase This class specifies the functionality expected of rigid objects and stages, particularly with regard to dynamic simulation, if such a library, such as bullet, is available.
- class RigidBaseManager Class template defining responsibilities and functionality shared for managing all esp::
physics:: AbstractManagedRigidBase wrappers. - struct RigidConstraintSettings Stores rigid constraint parameters for creation and updates.
- class RigidObject A RigidBase representing an individual rigid object instance attached to a SceneNode, updating its state through simulation. This may be a esp::
physics:: MotionType:: STATIC scene collision geometry or an object of any MotionType which can interact with other members of a physical world. Must have a collision mesh. By default, a RigidObject is MotionType:: KINEMATIC without an underlying simulator implementation. Derived classes can be used to introduce specific implementations of dynamics. - class RigidObjectManager Class template defining responsibilities and functionality shared for managing all esp::
physics:: ManagedRigidObject wrappers. - class RigidStage A RigidBase representing an individual rigid stage instance attached to a SceneNode. This construction currently may only be esp::
physics:: MotionType:: STATIC. - struct SimulationContactResultCallback Implements Bullet physics btCollisionWorld::
ContactResultCallback interface. - class URDFImporter Virtual base class for loading URDF into various simulator implementations.
- struct URDFToBulletCached Structure to hold construction time multi-body data.
- struct VelocityControl Convenience struct for applying constant velocity control to a rigid body.
-
namespace scene
- class CCSemanticObject This class exists to facilitate semantic object data access for bboxes derived from connected component analysis.
- struct GibsonObjectCategory
- class HM3DObjectCategory
- class HM3DObjectInstance
- class LoopRegionCategory
- struct Mp3dObjectCategory
- struct Mp3dRegionCategory
- struct ReplicaObjectCategory
- class SceneGraph
- class SceneManager
- class SceneNode
- class SemanticCategory Represents a semantic category.
- class SemanticLevel Represents a level of a SemanticScene.
- class SemanticObject Represents a distinct semantically annotated object.
- class SemanticRegion Represents a region (typically room) in a level of a house.
- class SemanticScene
-
namespace sensor
- class AudioEmptyStubChannelLayoutClass
- class AudioEmptyStubConfigurationClass
- class AudioSensor
- struct AudioSensorSpec
- class CameraSensor
- struct CameraSensorSpec
- class CubeMapSensorBase
- struct CubeMapSensorBaseSpec
- class EquirectangularSensor
- struct EquirectangularSensorSpec
- class FisheyeSensor
- struct FisheyeSensorDoubleSphereSpec
- struct FisheyeSensorSpec
- struct Observation
- struct ObservationSpace
- struct RedwoodNoiseModelGPUImpl
- class Sensor
- class SensorFactory
- struct SensorSpec
- class SensorSuite
- class VisualSensor
- struct VisualSensorSpec
-
namespace sim core physics simulation namespace
- class AbstractReplayRenderer
- class BatchPlayerImplementation
-
class BatchReplayRenderer
- struct EnvironmentRecord
-
class ClassicReplayRenderer
- struct EnvironmentRecord
- class ReplayRendererConfiguration
- class Simulator
- struct SimulatorConfiguration Class to hold configuration for a simulator.
- struct EnableIfT
- struct EnableIfT<true, T>
-
namespace spimpl
-
namespace details
- struct default_copier
- struct default_deleter
- struct is_default_manageable
-
class impl_ptr
- struct dummy_t_
-
namespace details
- namespace tinyxml2