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 Nate Koenig
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 
74  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
75 
77  public: virtual void Update();
78 
81  public: virtual void SetEnabled(bool _enable) const = 0;
82 
85  public: virtual bool GetEnabled() const = 0;
86 
90  public: virtual bool SetSelected(bool _set);
91 
94  public: virtual void SetGravityMode(bool _mode) = 0;
95 
98  public: virtual bool GetGravityMode() = 0;
99 
103  public: virtual void SetSelfCollide(bool _collide) = 0;
104 
105 
114  public: void SetCollideMode(const std::string &_mode);
115 
119  public: bool GetSelfCollide();
120 
123  public: void SetLaserRetro(float _retro);
124 
127  public: virtual void SetLinearVel(const math::Vector3 &_vel) = 0;
128 
131  public: virtual void SetAngularVel(const math::Vector3 &_vel) = 0;
132 
135  public: void SetLinearAccel(const math::Vector3 &_accel);
136 
139  public: void SetAngularAccel(const math::Vector3 &_accel);
140 
143  public: virtual void SetForce(const math::Vector3 &_force) = 0;
144 
147  public: virtual void SetTorque(const math::Vector3 &_torque) = 0;
148 
151  public: virtual void AddForce(const math::Vector3 &_force) = 0;
152 
156  public: virtual void AddRelativeForce(const math::Vector3 &_force) = 0;
157 
161  public: virtual void AddForceAtWorldPosition(const math::Vector3 &_force,
162  const math::Vector3 &_pos) = 0;
163 
168  public: virtual void AddForceAtRelativePosition(
169  const math::Vector3 &_force,
170  const math::Vector3 &_relPos) = 0;
171 
174  public: virtual void AddTorque(const math::Vector3 &_torque) = 0;
175 
179  public: virtual void AddRelativeTorque(const math::Vector3 &_torque) = 0;
180 
183  public: math::Vector3 GetRelativeLinearVel() const;
184 
187  public: math::Vector3 GetRelativeAngularVel() const;
188 
191  public: math::Vector3 GetRelativeLinearAccel() const;
192 
195  public: math::Vector3 GetWorldLinearAccel() const;
196 
199  public: math::Vector3 GetRelativeAngularAccel() const;
200 
204  public: math::Vector3 GetWorldAngularAccel() const;
205 
208  public: math::Vector3 GetRelativeForce() const;
209 
212  public: virtual math::Vector3 GetWorldForce() const = 0;
213 
216  public: math::Vector3 GetRelativeTorque() const;
217 
220  public: virtual math::Vector3 GetWorldTorque() const = 0;
221 
224  public: ModelPtr GetModel() const;
225 
228  public: InertialPtr GetInertial() const {return this->inertial;}
229 
232  public: void SetInertial(const InertialPtr &_inertial);
233 
237  public: CollisionPtr GetCollisionById(unsigned int _id) const;
238 
242  public: CollisionPtr GetCollision(const std::string &_name);
243 
247  public: CollisionPtr GetCollision(unsigned int _index) const;
248 
251  public: Collision_V GetCollisions() const;
252 
256  public: virtual math::Box GetBoundingBox() const;
257 
260  public: virtual void SetLinearDamping(double _damping) = 0;
261 
264  public: virtual void SetAngularDamping(double _damping) = 0;
265 
268  public: double GetLinearDamping() const;
269 
272  public: double GetAngularDamping() const;
273 
277  public: virtual void SetKinematic(const bool &_kinematic);
278 
282  public: virtual bool GetKinematic() const {return false;}
283 
290  public: unsigned int GetSensorCount() const;
291 
303  public: std::string GetSensorName(unsigned int _index) const;
304 
308  public: template<typename T>
310  {return enabledSignal.Connect(_subscriber);}
311 
315  {enabledSignal.Disconnect(_conn);}
316 
318  public: void FillLinkMsg(msgs::Link &_msg) GAZEBO_DEPRECATED;
319 
322  public: void FillMsg(msgs::Link &_msg);
323 
326  public: void ProcessMsg(const msgs::Link &_msg);
327 
330  public: void AddChildJoint(JointPtr _joint);
331 
334  public: void AddParentJoint(JointPtr _joint);
335 
338  public: void RemoveChildJoint(JointPtr _joint);
339 
342  public: void RemoveParentJoint(JointPtr _joint);
343 
347  public: void AttachStaticModel(ModelPtr &_model,
348  const math::Pose &_offset);
349 
352  public: void DetachStaticModel(const std::string &_modelName);
353 
355  public: void DetachAllStaticModels();
356 
359  public: virtual void OnPoseChange();
360 
363  public: void SetState(const LinkState &_state);
364 
366  public: virtual void UpdateMass() {}
367 
369  public: virtual void UpdateSurface() {}
370 
373  public: virtual void SetAutoDisable(bool _disable) = 0;
374 
377  public: Link_V GetChildJointsLinks() const;
378 
381  public: Link_V GetParentJointsLinks() const;
382 
385  private: void LoadCollision(sdf::ElementPtr _sdf);
386 
389  private: void SetInertialFromCollisions();
390 
392  protected: InertialPtr inertial;
393 
395  protected: std::vector<std::string> cgVisuals;
396 
398  protected: std::vector<std::string> visuals;
399 
402 
405 
407  protected: std::vector<math::Pose> attachedModelsOffset;
408 
410  private: event::EventT<void (bool)> enabledSignal;
411 
413  private: bool enabled;
414 
416  private: std::vector<std::string> sensors;
417 
419  private: std::vector<JointPtr> parentJoints;
420 
422  private: std::vector<JointPtr> childJoints;
423 
425  private: std::vector<ModelPtr> attachedModels;
426  };
428  }
429 }
430 #endif