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();
    79       public: 
virtual void UpdateParameters(sdf::ElementPtr _sdf);
    83       public: 
virtual void SetName(
const std::string &_name);
    87       public: 
void SetStatic(
const bool &_static);
    91       public: 
bool IsStatic() 
const;
    95       public: 
void SetInitialRelativePose(
const math::Pose &_pose);
    99       public: 
math::Pose GetInitialRelativePose() 
const;
   103       public: 
virtual math::Box GetBoundingBox() 
const;
   108               {
return this->worldPose;}
   118       public: 
void SetRelativePose(
const math::Pose &_pose,
   120                                    bool _publish = 
true);
   126       public: 
void SetWorldPose(
const math::Pose &_pose,
   128                                 bool _publish = 
true);
   172       public: 
void SetCanonicalLink(
bool _value);
   177               {
return this->isCanonicalLink;}
   183                                 boost::function<
void()> _onComplete);
   190       public: 
virtual void StopAnimation();
   199       public: 
CollisionPtr GetChildCollision(
const std::string &_name);
   204       public: 
LinkPtr GetChildLink(
const std::string &_name);
   210       public: 
void GetNearestEntityBelow(
double &_distBelow,
   211                                          std::string &_entityName);
   214       public: 
void PlaceOnNearestEntityBelow();
   219       public: 
void PlaceOnEntity(
const std::string &_entityName);
   223       public: 
math::Box GetCollisionBoundingBox() 
const;
   232                                  bool _updateChildren = 
true);
   239       public: 
const math::Pose &GetDirtyPose() 
const;
   243       protected: 
virtual void OnPoseChange() = 0;
   246       private: 
virtual void PublishPose();
   257       private: 
void SetWorldPoseModel(
const math::Pose &_pose,
   265       private: 
void SetWorldPoseCanonicalLink(
const math::Pose &_pose,
   266                                               bool _notify, 
bool _publish);
   272       private: 
void SetWorldPoseDefault(
const math::Pose &_pose, 
bool _notify,
   277       private: 
void OnPoseMsg(ConstPosePtr &_msg);
   284       private: 
void UpdatePhysicsPose(
bool update_children = 
true);
   327       protected: ignition::math::Vector3d 
scale;
   330       private: 
bool isStatic;
   333       private: 
bool isCanonicalLink;
   345       private: boost::function<void()> onAnimationComplete;
 
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:100
 
boost::shared_ptr< PoseAnimation > PoseAnimationPtr
Definition: CommonTypes.hh:128
 
Definition: JointMaker.hh:46
 
Forward declarations for the common classes. 
Definition: Animation.hh:33
 
math::Pose dirtyPose
The pose set by a physics engine. 
Definition: Entity.hh:324
 
Encapsulates a position and rotation in three space. 
Definition: Pose.hh:37
 
virtual math::Vector3 GetRelativeAngularAccel() const
Get the angular acceleration of the entity. 
Definition: Entity.hh:162
 
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:315
 
ignition::math::Vector3d scale
Scale of the entity. 
Definition: Entity.hh:327
 
Forward declarations for transport. 
 
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
 
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
 
bool IsCanonicalLink() const
A helper function that checks if this is a canonical body. 
Definition: Entity.hh:176
 
virtual math::Vector3 GetRelativeLinearVel() const
Get the linear velocity of the entity. 
Definition: Entity.hh:132
 
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 GetWorldAngularAccel() const
Get the angular acceleration of the entity in the world frame. 
Definition: Entity.hh:167
 
virtual math::Vector3 GetWorldLinearAccel() const
Get the linear acceleration of the entity in the world frame. 
Definition: Entity.hh:157
 
virtual const math::Pose & GetWorldPose() const
Get the absolute pose of the entity. 
Definition: Entity.hh:107
 
common::Time prevAnimationTime
Previous time an animation was updated. 
Definition: Entity.hh:312
 
transport::PublisherPtr requestPub
Request publisher. 
Definition: Entity.hh:303
 
Base class for most physics classes. 
Definition: Base.hh:81
 
virtual math::Vector3 GetRelativeAngularVel() const
Get the angular velocity of the entity. 
Definition: Entity.hh:142
 
event::ConnectionPtr animationConnection
Connection used to update an animation. 
Definition: Entity.hh:321
 
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:80
 
transport::PublisherPtr visPub
Visual publisher. 
Definition: Entity.hh:300
 
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:88
 
msgs::Visual * visualMsg
Visual message container. 
Definition: Entity.hh:306
 
common::PoseAnimationPtr animation
Current pose animation. 
Definition: Entity.hh:309
 
virtual math::Vector3 GetRelativeLinearAccel() const
Get the linear acceleration of the entity. 
Definition: Entity.hh:152
 
virtual math::Vector3 GetWorldAngularVel() const
Get the angular velocity of the entity in the world frame. 
Definition: Entity.hh:147
 
EntityPtr parentEntity
A helper that prevents numerous dynamic_casts. 
Definition: Entity.hh:291
 
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:104
 
math::Pose worldPose
World pose of the entity. 
Definition: Entity.hh:294
 
transport::NodePtr node
Communication node. 
Definition: Entity.hh:297
 
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:72
 
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:318
 
virtual math::Vector3 GetWorldLinearVel() const
Get the linear velocity of the entity in the world frame. 
Definition: Entity.hh:137