| 
|   | 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...
  | 
|   | 
|   | Model (BasePtr _parent) | 
|   | Constructor.  More...
  | 
|   | 
| virtual  | ~Model () | 
|   | Destructor.  More...
  | 
|   | 
| void  | AttachStaticModel (ModelPtr &_model, math::Pose _offset) | 
|   | Attach a static model to this model.  More...
  | 
|   | 
| gazebo::physics::JointPtr  | CreateJoint (const std::string &_name, const std::string &_type, physics::LinkPtr _parent, physics::LinkPtr _child) | 
|   | Create a joint for 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_V &  | GetJoints () const  | 
|   | Get the joints.  More...
  | 
|   | 
| LinkPtr  | GetLink (const std::string &_name="canonical") const  | 
|   | Get a link by name.  More...
  | 
|   | 
| const Link_V &  | GetLinks () 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...
  | 
|   | 
| bool  | GetSelfCollide () const  | 
|   | If true, all links within the model will collide by default.  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...
  | 
|   | 
| ModelPtr  | NestedModel (const std::string &_name) const  | 
|   | Get a nested model that is a direct child of this model.  More...
  | 
|   | 
| const Model_V &  | NestedModels () const  | 
|   | Get all the nested models.  More...
  | 
|   | 
| void  | ProcessMsg (const msgs::Model &_msg) | 
|   | Update parameters from a model message.  More...
  | 
|   | 
| virtual void  | RemoveChild (EntityPtr _child) | 
|   | Remove a child.  More...
  | 
|   | 
| bool  | RemoveJoint (const std::string &_name) | 
|   | Remove a joint for this model.  More...
  | 
|   | 
| void  | Reset () | 
|   | Reset the model.  More...
  | 
|   | 
| void  | ResetPhysicsStates () | 
|   | Reset the velocity, acceleration, force and torque of all child links.  More...
  | 
|   | 
| ignition::math::Vector3d  | Scale () const  | 
|   | Get the scale of model.  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) GAZEBO_DEPRECATED(7.0) | 
|   | Set the scale of model.  More...
  | 
|   | 
| void  | SetScale (const ignition::math::Vector3d &_scale, const bool _publish=false) | 
|   | Set the scale of model.  More...
  | 
|   | 
| void  | SetSelfCollide (bool _self_collide) | 
|   | Set this model's self_collide property.  More...
  | 
|   | 
| void  | SetState (const ModelState &_state) | 
|   | Set the current model state.  More...
  | 
|   | 
| boost::shared_ptr< Model >  | shared_from_this () | 
|   | Allow Model class to share itself as a boost shared_ptr.  More...
  | 
|   | 
| virtual void  | StopAnimation () | 
|   | Stop the current animations.  More...
  | 
|   | 
| virtual const sdf::ElementPtr  | UnscaledSDF () | 
|   | 
| void  | Update () | 
|   | Update the model.  More...
  | 
|   | 
|   | 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::Pose &  | GetDirtyPose () 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::Pose &  | GetWorldPose () 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...
  | 
|   | 
|   | 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 WorldPtr &  | GetWorld () 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...
  | 
|   |