22 #ifndef _BULLETJOINT_HH_
23 #define _BULLETJOINT_HH_
25 #include <boost/any.hpp>
50 public:
virtual void Load(sdf::ElementPtr _sdf);
53 public:
virtual void Reset();
57 public:
LinkPtr GetJointLink(
unsigned int _index)
const;
63 public:
virtual void Detach();
66 public:
virtual void SetAnchor(
unsigned int _index,
70 public:
virtual void SetDamping(
unsigned int _index,
double _damping);
73 public:
virtual bool SetPosition(
unsigned int _index,
double _position);
76 public:
virtual void SetStiffness(
unsigned int _index,
77 const double _stiffness);
80 public:
virtual void SetStiffnessDamping(
unsigned int _index,
81 double _stiffness,
double _damping,
double _reference = 0);
84 public:
virtual math::Vector3 GetAnchor(
unsigned int _index)
const;
88 public:
virtual math::Vector3 GetLinkForce(
unsigned int _index)
const;
92 public:
virtual math::Vector3 GetLinkTorque(
unsigned int _index)
const;
95 public:
virtual bool SetParam(
const std::string &_key,
97 const boost::any &_value);
100 public:
virtual double GetParam(
const std::string &_key,
101 unsigned int _index);
104 public:
virtual math::Angle GetHighStop(
unsigned int _index);
107 public:
virtual math::Angle GetLowStop(
unsigned int _index);
110 public:
virtual void CacheForceTorque();
113 public:
virtual JointWrench GetForceTorque(
unsigned int _index);
116 public:
virtual void SetForce(
unsigned int _index,
double _force);
119 public:
virtual double GetForce(
unsigned int _index);
122 public:
virtual void Init();
125 public:
virtual void ApplyStiffnessDamping();
137 protected:
virtual void SetForceImpl(
unsigned int _index,
142 protected:
void SetupJointFeedback();
147 private:
void SaveForce(
unsigned int _index,
double _force);
156 private: btJointFeedback *feedback;
160 private:
bool stiffnessDampingInitialized;
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:66
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
#define MAX_JOINT_AXIS
maximum number of axis per joint anticipated.
Definition: Joint.hh:39
Base class for all joints.
Definition: Joint.hh:50
Wrench information from a joint.
Definition: JointWrench.hh:39
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
btDynamicsWorld * bulletWorld
Pointer to Bullet's btDynamicsWorld.
Definition: BulletJoint.hh:153
An angle and related functions.
Definition: Angle.hh:52
btTypedConstraint * constraint
Pointer to a contraint object in Bullet.
Definition: BulletJoint.hh:150
Base class for all joints.
Definition: BulletJoint.hh:41
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:43