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();
88 public:
virtual void RemoveChild(
EntityPtr _child);
96 public:
void ResetPhysicsStates();
134 public:
virtual math::Vector3 GetRelativeLinearAccel()
const;
142 public:
virtual math::Vector3 GetRelativeAngularAccel()
const;
150 public:
virtual math::Box GetBoundingBox()
const;
154 public:
unsigned int GetJointCount()
const;
159 public:
const Link_V &GetLinks()
const;
163 public:
const Joint_V &GetJoints()
const;
168 public:
JointPtr GetJoint(
const std::string &name);
174 public:
LinkPtr GetLinkById(
unsigned int _id)
const;
180 public:
LinkPtr GetLink(
const std::string &_name =
"canonical")
const;
189 public:
bool GetSelfCollide()
const;
194 public:
void SetSelfCollide(
bool _self_collide);
198 public:
void SetGravityMode(
const bool &_value);
204 public:
void SetCollideMode(
const std::string &_mode);
208 public:
void SetLaserRetro(
const float _retro);
212 public:
virtual void FillMsg(msgs::Model &_msg);
216 public:
void ProcessMsg(
const msgs::Model &_msg);
222 public:
void SetJointPosition(
const std::string &_jointName,
223 double _position,
int _index = 0);
228 public:
void SetJointPositions(
229 const std::map<std::string, double> &_jointPositions);
235 public:
void SetJointAnimation(
236 const std::map<std::string, common::NumericAnimationPtr> &_anims,
237 boost::function<
void()> _onComplete =
NULL);
240 public:
virtual void StopAnimation();
261 public:
void DetachStaticModel(
const std::string &_model);
265 public:
void SetState(
const ModelState &_state);
273 public:
void SetEnabled(
bool _enabled);
281 public:
void SetLinkWorldPose(
const math::Pose &_pose,
282 std::string _linkName);
290 public:
void SetLinkWorldPose(
const math::Pose &_pose,
296 public:
void SetAutoDisable(
bool _disable);
300 public:
bool GetAutoDisable()
const;
305 public:
void LoadPlugins();
309 public:
unsigned int GetPluginCount()
const;
314 public:
unsigned int GetSensorCount()
const;
322 public:
GripperPtr GetGripper(
size_t _index)
const;
327 public:
size_t GetGripperCount()
const;
332 public:
double GetWorldEnergyPotential()
const;
338 public:
double GetWorldEnergyKinetic()
const;
344 public:
double GetWorldEnergy()
const;
347 protected:
virtual void OnPoseChange();
350 private:
void LoadLinks();
354 private:
void LoadJoint(sdf::ElementPtr _sdf);
358 private:
void LoadPlugin(sdf::ElementPtr _sdf);
362 private:
void LoadGripper(sdf::ElementPtr _sdf);
367 private:
void RemoveLink(
const std::string &_name);
379 private:
LinkPtr canonicalLink;
388 private: std::vector<GripperPtr> grippers;
391 private: std::vector<ModelPluginPtr> plugins;
394 private: std::map<std::string, common::NumericAnimationPtr>
398 private: boost::function<void()> onJointAnimationComplete;
401 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:376
#define GZ_PHYSICS_VISIBLE
Definition: system.hh:318
Definition: JointMaker.hh:41
Forward declarations for the common classes.
Definition: Animation.hh:33
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:373
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:53
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:57
std::vector< ModelPtr > attachedModels
used by Model::AttachStaticModel
Definition: Model.hh:370
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