68 public:
virtual ~
Link();
72 public:
virtual void Load(sdf::ElementPtr _sdf);
75 public:
virtual void Init();
84 public:
void ResetPhysicsStates();
88 public:
virtual void UpdateParameters(sdf::ElementPtr _sdf);
101 public:
virtual void SetEnabled(
bool _enable)
const = 0;
105 public:
virtual bool GetEnabled()
const = 0;
110 public:
virtual bool SetSelected(
bool _set);
114 public:
virtual void SetGravityMode(
bool _mode) = 0;
118 public:
virtual bool GetGravityMode()
const = 0;
123 public:
virtual void SetSelfCollide(
bool _collide) = 0;
133 public:
void SetCollideMode(
const std::string &_mode);
138 public:
bool GetSelfCollide()
const;
142 public:
void SetLaserRetro(
float _retro);
146 public:
virtual void SetLinearVel(
const math::Vector3 &_vel) = 0;
150 public:
virtual void SetAngularVel(
const math::Vector3 &_vel) = 0;
162 public:
virtual void SetForce(
const math::Vector3 &_force) = 0;
166 public:
virtual void SetTorque(
const math::Vector3 &_torque) = 0;
170 public:
virtual void AddForce(
const math::Vector3 &_force) = 0;
175 public:
virtual void AddRelativeForce(
const math::Vector3 &_force) = 0;
180 public:
virtual void AddForceAtWorldPosition(
const math::Vector3 &_force,
187 public:
virtual void AddForceAtRelativePosition(
193 public:
virtual void AddTorque(
const math::Vector3 &_torque) = 0;
198 public:
virtual void AddRelativeTorque(
const math::Vector3 &_torque) = 0;
237 public:
virtual math::Vector3 GetWorldCoGLinearVel()
const = 0;
290 public:
void SetInertial(
const InertialPtr &_inertial);
297 public:
math::Pose GetWorldInertialPose()
const;
309 public:
CollisionPtr GetCollisionById(
unsigned int _id)
const;
315 public:
CollisionPtr GetCollision(
const std::string &_name);
320 public:
CollisionPtr GetCollision(
unsigned int _index)
const;
329 public:
virtual math::Box GetBoundingBox()
const;
333 public:
virtual void SetLinearDamping(
double _damping) = 0;
337 public:
virtual void SetAngularDamping(
double _damping) = 0;
341 public:
double GetLinearDamping()
const;
345 public:
double GetAngularDamping()
const;
350 public:
virtual void SetKinematic(
const bool &_kinematic);
363 public:
unsigned int GetSensorCount()
const;
376 public: std::string GetSensorName(
unsigned int _index)
const;
381 public:
template<
typename T>
383 {
return enabledSignal.Connect(_subscriber);}
388 {enabledSignal.Disconnect(_conn);}
392 public:
void FillMsg(msgs::Link &_msg);
396 public:
void ProcessMsg(
const msgs::Link &_msg);
400 public:
void AddChildJoint(
JointPtr _joint);
404 public:
void AddParentJoint(
JointPtr _joint);
408 public:
void RemoveParentJoint(
const std::string &_jointName);
412 public:
void RemoveChildJoint(
const std::string &_jointName);
415 public:
virtual void RemoveChild(
EntityPtr _child);
421 public:
void AttachStaticModel(
ModelPtr &_model,
426 public:
void DetachStaticModel(
const std::string &_modelName);
429 public:
void DetachAllStaticModels();
433 public:
virtual void OnPoseChange();
437 public:
void SetState(
const LinkState &_state);
447 public:
virtual void SetAutoDisable(
bool _disable) = 0;
451 public:
Link_V GetChildJointsLinks()
const;
455 public:
Link_V GetParentJointsLinks()
const;
459 public:
void SetPublishData(
bool _enable);
462 public:
Joint_V GetParentJoints()
const;
465 public:
Joint_V GetChildJoints()
const;
469 public:
void RemoveCollision(
const std::string &_name);
474 public:
double GetWorldEnergyPotential()
const;
479 public:
double GetWorldEnergyKinetic()
const;
485 public:
double GetWorldEnergy()
const;
490 public: msgs::Visual GetVisualMessage(
const std::string &_name)
const;
495 public:
virtual void SetLinkStatic(
bool _static) = 0;
505 public:
void MoveFrame(
const math::Pose &_worldReferenceFrameSrc,
522 public:
bool FindAllConnectedLinksHelper(
523 const LinkPtr &_originalParentLink,
524 Link_V &_connectedLinks,
bool _fistLink =
false);
527 private:
void PublishData();
531 private:
void LoadCollision(sdf::ElementPtr _sdf);
535 private:
void SetInertialFromCollisions();
539 private:
void OnCollision(ConstContactsPtr &_msg);
542 private:
void ParseVisuals();
548 private:
bool ContainsLink(
const Link_V &_vector,
const LinkPtr &_value);
551 private:
void UpdateVisualSDF();
582 private:
bool enabled;
585 private: std::vector<std::string> sensors;
588 private: std::vector<JointPtr> parentJoints;
591 private: std::vector<JointPtr> childJoints;
594 private: std::vector<ModelPtr> attachedModels;
600 private: msgs::LinkData linkDataMsg;
603 private:
bool publishData;
606 private: boost::recursive_mutex *publishDataMutex;
615 private: std::vector<util::OpenALSourcePtr> audioSources;
bool initialized
This flag is set to true when the link is initialized.
Definition: Link.hh:576
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
virtual void UpdateSurface()
Update surface parameters.
Definition: Link.hh:443
virtual void UpdateMass()
Update the mass matrix.
Definition: Link.hh:440
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
virtual math::Vector3 GetWorldLinearVel() const
Get the linear velocity of the origin of the link frame, expressed in the world frame.
Definition: Link.hh:209
InertialPtr inertial
Inertial properties.
Definition: Link.hh:554
virtual bool GetKinematic() const
Implement this function.
Definition: Link.hh:355
Forward declarations for transport.
virtual void Update()
Update the object.
Definition: Base.hh:165
std::vector< std::string > cgVisuals
Center of gravity visual elements.
Definition: Link.hh:557
Link class defines a rigid body entity, containing information on inertia, visual and collision prope...
Definition: Link.hh:61
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:182
InertialPtr GetInertial() const
Get the inertia of the link.
Definition: Link.hh:286
Information for use in an update event.
Definition: UpdateInfo.hh:30
Visuals_M visuals
Link visual elements.
Definition: Link.hh:564
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
std::vector< math::Pose > attachedModelsOffset
Offsets for the attached models.
Definition: Link.hh:573
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
math::Vector3 linearAccel
Linear acceleration.
Definition: Link.hh:567
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.
void DisconnectEnabled(event::ConnectionPtr &_conn)
Disconnect to the add entity signal.
Definition: Link.hh:387
math::Vector3 angularAccel
Angular acceleration.
Definition: Link.hh:570
std::vector< CollisionPtr > Collision_V
Definition: PhysicsTypes.hh:186
std::map< uint32_t, msgs::Visual > Visuals_M
Definition: Link.hh:561
event::ConnectionPtr ConnectEnabled(T _subscriber)
Connect to the add entity signal.
Definition: Link.hh:382
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