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);
129 public:
virtual math::Vector3 GetRelativeLinearAccel()
const;
137 public:
virtual math::Vector3 GetRelativeAngularAccel()
const;
145 public:
virtual math::Box GetBoundingBox()
const;
149 public:
unsigned int GetJointCount()
const;
154 public:
const Link_V &GetLinks()
const;
158 public:
const Joint_V &GetJoints()
const;
163 public:
JointPtr GetJoint(
const std::string &name);
169 public:
LinkPtr GetLinkById(
unsigned int _id)
const;
175 public:
LinkPtr GetLink(
const std::string &_name =
"canonical")
const;
179 public:
void SetGravityMode(
const bool &_value);
185 public:
void SetCollideMode(
const std::string &_mode);
189 public:
void SetLaserRetro(
const float _retro);
193 public:
virtual void FillMsg(msgs::Model &_msg);
197 public:
void ProcessMsg(
const msgs::Model &_msg);
203 public:
void SetJointPosition(
const std::string &_jointName,
204 double _position,
int _index = 0);
209 public:
void SetJointPositions(
210 const std::map<std::string, double> &_jointPositions);
216 public:
void SetJointAnimation(
217 const std::map<std::string, common::NumericAnimationPtr> &_anims,
218 boost::function<
void()> _onComplete =
NULL);
221 public:
virtual void StopAnimation();
242 public:
void DetachStaticModel(
const std::string &_model);
246 public:
void SetState(
const ModelState &_state);
254 public:
void SetEnabled(
bool _enabled);
262 public:
void SetLinkWorldPose(
const math::Pose &_pose,
263 std::string _linkName);
271 public:
void SetLinkWorldPose(
const math::Pose &_pose,
277 public:
void SetAutoDisable(
bool _disable);
281 public:
bool GetAutoDisable()
const;
286 public:
void LoadPlugins();
290 public:
unsigned int GetPluginCount()
const;
295 public:
unsigned int GetSensorCount()
const;
303 public:
GripperPtr GetGripper(
size_t _index)
const;
308 public:
size_t GetGripperCount()
const;
313 public:
double GetWorldEnergyPotential()
const;
319 public:
double GetWorldEnergyKinetic()
const;
325 public:
double GetWorldEnergy()
const;
328 protected:
virtual void OnPoseChange();
331 private:
void LoadLinks();
335 private:
void LoadJoint(sdf::ElementPtr _sdf);
339 private:
void LoadPlugin(sdf::ElementPtr _sdf);
343 private:
void LoadGripper(sdf::ElementPtr _sdf);
348 private:
void RemoveLink(
const std::string &_name);
360 private:
LinkPtr canonicalLink;
369 private: std::vector<GripperPtr> grippers;
372 private: std::vector<ModelPluginPtr> plugins;
375 private: std::map<std::string, common::NumericAnimationPtr>
379 private: boost::function<void()> onJointAnimationComplete;
382 private:
mutable boost::recursive_mutex updateMutex;
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:174
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:66
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:82
transport::PublisherPtr jointPub
Publisher for joint info.
Definition: Model.hh:357
Encapsulates a position and rotation in three space.
Definition: Pose.hh:40
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
Mathematical representation of a box and related functions.
Definition: Box.hh:33
std::vector< math::Pose > attachedModelsOffset
used by Model::AttachStaticModel
Definition: Model.hh:354
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:182
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:102
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:74
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:98
#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:351
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:158
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:44
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90