28 #include <boost/function.hpp>    29 #include <boost/thread/recursive_mutex.hpp>    39   class recursive_mutex;
    60       public: 
virtual ~
Model();
    64       public: 
void Load(sdf::ElementPtr _sdf);
    67       public: 
void LoadJoints();
    70       public: 
virtual void Init();
    73       public: 
void Update();
    76       public: 
virtual void Fini();
    80       public: 
virtual void UpdateParameters(sdf::ElementPtr _sdf);
    84       public: 
virtual const sdf::ElementPtr GetSDF();
    91       public: 
virtual const sdf::ElementPtr UnscaledSDF();
    95       public: 
virtual void RemoveChild(
EntityPtr _child);
    96       using Base::RemoveChild;
   103       public: 
void ResetPhysicsStates();
   141       public: 
virtual math::Vector3 GetRelativeLinearAccel() 
const;
   149       public: 
virtual math::Vector3 GetRelativeAngularAccel() 
const;
   157       public: 
virtual math::Box GetBoundingBox() 
const;
   161       public: 
unsigned int GetJointCount() 
const;
   166       public: 
ModelPtr NestedModel(
const std::string &_name) 
const;
   170       public: 
const Model_V &NestedModels() 
const;
   175       public: 
const Link_V &GetLinks() 
const;
   179       public: 
const Joint_V &GetJoints() 
const;
   184       public: 
JointPtr GetJoint(
const std::string &name);
   190       public: 
LinkPtr GetLinkById(
unsigned int _id) 
const;
   196       public: 
LinkPtr GetLink(
const std::string &_name =
"canonical") 
const;
   205       public: 
bool GetSelfCollide() 
const;
   210       public: 
void SetSelfCollide(
bool _self_collide);
   214       public: 
void SetGravityMode(
const bool &_value);
   220       public: 
void SetCollideMode(
const std::string &_mode);
   224       public: 
void SetLaserRetro(
const float _retro);
   228       public: 
virtual void FillMsg(msgs::Model &_msg);
   232       public: 
void ProcessMsg(
const msgs::Model &_msg);
   238       public: 
void SetJointPosition(
const std::string &_jointName,
   239                                     double _position, 
int _index = 0);
   244       public: 
void SetJointPositions(
   245                   const std::map<std::string, double> &_jointPositions);
   251       public: 
void SetJointAnimation(
   252                const std::map<std::string, common::NumericAnimationPtr> &_anims,
   253                boost::function<
void()> _onComplete = 
NULL);
   256       public: 
virtual void StopAnimation();
   277       public: 
void DetachStaticModel(
const std::string &_model);
   281       public: 
void SetState(
const ModelState &_state);
   294       public: 
void SetScale(
const ignition::math::Vector3d &_scale,
   295           const bool _publish = 
false);
   301       public: ignition::math::Vector3d Scale() 
const;
   305       public: 
void SetEnabled(
bool _enabled);
   313       public: 
void SetLinkWorldPose(
const math::Pose &_pose,
   314                                     std::string _linkName);
   322       public: 
void SetLinkWorldPose(
const math::Pose &_pose,
   328       public: 
void SetAutoDisable(
bool _disable);
   332       public: 
bool GetAutoDisable() 
const;
   337       public: 
void LoadPlugins();
   341       public: 
unsigned int GetPluginCount() 
const;
   346       public: 
unsigned int GetSensorCount() 
const;
   354       public: 
GripperPtr GetGripper(
size_t _index) 
const;
   359       public: 
size_t GetGripperCount() 
const;
   364       public: 
double GetWorldEnergyPotential() 
const;
   370       public: 
double GetWorldEnergyKinetic() 
const;
   376       public: 
double GetWorldEnergy() 
const;
   388         const std::string &_name, 
const std::string &_type,
   394       public: 
bool RemoveJoint(
const std::string &_name);
   398       public: boost::shared_ptr<Model> shared_from_this();
   404       public: 
LinkPtr CreateLink(
const std::string &_name);
   407       protected: 
virtual void OnPoseChange();
   410       private: 
void LoadLinks();
   413       private: 
void LoadModels();
   417       private: 
void LoadJoint(sdf::ElementPtr _sdf);
   421       private: 
void LoadPlugin(sdf::ElementPtr _sdf);
   425       private: 
void LoadGripper(sdf::ElementPtr _sdf);
   430       private: 
void RemoveLink(
const std::string &_name);
   433       private: 
virtual void PublishScale();
   445       private: 
LinkPtr canonicalLink;
   457       private: std::vector<GripperPtr> grippers;
   460       private: std::vector<ModelPluginPtr> plugins;
   463       private: std::map<std::string, common::NumericAnimationPtr>
   467       private: boost::function<void()> onJointAnimationComplete;
   470       private: 
mutable boost::recursive_mutex updateMutex;
 boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:100
 
Definition: JointMaker.hh:46
 
Forward declarations for the common classes. 
Definition: Animation.hh:33
 
std::vector< ModelPtr > Model_V
Definition: PhysicsTypes.hh:196
 
Encapsulates a position and rotation in three space. 
Definition: Pose.hh:37
 
The Vector3 class represents the generic vector containing 3 elements. 
Definition: Vector3.hh:39
 
Mathematical representation of a box and related functions. 
Definition: Box.hh:35
 
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
 
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:48
 
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:108
 
std::vector< math::Pose > attachedModelsOffset
used by Model::AttachStaticModel 
Definition: Model.hh:439
 
std::vector< ModelPtr > attachedModels
used by Model::AttachStaticModel 
Definition: Model.hh:436
 
default namespace for gazebo 
 
A model is a collection of links, joints, and plugins. 
Definition: Model.hh:53
 
transport::PublisherPtr jointPub
Publisher for joint info. 
Definition: Model.hh:442
 
boost::shared_ptr< Gripper > GripperPtr
Definition: PhysicsTypes.hh:188
 
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:204
 
#define NULL
Definition: CommonTypes.hh:31
 
Base class for all physics objects in Gazebo. 
Definition: Entity.hh:58
 
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:80
 
boost::shared_ptr< JointController > JointControllerPtr
Definition: PhysicsTypes.hh:112
 
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:88
 
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message. 
 
Store state information of a physics::Model object. 
Definition: ModelState.hh:48
 
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:216
 
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:72