17 #ifndef GAZEBO_PHYSICS_MODEL_HH_
18 #define GAZEBO_PHYSICS_MODEL_HH_
24 #include <boost/function.hpp>
25 #include <boost/thread/recursive_mutex.hpp>
36 class recursive_mutex;
66 public:
virtual ~
Model();
70 public:
void Load(sdf::ElementPtr _sdf);
73 public:
void LoadJoints();
76 public:
virtual void Init();
79 public:
void Update();
82 public:
virtual void Fini();
86 public:
virtual void UpdateParameters(sdf::ElementPtr _sdf);
90 public:
virtual const sdf::ElementPtr GetSDF();
97 public:
virtual const sdf::ElementPtr UnscaledSDF();
101 public:
virtual void RemoveChild(
EntityPtr _child);
105 public:
void Reset();
110 public:
void ResetPhysicsStates();
120 public:
void SetLinearVel(
const ignition::math::Vector3d &_vel);
130 public:
void SetAngularVel(
const ignition::math::Vector3d &_vel);
142 public:
void SetLinearAccel(
const ignition::math::Vector3d &_vel);
154 public:
void SetAngularAccel(
const ignition::math::Vector3d &_vel);
165 public:
virtual ignition::math::Vector3d RelativeLinearVel()
const;
176 public:
virtual ignition::math::Vector3d WorldLinearVel()
const;
187 public:
virtual ignition::math::Vector3d RelativeAngularVel()
const;
198 public:
virtual ignition::math::Vector3d WorldAngularVel()
const;
209 public:
virtual ignition::math::Vector3d RelativeLinearAccel()
const;
220 public:
virtual ignition::math::Vector3d WorldLinearAccel()
const;
225 public:
virtual math::Vector3 GetRelativeAngularAccel()
const
231 public:
virtual ignition::math::Vector3d RelativeAngularAccel()
const;
242 public:
virtual ignition::math::Vector3d WorldAngularAccel()
const;
247 public:
virtual math::Box GetBoundingBox()
const
252 public:
virtual ignition::math::Box BoundingBox()
const;
256 public:
unsigned int GetJointCount()
const;
261 public:
ModelPtr NestedModel(
const std::string &_name)
const;
265 public:
const Model_V &NestedModels()
const;
270 public:
const Link_V &GetLinks()
const;
274 public:
const Joint_V &GetJoints()
const;
279 public:
JointPtr GetJoint(
const std::string &name);
285 public:
LinkPtr GetLinkById(
unsigned int _id)
const;
291 public:
LinkPtr GetLink(
const std::string &_name =
"canonical")
const;
300 public:
virtual bool GetSelfCollide()
const;
305 public:
virtual void SetSelfCollide(
bool _self_collide);
309 public:
void SetGravityMode(
const bool &_value);
315 public:
void SetCollideMode(
const std::string &_mode);
319 public:
void SetLaserRetro(
const float _retro);
323 public:
virtual void FillMsg(msgs::Model &_msg);
327 public:
void ProcessMsg(
const msgs::Model &_msg);
333 public:
void SetJointPosition(
const std::string &_jointName,
334 double _position,
int _index = 0);
339 public:
void SetJointPositions(
340 const std::map<std::string, double> &_jointPositions);
346 public:
void SetJointAnimation(
347 const std::map<std::string, common::NumericAnimationPtr> &_anims,
348 boost::function<
void()> _onComplete =
NULL);
351 public:
virtual void StopAnimation();
385 public:
void AttachStaticModel(
ModelPtr &_model,
386 ignition::math::Pose3d _offset);
391 public:
void DetachStaticModel(
const std::string &_model);
395 public:
void SetState(
const ModelState &_state);
402 public:
void SetScale(
const ignition::math::Vector3d &_scale,
403 const bool _publish =
false);
409 public: ignition::math::Vector3d Scale()
const;
413 public:
void SetEnabled(
bool _enabled);
422 public:
void SetLinkWorldPose(
const math::Pose &_pose,
431 public:
void SetLinkWorldPose(
const ignition::math::Pose3d &_pose,
432 std::string _linkName);
441 public:
void SetLinkWorldPose(
const math::Pose &_pose,
450 public:
void SetLinkWorldPose(
const ignition::math::Pose3d &_pose,
456 public:
void SetAutoDisable(
bool _disable);
460 public:
bool GetAutoDisable()
const;
465 public:
void LoadPlugins();
469 public:
unsigned int GetPluginCount()
const;
474 public:
unsigned int GetSensorCount()
const;
488 public: std::vector<std::string> SensorScopedName(
489 const std::string &_name)
const;
497 public:
GripperPtr GetGripper(
size_t _index)
const;
502 public:
size_t GetGripperCount()
const;
507 public:
double GetWorldEnergyPotential()
const;
513 public:
double GetWorldEnergyKinetic()
const;
519 public:
double GetWorldEnergy()
const;
531 const std::string &_name,
const std::string &_type,
545 public:
bool RemoveJoint(
const std::string &_name);
549 public:
virtual void SetWindMode(
const bool _mode);
553 public:
virtual bool WindMode()
const;
557 public: boost::shared_ptr<Model> shared_from_this();
563 public:
LinkPtr CreateLink(
const std::string &_name);
582 public:
void PluginInfo(
const common::URI &_pluginUri,
583 ignition::msgs::Plugin_V &_plugins,
bool &_success);
586 protected:
virtual void OnPoseChange();
589 protected:
virtual void RegisterIntrospectionItems();
592 private:
void LoadLinks();
595 private:
void LoadModels();
599 private:
void LoadJoint(sdf::ElementPtr _sdf);
603 private:
void LoadPlugin(sdf::ElementPtr _sdf);
607 private:
void LoadGripper(sdf::ElementPtr _sdf);
612 private:
void RemoveLink(
const std::string &_name);
615 private:
virtual void PublishScale();
627 private:
LinkPtr canonicalLink;
639 private: std::vector<GripperPtr> grippers;
642 private: std::vector<ModelPluginPtr> plugins;
645 private: std::map<std::string, common::NumericAnimationPtr>
649 private: boost::function<void()> onJointAnimationComplete;
655 private:
mutable boost::recursive_mutex updateMutex;
658 private: std::mutex receiveMutex;
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
std::vector< ModelPtr > Model_V
Definition: PhysicsTypes.hh:205
Encapsulates a position and rotation in three space.
Definition: Pose.hh:42
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:44
Mathematical representation of a box and related functions.
Definition: Box.hh:41
Forward declarations for transport.
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:117
std::vector< ignition::math::Pose3d > attachedModelsOffset
used by Model::AttachStaticModel
Definition: Model.hh:621
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
std::vector< ModelPtr > attachedModels
used by Model::AttachStaticModel
Definition: Model.hh:618
default namespace for gazebo
A complete URI.
Definition: URI.hh:176
A model is a collection of links, joints, and plugins.
Definition: Model.hh:59
transport::PublisherPtr jointPub
Publisher for joint info.
Definition: Model.hh:624
boost::shared_ptr< Gripper > GripperPtr
Definition: PhysicsTypes.hh:197
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:213
#define NULL
Definition: CommonTypes.hh:31
Base class for all physics objects in Gazebo.
Definition: Entity.hh:56
#define GAZEBO_DEPRECATED(version)
Definition: system.hh:302
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:85
boost::shared_ptr< JointController > JointControllerPtr
Definition: PhysicsTypes.hh:121
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:93
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
virtual void Reset()
Reset the entity.
Store state information of a physics::Model object.
Definition: ModelState.hh:49
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:225
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:77