All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Groups Pages
Link.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 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 #include <map>
25 #include <vector>
26 #include <string>
27 
28 #include "gazebo/msgs/msgs.hh"
30 
31 #include "gazebo/util/UtilTypes.hh"
32 #include "gazebo/common/Event.hh"
34 
36 #include "gazebo/physics/Entity.hh"
38 #include "gazebo/physics/Joint.hh"
39 #include "gazebo/util/system.hh"
40 
41 namespace gazebo
42 {
43  namespace util
44  {
45  class OpenALSource;
46  class OpenALSink;
47  }
48 
49  namespace physics
50  {
51  class Model;
52  class Collision;
53 
56 
61  class GAZEBO_VISIBLE Link : public Entity
62  {
65  public: explicit Link(EntityPtr _parent);
66 
68  public: virtual ~Link();
69 
72  public: virtual void Load(sdf::ElementPtr _sdf);
73 
75  public: virtual void Init();
76 
78  public: void Fini();
79 
81  public: void Reset();
82 
84  public: void ResetPhysicsStates();
85 
88  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
89 
92  public: void Update(const common::UpdateInfo &_info);
93  using Base::Update;
94 
97  public: void SetScale(const math::Vector3 &_scale);
98 
101  public: virtual void SetEnabled(bool _enable) const = 0;
102 
105  public: virtual bool GetEnabled() const = 0;
106 
110  public: virtual bool SetSelected(bool _set);
111 
114  public: virtual void SetGravityMode(bool _mode) = 0;
115 
118  public: virtual bool GetGravityMode() const = 0;
119 
123  public: virtual void SetSelfCollide(bool _collide) = 0;
124 
133  public: void SetCollideMode(const std::string &_mode);
134 
138  public: bool GetSelfCollide() const;
139 
142  public: void SetLaserRetro(float _retro);
143 
146  public: virtual void SetLinearVel(const math::Vector3 &_vel) = 0;
147 
150  public: virtual void SetAngularVel(const math::Vector3 &_vel) = 0;
151 
154  public: void SetLinearAccel(const math::Vector3 &_accel);
155 
158  public: void SetAngularAccel(const math::Vector3 &_accel);
159 
162  public: virtual void SetForce(const math::Vector3 &_force) = 0;
163 
166  public: virtual void SetTorque(const math::Vector3 &_torque) = 0;
167 
170  public: virtual void AddForce(const math::Vector3 &_force) = 0;
171 
175  public: virtual void AddRelativeForce(const math::Vector3 &_force) = 0;
176 
180  public: virtual void AddForceAtWorldPosition(const math::Vector3 &_force,
181  const math::Vector3 &_pos) = 0;
182 
187  public: virtual void AddForceAtRelativePosition(
188  const math::Vector3 &_force,
189  const math::Vector3 &_relPos) = 0;
190 
193  public: virtual void AddTorque(const math::Vector3 &_torque) = 0;
194 
198  public: virtual void AddRelativeTorque(const math::Vector3 &_torque) = 0;
199 
204  public: math::Pose GetWorldCoGPose() const;
205 
209  public: virtual math::Vector3 GetWorldLinearVel() const
210  {return this->GetWorldLinearVel(math::Vector3::Zero);}
211 
219  public: virtual math::Vector3 GetWorldLinearVel(
220  const math::Vector3 &_offset) const = 0;
221 
229  public: virtual math::Vector3 GetWorldLinearVel(
230  const math::Vector3 &_offset,
231  const math::Quaternion &_q) const = 0;
232 
237  public: virtual math::Vector3 GetWorldCoGLinearVel() const = 0;
238 
241  public: math::Vector3 GetRelativeLinearVel() const;
242 
245  public: math::Vector3 GetRelativeAngularVel() const;
246 
249  public: math::Vector3 GetRelativeLinearAccel() const;
250 
253  public: math::Vector3 GetWorldLinearAccel() const;
254 
257  public: math::Vector3 GetRelativeAngularAccel() const;
258 
262  public: math::Vector3 GetWorldAngularAccel() const;
263 
266  public: math::Vector3 GetRelativeForce() const;
267 
270  public: virtual math::Vector3 GetWorldForce() const = 0;
271 
274  public: math::Vector3 GetRelativeTorque() const;
275 
278  public: virtual math::Vector3 GetWorldTorque() const = 0;
279 
282  public: ModelPtr GetModel() const;
283 
286  public: InertialPtr GetInertial() const {return this->inertial;}
287 
290  public: void SetInertial(const InertialPtr &_inertial);
291 
297  public: math::Pose GetWorldInertialPose() const;
298 
302  public: math::Matrix3 GetWorldInertiaMatrix() const;
303 
309  public: CollisionPtr GetCollisionById(unsigned int _id) const;
311 
315  public: CollisionPtr GetCollision(const std::string &_name);
316 
320  public: CollisionPtr GetCollision(unsigned int _index) const;
321 
324  public: Collision_V GetCollisions() const;
325 
329  public: virtual math::Box GetBoundingBox() const;
330 
333  public: virtual void SetLinearDamping(double _damping) = 0;
334 
337  public: virtual void SetAngularDamping(double _damping) = 0;
338 
341  public: double GetLinearDamping() const;
342 
345  public: double GetAngularDamping() const;
346 
350  public: virtual void SetKinematic(const bool &_kinematic);
351 
355  public: virtual bool GetKinematic() const {return false;}
356 
363  public: unsigned int GetSensorCount() const;
364 
376  public: std::string GetSensorName(unsigned int _index) const;
377 
381  public: template<typename T>
383  {return enabledSignal.Connect(_subscriber);}
384 
388  {enabledSignal.Disconnect(_conn);}
389 
392  public: void FillMsg(msgs::Link &_msg);
393 
396  public: void ProcessMsg(const msgs::Link &_msg);
397 
400  public: void AddChildJoint(JointPtr _joint);
401 
404  public: void AddParentJoint(JointPtr _joint);
405 
408  public: void RemoveParentJoint(const std::string &_jointName);
409 
412  public: void RemoveChildJoint(const std::string &_jointName);
413 
414  // Documentation inherited.
415  public: virtual void RemoveChild(EntityPtr _child);
416  using Base::RemoveChild;
417 
421  public: void AttachStaticModel(ModelPtr &_model,
422  const math::Pose &_offset);
423 
426  public: void DetachStaticModel(const std::string &_modelName);
427 
429  public: void DetachAllStaticModels();
430 
433  public: virtual void OnPoseChange();
434 
437  public: void SetState(const LinkState &_state);
438 
440  public: virtual void UpdateMass() {}
441 
443  public: virtual void UpdateSurface() {}
444 
447  public: virtual void SetAutoDisable(bool _disable) = 0;
448 
451  public: Link_V GetChildJointsLinks() const;
452 
455  public: Link_V GetParentJointsLinks() const;
456 
459  public: void SetPublishData(bool _enable);
460 
462  public: Joint_V GetParentJoints() const;
463 
465  public: Joint_V GetChildJoints() const;
466 
469  public: void RemoveCollision(const std::string &_name);
470 
474  public: double GetWorldEnergyPotential() const;
475 
479  public: double GetWorldEnergyKinetic() const;
480 
485  public: double GetWorldEnergy() const;
486 
490  public: msgs::Visual GetVisualMessage(const std::string &_name) const;
491 
495  public: virtual void SetLinkStatic(bool _static) = 0;
496 
505  public: void MoveFrame(const math::Pose &_worldReferenceFrameSrc,
506  const math::Pose &_worldReferenceFrameDst);
507 
522  public: bool FindAllConnectedLinksHelper(
523  const LinkPtr &_originalParentLink,
524  Link_V &_connectedLinks, bool _fistLink = false);
525 
527  private: void PublishData();
528 
531  private: void LoadCollision(sdf::ElementPtr _sdf);
532 
535  private: void SetInertialFromCollisions();
536 
539  private: void OnCollision(ConstContactsPtr &_msg);
540 
542  private: void ParseVisuals();
543 
548  private: bool ContainsLink(const Link_V &_vector, const LinkPtr &_value);
549 
551  private: void UpdateVisualSDF();
552 
554  protected: InertialPtr inertial;
555 
557  protected: std::vector<std::string> cgVisuals;
558 
561  typedef std::map<uint32_t, msgs::Visual> Visuals_M;
562 
564  protected: Visuals_M visuals;
565 
568 
571 
573  protected: std::vector<math::Pose> attachedModelsOffset;
574 
576  protected: bool initialized;
577 
579  private: event::EventT<void (bool)> enabledSignal;
580 
582  private: bool enabled;
583 
585  private: std::vector<std::string> sensors;
586 
588  private: std::vector<JointPtr> parentJoints;
589 
591  private: std::vector<JointPtr> childJoints;
592 
594  private: std::vector<ModelPtr> attachedModels;
595 
597  private: transport::PublisherPtr dataPub;
598 
600  private: msgs::LinkData linkDataMsg;
601 
603  private: bool publishData;
604 
606  private: boost::recursive_mutex *publishDataMutex;
607 
609  private: Collision_V collisions;
610 
612  private: math::Vector3 scale;
613 
614 #ifdef HAVE_OPENAL
615  private: std::vector<util::OpenALSourcePtr> audioSources;
617 
619  private: util::OpenALSinkPtr audioSink;
620 
623  private: transport::SubscriberPtr audioContactsSub;
624 #endif
625  };
627  }
628 }
629 #endif
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:144
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:174
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:82
Encapsulates a position and rotation in three space.
Definition: Pose.hh:40
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
Mathematical representation of a box and related functions.
Definition: Box.hh:33
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:48
boost::shared_ptr< Inertial > InertialPtr
Definition: PhysicsTypes.hh:126
Forward declarations for transport.
virtual void Update()
Update the object.
Definition: Base.hh:165
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:182
Information for use in an update event.
Definition: UpdateInfo.hh:30
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:94
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:74
OpenAL Source.
Definition: OpenAL.hh:112
A quaternion class.
Definition: Quaternion.hh:45
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
static const Vector3 Zero
math::Vector3(0, 0, 0)
Definition: Vector3.hh:46
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:98
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:186
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:44
Store state information of a physics::Link object.
Definition: LinkState.hh:49
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90
OpenAL Listener.
Definition: OpenAL.hh:91