Entity.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef GAZEBO_PHYSICS_ENTITY_HH_
18 #define GAZEBO_PHYSICS_ENTITY_HH_
19 
20 #include <string>
21 #include <vector>
22 #include <ignition/math/Box.hh>
23 #include <ignition/math/Pose3.hh>
24 #include <ignition/math/Vector3.hh>
25 #include <ignition/transport/Node.hh>
26 
27 #include <boost/function.hpp>
28 #include "gazebo/msgs/msgs.hh"
29 
33 
34 #include "gazebo/math/MathTypes.hh"
35 #include "gazebo/math/Box.hh"
36 #include "gazebo/math/Pose.hh"
37 
39 #include "gazebo/physics/Base.hh"
40 #include "gazebo/util/system.hh"
41 
42 namespace boost
43 {
44  class recursive_mutex;
45 }
46 
47 namespace gazebo
48 {
49  namespace physics
50  {
53 
56  class GZ_PHYSICS_VISIBLE Entity : public Base
57  {
60  public: explicit Entity(BasePtr _parent);
61 
63  public: virtual ~Entity();
64 
67  public: virtual void Load(sdf::ElementPtr _sdf);
68 
70  public: virtual void Fini();
71 
73  public: virtual void Reset();
74  using Base::Reset;
75 
78  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
79 
82  public: virtual void SetName(const std::string &_name);
83 
86  public: void SetStatic(const bool &_static);
87 
90  public: bool IsStatic() const;
91 
95  public: void SetInitialRelativePose(const math::Pose &_pose)
96  GAZEBO_DEPRECATED(8.0);
97 
100  public: void SetInitialRelativePose(const ignition::math::Pose3d &_pose);
101 
105  public: math::Pose GetInitialRelativePose() const GAZEBO_DEPRECATED(8.0);
106 
109  public: ignition::math::Pose3d InitialRelativePose() const;
110 
114  public: virtual math::Box GetBoundingBox() const GAZEBO_DEPRECATED(8.0);
115 
118  public: virtual ignition::math::Box BoundingBox() const;
119 
123  public: inline virtual const math::Pose GetWorldPose() const
124  GAZEBO_DEPRECATED(8.0)
125  {
126 #ifndef _WIN32
127  #pragma GCC diagnostic push
128  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
129 #endif
130  return this->worldPose;
131 #ifndef _WIN32
132  #pragma GCC diagnostic pop
133 #endif
134  }
135 
138  public: inline virtual const ignition::math::Pose3d &WorldPose() const
139  {
140  return this->worldPose;
141  }
142 
146  public: math::Pose GetRelativePose() const GAZEBO_DEPRECATED(8.0);
147 
150  public: ignition::math::Pose3d RelativePose() const;
151 
157  public: void SetRelativePose(const math::Pose &_pose,
158  bool _notify = true,
159  bool _publish = true) GAZEBO_DEPRECATED(8.0);
160 
165  public: void SetRelativePose(const ignition::math::Pose3d &_pose,
166  const bool _notify = true,
167  const bool _publish = true);
168 
174  public: void SetWorldPose(const math::Pose &_pose,
175  bool _notify = true,
176  bool _publish = true) GAZEBO_DEPRECATED(8.0);
177 
182  public: void SetWorldPose(const ignition::math::Pose3d &_pose,
183  const bool _notify = true,
184  const bool _publish = true);
185 
189  public: virtual math::Vector3 GetRelativeLinearVel() const
190  GAZEBO_DEPRECATED(8.0);
191 
194  public: virtual ignition::math::Vector3d RelativeLinearVel() const;
195 
199  public: virtual math::Vector3 GetWorldLinearVel() const
200  GAZEBO_DEPRECATED(8.0);
201 
204  public: virtual ignition::math::Vector3d WorldLinearVel() const;
205 
209  public: virtual math::Vector3 GetRelativeAngularVel() const
210  GAZEBO_DEPRECATED(8.0);
211 
214  public: virtual ignition::math::Vector3d RelativeAngularVel() const;
215 
219  public: virtual math::Vector3 GetWorldAngularVel() const
220  GAZEBO_DEPRECATED(8.0);
221 
224  public: virtual ignition::math::Vector3d WorldAngularVel() const;
225 
229  public: virtual math::Vector3 GetRelativeLinearAccel() const
230  GAZEBO_DEPRECATED(8.0);
231 
234  public: virtual ignition::math::Vector3d RelativeLinearAccel() const;
235 
239  public: virtual math::Vector3 GetWorldLinearAccel() const
240  GAZEBO_DEPRECATED(8.0);
241 
244  public: virtual ignition::math::Vector3d WorldLinearAccel() const;
245 
249  public: virtual math::Vector3 GetRelativeAngularAccel() const
250  GAZEBO_DEPRECATED(8.0);
251 
254  public: virtual ignition::math::Vector3d RelativeAngularAccel() const;
255 
259  public: virtual math::Vector3 GetWorldAngularAccel() const
260  GAZEBO_DEPRECATED(8.0);
261 
264  public: virtual ignition::math::Vector3d WorldAngularAccel() const;
265 
268  public: void SetCanonicalLink(bool _value);
269 
272  public: inline bool IsCanonicalLink() const
273  {return this->isCanonicalLink;}
274 
278  public: void SetAnimation(const common::PoseAnimationPtr &_anim,
279  boost::function<void()> _onComplete);
280 
283  public: void SetAnimation(common::PoseAnimationPtr _anim);
284 
286  public: virtual void StopAnimation();
287 
290  public: ModelPtr GetParentModel();
291 
295  public: CollisionPtr GetChildCollision(const std::string &_name);
296 
300  public: LinkPtr GetChildLink(const std::string &_name);
301 
306  public: void GetNearestEntityBelow(double &_distBelow,
307  std::string &_entityName);
308 
310  public: void PlaceOnNearestEntityBelow();
311 
315  public: void PlaceOnEntity(const std::string &_entityName);
316 
320  public: math::Box GetCollisionBoundingBox() const GAZEBO_DEPRECATED(8.0);
321 
324  public: ignition::math::Box CollisionBoundingBox() const;
325 
332  public: void SetWorldTwist(const math::Vector3 &_linear,
333  const math::Vector3 &_angular,
334  bool _updateChildren = true)
335  GAZEBO_DEPRECATED(8.0);
336 
342  public: void SetWorldTwist(const ignition::math::Vector3d &_linear,
343  const ignition::math::Vector3d &_angular,
344  const bool _updateChildren = true);
345 
352  public: const math::Pose GetDirtyPose() const GAZEBO_DEPRECATED(8.0);
353 
359  public: const ignition::math::Pose3d &DirtyPose() const;
360 
363  protected: virtual void OnPoseChange() = 0;
364 
366  private: virtual void PublishPose();
367 
371  private: ignition::math::Box CollisionBoundingBoxHelper(
372  BasePtr _base) const;
373 
378  private: void SetWorldPoseModel(const ignition::math::Pose3d &_pose,
379  const bool _notify,
380  const bool _publish);
381 
386  private: void SetWorldPoseCanonicalLink(
387  const ignition::math::Pose3d &_pose,
388  const bool _notify, const bool _publish);
389 
394  private: void SetWorldPoseDefault(const ignition::math::Pose3d &_pose,
395  const bool _notify, const bool _publish);
396 
399  private: void OnPoseMsg(ConstPosePtr &_msg);
400 
406  private: void UpdatePhysicsPose(bool update_children = true);
407 
410  private: void UpdateAnimation(const common::UpdateInfo &_info);
411 
413  protected: EntityPtr parentEntity;
414 
416  protected: mutable ignition::math::Pose3d worldPose;
417 
419  protected: transport::NodePtr node;
420 
422  protected: transport::PublisherPtr visPub;
423 
425  protected: transport::PublisherPtr requestPub;
426 
428  protected: msgs::Visual *visualMsg;
429 
431  protected: common::PoseAnimationPtr animation;
432 
434  protected: common::Time prevAnimationTime;
435 
437  protected: ignition::math::Pose3d animationStartPose;
438 
440  protected: std::vector<event::ConnectionPtr> connections;
441 
443  protected: event::ConnectionPtr animationConnection;
444 
446  protected: ignition::math::Pose3d dirtyPose;
447 
449  protected: ignition::math::Vector3d scale;
450 
452  private: bool isStatic;
453 
455  private: bool isCanonicalLink;
456 
458  private: ignition::math::Pose3d initialRelativePose;
459 
461  private: transport::PublisherPtr posePub;
462 
464  private: transport::SubscriberPtr poseSub;
465 
467  private: boost::function<void()> onAnimationComplete;
468 
470  private: void (Entity::*setWorldPoseFunc)(const ignition::math::Pose3d &,
471  const bool, const bool);
472 
473  // Place ignition::transport objects at the end of this file to
474  // guarantee they are destructed first.
475 
477  protected: ignition::transport::Node nodeIgn;
478 
480  protected: ignition::transport::Node::Publisher visPubIgn;
481 
483  protected: ignition::transport::Node::Publisher requestPubIgn;
484 
486  private: ignition::transport::Node::Publisher posePubIgn;
487  };
489  }
490 }
491 #endif
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