Link.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2015 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 /* Desc: Link class
18  * Author: Nate Koenig
19  */
20 
21 #ifndef _LINK_HH_
22 #define _LINK_HH_
23 
24 #ifdef _WIN32
25  // Ensure that Winsock2.h is included before Windows.h, which can get
26  // pulled in by anybody (e.g., Boost).
27  #include <Winsock2.h>
28 #endif
29 
30 #include <map>
31 #include <vector>
32 #include <string>
33 
34 #include "gazebo/msgs/msgs.hh"
36 
37 #include "gazebo/util/UtilTypes.hh"
38 #include "gazebo/common/Event.hh"
40 
42 #include "gazebo/physics/Entity.hh"
44 #include "gazebo/physics/Joint.hh"
45 #include "gazebo/util/system.hh"
46 
47 namespace gazebo
48 {
49  namespace util
50  {
51  class OpenALSource;
52  class OpenALSink;
53  }
54 
55  namespace physics
56  {
57  class Model;
58  class Collision;
59 
62 
68  {
71  public: explicit Link(EntityPtr _parent);
72 
74  public: virtual ~Link();
75 
78  public: virtual void Load(sdf::ElementPtr _sdf);
79 
81  public: virtual void Init();
82 
84  public: void Fini();
85 
87  public: void Reset();
88 
90  public: void ResetPhysicsStates();
91 
94  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
95 
98  public: void Update(const common::UpdateInfo &_info);
99  using Base::Update;
100 
103  public: void SetScale(const math::Vector3 &_scale);
104 
107  public: virtual void SetEnabled(bool _enable) const = 0;
108 
111  public: virtual bool GetEnabled() const = 0;
112 
116  public: virtual bool SetSelected(bool _set);
117 
120  public: virtual void SetGravityMode(bool _mode) = 0;
121 
124  public: virtual bool GetGravityMode() const = 0;
125 
130  public: virtual void SetSelfCollide(bool _collide) = 0;
131 
140  public: void SetCollideMode(const std::string &_mode);
141 
149  public: bool GetSelfCollide() const;
150 
153  public: void SetLaserRetro(float _retro);
154 
157  public: virtual void SetLinearVel(const math::Vector3 &_vel) = 0;
158 
161  public: virtual void SetAngularVel(const math::Vector3 &_vel) = 0;
162 
165  public: void SetLinearAccel(const math::Vector3 &_accel);
166 
169  public: void SetAngularAccel(const math::Vector3 &_accel);
170 
173  public: virtual void SetForce(const math::Vector3 &_force) = 0;
174 
177  public: virtual void SetTorque(const math::Vector3 &_torque) = 0;
178 
181  public: virtual void AddForce(const math::Vector3 &_force) = 0;
182 
186  public: virtual void AddRelativeForce(const math::Vector3 &_force) = 0;
187 
191  public: virtual void AddForceAtWorldPosition(const math::Vector3 &_force,
192  const math::Vector3 &_pos) = 0;
193 
198  public: virtual void AddForceAtRelativePosition(
199  const math::Vector3 &_force,
200  const math::Vector3 &_relPos) = 0;
201 
208  public: virtual void AddLinkForce(const math::Vector3 &_force,
209  const math::Vector3 &_offset = math::Vector3::Zero) = 0;
210 
213  public: virtual void AddTorque(const math::Vector3 &_torque) = 0;
214 
218  public: virtual void AddRelativeTorque(const math::Vector3 &_torque) = 0;
219 
224  public: math::Pose GetWorldCoGPose() const;
225 
229  public: virtual math::Vector3 GetWorldLinearVel() const
230  {return this->GetWorldLinearVel(math::Vector3::Zero);}
231 
239  public: virtual math::Vector3 GetWorldLinearVel(
240  const math::Vector3 &_offset) const = 0;
241 
249  public: virtual math::Vector3 GetWorldLinearVel(
250  const math::Vector3 &_offset,
251  const math::Quaternion &_q) const = 0;
252 
257  public: virtual math::Vector3 GetWorldCoGLinearVel() const = 0;
258 
261  public: math::Vector3 GetRelativeLinearVel() const;
262 
265  public: math::Vector3 GetRelativeAngularVel() const;
266 
269  public: math::Vector3 GetRelativeLinearAccel() const;
270 
273  public: math::Vector3 GetWorldLinearAccel() const;
274 
277  public: math::Vector3 GetRelativeAngularAccel() const;
278 
284  public: math::Vector3 GetWorldAngularMomentum() const;
285 
293  public: math::Vector3 GetWorldAngularAccel() const;
294 
297  public: math::Vector3 GetRelativeForce() const;
298 
301  public: virtual math::Vector3 GetWorldForce() const = 0;
302 
305  public: math::Vector3 GetRelativeTorque() const;
306 
309  public: virtual math::Vector3 GetWorldTorque() const = 0;
310 
313  public: ModelPtr GetModel() const;
314 
317  public: InertialPtr GetInertial() const {return this->inertial;}
318 
321  public: void SetInertial(const InertialPtr &_inertial);
322 
328  public: math::Pose GetWorldInertialPose() const;
329 
333  public: math::Matrix3 GetWorldInertiaMatrix() const;
334 
340  public: CollisionPtr GetCollisionById(unsigned int _id) const;
342 
346  public: CollisionPtr GetCollision(const std::string &_name);
347 
351  public: CollisionPtr GetCollision(unsigned int _index) const;
352 
355  public: Collision_V GetCollisions() const;
356 
360  public: virtual math::Box GetBoundingBox() const;
361 
364  public: virtual void SetLinearDamping(double _damping) = 0;
365 
368  public: virtual void SetAngularDamping(double _damping) = 0;
369 
372  public: double GetLinearDamping() const;
373 
376  public: double GetAngularDamping() const;
377 
381  public: virtual void SetKinematic(const bool &_kinematic);
382 
386  public: virtual bool GetKinematic() const {return false;}
387 
394  public: unsigned int GetSensorCount() const;
395 
407  public: std::string GetSensorName(unsigned int _index) const;
408 
412  public: template<typename T>
414  {return enabledSignal.Connect(_subscriber);}
415 
419  {enabledSignal.Disconnect(_conn);}
420 
423  public: void FillMsg(msgs::Link &_msg);
424 
427  public: void ProcessMsg(const msgs::Link &_msg);
428 
431  public: void AddChildJoint(JointPtr _joint);
432 
435  public: void AddParentJoint(JointPtr _joint);
436 
439  public: void RemoveParentJoint(const std::string &_jointName);
440 
443  public: void RemoveChildJoint(const std::string &_jointName);
444 
445  // Documentation inherited.
446  public: virtual void RemoveChild(EntityPtr _child);
447  using Base::RemoveChild;
448 
452  public: void AttachStaticModel(ModelPtr &_model,
453  const math::Pose &_offset);
454 
457  public: void DetachStaticModel(const std::string &_modelName);
458 
460  public: void DetachAllStaticModels();
461 
464  public: virtual void OnPoseChange();
465 
468  public: void SetState(const LinkState &_state);
469 
471  public: virtual void UpdateMass() {}
472 
474  public: virtual void UpdateSurface() {}
475 
478  public: virtual void SetAutoDisable(bool _disable) = 0;
479 
482  public: Link_V GetChildJointsLinks() const;
483 
486  public: Link_V GetParentJointsLinks() const;
487 
490  public: void SetPublishData(bool _enable);
491 
493  public: Joint_V GetParentJoints() const;
494 
496  public: Joint_V GetChildJoints() const;
497 
500  public: void RemoveCollision(const std::string &_name);
501 
505  public: double GetWorldEnergyPotential() const;
506 
510  public: double GetWorldEnergyKinetic() const;
511 
516  public: double GetWorldEnergy() const;
517 
521  public: msgs::Visual GetVisualMessage(const std::string &_name) const;
522 
526  public: virtual void SetLinkStatic(bool _static) = 0;
527 
536  public: void MoveFrame(const math::Pose &_worldReferenceFrameSrc,
537  const math::Pose &_worldReferenceFrameDst);
538 
553  public: bool FindAllConnectedLinksHelper(
554  const LinkPtr &_originalParentLink,
555  Link_V &_connectedLinks, bool _fistLink = false);
556 
558  private: void PublishData();
559 
562  private: void LoadCollision(sdf::ElementPtr _sdf);
563 
566  private: void SetInertialFromCollisions();
567 
570  private: void OnCollision(ConstContactsPtr &_msg);
571 
573  private: void ParseVisuals();
574 
579  private: bool ContainsLink(const Link_V &_vector, const LinkPtr &_value);
580 
583  private: void UpdateVisualGeomSDF(const math::Vector3 &_scale);
584 
586  private: void UpdateVisualMsg();
587 
591  private: void OnWrenchMsg(ConstWrenchPtr &_msg);
592 
595  private: void ProcessWrenchMsg(const msgs::Wrench &_msg);
596 
598  protected: InertialPtr inertial;
599 
601  protected: std::vector<std::string> cgVisuals;
602 
605  typedef std::map<uint32_t, msgs::Visual> Visuals_M;
606 
608  protected: Visuals_M visuals;
609 
612 
615 
617  protected: std::vector<math::Pose> attachedModelsOffset;
618 
620  protected: bool initialized;
621 
623  private: event::EventT<void (bool)> enabledSignal;
624 
626  private: bool enabled;
627 
629  private: std::vector<std::string> sensors;
630 
632  private: std::vector<JointPtr> parentJoints;
633 
635  private: std::vector<JointPtr> childJoints;
636 
638  private: std::vector<ModelPtr> attachedModels;
639 
641  private: transport::PublisherPtr dataPub;
642 
644  private: msgs::LinkData linkDataMsg;
645 
647  private: bool publishData;
648 
650  private: boost::recursive_mutex *publishDataMutex;
651 
653  private: Collision_V collisions;
654 
656  private: transport::SubscriberPtr wrenchSub;
657 
659  private: std::vector<msgs::Wrench> wrenchMsgs;
660 
662  private: boost::mutex wrenchMsgMutex;
663 
664 #ifdef HAVE_OPENAL
665  private: std::vector<util::OpenALSourcePtr> audioSources;
667 
669  private: util::OpenALSinkPtr audioSink;
670 
673  private: transport::SubscriberPtr audioContactsSub;
674 #endif
675  };
677  }
678 }
679 #endif
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:147
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:188
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:84
#define GZ_PHYSICS_VISIBLE
Definition: system.hh:318
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
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
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
boost::shared_ptr< Inertial > InertialPtr
Definition: PhysicsTypes.hh:132
Forward declarations for transport.
virtual void Update()
Update the object.
Definition: Base.hh:173
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:196
Information for use in an update event.
Definition: UpdateInfo.hh:30
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:96
boost::shared_ptr< OpenALSink > OpenALSinkPtr
Definition: UtilTypes.hh:42
A 3x3 matrix class.
Definition: Matrix3.hh:34
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:76
OpenAL Source.
Definition: OpenAL.hh:131
A quaternion class.
Definition: Quaternion.hh:42
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
static const Vector3 Zero
math::Vector3(0, 0, 0)
Definition: Vector3.hh:42
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:100
Base class for all physics objects in Gazebo.
Definition: Entity.hh:56
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
std::vector< CollisionPtr > Collision_V
Definition: PhysicsTypes.hh:200
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
Store state information of a physics::Link object.
Definition: LinkState.hh:49
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:92
OpenAL Listener.
Definition: OpenAL.hh:95