Link.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2016 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  class Battery;
60 
63 
69  {
72  public: explicit Link(EntityPtr _parent);
73 
75  public: virtual ~Link();
76 
79  public: virtual void Load(sdf::ElementPtr _sdf);
80 
82  public: virtual void Init();
83 
85  public: void Fini();
86 
88  public: void Reset();
89 
91  public: void ResetPhysicsStates();
92 
95  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
96 
99  public: void Update(const common::UpdateInfo &_info);
100  using Base::Update;
101 
104  public: void SetScale(const math::Vector3 &_scale);
105 
108  public: virtual void SetEnabled(bool _enable) const = 0;
109 
112  public: virtual bool GetEnabled() const = 0;
113 
117  public: virtual bool SetSelected(bool _set);
118 
121  public: virtual void SetGravityMode(bool _mode) = 0;
122 
125  public: virtual bool GetGravityMode() const = 0;
126 
131  public: virtual void SetSelfCollide(bool _collide) = 0;
132 
141  public: void SetCollideMode(const std::string &_mode);
142 
150  public: bool GetSelfCollide() const;
151 
154  public: void SetLaserRetro(float _retro);
155 
158  public: virtual void SetLinearVel(const math::Vector3 &_vel) = 0;
159 
162  public: virtual void SetAngularVel(const math::Vector3 &_vel) = 0;
163 
166  public: void SetLinearAccel(const math::Vector3 &_accel);
167 
170  public: void SetAngularAccel(const math::Vector3 &_accel);
171 
174  public: virtual void SetForce(const math::Vector3 &_force) = 0;
175 
178  public: virtual void SetTorque(const math::Vector3 &_torque) = 0;
179 
182  public: virtual void AddForce(const math::Vector3 &_force) = 0;
183 
187  public: virtual void AddRelativeForce(const math::Vector3 &_force) = 0;
188 
192  public: virtual void AddForceAtWorldPosition(const math::Vector3 &_force,
193  const math::Vector3 &_pos) = 0;
194 
199  public: virtual void AddForceAtRelativePosition(
200  const math::Vector3 &_force,
201  const math::Vector3 &_relPos) = 0;
202 
209  public: virtual void AddLinkForce(const math::Vector3 &_force,
210  const math::Vector3 &_offset = math::Vector3::Zero) = 0;
211 
214  public: virtual void AddTorque(const math::Vector3 &_torque) = 0;
215 
219  public: virtual void AddRelativeTorque(const math::Vector3 &_torque) = 0;
220 
225  public: math::Pose GetWorldCoGPose() const;
226 
230  public: virtual math::Vector3 GetWorldLinearVel() const
231  {return this->GetWorldLinearVel(math::Vector3::Zero);}
232 
240  public: virtual math::Vector3 GetWorldLinearVel(
241  const math::Vector3 &_offset) const = 0;
242 
250  public: virtual math::Vector3 GetWorldLinearVel(
251  const math::Vector3 &_offset,
252  const math::Quaternion &_q) const = 0;
253 
258  public: virtual math::Vector3 GetWorldCoGLinearVel() const = 0;
259 
262  public: math::Vector3 GetRelativeLinearVel() const;
263 
266  public: math::Vector3 GetRelativeAngularVel() const;
267 
270  public: math::Vector3 GetRelativeLinearAccel() const;
271 
274  public: math::Vector3 GetWorldLinearAccel() const;
275 
278  public: math::Vector3 GetRelativeAngularAccel() const;
279 
285  public: math::Vector3 GetWorldAngularMomentum() const;
286 
294  public: math::Vector3 GetWorldAngularAccel() const;
295 
298  public: math::Vector3 GetRelativeForce() const;
299 
302  public: virtual math::Vector3 GetWorldForce() const = 0;
303 
306  public: math::Vector3 GetRelativeTorque() const;
307 
310  public: virtual math::Vector3 GetWorldTorque() const = 0;
311 
314  public: ModelPtr GetModel() const;
315 
318  public: InertialPtr GetInertial() const {return this->inertial;}
319 
322  public: void SetInertial(const InertialPtr &_inertial);
323 
329  public: math::Pose GetWorldInertialPose() const;
330 
334  public: math::Matrix3 GetWorldInertiaMatrix() const;
335 
341  public: CollisionPtr GetCollisionById(unsigned int _id) const;
343 
347  public: CollisionPtr GetCollision(const std::string &_name);
348 
352  public: CollisionPtr GetCollision(unsigned int _index) const;
353 
356  public: Collision_V GetCollisions() const;
357 
361  public: virtual math::Box GetBoundingBox() const;
362 
365  public: virtual void SetLinearDamping(double _damping) = 0;
366 
369  public: virtual void SetAngularDamping(double _damping) = 0;
370 
373  public: double GetLinearDamping() const;
374 
377  public: double GetAngularDamping() const;
378 
382  public: virtual void SetKinematic(const bool &_kinematic);
383 
387  public: virtual bool GetKinematic() const {return false;}
388 
395  public: unsigned int GetSensorCount() const;
396 
408  public: std::string GetSensorName(unsigned int _index) const;
409 
413  public: template<typename T>
415  {return enabledSignal.Connect(_subscriber);}
416 
420  {enabledSignal.Disconnect(_conn);}
421 
424  public: void FillMsg(msgs::Link &_msg);
425 
428  public: void ProcessMsg(const msgs::Link &_msg);
429 
432  public: void AddChildJoint(JointPtr _joint);
433 
436  public: void AddParentJoint(JointPtr _joint);
437 
440  public: void RemoveParentJoint(const std::string &_jointName);
441 
444  public: void RemoveChildJoint(const std::string &_jointName);
445 
446  // Documentation inherited.
447  public: virtual void RemoveChild(EntityPtr _child);
448  using Base::RemoveChild;
449 
453  public: void AttachStaticModel(ModelPtr &_model,
454  const math::Pose &_offset);
455 
458  public: void DetachStaticModel(const std::string &_modelName);
459 
461  public: void DetachAllStaticModels();
462 
465  public: virtual void OnPoseChange();
466 
469  public: void SetState(const LinkState &_state);
470 
472  public: virtual void UpdateMass() {}
473 
475  public: virtual void UpdateSurface() {}
476 
479  public: virtual void SetAutoDisable(bool _disable) = 0;
480 
483  public: Link_V GetChildJointsLinks() const;
484 
487  public: Link_V GetParentJointsLinks() const;
488 
491  public: void SetPublishData(bool _enable);
492 
494  public: Joint_V GetParentJoints() const;
495 
497  public: Joint_V GetChildJoints() const;
498 
501  public: void RemoveCollision(const std::string &_name);
502 
506  public: double GetWorldEnergyPotential() const;
507 
511  public: double GetWorldEnergyKinetic() const;
512 
517  public: double GetWorldEnergy() const;
518 
522  public: msgs::Visual GetVisualMessage(const std::string &_name) const;
523 
527  public: virtual void SetLinkStatic(bool _static) = 0;
528 
537  public: void MoveFrame(const math::Pose &_worldReferenceFrameSrc,
538  const math::Pose &_worldReferenceFrameDst);
539 
554  public: bool FindAllConnectedLinksHelper(
555  const LinkPtr &_originalParentLink,
556  Link_V &_connectedLinks, bool _fistLink = false);
557 
561  public: common::BatteryPtr Battery(const std::string &_name) const;
562 
565  public: common::BatteryPtr Battery(const size_t _index) const;
566 
570  public: size_t BatteryCount() const;
571 
576  public: bool VisualId(const std::string &_visName, uint32_t &_visualId)
577  const;
578 
583  public: bool VisualPose(const uint32_t _id,
584  ignition::math::Pose3d &_pose) const;
585 
590  public: bool SetVisualPose(const uint32_t _id,
591  const ignition::math::Pose3d &_pose);
592 
594  private: void PublishData();
595 
598  private: void LoadCollision(sdf::ElementPtr _sdf);
599 
602  private: void SetInertialFromCollisions();
603 
606  private: void OnCollision(ConstContactsPtr &_msg);
607 
609  private: void ParseVisuals();
610 
615  private: bool ContainsLink(const Link_V &_vector, const LinkPtr &_value);
616 
619  private: void UpdateVisualGeomSDF(const math::Vector3 &_scale);
620 
622  private: void UpdateVisualMsg();
623 
627  private: void OnWrenchMsg(ConstWrenchPtr &_msg);
628 
631  private: void ProcessWrenchMsg(const msgs::Wrench &_msg);
632 
635  private: void LoadBattery(const sdf::ElementPtr _sdf);
636 
638  protected: InertialPtr inertial;
639 
641  protected: std::vector<std::string> cgVisuals;
642 
645  typedef std::map<uint32_t, msgs::Visual> Visuals_M;
646 
648  protected: Visuals_M visuals;
649 
652 
655 
657  protected: std::vector<math::Pose> attachedModelsOffset;
658 
660  protected: bool initialized;
661 
663  private: event::EventT<void (bool)> enabledSignal;
664 
666  private: bool enabled;
667 
669  private: std::vector<std::string> sensors;
670 
672  private: std::vector<JointPtr> parentJoints;
673 
675  private: std::vector<JointPtr> childJoints;
676 
678  private: std::vector<ModelPtr> attachedModels;
679 
681  private: transport::PublisherPtr dataPub;
682 
684  private: msgs::LinkData linkDataMsg;
685 
687  private: bool publishData;
688 
690  private: boost::recursive_mutex *publishDataMutex;
691 
693  private: Collision_V collisions;
694 
696  private: transport::SubscriberPtr wrenchSub;
697 
699  private: std::vector<msgs::Wrench> wrenchMsgs;
700 
702  private: boost::mutex wrenchMsgMutex;
703 
705  private: std::vector<common::BatteryPtr> batteries;
706 
707 #ifdef HAVE_OPENAL
708  private: std::vector<util::OpenALSourcePtr> audioSources;
710 
712  private: util::OpenALSinkPtr audioSink;
713 
716  private: transport::SubscriberPtr audioContactsSub;
717 #endif
718  };
720  }
721 }
722 #endif
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:153
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:204
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:88
#define GZ_PHYSICS_VISIBLE
Definition: system.hh:259
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:148
Forward declarations for transport.
std::shared_ptr< OpenALSink > OpenALSinkPtr
Definition: UtilTypes.hh:44
virtual void Update()
Update the object.
Definition: Base.hh:173
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:216
Information for use in an update event.
Definition: UpdateInfo.hh:30
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:104
A 3x3 matrix class.
Definition: Matrix3.hh:34
std::shared_ptr< Battery > BatteryPtr
Definition: CommonTypes.hh:144
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:80
OpenAL Source.
Definition: OpenAL.hh:108
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:108
Base class for all physics objects in Gazebo.
Definition: Entity.hh:58
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
std::vector< CollisionPtr > Collision_V
Definition: PhysicsTypes.hh:220
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:100
OpenAL Listener.
Definition: OpenAL.hh:87