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>
44 class recursive_mutex;
67 public:
virtual void Load(sdf::ElementPtr _sdf);
70 public:
virtual void Fini();
73 public:
virtual void Reset();
78 public:
virtual void UpdateParameters(sdf::ElementPtr _sdf);
82 public:
virtual void SetName(
const std::string &_name);
86 public:
void SetStatic(
const bool &_static);
90 public:
bool IsStatic()
const;
95 public:
void SetInitialRelativePose(
const math::Pose &_pose)
100 public:
void SetInitialRelativePose(
const ignition::math::Pose3d &_pose);
109 public: ignition::math::Pose3d InitialRelativePose()
const;
118 public:
virtual ignition::math::Box BoundingBox()
const;
124 GAZEBO_DEPRECATED(8.0)
127 #pragma GCC diagnostic push
128 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
130 return this->worldPose;
132 #pragma GCC diagnostic pop
138 public:
inline virtual const ignition::math::Pose3d &
WorldPose()
const
140 return this->worldPose;
146 public:
math::Pose GetRelativePose() const GAZEBO_DEPRECATED(8.0);
150 public: ignition::math::Pose3d RelativePose() const;
157 public:
void SetRelativePose(const math::Pose &_pose,
159 bool _publish = true) GAZEBO_DEPRECATED(8.0);
165 public:
void SetRelativePose(const ignition::math::Pose3d &_pose,
166 const
bool _notify = true,
167 const
bool _publish = true);
174 public:
void SetWorldPose(const math::Pose &_pose,
176 bool _publish = true) GAZEBO_DEPRECATED(8.0);
182 public:
void SetWorldPose(const ignition::math::Pose3d &_pose,
183 const
bool _notify = true,
184 const
bool _publish = true);
189 public: virtual math::Vector3 GetRelativeLinearVel() const
190 GAZEBO_DEPRECATED(8.0);
194 public: virtual ignition::math::Vector3d RelativeLinearVel() const;
199 public: virtual math::Vector3 GetWorldLinearVel() const
200 GAZEBO_DEPRECATED(8.0);
204 public: virtual ignition::math::Vector3d WorldLinearVel() const;
209 public: virtual math::Vector3 GetRelativeAngularVel() const
210 GAZEBO_DEPRECATED(8.0);
214 public: virtual ignition::math::Vector3d RelativeAngularVel() const;
219 public: virtual math::Vector3 GetWorldAngularVel() const
220 GAZEBO_DEPRECATED(8.0);
224 public: virtual ignition::math::Vector3d WorldAngularVel() const;
229 public: virtual math::Vector3 GetRelativeLinearAccel() const
230 GAZEBO_DEPRECATED(8.0);
234 public: virtual ignition::math::Vector3d RelativeLinearAccel() const;
239 public: virtual math::Vector3 GetWorldLinearAccel() const
240 GAZEBO_DEPRECATED(8.0);
244 public: virtual ignition::math::Vector3d WorldLinearAccel() const;
249 public: virtual math::Vector3 GetRelativeAngularAccel() const
250 GAZEBO_DEPRECATED(8.0);
254 public: virtual ignition::math::Vector3d RelativeAngularAccel() const;
259 public: virtual math::Vector3 GetWorldAngularAccel() const
260 GAZEBO_DEPRECATED(8.0);
264 public: virtual ignition::math::Vector3d WorldAngularAccel() const;
268 public:
void SetCanonicalLink(
bool _value);
272 public: inline
bool IsCanonicalLink()
const
273 {
return this->isCanonicalLink;}
279 boost::function<
void()> _onComplete);
286 public:
virtual void StopAnimation();
295 public:
CollisionPtr GetChildCollision(
const std::string &_name);
300 public:
LinkPtr GetChildLink(
const std::string &_name);
306 public:
void GetNearestEntityBelow(
double &_distBelow,
307 std::string &_entityName);
310 public:
void PlaceOnNearestEntityBelow();
315 public:
void PlaceOnEntity(
const std::string &_entityName);
320 public:
math::Box GetCollisionBoundingBox() const GAZEBO_DEPRECATED(8.0);
324 public: ignition::math::Box CollisionBoundingBox() const;
332 public:
void SetWorldTwist(const math::Vector3 &_linear,
333 const math::Vector3 &_angular,
334 bool _updateChildren = true)
335 GAZEBO_DEPRECATED(8.0);
342 public:
void SetWorldTwist(const ignition::math::Vector3d &_linear,
343 const ignition::math::Vector3d &_angular,
344 const
bool _updateChildren = true);
352 public: const math::Pose GetDirtyPose() const GAZEBO_DEPRECATED(8.0);
359 public: const ignition::math::Pose3d &DirtyPose() const;
363 protected: virtual
void OnPoseChange() = 0;
366 private: virtual
void PublishPose();
371 private: ignition::math::Box CollisionBoundingBoxHelper(
378 private:
void SetWorldPoseModel(const ignition::math::Pose3d &_pose,
380 const
bool _publish);
386 private:
void SetWorldPoseCanonicalLink(
387 const ignition::math::Pose3d &_pose,
388 const
bool _notify, const
bool _publish);
394 private:
void SetWorldPoseDefault(const ignition::math::Pose3d &_pose,
395 const
bool _notify, const
bool _publish);
399 private:
void OnPoseMsg(ConstPosePtr &_msg);
406 private:
void UpdatePhysicsPose(
bool update_children = true);
410 private:
void UpdateAnimation(const common::UpdateInfo &_info);
416 protected: mutable ignition::math::Pose3d worldPose;
428 protected: msgs::Visual *visualMsg;
434 protected: common::Time prevAnimationTime;
437 protected: ignition::math::Pose3d animationStartPose;
446 protected: ignition::math::Pose3d dirtyPose;
449 protected: ignition::math::Vector3d scale;
452 private:
bool isStatic;
455 private:
bool isCanonicalLink;
458 private: ignition::math::Pose3d initialRelativePose;
467 private: boost::function<
void()> onAnimationComplete;
470 private:
void (
Entity::*setWorldPoseFunc)(const ignition::math::Pose3d &,
471 const
bool, const
bool);
477 protected: ignition::transport::Node nodeIgn;
480 protected: ignition::transport::Node::Publisher visPubIgn;
483 protected: ignition::transport::Node::Publisher requestPubIgn;
486 private: ignition::transport::Node::Publisher posePubIgn;
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
boost::shared_ptr< PoseAnimation > PoseAnimationPtr
Definition: CommonTypes.hh:109
Encapsulates a position and rotation in three space.
Definition: Pose.hh:42
Mathematical representation of a box and related functions.
Definition: Box.hh:41
virtual void Reset()
Reset the object.
Forward declarations for transport.
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
default namespace for gazebo
virtual const ignition::math::Pose3d & WorldPose() const
Get the absolute pose of the entity.
Definition: Entity.hh:138
Base class for most physics classes.
Definition: Base.hh:77
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
Forward declarations for the math classes.
virtual const math::Pose GetWorldPose() const GAZEBO_DEPRECATED(8.0)
Get the absolute pose of the entity.
Definition: Entity.hh:123
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< Model > ModelPtr
Definition: PhysicsTypes.hh:93
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:113
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:77