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/common/Event.hh"
30 
32 #include "gazebo/physics/Entity.hh"
34 #include "gazebo/physics/Joint.hh"
35 
36 namespace gazebo
37 {
38  namespace physics
39  {
40  class Model;
41  class Collision;
42 
45 
50  class Link : public Entity
51  {
54  public: explicit Link(EntityPtr _parent);
55 
57  public: virtual ~Link();
58 
61  public: virtual void Load(sdf::ElementPtr _sdf);
62 
64  public: virtual void Init();
65 
67  public: void Fini();
68 
70  public: void Reset();
71 
73  public: void ResetPhysicsStates();
74 
77  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
78 
80  public: virtual void Update();
81 
84  public: virtual void SetEnabled(bool _enable) const = 0;
85 
88  public: virtual bool GetEnabled() const = 0;
89 
93  public: virtual bool SetSelected(bool _set);
94 
97  public: virtual void SetGravityMode(bool _mode) = 0;
98 
101  public: virtual bool GetGravityMode() const = 0;
102 
106  public: virtual void SetSelfCollide(bool _collide) = 0;
107 
108 
117  public: void SetCollideMode(const std::string &_mode);
118 
122  public: bool GetSelfCollide();
123 
126  public: void SetLaserRetro(float _retro);
127 
130  public: virtual void SetLinearVel(const math::Vector3 &_vel) = 0;
131 
134  public: virtual void SetAngularVel(const math::Vector3 &_vel) = 0;
135 
138  public: void SetLinearAccel(const math::Vector3 &_accel);
139 
142  public: void SetAngularAccel(const math::Vector3 &_accel);
143 
146  public: virtual void SetForce(const math::Vector3 &_force) = 0;
147 
150  public: virtual void SetTorque(const math::Vector3 &_torque) = 0;
151 
154  public: virtual void AddForce(const math::Vector3 &_force) = 0;
155 
159  public: virtual void AddRelativeForce(const math::Vector3 &_force) = 0;
160 
164  public: virtual void AddForceAtWorldPosition(const math::Vector3 &_force,
165  const math::Vector3 &_pos) = 0;
166 
171  public: virtual void AddForceAtRelativePosition(
172  const math::Vector3 &_force,
173  const math::Vector3 &_relPos) = 0;
174 
177  public: virtual void AddTorque(const math::Vector3 &_torque) = 0;
178 
182  public: virtual void AddRelativeTorque(const math::Vector3 &_torque) = 0;
183 
188  public: math::Pose GetWorldCoGPose() const;
189 
197  public: virtual math::Vector3 GetWorldLinearVel(
198  const math::Vector3 &_offset = math::Vector3(0, 0, 0)) const = 0;
199 
207  public: virtual math::Vector3 GetWorldLinearVel(
208  const math::Vector3 &_offset,
209  const math::Quaternion &_q) const = 0;
210 
215  public: virtual math::Vector3 GetWorldCoGLinearVel() const = 0;
216 
219  public: math::Vector3 GetRelativeLinearVel() const;
220 
223  public: math::Vector3 GetRelativeAngularVel() const;
224 
227  public: math::Vector3 GetRelativeLinearAccel() const;
228 
231  public: math::Vector3 GetWorldLinearAccel() const;
232 
235  public: math::Vector3 GetRelativeAngularAccel() const;
236 
240  public: math::Vector3 GetWorldAngularAccel() const;
241 
244  public: math::Vector3 GetRelativeForce() const;
245 
248  public: virtual math::Vector3 GetWorldForce() const = 0;
249 
252  public: math::Vector3 GetRelativeTorque() const;
253 
256  public: virtual math::Vector3 GetWorldTorque() const = 0;
257 
260  public: ModelPtr GetModel() const;
261 
264  public: InertialPtr GetInertial() const {return this->inertial;}
265 
268  public: void SetInertial(const InertialPtr &_inertial);
269 
275  public: CollisionPtr GetCollisionById(unsigned int _id) const;
277 
281  public: CollisionPtr GetCollision(const std::string &_name);
282 
286  public: CollisionPtr GetCollision(unsigned int _index) const;
287 
290  public: Collision_V GetCollisions() const;
291 
295  public: virtual math::Box GetBoundingBox() const;
296 
299  public: virtual void SetLinearDamping(double _damping) = 0;
300 
303  public: virtual void SetAngularDamping(double _damping) = 0;
304 
307  public: double GetLinearDamping() const;
308 
311  public: double GetAngularDamping() const;
312 
316  public: virtual void SetKinematic(const bool &_kinematic);
317 
321  public: virtual bool GetKinematic() const {return false;}
322 
329  public: unsigned int GetSensorCount() const;
330 
342  public: std::string GetSensorName(unsigned int _index) const;
343 
347  public: template<typename T>
349  {return enabledSignal.Connect(_subscriber);}
350 
354  {enabledSignal.Disconnect(_conn);}
355 
358  public: void FillMsg(msgs::Link &_msg);
359 
362  public: void ProcessMsg(const msgs::Link &_msg);
363 
366  public: void AddChildJoint(JointPtr _joint);
367 
370  public: void AddParentJoint(JointPtr _joint);
371 
374  public: void RemoveChildJoint(JointPtr _joint);
375 
378  public: void RemoveParentJoint(JointPtr _joint);
379 
383  public: void AttachStaticModel(ModelPtr &_model,
384  const math::Pose &_offset);
385 
388  public: void DetachStaticModel(const std::string &_modelName);
389 
391  public: void DetachAllStaticModels();
392 
395  public: virtual void OnPoseChange();
396 
399  public: void SetState(const LinkState &_state);
400 
402  public: virtual void UpdateMass() {}
403 
405  public: virtual void UpdateSurface() {}
406 
409  public: virtual void SetAutoDisable(bool _disable) = 0;
410 
413  public: Link_V GetChildJointsLinks() const;
414 
417  public: Link_V GetParentJointsLinks() const;
418 
421  private: void LoadCollision(sdf::ElementPtr _sdf);
422 
425  private: void SetInertialFromCollisions();
426 
428  protected: InertialPtr inertial;
429 
431  protected: std::vector<std::string> cgVisuals;
432 
434  protected: std::vector<std::string> visuals;
435 
438 
441 
443  protected: std::vector<math::Pose> attachedModelsOffset;
444 
446  private: event::EventT<void (bool)> enabledSignal;
447 
449  private: bool enabled;
450 
452  private: std::vector<std::string> sensors;
453 
455  private: std::vector<JointPtr> parentJoints;
456 
458  private: std::vector<JointPtr> childJoints;
459 
461  private: std::vector<ModelPtr> attachedModels;
462  };
464  }
465 }
466 #endif