Go to the documentation of this file.
17 #ifndef GAZEBO_PHYSICS_ENTITY_HH_
18 #define GAZEBO_PHYSICS_ENTITY_HH_
22 #include <ignition/math/Box.hh>
23 #include <ignition/math/Pose3.hh>
24 #include <ignition/math/Vector3.hh>
25 #include <ignition/transport/Node.hh>
27 #include <boost/function.hpp>
40 class recursive_mutex;
63 public:
virtual void Load(sdf::ElementPtr _sdf);
66 public:
virtual void Fini();
69 public:
virtual void Reset();
74 public:
virtual void UpdateParameters(sdf::ElementPtr _sdf);
78 public:
virtual void SetName(
const std::string &_name);
82 public:
void SetStatic(
const bool &_static);
86 public:
bool IsStatic()
const;
90 public:
void SetInitialRelativePose(
const ignition::math::Pose3d &_pose);
94 public: ignition::math::Pose3d InitialRelativePose()
const;
98 public:
virtual ignition::math::Box BoundingBox()
const;
102 public:
inline virtual const ignition::math::Pose3d &
WorldPose()
const
104 return this->worldPose;
109 public: ignition::math::Pose3d RelativePose()
const;
115 public:
void SetRelativePose(
const ignition::math::Pose3d &_pose,
116 const bool _notify =
true,
117 const bool _publish =
true);
123 public:
void SetWorldPose(
const ignition::math::Pose3d &_pose,
124 const bool _notify =
true,
125 const bool _publish =
true);
129 public:
virtual ignition::math::Vector3d RelativeLinearVel()
const;
133 public:
virtual ignition::math::Vector3d WorldLinearVel()
const;
137 public:
virtual ignition::math::Vector3d RelativeAngularVel()
const;
141 public:
virtual ignition::math::Vector3d WorldAngularVel()
const;
145 public:
virtual ignition::math::Vector3d RelativeLinearAccel()
const;
149 public:
virtual ignition::math::Vector3d WorldLinearAccel()
const;
153 public:
virtual ignition::math::Vector3d RelativeAngularAccel()
const;
157 public:
virtual ignition::math::Vector3d WorldAngularAccel()
const;
161 public:
void SetCanonicalLink(
bool _value);
166 {
return this->isCanonicalLink;}
172 boost::function<
void()> _onComplete);
179 public:
virtual void StopAnimation();
188 public:
CollisionPtr GetChildCollision(
const std::string &_name);
193 public:
LinkPtr GetChildLink(
const std::string &_name);
199 public:
void GetNearestEntityBelow(
double &_distBelow,
200 std::string &_entityName);
203 public:
void PlaceOnNearestEntityBelow();
208 public:
void PlaceOnEntity(
const std::string &_entityName);
212 public: ignition::math::Box CollisionBoundingBox()
const;
219 public:
void SetWorldTwist(
const ignition::math::Vector3d &_linear,
220 const ignition::math::Vector3d &_angular,
221 const bool _updateChildren =
true);
228 public:
const ignition::math::Pose3d &DirtyPose()
const;
232 protected:
virtual void OnPoseChange() = 0;
235 private:
virtual void PublishPose();
240 private: ignition::math::Box CollisionBoundingBoxHelper(
247 private:
void SetWorldPoseModel(
const ignition::math::Pose3d &_pose,
249 const bool _publish);
255 private:
void SetWorldPoseCanonicalLink(
256 const ignition::math::Pose3d &_pose,
257 const bool _notify,
const bool _publish);
263 private:
void SetWorldPoseDefault(
const ignition::math::Pose3d &_pose,
264 const bool _notify,
const bool _publish);
268 private:
void OnPoseMsg(ConstPosePtr &_msg);
275 private:
void UpdatePhysicsPose(
bool update_children =
true);
318 protected: ignition::math::Vector3d
scale;
321 private:
bool isStatic;
324 private:
bool isCanonicalLink;
327 private: ignition::math::Pose3d initialRelativePose;
336 private: boost::function<void()> onAnimationComplete;
339 private: void (
Entity::*setWorldPoseFunc)(
const ignition::math::Pose3d &,
340 const bool,
const bool);
349 protected: ignition::transport::Node::Publisher
visPubIgn;
355 private: ignition::transport::Node::Publisher posePubIgn;
virtual void Fini()
Finalize the entity.
ignition::math::Vector3d scale
Scale of the entity.
Definition: Entity.hh:318
virtual ~Entity()
Destructor.
virtual ignition::math::Vector3d WorldAngularAccel() const
Get the angular acceleration of the entity in the world frame.
void PlaceOnNearestEntityBelow()
Move this entity to be ontop of the nearest entity below.
event::ConnectionPtr animationConnection
Connection used to update an animation.
Definition: Entity.hh:312
ignition::math::Pose3d dirtyPose
The pose set by a physics engine.
Definition: Entity.hh:315
Forward declarations for the common classes.
Definition: Animation.hh:26
virtual ignition::math::Box BoundingBox() const
Return the bounding box for the entity.
A Time class, can be used to hold wall- or sim-time. stored as sec and nano-sec.
Definition: Time.hh:47
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:93
void SetWorldPose(const ignition::math::Pose3d &_pose, const bool _notify=true, const bool _publish=true)
Set the world pose of the entity.
virtual void OnPoseChange()=0
This function is called when the entity's (or one of its parents) pose of the parent has changed.
transport::NodePtr node
Communication node.
Definition: Entity.hh:288
void SetWorldTwist(const ignition::math::Vector3d &_linear, const ignition::math::Vector3d &_angular, const bool _updateChildren=true)
Set angular and linear rates of an physics::Entity.
LinkPtr GetChildLink(const std::string &_name)
Get a child linke entity, if one exists.
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
void SetCanonicalLink(bool _value)
Set to true if this entity is a canonical link for a model.
friend class Entity
Definition: Base.hh:366
virtual ignition::math::Vector3d RelativeLinearAccel() const
Get the linear acceleration of the entity.
Forward declarations for transport.
ignition::math::Pose3d animationStartPose
Start pose of an animation.
Definition: Entity.hh:306
Definition: JointMaker.hh:44
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
virtual void Reset()
Reset the entity.
default namespace for gazebo
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
virtual ignition::math::Vector3d WorldAngularVel() const
Get the angular velocity of the entity in the world frame.
bool IsStatic() const
Return whether this entity is static.
void PlaceOnEntity(const std::string &_entityName)
Move this entity to be ontop of another entity by name.
ignition::math::Pose3d RelativePose() const
Get the pose of the entity relative to its parent.
virtual void UpdateParameters(sdf::ElementPtr _sdf)
Update the parameters using new sdf values.
virtual void Reset()
Reset the object.
common::PoseAnimationPtr animation
Current pose animation.
Definition: Entity.hh:300
bool IsCanonicalLink() const
A helper function that checks if this is a canonical body.
Definition: Entity.hh:165
virtual void Load(sdf::ElementPtr _sdf)
Load the entity.
virtual void StopAnimation()
Stop the current animation, if any.
void GetNearestEntityBelow(double &_distBelow, std::string &_entityName)
Get the distance to the nearest entity below (along the Z-axis) this entity.
Base class for most physics classes.
Definition: Base.hh:71
virtual void SetName(const std::string &_name)
Set the name of the entity.
void SetAnimation(const common::PoseAnimationPtr &_anim, boost::function< void()> _onComplete)
Set an animation for this entity.
virtual ignition::math::Vector3d RelativeAngularVel() const
Get the angular velocity of the entity.
std::vector< event::ConnectionPtr > connections
All our event connections.
Definition: Entity.hh:309
ModelPtr GetParentModel()
Get the parent model, if one exists.
ignition::transport::Node nodeIgn
Ignition communication node.
Definition: Entity.hh:346
void SetRelativePose(const ignition::math::Pose3d &_pose, const bool _notify=true, const bool _publish=true)
Set the pose of the entity relative to its parent.
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:77
transport::PublisherPtr requestPub
Request publisher.
Definition: Entity.hh:294
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
virtual ignition::math::Vector3d WorldLinearVel() const
Get the linear velocity of the entity in the world frame.
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
ignition::math::Pose3d InitialRelativePose() const
Get the initial relative pose.
virtual ignition::math::Vector3d WorldLinearAccel() const
Get the linear acceleration of the entity in the world frame.
void SetInitialRelativePose(const ignition::math::Pose3d &_pose)
Set the initial pose.
EntityPtr parentEntity
A helper that prevents numerous dynamic_casts.
Definition: Entity.hh:282
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:85
Base class for all physics objects in Gazebo.
Definition: Entity.hh:52
const ignition::math::Pose3d & DirtyPose() const
Returns Entity::dirtyPose.
ignition::transport::Node::Publisher requestPubIgn
Request publisher.
Definition: Entity.hh:352
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:113
ignition::math::Pose3d worldPose
World pose of the entity.
Definition: Entity.hh:285
msgs::Visual * visualMsg
Visual message container.
Definition: Entity.hh:297
ignition::transport::Node::Publisher visPubIgn
Visual publisher.
Definition: Entity.hh:349
virtual ignition::math::Vector3d RelativeLinearVel() const
Get the linear velocity of the entity.
virtual const ignition::math::Pose3d & WorldPose() const
Get the absolute pose of the entity.
Definition: Entity.hh:102
ignition::math::Box CollisionBoundingBox() const
Returns collision bounding box.
virtual ignition::math::Vector3d RelativeAngularAccel() const
Get the angular acceleration of the entity.
Information for use in an update event.
Definition: UpdateInfo.hh:30
void SetStatic(const bool &_static)
Set whether this entity is static: immovable.
boost::shared_ptr< PoseAnimation > PoseAnimationPtr
Definition: CommonTypes.hh:109
transport::PublisherPtr visPub
Visual publisher.
Definition: Entity.hh:291
common::Time prevAnimationTime
Previous time an animation was updated.
Definition: Entity.hh:303
CollisionPtr GetChildCollision(const std::string &_name)
Get a child collision entity, if one exists.