Scene manager class for loading and managing objects in the scene. More...
#include <SceneManager.hh>
Public Member Functions | |
SceneManager () | |
Constructor. More... | |
~SceneManager () | |
Destructor. More... | |
AnimationUpdateData | ActorAnimationAt (Entity _id, std::chrono::steady_clock::duration _time) const |
Get the actor animation update data given an id. Use this function to let the render engine handle the actor animation. by setting the animation name to be played. More... | |
rendering::MeshPtr | ActorMeshById (Entity _id) const |
Get a rendering mesh given an id. More... | |
common::SkeletonPtr | ActorSkeletonById (Entity _id) const |
Get a skeleton given an id. More... | |
std::map< std::string, math::Matrix4d > | ActorSkeletonTransformsAt (Entity _id, std::chrono::steady_clock::duration _time) const |
Get the skeleton local transforms of actor mesh given an id. Use this function if you are animating the actor manually by its skeleton node pose. More... | |
bool | AddSensor (Entity _simId, const std::string &_sensorName, Entity _parentGazeboId=0) |
Gazebo Sensors is the one responsible for adding sensors to the scene. Here we just keep track of it and make sure it has the correct parent. More... | |
void | Clear () |
Clear the scene manager Clears internal resources stored in the scene manager. Note: this does not actually destroy the objects. More... | |
std::pair< rendering::VisualPtr, std::vector< Entity > > | CopyVisual (Entity _id, const std::string &_visual, Entity _parentId=0) |
Copy a visual that currently exists in the scene. More... | |
rendering::VisualPtr | CreateActor (Entity _id, const sdf::Actor &_actor, const std::string &_name, Entity _parentId=0) |
Create an actor. More... | |
rendering::VisualPtr | CreateCollision (Entity _id, const sdf::Collision &_collision, Entity _parentId=0) |
Create a collision visual. More... | |
rendering::VisualPtr | CreateCOMVisual (Entity _id, const math::Inertiald &_inertial, Entity _parentId=0) |
Create a center of mass visual. More... | |
rendering::VisualPtr | CreateInertiaVisual (Entity _id, const math::Inertiald &_inertial, Entity _parentId=0) |
Create an inertia visual. More... | |
rendering::VisualPtr | CreateJointVisual (Entity _id, const sdf::Joint &_joint, Entity _childId=0, Entity _parentId=0) |
Create a joint visual. More... | |
rendering::LightPtr | CreateLight (Entity _id, const sdf::Light &_light, const std::string &_name, Entity _parentId) |
Create a light. More... | |
rendering::VisualPtr | CreateLightVisual (Entity _id, const sdf::Light &_light, const std::string &_name, Entity _parentId) |
Create a light. More... | |
rendering::VisualPtr | CreateLink (Entity _id, const sdf::Link &_link, Entity _parentId=0) |
Create a link. More... | |
rendering::VisualPtr | CreateModel (Entity _id, const sdf::Model &_model, Entity _parentId=0) |
Create a model. More... | |
rendering::ParticleEmitterPtr | CreateParticleEmitter (Entity _id, const msgs::ParticleEmitter &_emitter, Entity _parentId) |
Create a particle emitter. More... | |
rendering::ProjectorPtr | CreateProjector (Entity _id, const sdf::Projector &_projector, Entity _parentId) |
Create a projector. More... | |
rendering::VisualPtr | CreateVisual (Entity _id, const sdf::Visual &_visual, Entity _parentId=0) |
Create a visual. More... | |
std::vector< rendering::NodePtr > | Filter (const std::string &_node, std::function< bool(const rendering::NodePtr _nodeToFilter)> _filter) const |
Filter a node and its children according to specific criteria. More... | |
bool | HasEntity (Entity _id) const |
Check if entity exists. More... | |
std::unordered_map< std::string, unsigned int > | LoadAnimations (const sdf::Actor &_actor) |
Load Actor animations. More... | |
rendering::NodePtr | NodeById (Entity _id) const |
Get a rendering node given an entity id. More... | |
void | RemoveEntity (Entity _id) |
Remove an entity by id. More... | |
rendering::ScenePtr | Scene () const |
Get the scene. More... | |
void | SequenceTrajectories (std::vector< common::TrajectoryInfo > &_trajectories, std::chrono::steady_clock::time_point _time) |
Sequences Trajectories. More... | |
void | SetScene (rendering::ScenePtr _scene) |
Set the scene to manage. More... | |
void | SetSphericalCoordinates (const math::SphericalCoordinates &_sphericalCoordinates) |
Set the spherical coordinates from world. More... | |
void | SetWorldId (Entity _id) |
Set the world's ID. More... | |
rendering::NodePtr | TopLevelNode (const rendering::NodePtr &_node) const |
Get the top level node for the given node, which is the ancestor which is a direct child to the root visual. Usually, this will be a model or a light. More... | |
rendering::VisualPtr | TopLevelVisual (const rendering::VisualPtr &_visual) const |
Get the top level visual for the given visual, which is the ancestor which is a direct child to the root visual. Usually, this will be a model or a light. More... | |
Entity | UniqueId () const |
Create a unique entity ID. More... | |
void | UpdateJointParentPose (Entity _jointId) |
Updates the world pose of joint parent visual according to its child. More... | |
rendering::ParticleEmitterPtr | UpdateParticleEmitter (Entity _id, const msgs::ParticleEmitter &_emitter) |
Update an existing particle emitter. More... | |
void | UpdateTransparency (const rendering::NodePtr &_node, bool _makeTransparent) |
Updates the node to increase its transparency or reset back to its original transparency value, an opaque call requires a previous transparent call, otherwise, no action will be taken Usually, this will be a link visual. More... | |
rendering::VisualPtr | VisualById (Entity _id) |
Retrieve visual. More... | |
Entity | WorldId () const |
Get the world's ID. More... | |
Detailed Description
Scene manager class for loading and managing objects in the scene.
Constructor & Destructor Documentation
◆ SceneManager()
SceneManager | ( | ) |
Constructor.
◆ ~SceneManager()
~SceneManager | ( | ) |
Destructor.
Member Function Documentation
◆ ActorAnimationAt()
AnimationUpdateData ActorAnimationAt | ( | Entity | _id, |
std::chrono::steady_clock::duration | _time | ||
) | const |
Get the actor animation update data given an id. Use this function to let the render engine handle the actor animation. by setting the animation name to be played.
- Parameters
-
[in] _id Entity's unique id [in] _time Simulation time
- Returns
- Data needed to update the animation, including the name and time of animation to play, and trajectory animation info.
◆ ActorMeshById()
rendering::MeshPtr ActorMeshById | ( | Entity | _id | ) | const |
Get a rendering mesh given an id.
- Parameters
-
[in] _id Actor entity's unique id
- Returns
- Pointer to requested entity's mesh
◆ ActorSkeletonById()
common::SkeletonPtr ActorSkeletonById | ( | Entity | _id | ) | const |
Get a skeleton given an id.
- Parameters
-
[in] _id Actor entity's unique id
- Returns
- Pointer to requested entity's skeleton
◆ ActorSkeletonTransformsAt()
std::map<std::string, math::Matrix4d> ActorSkeletonTransformsAt | ( | Entity | _id, |
std::chrono::steady_clock::duration | _time | ||
) | const |
Get the skeleton local transforms of actor mesh given an id. Use this function if you are animating the actor manually by its skeleton node pose.
- Parameters
-
[in] _id Entity's unique id [in] _time SimulationTime
- Returns
- Map from the skeleton node name to transforms
◆ AddSensor()
bool AddSensor | ( | Entity | _simId, |
const std::string & | _sensorName, | ||
Entity | _parentGazeboId = 0 |
||
) |
Gazebo Sensors is the one responsible for adding sensors to the scene. Here we just keep track of it and make sure it has the correct parent.
- Parameters
-
[in] _simId Entity in Sim [in] _sensorName Name of sensor node in Gazebo Rendering. [in] _parentGazeboId Parent Id on Gazebo.
- Returns
- True if sensor is successfully handled
◆ Clear()
void Clear | ( | ) |
Clear the scene manager Clears internal resources stored in the scene manager. Note: this does not actually destroy the objects.
◆ CopyVisual()
std::pair<rendering::VisualPtr, std::vector<Entity> > CopyVisual | ( | Entity | _id, |
const std::string & | _visual, | ||
Entity | _parentId = 0 |
||
) |
Copy a visual that currently exists in the scene.
- Parameters
-
[in] _id Unique visual id of the copied visual [in] _visual Name of the visual to copy [in] _parentId Parent id of the copied visual
- Returns
- A pair with the first element being the copied visual object, and the second element being a list of the entity IDs for the copied visual's children, in level order. If copying the visual failed, the first element will be nullptr. If the copied visual has no children, the second element will be empty.
◆ CreateActor()
rendering::VisualPtr CreateActor | ( | Entity | _id, |
const sdf::Actor & | _actor, | ||
const std::string & | _name, | ||
Entity | _parentId = 0 |
||
) |
◆ CreateCollision()
rendering::VisualPtr CreateCollision | ( | Entity | _id, |
const sdf::Collision & | _collision, | ||
Entity | _parentId = 0 |
||
) |
Create a collision visual.
- Parameters
-
[in] _id Unique visual id [in] _collision Collision sdf dom [in] _parentId Parent id
- Returns
- Visual (collision) object created from the sdf dom
◆ CreateCOMVisual()
rendering::VisualPtr CreateCOMVisual | ( | Entity | _id, |
const math::Inertiald & | _inertial, | ||
Entity | _parentId = 0 |
||
) |
Create a center of mass visual.
- Parameters
-
[in] _id Unique visual id [in] _inertial Inertial component of the link [in] _parentId Parent id
- Returns
- Visual (center of mass) object created from the inertial
◆ CreateInertiaVisual()
rendering::VisualPtr CreateInertiaVisual | ( | Entity | _id, |
const math::Inertiald & | _inertial, | ||
Entity | _parentId = 0 |
||
) |
Create an inertia visual.
- Parameters
-
[in] _id Unique visual id [in] _inertial Inertial component of the link [in] _parentId Parent id
- Returns
- Visual (inertia) object created from the inertial
◆ CreateJointVisual()
◆ CreateLight()
rendering::LightPtr CreateLight | ( | Entity | _id, |
const sdf::Light & | _light, | ||
const std::string & | _name, | ||
Entity | _parentId | ||
) |
◆ CreateLightVisual()
rendering::VisualPtr CreateLightVisual | ( | Entity | _id, |
const sdf::Light & | _light, | ||
const std::string & | _name, | ||
Entity | _parentId | ||
) |
◆ CreateLink()
◆ CreateModel()
◆ CreateParticleEmitter()
rendering::ParticleEmitterPtr CreateParticleEmitter | ( | Entity | _id, |
const msgs::ParticleEmitter & | _emitter, | ||
Entity | _parentId | ||
) |
Create a particle emitter.
- Parameters
-
[in] _id Unique particle emitter id [in] _emitter Particle emitter data [in] _parentId Parent id
- Returns
- Default particle emitter object created
◆ CreateProjector()
rendering::ProjectorPtr CreateProjector | ( | Entity | _id, |
const sdf::Projector & | _projector, | ||
Entity | _parentId | ||
) |
Create a projector.
- Parameters
-
[in] _id Unique projector id [in] _projector Projector sdf dom [in] _parentId Parent id
- Returns
- Projector object created from the sdf dom
◆ CreateVisual()
Create a visual.
- Parameters
-
[in] _id Unique visual id [in] _visual Visual sdf dom [in] _parentId Parent id
- Returns
- Visual object created from the sdf dom
◆ Filter()
std::vector<rendering::NodePtr> Filter | ( | const std::string & | _node, |
std::function< bool(const rendering::NodePtr _nodeToFilter)> | _filter | ||
) | const |
Filter a node and its children according to specific criteria.
- Parameters
-
[in] _node The name of the node where filtering should start. [in] _filter Callback function that defines how _node and its children should be filtered. The function parameter is a node. The callback returns true if the node should be filtered; false otherwise.
- Returns
- A list of filtered nodes in top level order. This list can contain _node itself, or child nodes of _node. An empty list means no nodes were filtered.
◆ HasEntity()
bool HasEntity | ( | Entity | _id | ) | const |
Check if entity exists.
- Parameters
-
[in] _id Unique entity id
- Returns
- true if exists, false otherwise
◆ LoadAnimations()
std::unordered_map<std::string, unsigned int> LoadAnimations | ( | const sdf::Actor & | _actor | ) |
◆ NodeById()
rendering::NodePtr NodeById | ( | Entity | _id | ) | const |
Get a rendering node given an entity id.
- Parameters
-
[in] _id Entity's unique id
- Returns
- Pointer to requested entity's node
◆ RemoveEntity()
void RemoveEntity | ( | Entity | _id | ) |
Remove an entity by id.
- Parameters
-
[in] _id Entity's unique id
◆ Scene()
rendering::ScenePtr Scene | ( | ) | const |
Get the scene.
- Returns
- Pointer to scene
◆ SequenceTrajectories()
void SequenceTrajectories | ( | std::vector< common::TrajectoryInfo > & | _trajectories, |
std::chrono::steady_clock::time_point | _time | ||
) |
◆ SetScene()
void SetScene | ( | rendering::ScenePtr | _scene | ) |
Set the scene to manage.
- Parameters
-
[in] _scene Scene pointer.
◆ SetSphericalCoordinates()
void SetSphericalCoordinates | ( | const math::SphericalCoordinates & | _sphericalCoordinates | ) |
Set the spherical coordinates from world.
- Parameters
-
[in] _sphericalCoordinates SphericalCoordinates from the world.
◆ SetWorldId()
◆ TopLevelNode()
rendering::NodePtr TopLevelNode | ( | const rendering::NodePtr & | _node | ) | const |
Get the top level node for the given node, which is the ancestor which is a direct child to the root visual. Usually, this will be a model or a light.
- Parameters
-
[in] _node Child node
- Returns
- Top level node containing this node
◆ TopLevelVisual()
rendering::VisualPtr TopLevelVisual | ( | const rendering::VisualPtr & | _visual | ) | const |
Get the top level visual for the given visual, which is the ancestor which is a direct child to the root visual. Usually, this will be a model or a light.
- Parameters
-
[in] _visual Child visual
- Returns
- Top level visual containing this visual
◆ UniqueId()
Entity UniqueId | ( | ) | const |
Create a unique entity ID.
- Returns
- A unique entity ID. kNullEntity is returned if no unique entity IDs are available
◆ UpdateJointParentPose()
void UpdateJointParentPose | ( | Entity | _jointId | ) |
Updates the world pose of joint parent visual according to its child.
- Parameters
-
[in] _jointId Joint visual id.
◆ UpdateParticleEmitter()
rendering::ParticleEmitterPtr UpdateParticleEmitter | ( | Entity | _id, |
const msgs::ParticleEmitter & | _emitter | ||
) |
Update an existing particle emitter.
_id Emitter id to update
_emitter Data to update the particle emitter
- Returns
- Particle emitter updated
◆ UpdateTransparency()
void UpdateTransparency | ( | const rendering::NodePtr & | _node, |
bool | _makeTransparent | ||
) |
Updates the node to increase its transparency or reset back to its original transparency value, an opaque call requires a previous transparent call, otherwise, no action will be taken Usually, this will be a link visual.
- Parameters
-
[in] _node The node to update. [in] _makeTransparent true if updating to increase transparency, false to set back to original transparency values (make more opaque)
◆ VisualById()
rendering::VisualPtr VisualById | ( | Entity | _id | ) |
Retrieve visual.
- Parameters
-
[in] _id Unique visual (entity) id
- Returns
- Pointer to requested visual
◆ WorldId()
The documentation for this class was generated from the following file: