Public Member Functions | Protected Attributes | List of all members
gazebo::physics::Actor Class Reference

Actor class enables GPU based mesh model / skeleton scriptable animation. More...

#include <physics/physics.hh>

Inheritance diagram for gazebo::physics::Actor:
Inheritance graph
[legend]

Public Member Functions

 Actor (BasePtr _parent)
 Constructor. More...
 
virtual ~Actor ()
 Destructor. More...
 
virtual void Fini ()
 Finalize the actor. More...
 
virtual const sdf::ElementPtr GetSDF ()
 Get the SDF values for the actor. More...
 
virtual void Init ()
 Initialize the actor. More...
 
virtual bool IsActive ()
 Returns true when actor is playing animation. More...
 
void Load (sdf::ElementPtr _sdf)
 Load the actor. More...
 
virtual void Play ()
 Start playing the script. More...
 
virtual void Stop ()
 Stop playing the script. More...
 
void Update ()
 Update the actor. More...
 
virtual void UpdateParameters (sdf::ElementPtr _sdf)
 update the parameters using new sdf values. More...
 
- Public Member Functions inherited from gazebo::physics::Model
 Model (BasePtr _parent)
 Constructor. More...
 
virtual ~Model ()
 Destructor. More...
 
void AttachStaticModel (ModelPtr &_model, math::Pose _offset)
 Attach a static model to this model. More...
 
void DetachStaticModel (const std::string &_model)
 Detach a static model from this model. More...
 
virtual void FillMsg (msgs::Model &_msg)
 Fill a model message. More...
 
bool GetAutoDisable () const
 Return the value of the SDF <allow_auto_disable> element. More...
 
virtual math::Box GetBoundingBox () const
 Get the size of the bounding box. More...
 
GripperPtr GetGripper (size_t _index) const
 Get a gripper based on an index. More...
 
size_t GetGripperCount () const
 Get the number of grippers in this model. More...
 
JointPtr GetJoint (const std::string &name)
 Get a joint. More...
 
JointControllerPtr GetJointController ()
 Get a handle to the Controller for the joints in this model. More...
 
unsigned int GetJointCount () const
 Get the number of joints. More...
 
const Joint_VGetJoints () const
 Get the joints. More...
 
LinkPtr GetLink (const std::string &_name="canonical") const
 Get a link by name. More...
 
const Link_VGetLinks () const
 Construct and return a vector of Link's in this model Note this constructs the vector of Link's on the fly, could be costly. More...
 
unsigned int GetPluginCount () const
 Get the number of plugins this model has. More...
 
virtual math::Vector3 GetRelativeAngularAccel () const
 Get the angular acceleration of the entity. More...
 
virtual math::Vector3 GetRelativeAngularVel () const
 Get the angular velocity of the entity. More...
 
virtual math::Vector3 GetRelativeLinearAccel () const
 Get the linear acceleration of the entity. More...
 
virtual math::Vector3 GetRelativeLinearVel () const
 Get the linear velocity of the entity. More...
 
unsigned int GetSensorCount () const
 Get the number of sensors attached to this model. More...
 
virtual math::Vector3 GetWorldAngularAccel () const
 Get the angular acceleration of the entity in the world frame. More...
 
virtual math::Vector3 GetWorldAngularVel () const
 Get the angular velocity of the entity in the world frame. More...
 
double GetWorldEnergy () const
 Returns this model's total energy, or sum of Model::GetWorldEnergyPotential() and Model::GetWorldEnergyKinetic(). More...
 
double GetWorldEnergyKinetic () const
 Returns sum of the kinetic energies of all links in this model. More...
 
double GetWorldEnergyPotential () const
 Returns the potential energy of all links and joint springs in the model. More...
 
virtual math::Vector3 GetWorldLinearAccel () const
 Get the linear acceleration of the entity in the world frame. More...
 
virtual math::Vector3 GetWorldLinearVel () const
 Get the linear velocity of the entity in the world frame. More...
 
void Load (sdf::ElementPtr _sdf)
 Load the model. More...
 
void LoadJoints ()
 Load all the joints. More...
 
void LoadPlugins ()
 Load all plugins. More...
 
void ProcessMsg (const msgs::Model &_msg)
 Update parameters from a model message. More...
 
virtual void RemoveChild (EntityPtr _child)
 Remove a child. More...
 
void Reset ()
 Reset the model. More...
 
void ResetPhysicsStates ()
 Reset the velocity, acceleration, force and torque of all child links. More...
 
void SetAngularAccel (const math::Vector3 &_vel)
 Set the angular acceleration of the model, and all its links. More...
 
void SetAngularVel (const math::Vector3 &_vel)
 Set the angular velocity of the model, and all its links. More...
 
void SetAutoDisable (bool _disable)
 Allow the model the auto disable. More...
 
void SetCollideMode (const std::string &_mode)
 This is not implemented in Link, which means this function doesn't do anything. More...
 
void SetEnabled (bool _enabled)
 Enable all the links in all the models. More...
 
void SetGravityMode (const bool &_value)
 Set the gravity mode of the model. More...
 
void SetJointAnimation (const std::map< std::string, common::NumericAnimationPtr > &_anims, boost::function< void()> _onComplete=NULL)
 Joint Animation. More...
 
void SetJointPosition (const std::string &_jointName, double _position, int _index=0)
 Set the positions of a Joint by name. More...
 
void SetJointPositions (const std::map< std::string, double > &_jointPositions)
 Set the positions of a set of joints. More...
 
void SetLaserRetro (const float _retro)
 Set the laser retro reflectiveness of the model. More...
 
void SetLinearAccel (const math::Vector3 &_vel)
 Set the linear acceleration of the model, and all its links. More...
 
void SetLinearVel (const math::Vector3 &_vel)
 Set the linear velocity of the model, and all its links. More...
 
void SetLinkWorldPose (const math::Pose &_pose, std::string _linkName)
 Set the Pose of the entire Model by specifying desired Pose of a Link within the Model. More...
 
void SetLinkWorldPose (const math::Pose &_pose, const LinkPtr &_link)
 Set the Pose of the entire Model by specifying desired Pose of a Link within the Model. More...
 
void SetScale (const math::Vector3 &_scale)
 Set the scale of model. More...
 
void SetState (const ModelState &_state)
 Set the current model state. More...
 
virtual void StopAnimation ()
 Stop the current animations. More...
 
void Update ()
 Update the model. More...
 
- Public Member Functions inherited from gazebo::physics::Entity
 Entity (BasePtr _parent)
 Constructor. More...
 
virtual ~Entity ()
 Destructor. More...
 
CollisionPtr GetChildCollision (const std::string &_name)
 Get a child collision entity, if one exists. More...
 
LinkPtr GetChildLink (const std::string &_name)
 Get a child linke entity, if one exists. More...
 
math::Box GetCollisionBoundingBox () const
 Returns collision bounding box. More...
 
const math::PoseGetDirtyPose () const
 Returns Entity::dirtyPose. More...
 
math::Pose GetInitialRelativePose () const
 Get the initial relative pose. More...
 
void GetNearestEntityBelow (double &_distBelow, std::string &_entityName)
 Get the distance to the nearest entity below (along the Z-axis) this entity. More...
 
ModelPtr GetParentModel ()
 Get the parent model, if one exists. More...
 
math::Pose GetRelativePose () const
 Get the pose of the entity relative to its parent. More...
 
virtual const math::PoseGetWorldPose () const
 Get the absolute pose of the entity. More...
 
bool IsCanonicalLink () const
 A helper function that checks if this is a canonical body. More...
 
bool IsStatic () const
 Return whether this entity is static. More...
 
void PlaceOnEntity (const std::string &_entityName)
 Move this entity to be ontop of another entity by name. More...
 
void PlaceOnNearestEntityBelow ()
 Move this entity to be ontop of the nearest entity below. More...
 
void SetAnimation (const common::PoseAnimationPtr &_anim, boost::function< void()> _onComplete)
 Set an animation for this entity. More...
 
void SetAnimation (common::PoseAnimationPtr _anim)
 Set an animation for this entity. More...
 
void SetCanonicalLink (bool _value)
 Set to true if this entity is a canonical link for a model. More...
 
void SetInitialRelativePose (const math::Pose &_pose)
 Set the initial pose. More...
 
virtual void SetName (const std::string &_name)
 Set the name of the entity. More...
 
void SetRelativePose (const math::Pose &_pose, bool _notify=true, bool _publish=true)
 Set the pose of the entity relative to its parent. More...
 
void SetStatic (const bool &_static)
 Set whether this entity is static: immovable. More...
 
void SetWorldPose (const math::Pose &_pose, bool _notify=true, bool _publish=true)
 Set the world pose of the entity. More...
 
void SetWorldTwist (const math::Vector3 &_linear, const math::Vector3 &_angular, bool _updateChildren=true)
 Set angular and linear rates of an physics::Entity. More...
 
- Public Member Functions inherited from gazebo::physics::Base
 Base (BasePtr _parent)
 Constructor. More...
 
virtual ~Base ()
 Destructor. More...
 
void AddChild (BasePtr _child)
 Add a child to this entity. More...
 
void AddType (EntityType _type)
 Add a type specifier. More...
 
BasePtr GetByName (const std::string &_name)
 Get by name. More...
 
BasePtr GetChild (unsigned int _i) const
 Get a child by index. More...
 
BasePtr GetChild (const std::string &_name)
 Get a child by name. More...
 
unsigned int GetChildCount () const
 Get the number of children. More...
 
uint32_t GetId () const
 Return the ID of this entity. More...
 
std::string GetName () const
 Return the name of the entity. More...
 
BasePtr GetParent () const
 Get the parent. More...
 
int GetParentId () const
 Return the ID of the parent. More...
 
bool GetSaveable () const
 Get whether the object should be "saved", when the user selects to save the world to xml. More...
 
std::string GetScopedName (bool _prependWorldName=false) const
 Return the name of this entity with the model scope model1::...::modelN::entityName. More...
 
unsigned int GetType () const
 Get the full type definition. More...
 
const WorldPtrGetWorld () const
 Get the World this object is in. More...
 
bool HasType (const EntityType &_t) const
 Returns true if this object's type definition has the given type. More...
 
bool IsSelected () const
 True if the entity is selected by the user. More...
 
bool operator== (const Base &_ent) const
 Returns true if the entities are the same. More...
 
void Print (const std::string &_prefix)
 Print this object to screen via gzmsg. More...
 
virtual void RemoveChild (unsigned int _id)
 Remove a child from this entity. More...
 
void RemoveChild (const std::string &_name)
 Remove a child by name. More...
 
void RemoveChildren ()
 Remove all children. More...
 
virtual void Reset (Base::EntityType _resetType)
 Calls recursive Reset on one of the Base::EntityType's. More...
 
void SetParent (BasePtr _parent)
 Set the parent. More...
 
void SetSaveable (bool _v)
 Set whether the object should be "saved", when the user selects to save the world to xml. More...
 
virtual bool SetSelected (bool _show)
 Set whether this entity has been selected by the user through the gui. More...
 
void SetWorld (const WorldPtr &_newWorld)
 Set the world this object belongs to. More...
 

Protected Attributes

bool active
 True if the actor is being updated. More...
 
bool autoStart
 True if the actor should start running automatically. More...
 
transport::PublisherPtr bonePosePub
 Where to send bone info. More...
 
std::map< std::string, bool > interpolateX
 True to interpolate along x direction. More...
 
math::Vector3 lastPos
 Last position of the actor. More...
 
double lastScriptTime
 Time the scipt was last updated. More...
 
unsigned int lastTraj
 THe last trajectory. More...
 
bool loop
 True if the animation should loop. More...
 
LinkPtr mainLink
 Base link. More...
 
const common::Meshmesh
 Pointer to the actor's mesh. More...
 
std::string oldAction
 THe old action. More...
 
double pathLength
 Length of the actor's path. More...
 
common::Time playStartTime
 Time when the animation was started. More...
 
common::Time prevFrameTime
 Time of the previous frame. More...
 
double scriptLength
 Time length of a scipt. More...
 
std::map< std::string,
common::SkeletonAnimation * > 
skelAnimation
 Skeleton animations. More...
 
common::Skeletonskeleton
 The actor's skeleton. More...
 
std::map< std::string,
std::map< std::string,
std::string > > 
skelNodesMap
 Skeleton to naode map. More...
 
std::string skinFile
 Filename for the skin. More...
 
double skinScale
 Scaling factor to apply to the skin. More...
 
double startDelay
 Amount of time to delay start by. More...
 
std::map< unsigned int,
common::PoseAnimation * > 
trajectories
 All the trajectories. More...
 
std::vector< TrajectoryInfotrajInfo
 Trajectory information. More...
 
uint32_t visualId
 ID for this visual. More...
 
std::string visualName
 Name of the visual. More...
 
- Protected Attributes inherited from gazebo::physics::Model
std::vector< ModelPtrattachedModels
 used by Model::AttachStaticModel More...
 
std::vector< math::PoseattachedModelsOffset
 used by Model::AttachStaticModel More...
 
transport::PublisherPtr jointPub
 Publisher for joint info. More...
 
- Protected Attributes inherited from gazebo::physics::Entity
common::PoseAnimationPtr animation
 Current pose animation. More...
 
event::ConnectionPtr animationConnection
 Connection used to update an animation. More...
 
math::Pose animationStartPose
 Start pose of an animation. More...
 
std::vector< event::ConnectionPtrconnections
 All our event connections. More...
 
math::Pose dirtyPose
 The pose set by a physics engine. More...
 
transport::NodePtr node
 Communication node. More...
 
EntityPtr parentEntity
 A helper that prevents numerous dynamic_casts. More...
 
common::Time prevAnimationTime
 Previous time an animation was updated. More...
 
transport::PublisherPtr requestPub
 Request publisher. More...
 
math::Vector3 scale
 Scale of the entity. More...
 
transport::PublisherPtr visPub
 Visual publisher. More...
 
msgs::Visual * visualMsg
 Visual message container. More...
 
math::Pose worldPose
 World pose of the entity. More...
 
- Protected Attributes inherited from gazebo::physics::Base
Base_V children
 Children of this entity. More...
 
BasePtr parent
 Parent of this entity. More...
 
sdf::ElementPtr sdf
 The SDF values for this object. More...
 
WorldPtr world
 Pointer to the world. More...
 

Additional Inherited Members

- Public Types inherited from gazebo::physics::Base
enum  EntityType {
  BASE = 0x00000000, ENTITY = 0x00000001, MODEL = 0x00000002, LINK = 0x00000004,
  COLLISION = 0x00000008, ACTOR = 0x00000016, LIGHT = 0x00000010, VISUAL = 0x00000020,
  JOINT = 0x00000040, BALL_JOINT = 0x00000080, HINGE2_JOINT = 0x00000100, HINGE_JOINT = 0x00000200,
  SLIDER_JOINT = 0x00000400, SCREW_JOINT = 0x00000800, UNIVERSAL_JOINT = 0x00001000, GEARBOX_JOINT = 0x00002000,
  SHAPE = 0x00010000, BOX_SHAPE = 0x00020000, CYLINDER_SHAPE = 0x00040000, HEIGHTMAP_SHAPE = 0x00080000,
  MAP_SHAPE = 0x00100000, MULTIRAY_SHAPE = 0x00200000, RAY_SHAPE = 0x00400000, PLANE_SHAPE = 0x00800000,
  SPHERE_SHAPE = 0x01000000, MESH_SHAPE = 0x02000000, POLYLINE_SHAPE = 0x04000000, SENSOR_COLLISION = 0x10000000
}
 Unique identifiers for all entity types. More...
 
- Protected Member Functions inherited from gazebo::physics::Model
virtual void OnPoseChange ()
 Callback when the pose of the model has been changed. More...
 
- Protected Member Functions inherited from gazebo::physics::Base
void ComputeScopedName ()
 Compute the scoped name of this object based on its parents. More...
 

Detailed Description

Actor class enables GPU based mesh model / skeleton scriptable animation.

Constructor & Destructor Documentation

gazebo::physics::Actor::Actor ( BasePtr  _parent)
explicit

Constructor.

Parameters
[in]_parentParent object
virtual gazebo::physics::Actor::~Actor ( )
virtual

Destructor.

Member Function Documentation

virtual void gazebo::physics::Actor::Fini ( )
virtual

Finalize the actor.

Reimplemented from gazebo::physics::Model.

virtual const sdf::ElementPtr gazebo::physics::Actor::GetSDF ( )
virtual

Get the SDF values for the actor.

Returns
Pointer to the SDF values.

Reimplemented from gazebo::physics::Model.

virtual void gazebo::physics::Actor::Init ( )
virtual

Initialize the actor.

Reimplemented from gazebo::physics::Model.

virtual bool gazebo::physics::Actor::IsActive ( )
virtual

Returns true when actor is playing animation.

void gazebo::physics::Actor::Load ( sdf::ElementPtr  _sdf)
virtual

Load the actor.

Parameters
[in]_sdfSDF parameters

Reimplemented from gazebo::physics::Entity.

virtual void gazebo::physics::Actor::Play ( )
virtual

Start playing the script.

virtual void gazebo::physics::Actor::Stop ( )
virtual

Stop playing the script.

void gazebo::physics::Actor::Update ( )
virtual

Update the actor.

Reimplemented from gazebo::physics::Base.

virtual void gazebo::physics::Actor::UpdateParameters ( sdf::ElementPtr  _sdf)
virtual

update the parameters using new sdf values.

Parameters
[in]_sdfSDF values to update from.

Reimplemented from gazebo::physics::Model.

Member Data Documentation

bool gazebo::physics::Actor::active
protected

True if the actor is being updated.

bool gazebo::physics::Actor::autoStart
protected

True if the actor should start running automatically.

transport::PublisherPtr gazebo::physics::Actor::bonePosePub
protected

Where to send bone info.

std::map<std::string, bool> gazebo::physics::Actor::interpolateX
protected

True to interpolate along x direction.

math::Vector3 gazebo::physics::Actor::lastPos
protected

Last position of the actor.

double gazebo::physics::Actor::lastScriptTime
protected

Time the scipt was last updated.

unsigned int gazebo::physics::Actor::lastTraj
protected

THe last trajectory.

bool gazebo::physics::Actor::loop
protected

True if the animation should loop.

LinkPtr gazebo::physics::Actor::mainLink
protected

Base link.

const common::Mesh* gazebo::physics::Actor::mesh
protected

Pointer to the actor's mesh.

std::string gazebo::physics::Actor::oldAction
protected

THe old action.

double gazebo::physics::Actor::pathLength
protected

Length of the actor's path.

common::Time gazebo::physics::Actor::playStartTime
protected

Time when the animation was started.

common::Time gazebo::physics::Actor::prevFrameTime
protected

Time of the previous frame.

double gazebo::physics::Actor::scriptLength
protected

Time length of a scipt.

std::map<std::string, common::SkeletonAnimation*> gazebo::physics::Actor::skelAnimation
protected

Skeleton animations.

common::Skeleton* gazebo::physics::Actor::skeleton
protected

The actor's skeleton.

std::map<std::string, std::map<std::string, std::string> > gazebo::physics::Actor::skelNodesMap
protected

Skeleton to naode map.

std::string gazebo::physics::Actor::skinFile
protected

Filename for the skin.

double gazebo::physics::Actor::skinScale
protected

Scaling factor to apply to the skin.

double gazebo::physics::Actor::startDelay
protected

Amount of time to delay start by.

std::map<unsigned int, common::PoseAnimation*> gazebo::physics::Actor::trajectories
protected

All the trajectories.

std::vector<TrajectoryInfo> gazebo::physics::Actor::trajInfo
protected

Trajectory information.

uint32_t gazebo::physics::Actor::visualId
protected

ID for this visual.

std::string gazebo::physics::Actor::visualName
protected

Name of the visual.


The documentation for this class was generated from the following file: