All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Link.hh
Go to the documentation of this file.
1 /*
2  * Copyright 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 /* 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 
40 namespace gazebo
41 {
42  namespace util
43  {
44  class OpenALSource;
45  class OpenALSink;
46  }
47 
48  namespace physics
49  {
50  class Model;
51  class Collision;
52 
55 
60  class Link : public Entity
61  {
64  public: explicit Link(EntityPtr _parent);
65 
67  public: virtual ~Link();
68 
71  public: virtual void Load(sdf::ElementPtr _sdf);
72 
74  public: virtual void Init();
75 
77  public: void Fini();
78 
80  public: void Reset();
81 
83  public: void ResetPhysicsStates();
84 
87  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
88 
91  public: void Update(const common::UpdateInfo &_info);
92 
95  public: void SetScale(const math::Vector3 &_scale);
96 
99  public: virtual void SetEnabled(bool _enable) const = 0;
100 
103  public: virtual bool GetEnabled() const = 0;
104 
108  public: virtual bool SetSelected(bool _set);
109 
112  public: virtual void SetGravityMode(bool _mode) = 0;
113 
116  public: virtual bool GetGravityMode() const = 0;
117 
121  public: virtual void SetSelfCollide(bool _collide) = 0;
122 
131  public: void SetCollideMode(const std::string &_mode);
132 
136  public: bool GetSelfCollide() const;
137 
140  public: void SetLaserRetro(float _retro);
141 
144  public: virtual void SetLinearVel(const math::Vector3 &_vel) = 0;
145 
148  public: virtual void SetAngularVel(const math::Vector3 &_vel) = 0;
149 
152  public: void SetLinearAccel(const math::Vector3 &_accel);
153 
156  public: void SetAngularAccel(const math::Vector3 &_accel);
157 
160  public: virtual void SetForce(const math::Vector3 &_force) = 0;
161 
164  public: virtual void SetTorque(const math::Vector3 &_torque) = 0;
165 
168  public: virtual void AddForce(const math::Vector3 &_force) = 0;
169 
173  public: virtual void AddRelativeForce(const math::Vector3 &_force) = 0;
174 
178  public: virtual void AddForceAtWorldPosition(const math::Vector3 &_force,
179  const math::Vector3 &_pos) = 0;
180 
185  public: virtual void AddForceAtRelativePosition(
186  const math::Vector3 &_force,
187  const math::Vector3 &_relPos) = 0;
188 
191  public: virtual void AddTorque(const math::Vector3 &_torque) = 0;
192 
196  public: virtual void AddRelativeTorque(const math::Vector3 &_torque) = 0;
197 
202  public: math::Pose GetWorldCoGPose() const;
203 
211  public: virtual math::Vector3 GetWorldLinearVel(
212  const math::Vector3 &_offset = math::Vector3(0, 0, 0)) const = 0;
213 
221  public: virtual math::Vector3 GetWorldLinearVel(
222  const math::Vector3 &_offset,
223  const math::Quaternion &_q) const = 0;
224 
229  public: virtual math::Vector3 GetWorldCoGLinearVel() const = 0;
230 
233  public: math::Vector3 GetRelativeLinearVel() const;
234 
237  public: math::Vector3 GetRelativeAngularVel() const;
238 
241  public: math::Vector3 GetRelativeLinearAccel() const;
242 
245  public: math::Vector3 GetWorldLinearAccel() const;
246 
249  public: math::Vector3 GetRelativeAngularAccel() const;
250 
254  public: math::Vector3 GetWorldAngularAccel() const;
255 
258  public: math::Vector3 GetRelativeForce() const;
259 
262  public: virtual math::Vector3 GetWorldForce() const = 0;
263 
266  public: math::Vector3 GetRelativeTorque() const;
267 
270  public: virtual math::Vector3 GetWorldTorque() const = 0;
271 
274  public: ModelPtr GetModel() const;
275 
278  public: InertialPtr GetInertial() const {return this->inertial;}
279 
282  public: void SetInertial(const InertialPtr &_inertial);
283 
289  public: CollisionPtr GetCollisionById(unsigned int _id) const;
291 
295  public: CollisionPtr GetCollision(const std::string &_name);
296 
300  public: CollisionPtr GetCollision(unsigned int _index) const;
301 
304  public: Collision_V GetCollisions() const;
305 
309  public: virtual math::Box GetBoundingBox() const;
310 
313  public: virtual void SetLinearDamping(double _damping) = 0;
314 
317  public: virtual void SetAngularDamping(double _damping) = 0;
318 
321  public: double GetLinearDamping() const;
322 
325  public: double GetAngularDamping() const;
326 
330  public: virtual void SetKinematic(const bool &_kinematic);
331 
335  public: virtual bool GetKinematic() const {return false;}
336 
343  public: unsigned int GetSensorCount() const;
344 
356  public: std::string GetSensorName(unsigned int _index) const;
357 
361  public: template<typename T>
363  {return enabledSignal.Connect(_subscriber);}
364 
368  {enabledSignal.Disconnect(_conn);}
369 
372  public: void FillMsg(msgs::Link &_msg);
373 
376  public: void ProcessMsg(const msgs::Link &_msg);
377 
380  public: void AddChildJoint(JointPtr _joint);
381 
384  public: void AddParentJoint(JointPtr _joint);
385 
388  public: void RemoveParentJoint(const std::string &_jointName);
389 
392  public: void RemoveChildJoint(const std::string &_jointName);
393 
394  // Documentation inherited.
395  public: virtual void RemoveChild(EntityPtr _child);
396 
400  public: void AttachStaticModel(ModelPtr &_model,
401  const math::Pose &_offset);
402 
405  public: void DetachStaticModel(const std::string &_modelName);
406 
408  public: void DetachAllStaticModels();
409 
412  public: virtual void OnPoseChange();
413 
416  public: void SetState(const LinkState &_state);
417 
419  public: virtual void UpdateMass() {}
420 
422  public: virtual void UpdateSurface() {}
423 
426  public: virtual void SetAutoDisable(bool _disable) = 0;
427 
430  public: Link_V GetChildJointsLinks() const;
431 
434  public: Link_V GetParentJointsLinks() const;
435 
438  public: void SetPublishData(bool _enable);
439 
441  public: Joint_V GetParentJoints() const;
442 
444  public: Joint_V GetChildJoints() const;
445 
448  public: void RemoveCollision(const std::string &_name);
449 
453  public: virtual void SetLinkStatic(bool _static) = 0;
454 
456  private: void PublishData();
457 
460  private: void LoadCollision(sdf::ElementPtr _sdf);
461 
464  private: void SetInertialFromCollisions();
465 
468  private: void OnCollision(ConstContactsPtr &_msg);
469 
471  private: void ParseVisuals();
472 
474  protected: InertialPtr inertial;
475 
477  protected: std::vector<std::string> cgVisuals;
478 
481  typedef std::map<uint32_t, msgs::Visual> Visuals_M;
482 
484  protected: Visuals_M visuals;
485 
488 
491 
493  protected: std::vector<math::Pose> attachedModelsOffset;
494 
496  private: event::EventT<void (bool)> enabledSignal;
497 
499  private: bool enabled;
500 
502  private: std::vector<std::string> sensors;
503 
505  private: std::vector<JointPtr> parentJoints;
506 
508  private: std::vector<JointPtr> childJoints;
509 
511  private: std::vector<ModelPtr> attachedModels;
512 
514  private: transport::PublisherPtr dataPub;
515 
517  private: msgs::LinkData linkDataMsg;
518 
520  private: std::vector<event::ConnectionPtr> connections;
521 
523  private: bool publishData;
524 
526  private: boost::recursive_mutex *publishDataMutex;
527 
529  private: Collision_V collisions;
530 
531 #ifdef HAVE_OPENAL
532 
533  private: std::vector<util::OpenALSourcePtr> audioSources;
534 
536  private: util::OpenALSinkPtr audioSink;
537 
540  private: transport::SubscriberPtr audioContactsSub;
541 #endif
542  };
544  }
545 }
546 #endif