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/common/Event.hh"
33 
35 #include "gazebo/physics/Entity.hh"
37 #include "gazebo/physics/Joint.hh"
38 
39 namespace gazebo
40 {
41  namespace physics
42  {
43  class Model;
44  class Collision;
45 
48 
53  class Link : public Entity
54  {
57  public: explicit Link(EntityPtr _parent);
58 
60  public: virtual ~Link();
61 
64  public: virtual void Load(sdf::ElementPtr _sdf);
65 
67  public: virtual void Init();
68 
70  public: void Fini();
71 
73  public: void Reset();
74 
76  public: void ResetPhysicsStates();
77 
80  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
81 
83  public: virtual void Update();
84 
87  public: virtual void SetEnabled(bool _enable) const = 0;
88 
91  public: virtual bool GetEnabled() const = 0;
92 
96  public: virtual bool SetSelected(bool _set);
97 
100  public: virtual void SetGravityMode(bool _mode) = 0;
101 
104  public: virtual bool GetGravityMode() const = 0;
105 
109  public: virtual void SetSelfCollide(bool _collide) = 0;
110 
111 
120  public: void SetCollideMode(const std::string &_mode);
121 
125  public: bool GetSelfCollide();
126 
129  public: void SetLaserRetro(float _retro);
130 
133  public: virtual void SetLinearVel(const math::Vector3 &_vel) = 0;
134 
137  public: virtual void SetAngularVel(const math::Vector3 &_vel) = 0;
138 
141  public: void SetLinearAccel(const math::Vector3 &_accel);
142 
145  public: void SetAngularAccel(const math::Vector3 &_accel);
146 
149  public: virtual void SetForce(const math::Vector3 &_force) = 0;
150 
153  public: virtual void SetTorque(const math::Vector3 &_torque) = 0;
154 
157  public: virtual void AddForce(const math::Vector3 &_force) = 0;
158 
162  public: virtual void AddRelativeForce(const math::Vector3 &_force) = 0;
163 
167  public: virtual void AddForceAtWorldPosition(const math::Vector3 &_force,
168  const math::Vector3 &_pos) = 0;
169 
174  public: virtual void AddForceAtRelativePosition(
175  const math::Vector3 &_force,
176  const math::Vector3 &_relPos) = 0;
177 
180  public: virtual void AddTorque(const math::Vector3 &_torque) = 0;
181 
185  public: virtual void AddRelativeTorque(const math::Vector3 &_torque) = 0;
186 
191  public: math::Pose GetWorldCoGPose() const;
192 
200  public: virtual math::Vector3 GetWorldLinearVel(
201  const math::Vector3 &_offset = math::Vector3(0, 0, 0)) const = 0;
202 
210  public: virtual math::Vector3 GetWorldLinearVel(
211  const math::Vector3 &_offset,
212  const math::Quaternion &_q) const = 0;
213 
218  public: virtual math::Vector3 GetWorldCoGLinearVel() const = 0;
219 
222  public: math::Vector3 GetRelativeLinearVel() const;
223 
226  public: math::Vector3 GetRelativeAngularVel() const;
227 
230  public: math::Vector3 GetRelativeLinearAccel() const;
231 
234  public: math::Vector3 GetWorldLinearAccel() const;
235 
238  public: math::Vector3 GetRelativeAngularAccel() const;
239 
243  public: math::Vector3 GetWorldAngularAccel() const;
244 
247  public: math::Vector3 GetRelativeForce() const;
248 
251  public: virtual math::Vector3 GetWorldForce() const = 0;
252 
255  public: math::Vector3 GetRelativeTorque() const;
256 
259  public: virtual math::Vector3 GetWorldTorque() const = 0;
260 
263  public: ModelPtr GetModel() const;
264 
267  public: InertialPtr GetInertial() const {return this->inertial;}
268 
271  public: void SetInertial(const InertialPtr &_inertial);
272 
278  public: CollisionPtr GetCollisionById(unsigned int _id) const;
280 
284  public: CollisionPtr GetCollision(const std::string &_name);
285 
289  public: CollisionPtr GetCollision(unsigned int _index) const;
290 
293  public: Collision_V GetCollisions() const;
294 
298  public: virtual math::Box GetBoundingBox() const;
299 
302  public: virtual void SetLinearDamping(double _damping) = 0;
303 
306  public: virtual void SetAngularDamping(double _damping) = 0;
307 
310  public: double GetLinearDamping() const;
311 
314  public: double GetAngularDamping() const;
315 
319  public: virtual void SetKinematic(const bool &_kinematic);
320 
324  public: virtual bool GetKinematic() const {return false;}
325 
332  public: unsigned int GetSensorCount() const;
333 
345  public: std::string GetSensorName(unsigned int _index) const;
346 
350  public: template<typename T>
352  {return enabledSignal.Connect(_subscriber);}
353 
357  {enabledSignal.Disconnect(_conn);}
358 
361  public: void FillMsg(msgs::Link &_msg);
362 
365  public: void ProcessMsg(const msgs::Link &_msg);
366 
369  public: void AddChildJoint(JointPtr _joint);
370 
373  public: void AddParentJoint(JointPtr _joint);
374 
377  public: void RemoveChildJoint(JointPtr _joint) GAZEBO_DEPRECATED(1.5);
378 
381  public: void RemoveParentJoint(JointPtr _joint) GAZEBO_DEPRECATED(1.5);
382 
385  public: void RemoveParentJoint(const std::string &_jointName);
386 
389  public: void RemoveChildJoint(const std::string &_jointName);
390 
394  public: void AttachStaticModel(ModelPtr &_model,
395  const math::Pose &_offset);
396 
399  public: void DetachStaticModel(const std::string &_modelName);
400 
402  public: void DetachAllStaticModels();
403 
406  public: virtual void OnPoseChange();
407 
410  public: void SetState(const LinkState &_state);
411 
413  public: virtual void UpdateMass() {}
414 
416  public: virtual void UpdateSurface() {}
417 
420  public: virtual void SetAutoDisable(bool _disable) = 0;
421 
424  public: Link_V GetChildJointsLinks() const;
425 
428  public: Link_V GetParentJointsLinks() const;
429 
432  public: void SetPublishData(bool _enable);
433 
435  private: void PublishData();
436 
439  private: void LoadCollision(sdf::ElementPtr _sdf);
440 
443  private: void SetInertialFromCollisions();
444 
446  protected: InertialPtr inertial;
447 
449  protected: std::vector<std::string> cgVisuals;
450 
452  protected: std::vector<std::string> visuals;
453 
456 
459 
461  protected: std::vector<math::Pose> attachedModelsOffset;
462 
464  private: event::EventT<void (bool)> enabledSignal;
465 
467  private: bool enabled;
468 
470  private: std::vector<std::string> sensors;
471 
473  private: std::vector<JointPtr> parentJoints;
474 
476  private: std::vector<JointPtr> childJoints;
477 
479  private: std::vector<ModelPtr> attachedModels;
480 
482  private: transport::PublisherPtr dataPub;
483 
485  private: msgs::LinkData linkDataMsg;
486 
488  private: std::vector<event::ConnectionPtr> connections;
489 
491  private: bool publishData;
492 
494  private: boost::recursive_mutex *publishDataMutex;
495  };
497  }
498 }
499 #endif