17 #ifndef GAZEBO_PHYSICS_ENTITY_HH_    18 #define GAZEBO_PHYSICS_ENTITY_HH_    22 #include <ignition/math/AxisAlignedBox.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::AxisAlignedBox 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::AxisAlignedBox 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::AxisAlignedBox 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;
 
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:110
boost::shared_ptr< PoseAnimation > PoseAnimationPtr
Definition: CommonTypes.hh:109
Definition: JointMaker.hh:44
Forward declarations for the common classes. 
Definition: Animation.hh:26
ignition::transport::Node nodeIgn
Ignition communication node. 
Definition: Entity.hh:346
ignition::math::Vector3d scale
Scale of the entity. 
Definition: Entity.hh:318
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:165
Information for use in an update event. 
Definition: UpdateInfo.hh:30
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
ignition::math::Pose3d worldPose
World pose of the entity. 
Definition: Entity.hh:285
default namespace for gazebo 
common::Time prevAnimationTime
Previous time an animation was updated. 
Definition: Entity.hh:303
transport::PublisherPtr requestPub
Request publisher. 
Definition: Entity.hh:294
ignition::transport::Node::Publisher requestPubIgn
Request publisher. 
Definition: Entity.hh:352
Base class for most physics classes. 
Definition: Base.hh:72
ignition::transport::Node::Publisher visPubIgn
Visual publisher. 
Definition: Entity.hh:349
virtual const ignition::math::Pose3d & WorldPose() const
Get the absolute pose of the entity. 
Definition: Entity.hh:102
event::ConnectionPtr animationConnection
Connection used to update an animation. 
Definition: Entity.hh:312
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
Base class for all physics objects in Gazebo. 
Definition: Entity.hh:52
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:86
transport::PublisherPtr visPub
Visual publisher. 
Definition: Entity.hh:291
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:94
ignition::math::Pose3d animationStartPose
Start pose of an animation. 
Definition: Entity.hh:306
msgs::Visual * visualMsg
Visual message container. 
Definition: Entity.hh:297
common::PoseAnimationPtr animation
Current pose animation. 
Definition: Entity.hh:300
EntityPtr parentEntity
A helper that prevents numerous dynamic_casts. 
Definition: Entity.hh:282
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:114
transport::NodePtr node
Communication node. 
Definition: Entity.hh:288
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:78
A Time class, can be used to hold wall- or sim-time. 
Definition: Time.hh:47
ignition::math::Pose3d dirtyPose
The pose set by a physics engine. 
Definition: Entity.hh:315
std::vector< event::ConnectionPtr > connections
All our event connections. 
Definition: Entity.hh:309