28 #include <boost/thread/recursive_mutex.hpp>
38 class recursive_mutex;
59 public:
virtual ~
Model();
63 public:
void Load(sdf::ElementPtr _sdf);
66 public:
void LoadJoints();
69 public:
virtual void Init();
72 public:
void Update();
75 public:
virtual void Fini();
79 public:
virtual void UpdateParameters(sdf::ElementPtr _sdf);
83 public:
virtual const sdf::ElementPtr GetSDF();
87 public:
virtual void RemoveChild(
EntityPtr _child);
95 public:
void ResetPhysicsStates();
133 public:
virtual math::Vector3 GetRelativeLinearAccel()
const;
141 public:
virtual math::Vector3 GetRelativeAngularAccel()
const;
149 public:
virtual math::Box GetBoundingBox()
const;
153 public:
unsigned int GetJointCount()
const;
158 public:
const Link_V &GetLinks()
const;
162 public:
const Joint_V &GetJoints()
const;
167 public:
JointPtr GetJoint(
const std::string &name);
173 public:
LinkPtr GetLinkById(
unsigned int _id)
const;
179 public:
LinkPtr GetLink(
const std::string &_name =
"canonical")
const;
188 public:
bool GetSelfCollide()
const;
193 public:
void SetSelfCollide(
bool _self_collide);
197 public:
void SetGravityMode(
const bool &_value);
203 public:
void SetCollideMode(
const std::string &_mode);
207 public:
void SetLaserRetro(
const float _retro);
211 public:
virtual void FillMsg(msgs::Model &_msg);
215 public:
void ProcessMsg(
const msgs::Model &_msg);
221 public:
void SetJointPosition(
const std::string &_jointName,
222 double _position,
int _index = 0);
227 public:
void SetJointPositions(
228 const std::map<std::string, double> &_jointPositions);
234 public:
void SetJointAnimation(
235 const std::map<std::string, common::NumericAnimationPtr> &_anims,
236 boost::function<
void()> _onComplete =
NULL);
239 public:
virtual void StopAnimation();
260 public:
void DetachStaticModel(
const std::string &_model);
264 public:
void SetState(
const ModelState &_state);
272 public:
void SetEnabled(
bool _enabled);
280 public:
void SetLinkWorldPose(
const math::Pose &_pose,
281 std::string _linkName);
289 public:
void SetLinkWorldPose(
const math::Pose &_pose,
295 public:
void SetAutoDisable(
bool _disable);
299 public:
bool GetAutoDisable()
const;
304 public:
void LoadPlugins();
308 public:
unsigned int GetPluginCount()
const;
313 public:
unsigned int GetSensorCount()
const;
321 public:
GripperPtr GetGripper(
size_t _index)
const;
326 public:
size_t GetGripperCount()
const;
331 public:
double GetWorldEnergyPotential()
const;
337 public:
double GetWorldEnergyKinetic()
const;
343 public:
double GetWorldEnergy()
const;
346 protected:
virtual void OnPoseChange();
349 private:
void LoadLinks();
353 private:
void LoadJoint(sdf::ElementPtr _sdf);
357 private:
void LoadPlugin(sdf::ElementPtr _sdf);
361 private:
void LoadGripper(sdf::ElementPtr _sdf);
366 private:
void RemoveLink(
const std::string &_name);
378 private:
LinkPtr canonicalLink;
387 private: std::vector<GripperPtr> grippers;
390 private: std::vector<ModelPluginPtr> plugins;
393 private: std::map<std::string, common::NumericAnimationPtr>
397 private: boost::function<void()> onJointAnimationComplete;
400 private:
mutable boost::recursive_mutex updateMutex;
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:188
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:68
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:84
transport::PublisherPtr jointPub
Publisher for joint info.
Definition: Model.hh:375
#define GZ_PHYSICS_VISIBLE
Definition: system.hh:318
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
std::vector< math::Pose > attachedModelsOffset
used by Model::AttachStaticModel
Definition: Model.hh:372
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:196
default namespace for gazebo
A model is a collection of links, joints, and plugins.
Definition: Model.hh:52
boost::shared_ptr< JointController > JointControllerPtr
Definition: PhysicsTypes.hh:104
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:76
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:100
#define NULL
Definition: CommonTypes.hh:30
Base class for all physics objects in Gazebo.
Definition: Entity.hh:56
std::vector< ModelPtr > attachedModels
used by Model::AttachStaticModel
Definition: Model.hh:369
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:50
boost::shared_ptr< Gripper > GripperPtr
Definition: PhysicsTypes.hh:172
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:92