20 #include <boost/any.hpp>    43         DAMPING_ACTIVE = 0x00000001,
    45         JOINT_LIMIT    = 0x00000002
    56       public: 
virtual void Load(sdf::ElementPtr _sdf);
    59       public: 
virtual void Fini();
    62       public: 
virtual void Reset();
    65       public: 
virtual LinkPtr GetJointLink(
unsigned int _index) 
const;
    68       public: 
virtual bool AreConnected(
LinkPtr _one, 
LinkPtr _two) 
const;
    71       public: 
virtual void CacheForceTorque();
    79       public: 
virtual double GetParam(
unsigned int _parameter) 
const;
    87       public: 
virtual void SetParam(
unsigned int _parameter, 
double _value);
    90       public: 
virtual void SetDamping(
unsigned int _index, 
double _damping);
    93       public: 
virtual bool SetPosition(
unsigned int _index, 
double _position);
    96       public: 
virtual void SetStiffness(
unsigned int _index,
    97                                         const double _stiffness);
   100       public: 
virtual void SetStiffnessDamping(
unsigned int _index,
   101         double _stiffness, 
double _damping, 
double _reference = 0);
   107       public: 
virtual void Detach();
   111       public: 
void SetERP(
double _erp);
   115       public: 
double GetERP();
   119       public: 
void SetCFM(
double _cfm);
   123       public: 
double GetCFM();
   127       public: dJointFeedback *GetFeedback();
   131       public: 
bool UsesImplicitSpringDamper();
   135       public: 
void UseImplicitSpringDamper(
const bool _implicit);
   139       public: 
void ApplyImplicitStiffnessDamping();
   142       public: 
void ApplyExplicitStiffnessDamping();
   148         return this->stopCFM;
   155         return this->stopERP;
   167       private: 
double ApplyAdaptiveDamping(
unsigned int _index,
   168                    const double _damping);
   176       private: 
void KpKdToCFMERP(
const double _dt,
   177                                  const double _kp, 
const double _kd,
   178                                  double &_cfm, 
double &_erp);
   186       private: 
void CFMERPToKpKd(
const double _dt,
   187                                  const double _cfm, 
const double _erp,
   188                                  double &_kp, 
double &_kd);
   201       private: 
bool stiffnessDampingInitialized;
   204       private: 
bool useImplicitSpringDamper;
   207       public: 
virtual bool SetHighStop(
unsigned int _index,
   211       public: 
virtual bool SetLowStop(
unsigned int _index,
   215       public: 
virtual math::Angle GetHighStop(
unsigned int _index);
   218       public: 
virtual math::Angle GetLowStop(
unsigned int _index);
   221       public: 
virtual math::Vector3 GetLinkForce(
unsigned int _index) 
const;
   224       public: 
virtual math::Vector3 GetLinkTorque(
unsigned int _index) 
const;
   227       public: 
virtual void SetAxis(
unsigned int _index,
   231       public: 
virtual bool SetParam(
const std::string &_key,
   233                                         const boost::any &_value);
   236       public: 
virtual double GetParam(
const std::string &_key,
   237                                                 unsigned int _index);
   240       public: 
virtual void SetProvideFeedback(
bool _enable);
   243       public: 
virtual JointWrench GetForceTorque(
unsigned int _index);
   246       public: 
virtual void SetForce(
unsigned int _index, 
double _force);
   249       public: 
virtual double GetForce(
unsigned int _index);
   252       public: 
virtual void ApplyStiffnessDamping();
   263       protected: 
virtual void SetForceImpl(
   264                      unsigned int _index, 
double _force) = 0;
   269       private: 
void SaveForce(
unsigned int _index, 
double _force);
   275       private: dJointFeedback *feedback;
   278       private: 
double stopCFM;
   281       private: 
double stopERP;
 boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:100
 
Forward declarations for the common classes. 
Definition: Animation.hh:33
 
The Vector3 class represents the generic vector containing 3 elements. 
Definition: Vector3.hh:39
 
double GetStopERP()
Get access to stopERP. 
Definition: ODEJoint.hh:153
 
dJointID jointId
This is our ODE ID. 
Definition: ODEJoint.hh:272
 
double GetStopCFM()
Get access to stopCFM. 
Definition: ODEJoint.hh:146
 
CFMMode
internal variables used for implicit damping 
Definition: ODEJoint.hh:38
 
#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
 
ODE joint interface. 
Definition: ODEJoint.hh:35
 
An angle and related functions. 
Definition: Angle.hh:53
 
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:72
 
A Time class, can be used to hold wall- or sim-time. 
Definition: Time.hh:44