27 #include <ignition/math/Vector3.hh>
29 #include <boost/function.hpp>
46 class recursive_mutex;
69 public:
virtual void Load(sdf::ElementPtr _sdf);
72 public:
virtual void Fini();
75 public:
virtual void Reset();
80 public:
virtual void UpdateParameters(sdf::ElementPtr _sdf);
84 public:
virtual void SetName(
const std::string &_name);
88 public:
void SetStatic(
const bool &_static);
92 public:
bool IsStatic()
const;
96 public:
void SetInitialRelativePose(
const math::Pose &_pose);
100 public:
math::Pose GetInitialRelativePose()
const;
104 public:
virtual math::Box GetBoundingBox()
const;
109 {
return this->worldPose;}
119 public:
void SetRelativePose(
const math::Pose &_pose,
121 bool _publish =
true);
127 public:
void SetWorldPose(
const math::Pose &_pose,
129 bool _publish =
true);
173 public:
void SetCanonicalLink(
bool _value);
178 {
return this->isCanonicalLink;}
184 boost::function<
void()> _onComplete);
191 public:
virtual void StopAnimation();
200 public:
CollisionPtr GetChildCollision(
const std::string &_name);
205 public:
LinkPtr GetChildLink(
const std::string &_name);
211 public:
void GetNearestEntityBelow(
double &_distBelow,
212 std::string &_entityName);
215 public:
void PlaceOnNearestEntityBelow();
220 public:
void PlaceOnEntity(
const std::string &_entityName);
224 public:
math::Box GetCollisionBoundingBox()
const;
233 bool _updateChildren =
true);
240 public:
const math::Pose &GetDirtyPose()
const;
244 protected:
virtual void OnPoseChange() = 0;
247 private:
virtual void PublishPose();
258 private:
void SetWorldPoseModel(
const math::Pose &_pose,
266 private:
void SetWorldPoseCanonicalLink(
const math::Pose &_pose,
267 bool _notify,
bool _publish);
273 private:
void SetWorldPoseDefault(
const math::Pose &_pose,
bool _notify,
278 private:
void OnPoseMsg(ConstPosePtr &_msg);
285 private:
void UpdatePhysicsPose(
bool update_children =
true);
328 protected: ignition::math::Vector3d
scale;
331 private:
bool isStatic;
334 private:
bool isCanonicalLink;
346 private: boost::function<void()> onAnimationComplete;
virtual math::Vector3 GetWorldAngularVel() const
Get the angular velocity of the entity in the world frame.
Definition: Entity.hh:148
virtual math::Vector3 GetWorldLinearVel() const
Get the linear velocity of the entity in the world frame.
Definition: Entity.hh:138
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
boost::shared_ptr< PoseAnimation > PoseAnimationPtr
Definition: CommonTypes.hh:128
math::Pose dirtyPose
The pose set by a physics engine.
Definition: Entity.hh:325
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
virtual math::Vector3 GetRelativeLinearAccel() const
Get the linear acceleration of the entity.
Definition: Entity.hh:153
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
math::Pose animationStartPose
Start pose of an animation.
Definition: Entity.hh:316
ignition::math::Vector3d scale
Scale of the entity.
Definition: Entity.hh:328
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
Information for use in an update event.
Definition: UpdateInfo.hh:30
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
default namespace for gazebo
virtual math::Vector3 GetRelativeAngularVel() const
Get the angular velocity of the entity.
Definition: Entity.hh:143
virtual math::Vector3 GetWorldLinearAccel() const
Get the linear acceleration of the entity in the world frame.
Definition: Entity.hh:158
virtual math::Vector3 GetWorldAngularAccel() const
Get the angular acceleration of the entity in the world frame.
Definition: Entity.hh:168
bool IsCanonicalLink() const
A helper function that checks if this is a canonical body.
Definition: Entity.hh:177
common::Time prevAnimationTime
Previous time an animation was updated.
Definition: Entity.hh:313
transport::PublisherPtr requestPub
Request publisher.
Definition: Entity.hh:304
Base class for most physics classes.
Definition: Base.hh:77
event::ConnectionPtr animationConnection
Connection used to update an animation.
Definition: Entity.hh:322
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:153
Forward declarations for the math classes.
Base class for all physics objects in Gazebo.
Definition: Entity.hh:58
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:85
transport::PublisherPtr visPub
Visual publisher.
Definition: Entity.hh:301
virtual const math::Pose & GetWorldPose() const
Get the absolute pose of the entity.
Definition: Entity.hh:108
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:93
virtual math::Vector3 GetRelativeLinearVel() const
Get the linear velocity of the entity.
Definition: Entity.hh:133
msgs::Visual * visualMsg
Visual message container.
Definition: Entity.hh:307
common::PoseAnimationPtr animation
Current pose animation.
Definition: Entity.hh:310
virtual math::Vector3 GetRelativeAngularAccel() const
Get the angular acceleration of the entity.
Definition: Entity.hh:163
EntityPtr parentEntity
A helper that prevents numerous dynamic_casts.
Definition: Entity.hh:292
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:113
math::Pose worldPose
World pose of the entity.
Definition: Entity.hh:295
transport::NodePtr node
Communication node.
Definition: Entity.hh:298
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:77
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:44
std::vector< event::ConnectionPtr > connections
All our event connections.
Definition: Entity.hh:319