Go to the documentation of this file.
17 #ifndef GAZEBO_PHYSICS_BULLET_BULLETLINK_HH_
18 #define GAZEBO_PHYSICS_BULLET_BULLETLINK_HH_
31 class BulletMotionState;
46 public:
virtual void Load(sdf::ElementPtr _ptr);
49 public:
virtual void Init();
52 public:
virtual void Fini();
55 public:
virtual void OnPoseChange();
58 public:
virtual void SetEnabled(
bool _enable)
const;
61 public:
virtual bool GetEnabled()
const;
64 public:
virtual void SetLinearVel(
const ignition::math::Vector3d &_vel);
67 public:
virtual void SetAngularVel(
const ignition::math::Vector3d &_vel);
70 public:
virtual void SetForce(
const ignition::math::Vector3d &_force);
73 public:
virtual void SetTorque(
const ignition::math::Vector3d &_torque);
76 public:
virtual ignition::math::Vector3d WorldLinearVel(
77 const ignition::math::Vector3d &_offset)
const;
80 public:
virtual ignition::math::Vector3d WorldLinearVel(
81 const ignition::math::Vector3d &_offset,
82 const ignition::math::Quaterniond &_q)
const;
85 public:
virtual ignition::math::Vector3d WorldCoGLinearVel()
const;
88 public:
virtual ignition::math::Vector3d WorldAngularVel()
const;
91 public:
virtual ignition::math::Vector3d WorldForce()
const;
94 public:
virtual ignition::math::Vector3d WorldTorque()
const;
97 public:
virtual void SetGravityMode(
bool _mode);
100 public:
virtual bool GetGravityMode()
const;
103 public:
virtual void SetSelfCollide(
bool _collide);
107 public: btRigidBody *GetBulletLink()
const;
110 public:
void RemoveAndAddBody()
const;
114 public:
void ClearCollisionCache();
117 public:
virtual void SetLinearDamping(
double _damping);
120 public:
virtual void SetAngularDamping(
double _damping);
127 public:
virtual void AddForce(
const ignition::math::Vector3d &_force);
130 public:
virtual void AddRelativeForce(
131 const ignition::math::Vector3d &_force);
134 public:
virtual void AddForceAtWorldPosition(
135 const ignition::math::Vector3d &_force,
136 const ignition::math::Vector3d &_pos);
139 public:
virtual void AddForceAtRelativePosition(
140 const ignition::math::Vector3d &_force,
141 const ignition::math::Vector3d &_relpos);
144 public:
virtual void AddLinkForce(
145 const ignition::math::Vector3d &_force,
146 const ignition::math::Vector3d &_offset =
147 ignition::math::Vector3d::Zero);
150 public:
virtual void AddTorque(
const ignition::math::Vector3d &_torque);
153 public:
virtual void AddRelativeTorque(
154 const ignition::math::Vector3d &_torque);
157 public:
virtual void SetAutoDisable(
bool _disable);
160 public:
virtual void SetLinkStatic(
bool _static);
163 public:
virtual void UpdateMass();
167 private: btCollisionShape *compoundShape;
174 private: btRigidBody *rigidLink;
virtual void SetTorque(const ignition::math::Vector3d &_torque)
Set the torque applied to the body.
virtual ignition::math::Vector3d WorldLinearVel() const
Get the linear velocity of the origin of the link frame, expressed in the world frame.
Forward declarations for the common classes.
Definition: Animation.hh:26
void RemoveAndAddBody() const
Remove and re-add this rigid body from the world.
virtual void SetAutoDisable(bool _disable)
Allow the link to auto disable.
virtual void SetAngularDamping(double _damping)
Set the angular damping factor.
virtual ignition::math::Vector3d WorldAngularVel() const
Get the angular velocity of the entity in the world frame.
virtual ignition::math::Vector3d WorldCoGLinearVel() const
Get the linear velocity at the body's center of gravity in the world frame.
Bullet Link class.
Definition: BulletLink.hh:37
virtual void Load(sdf::ElementPtr _ptr)
Load the body based on an SDF element.
Bullet wrapper forward declarations and typedefs.
virtual void SetForce(const ignition::math::Vector3d &_force)
Set the force applied to the body.
virtual void AddRelativeForce(const ignition::math::Vector3d &_force)
Add a force to the body, components are relative to the body's own frame of reference.
virtual void SetSelfCollide(bool _collide)
Set whether this body will collide with others in the model.
btRigidBody * GetBulletLink() const
Get the bullet rigid body.
boost::shared_ptr< BulletPhysics > BulletPhysicsPtr
Definition: BulletTypes.hh:44
virtual ignition::math::Vector3d WorldForce() const
Get the force applied to the body in the world frame.
virtual void SetGravityMode(bool _mode)
Set whether gravity affects this body.
virtual void SetLinearVel(const ignition::math::Vector3d &_vel)
Set the linear velocity of the body.
virtual void SetLinkStatic(bool _static)
Freeze link to ground (inertial frame).
virtual bool GetGravityMode() const
Get the gravity mode.
virtual void OnPoseChange()
This function is called when the entity's (or one of its parents) pose of the parent has changed.
Link class defines a rigid body entity, containing information on inertia, visual and collision prope...
Definition: Link.hh:52
void ClearCollisionCache()
virtual ignition::math::Vector3d WorldTorque() const
Get the torque applied to the body about the center of mass in world frame coordinates.
virtual void Fini()
Finalize the entity.
virtual void Init()
Initialize the body.
virtual void AddRelativeTorque(const ignition::math::Vector3d &_torque)
Add a torque to the body, components are relative to the body's own frame of reference.
virtual void AddForceAtWorldPosition(const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_pos)
Add a force to the body using a global position.
virtual void SetEnabled(bool _enable) const
Set whether this body is enabled.
virtual void AddTorque(const ignition::math::Vector3d &_torque)
Add a torque to the body.
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
virtual void AddForceAtRelativePosition(const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_relpos)
Add a force (in world frame coordinates) to the body at a position relative to the center of mass whi...
BulletLink(EntityPtr _parent)
Constructor.
virtual ~BulletLink()
Destructor.
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:85
virtual void SetLinearDamping(double _damping)
Set the linear damping factor.
BulletMotionStatePtr motionState
Pointer to bullet motion state, which manages updates to the world pose from bullet.
Definition: BulletLink.hh:171
virtual void AddForce(const ignition::math::Vector3d &_force)
Set the relative pose of a child collision.
virtual void UpdateMass()
Update the mass matrix.
boost::shared_ptr< BulletMotionState > BulletMotionStatePtr
Definition: BulletTypes.hh:43
virtual void AddLinkForce(const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_offset=ignition::math::Vector3d::Zero)
Add a force expressed in the link frame.
virtual void SetAngularVel(const ignition::math::Vector3d &_vel)
Set the angular velocity of the body.
virtual bool GetEnabled() const
Get whether this body is enabled in the physics engine.