Link.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_LINK_HH_
18 #define GAZEBO_PHYSICS_LINK_HH_
19 
20 #ifdef _WIN32
21  // Ensure that Winsock2.h is included before Windows.h, which can get
22  // pulled in by anybody (e.g., Boost).
23  #include <Winsock2.h>
24 #endif
25 
26 #include <map>
27 #include <vector>
28 #include <string>
29 #include <ignition/math/Matrix3.hh>
30 
31 #include "gazebo/msgs/msgs.hh"
33 
34 #include "gazebo/util/UtilTypes.hh"
35 #include "gazebo/common/Event.hh"
37 
39 #include "gazebo/physics/Entity.hh"
41 #include "gazebo/physics/Joint.hh"
42 #include "gazebo/util/system.hh"
43 
44 namespace gazebo
45 {
46  namespace util
47  {
48  class OpenALSource;
49  class OpenALSink;
50  }
51 
52  namespace physics
53  {
54  class Model;
55  class Collision;
56  class Battery;
57 
60 
65  class GZ_PHYSICS_VISIBLE Link : public Entity
66  {
69  public: explicit Link(EntityPtr _parent);
70 
72  public: virtual ~Link();
73 
76  public: virtual void Load(sdf::ElementPtr _sdf);
77 
79  public: virtual void Init();
80 
82  public: void Fini();
83 
85  public: void Reset();
86  using Entity::Reset;
87 
89  public: void ResetPhysicsStates();
90 
93  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
94 
97  public: void Update(const common::UpdateInfo &_info);
98  using Base::Update;
99 
103  public: void SetScale(const math::Vector3 &_scale) GAZEBO_DEPRECATED(8.0);
104 
107  public: void SetScale(const ignition::math::Vector3d &_scale);
108 
111  public: virtual void SetEnabled(bool _enable) const = 0;
112 
115  public: virtual bool GetEnabled() const = 0;
116 
120  public: virtual bool SetSelected(bool _set);
121 
124  public: virtual void SetGravityMode(bool _mode) = 0;
125 
128  public: virtual bool GetGravityMode() const = 0;
129 
132  public: virtual void SetWindMode(const bool _mode);
133 
136  public: virtual bool WindMode() const;
137 
142  public: virtual void SetSelfCollide(bool _collide) = 0;
143 
152  public: void SetCollideMode(const std::string &_mode);
153 
161  public: bool GetSelfCollide() const;
162 
165  public: void SetLaserRetro(float _retro);
166 
170  public: virtual void SetLinearVel(const math::Vector3 &_vel)
171  GAZEBO_DEPRECATED(8.0);
172 
175  public: virtual void SetLinearVel(
176  const ignition::math::Vector3d &_vel) = 0;
177 
181  public: virtual void SetAngularVel(const math::Vector3 &_vel)
182  GAZEBO_DEPRECATED(8.0);
183 
186  public: virtual void SetAngularVel(
187  const ignition::math::Vector3d &_vel) = 0;
188 
189 
193  public: void SetLinearAccel(const math::Vector3 &_accel)
194  GAZEBO_DEPRECATED(8.0);
195 
199  public: void SetAngularAccel(const math::Vector3 &_accel)
200  GAZEBO_DEPRECATED(8.0);
201 
205  public: virtual void SetForce(const math::Vector3 &_force)
206  GAZEBO_DEPRECATED(8.0);
207 
211  public: virtual void SetTorque(const math::Vector3 &_torque)
212  GAZEBO_DEPRECATED(8.0);
213 
217  public: virtual void AddForce(const math::Vector3 &_force)
218  GAZEBO_DEPRECATED(8.0);
219 
224  public: virtual void AddRelativeForce(const math::Vector3 &_force)
225  GAZEBO_DEPRECATED(8.0);
226 
231  public: virtual void AddForceAtWorldPosition(const math::Vector3 &_force,
232  const math::Vector3 &_pos) GAZEBO_DEPRECATED(8.0);
233 
239  public: virtual void AddForceAtRelativePosition(
240  const math::Vector3 &_force,
241  const math::Vector3 &_relPos) GAZEBO_DEPRECATED(8.0);
242 
250  public: virtual void AddLinkForce(const math::Vector3 &_force,
251  const math::Vector3 &_offset = math::Vector3::Zero)
252  GAZEBO_DEPRECATED(8.0);
253 
257  public: virtual void AddTorque(const math::Vector3 &_torque)
258  GAZEBO_DEPRECATED(8.0);
259 
264  public: virtual void AddRelativeTorque(const math::Vector3 &_torque)
265  GAZEBO_DEPRECATED(8.0);
266 
269  public: void SetLinearAccel(const ignition::math::Vector3d &_accel);
270 
273  public: void SetAngularAccel(const ignition::math::Vector3d &_accel);
274 
277  public: virtual void SetForce(
278  const ignition::math::Vector3d &_force) = 0;
279 
282  public: virtual void SetTorque(
283  const ignition::math::Vector3d &_torque) = 0;
284 
287  public: virtual void AddForce(const ignition::math::Vector3d &_force) = 0;
288 
292  public: virtual void AddRelativeForce(
293  const ignition::math::Vector3d &_force) = 0;
294 
298  public: virtual void AddForceAtWorldPosition(
299  const ignition::math::Vector3d &_force,
300  const ignition::math::Vector3d &_pos) = 0;
301 
306  public: virtual void AddForceAtRelativePosition(
307  const ignition::math::Vector3d &_force,
308  const ignition::math::Vector3d &_relPos) = 0;
309 
316  public: virtual void AddLinkForce(const ignition::math::Vector3d &_force,
317  const ignition::math::Vector3d &_offset =
318  ignition::math::Vector3d::Zero) = 0;
319 
322  public: virtual void AddTorque(
323  const ignition::math::Vector3d &_torque) = 0;
324 
328  public: virtual void AddRelativeTorque(
329  const ignition::math::Vector3d &_torque) = 0;
330 
336  public: math::Pose GetWorldCoGPose() const GAZEBO_DEPRECATED(8.0);
337 
342  public: ignition::math::Pose3d WorldCoGPose() const;
343 
348  public: virtual math::Vector3 GetWorldLinearVel() const
349  GAZEBO_DEPRECATED(8.0);
350 
354  public: virtual ignition::math::Vector3d WorldLinearVel() const;
355 
365  public: virtual math::Vector3 GetWorldLinearVel(
366  const math::Vector3 &_offset) const GAZEBO_DEPRECATED(8.0);
367 
375  public: virtual ignition::math::Vector3d WorldLinearVel(
376  const ignition::math::Vector3d &_offset) const = 0;
377 
386  public: virtual math::Vector3 GetWorldLinearVel(
387  const math::Vector3 &_offset,
388  const math::Quaternion &_q) const GAZEBO_DEPRECATED(8.0);
389 
397  public: virtual ignition::math::Vector3d WorldLinearVel(
398  const ignition::math::Vector3d &_offset,
399  const ignition::math::Quaterniond &_q) const = 0;
400 
406  public: virtual math::Vector3 GetWorldCoGLinearVel() const
407  GAZEBO_DEPRECATED(8.0);
408 
413  public: virtual ignition::math::Vector3d WorldCoGLinearVel() const = 0;
414 
418  public: math::Vector3 GetRelativeLinearVel() const
419  GAZEBO_DEPRECATED(8.0);
420 
423  public: ignition::math::Vector3d RelativeLinearVel() const;
424 
428  public: math::Vector3 GetRelativeAngularVel() const
429  GAZEBO_DEPRECATED(8.0);
430 
433  public: ignition::math::Vector3d RelativeAngularVel() const;
434 
438  public: math::Vector3 GetRelativeLinearAccel() const
439  GAZEBO_DEPRECATED(8.0);
440 
443  public: ignition::math::Vector3d RelativeLinearAccel() const;
444 
448  public: math::Vector3 GetWorldLinearAccel() const
449  GAZEBO_DEPRECATED(8.0);
450 
453  public: ignition::math::Vector3d WorldLinearAccel() const;
454 
458  public: math::Vector3 GetRelativeAngularAccel() const
459  GAZEBO_DEPRECATED(8.0);
460 
463  public: ignition::math::Vector3d RelativeAngularAccel() const;
464 
471  public: math::Vector3 GetWorldAngularMomentum() const
472  GAZEBO_DEPRECATED(8.0);
473 
479  public: ignition::math::Vector3d WorldAngularMomentum() const;
480 
489  public: math::Vector3 GetWorldAngularAccel() const GAZEBO_DEPRECATED(8.0);
490 
498  public: ignition::math::Vector3d WorldAngularAccel() const;
499 
503  public: math::Vector3 GetRelativeForce() const GAZEBO_DEPRECATED(8.0);
504 
508  public: ignition::math::Vector3d RelativeForce() const;
509 
513  public: virtual math::Vector3 GetWorldForce() const
514  GAZEBO_DEPRECATED(8.0);
515 
518  public: virtual ignition::math::Vector3d WorldForce() const = 0;
519 
523  public: math::Vector3 GetRelativeTorque() const GAZEBO_DEPRECATED(8.0);
524 
527  public: ignition::math::Vector3d RelativeTorque() const;
528 
532  public: virtual math::Vector3 GetWorldTorque() const
533  GAZEBO_DEPRECATED(8.0);
534 
537  public: virtual ignition::math::Vector3d WorldTorque() const = 0;
538 
541  public: ModelPtr GetModel() const;
542 
545  public: InertialPtr GetInertial() const {return this->inertial;}
546 
549  public: void SetInertial(const InertialPtr &_inertial);
550 
557  public: math::Pose GetWorldInertialPose() const GAZEBO_DEPRECATED(8.0);
558 
564  public: ignition::math::Pose3d WorldInertialPose() const;
565 
570  public: math::Matrix3 GetWorldInertiaMatrix() const
571  GAZEBO_DEPRECATED(8.0);
572 
576  public: ignition::math::Matrix3d WorldInertiaMatrix() const;
577 
583  public: CollisionPtr GetCollisionById(unsigned int _id) const;
585 
589  public: CollisionPtr GetCollision(const std::string &_name);
590 
594  public: CollisionPtr GetCollision(unsigned int _index) const;
595 
598  public: Collision_V GetCollisions() const;
599 
603  public: virtual ignition::math::Box BoundingBox() const;
604 
607  public: virtual void SetLinearDamping(double _damping) = 0;
608 
611  public: virtual void SetAngularDamping(double _damping) = 0;
612 
615  public: double GetLinearDamping() const;
616 
619  public: double GetAngularDamping() const;
620 
624  public: virtual void SetKinematic(const bool &_kinematic);
625 
629  public: virtual bool GetKinematic() const {return false;}
630 
637  public: unsigned int GetSensorCount() const;
638 
650  public: std::string GetSensorName(unsigned int _index) const;
651 
655  public: template<typename T>
657  {return enabledSignal.Connect(_subscriber);}
658 
663  GAZEBO_DEPRECATED(8.0)
664  {enabledSignal.Disconnect(_conn->Id());}
665 
668  public: void FillMsg(msgs::Link &_msg);
669 
672  public: void ProcessMsg(const msgs::Link &_msg);
673 
676  public: void AddChildJoint(JointPtr _joint);
677 
680  public: void AddParentJoint(JointPtr _joint);
681 
684  public: void RemoveParentJoint(const std::string &_jointName);
685 
688  public: void RemoveChildJoint(const std::string &_jointName);
689 
690  // Documentation inherited.
691  public: virtual void RemoveChild(EntityPtr _child);
692  using Base::RemoveChild;
693 
698  public: void AttachStaticModel(ModelPtr &_model,
699  const math::Pose &_offset) GAZEBO_DEPRECATED(8.0);
700 
704  public: void AttachStaticModel(ModelPtr &_model,
705  const ignition::math::Pose3d &_offset);
706 
709  public: void DetachStaticModel(const std::string &_modelName);
710 
712  public: void DetachAllStaticModels();
713 
716  public: virtual void OnPoseChange();
717 
720  public: void SetState(const LinkState &_state);
721 
723  public: virtual void UpdateMass() {}
724 
726  public: virtual void UpdateSurface() {}
727 
730  public: virtual void SetAutoDisable(bool _disable) = 0;
731 
734  public: Link_V GetChildJointsLinks() const;
735 
738  public: Link_V GetParentJointsLinks() const;
739 
742  public: void SetPublishData(bool _enable);
743 
745  public: Joint_V GetParentJoints() const;
746 
748  public: Joint_V GetChildJoints() const;
749 
752  public: void RemoveCollision(const std::string &_name);
753 
757  public: double GetWorldEnergyPotential() const;
758 
762  public: double GetWorldEnergyKinetic() const;
763 
768  public: double GetWorldEnergy() const;
769 
773  public: msgs::Visual GetVisualMessage(const std::string &_name) const;
774 
778  public: virtual void SetLinkStatic(bool _static) = 0;
779 
780  // Documentation inherited
781  public: virtual void SetStatic(const bool &_static);
782  using Entity::SetStatic;
783 
793  public: void MoveFrame(const math::Pose &_worldReferenceFrameSrc,
794  const math::Pose &_worldReferenceFrameDst)
795  GAZEBO_DEPRECATED(8.0);
796 
805  public: void MoveFrame(
806  const ignition::math::Pose3d &_worldReferenceFrameSrc,
807  const ignition::math::Pose3d &_worldReferenceFrameDst);
808 
823  public: bool FindAllConnectedLinksHelper(
824  const LinkPtr &_originalParentLink,
825  Link_V &_connectedLinks, bool _fistLink = false);
826 
829  public: void SetWindEnabled(const bool _enable);
830 
834  public: const ignition::math::Vector3d WorldWindLinearVel() const;
835 
838  public: const ignition::math::Vector3d RelativeWindLinearVel() const;
839 
842  public: void UpdateWind(const common::UpdateInfo &_info);
843 
847  public: common::BatteryPtr Battery(const std::string &_name) const;
848 
851  public: common::BatteryPtr Battery(const size_t _index) const;
852 
856  public: size_t BatteryCount() const;
857 
862  public: bool VisualId(const std::string &_visName, uint32_t &_visualId)
863  const;
864 
869  public: bool VisualPose(const uint32_t _id,
870  ignition::math::Pose3d &_pose) const;
871 
876  public: bool SetVisualPose(const uint32_t _id,
877  const ignition::math::Pose3d &_pose);
878 
880  private: void PublishData();
881 
884  private: void LoadCollision(sdf::ElementPtr _sdf);
885 
888  private: void SetInertialFromCollisions();
889 
892  private: void OnCollision(ConstContactsPtr &_msg);
893 
895  private: void ParseVisuals();
896 
901  private: bool ContainsLink(const Link_V &_vector, const LinkPtr &_value);
902 
905  private: void UpdateVisualGeomSDF(const ignition::math::Vector3d &_scale);
906 
908  private: void UpdateVisualMsg();
909 
913  private: void OnWrenchMsg(ConstWrenchPtr &_msg);
914 
917  private: void ProcessWrenchMsg(const msgs::Wrench &_msg);
918 
921  private: void LoadBattery(const sdf::ElementPtr _sdf);
922 
924  protected: virtual void RegisterIntrospectionItems();
925 
927  protected: InertialPtr inertial;
928 
931  typedef std::map<uint32_t, msgs::Visual> Visuals_M;
932 
934  protected: Visuals_M visuals;
935 
937  protected: ignition::math::Vector3d linearAccel;
938 
940  protected: ignition::math::Vector3d angularAccel;
941 
943  protected: std::vector<ignition::math::Pose3d> attachedModelsOffset;
944 
946  protected: bool initialized;
947 
949  private: event::EventT<void (bool)> enabledSignal;
950 
952  private: bool enabled;
953 
955  private: std::vector<std::string> sensors;
956 
958  private: std::vector<JointPtr> parentJoints;
959 
961  private: std::vector<JointPtr> childJoints;
962 
964  private: std::vector<ModelPtr> attachedModels;
965 
967  private: transport::PublisherPtr dataPub;
968 
970  private: msgs::LinkData linkDataMsg;
971 
973  private: bool publishData;
974 
976  private: boost::recursive_mutex *publishDataMutex;
977 
979  private: Collision_V collisions;
980 
982  private: transport::SubscriberPtr wrenchSub;
983 
985  private: std::vector<msgs::Wrench> wrenchMsgs;
986 
988  private: boost::mutex wrenchMsgMutex;
989 
991  private: ignition::math::Vector3d windLinearVel;
992 
994  private: event::ConnectionPtr updateConnection;
995 
997  private: std::vector<common::BatteryPtr> batteries;
998 
999 #ifdef HAVE_OPENAL
1000  private: std::vector<util::OpenALSourcePtr> audioSources;
1002 
1004  private: util::OpenALSinkPtr audioSink;
1005 
1008  private: transport::SubscriberPtr audioContactsSub;
1009 #endif
1010  };
1012  }
1013 }
1014 #endif
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
Encapsulates a position and rotation in three space.
Definition: Pose.hh:42
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:44
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< Joint > JointPtr
Definition: PhysicsTypes.hh:117
virtual void Update()
Update the object.
Definition: Base.hh:171
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
Information for use in an update event.
Definition: UpdateInfo.hh:30
void SetStatic(const bool &_static)
Set whether this entity is static: immovable.
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:213
std::vector< CollisionPtr > Collision_V
Definition: PhysicsTypes.hh:229
A quaternion class.
Definition: Quaternion.hh:48
std::shared_ptr< Battery > BatteryPtr
Definition: CommonTypes.hh:125
boost::shared_ptr< Inertial > InertialPtr
Definition: PhysicsTypes.hh:157
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
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
std::shared_ptr< OpenALSink > OpenALSinkPtr
Definition: UtilTypes.hh:44
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
virtual void Reset()
Reset the entity.
static const Vector3 Zero
math::Vector3(0, 0, 0)
Definition: Vector3.hh:47
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:225
Store state information of a physics::Link object.
Definition: LinkState.hh:47
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:113