18 #ifndef _SIMBODY_JOINT_HH_ 
   19 #define _SIMBODY_JOINT_HH_ 
   21 #include <boost/any.hpp> 
   46       public: 
virtual void Load(sdf::ElementPtr _sdf);
 
   49       public: 
virtual void Reset();
 
   52       public: 
virtual LinkPtr GetJointLink(
unsigned int _index) 
const;
 
   55       public: 
virtual bool AreConnected(
LinkPtr _one, 
LinkPtr _two) 
const;
 
   58       public: 
virtual void Detach();
 
   61       public: 
virtual void SetAnchor(
unsigned int _index,
 
   65       public: 
virtual void SetDamping(
unsigned int _index,
 
   66                                       const double _damping);
 
   69       public: 
virtual void SetStiffness(
unsigned int _index,
 
   70                                         const double _stiffness);
 
   73       public: 
virtual void SetStiffnessDamping(
unsigned int _index,
 
   74         double _stiffness, 
double _damping, 
double _reference = 0);
 
   77       public: 
virtual math::Vector3 GetAnchor(
unsigned int _index) 
const;
 
   80       public: 
virtual math::Vector3 GetLinkForce(
unsigned int _index) 
const;
 
   83       public: 
virtual math::Vector3 GetLinkTorque(
unsigned int _index) 
const;
 
   86       public: 
virtual bool SetParam(
const std::string &_key,
 
   88                                         const boost::any &_value);
 
   91       public: 
virtual double GetParam(
const std::string &_key,
 
   95       public: 
virtual void SaveSimbodyState(
const SimTK::State &_state);
 
   98       public: 
virtual void RestoreSimbodyState(SimTK::State &_state);
 
  101       public: 
virtual void SetForce(
unsigned int _index, 
double _force);
 
  104       public: 
virtual double GetForce(
unsigned int _index);
 
  107       public: 
virtual void SetAxis(
unsigned int _index,
 
  111       public: 
virtual JointWrench GetForceTorque(
unsigned int _index);
 
  123       protected: 
virtual void SetForceImpl(
unsigned int _index,
 
  129       private: 
void SaveForce(
unsigned int _index, 
double _force);
 
  132       public: 
virtual void CacheForceTorque();
 
  141       public: SimTK::Transform 
xPA;
 
  144       public: SimTK::Transform 
xCB;
 
  191       public: 
virtual bool SetHighStop(
unsigned int _index,
 
  195       public: 
virtual bool SetLowStop(
unsigned int _index,
 
  199       public: 
virtual math::Angle GetHighStop(
unsigned int _index);
 
  202       public: 
virtual math::Angle GetLowStop(
unsigned int _index);
 
  205       protected: SimTK::MultibodySystem *
world;
 
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
 
The Vector3 class represents the generic vector containing 3 elements. 
Definition: Vector3.hh:39
 
SimTK::Constraint constraint
: isValid() if we used a constraint to model this joint. 
Definition: SimbodyJoint.hh:185
 
bool isReversed
: if mobilizer, did it reverse parent&child? Set when we build the Simbody model. ...
Definition: SimbodyJoint.hh:178
 
SimTK::Transform xCB
child body frame to mobilizer frame 
Definition: SimbodyJoint.hh:144
 
SimTK::Transform xPA
Normally A=F, B=M. 
Definition: SimbodyJoint.hh:141
 
SimbodyPhysicsPtr simbodyPhysics
keep a pointer to the simbody physics engine for convenience 
Definition: SimbodyJoint.hh:208
 
Base class for all joints. 
Definition: SimbodyJoint.hh:37
 
boost::shared_ptr< SimbodyPhysics > SimbodyPhysicsPtr
Definition: SimbodyTypes.hh:40
 
#define MAX_JOINT_AXIS
maximum number of axis per joint anticipated. 
Definition: Joint.hh:39
 
SimTK::MultibodySystem * world
Simbody Multibody System. 
Definition: SimbodyJoint.hh:205
 
SimTK::Transform defxAB
default mobilizer pose 
Definition: SimbodyJoint.hh:147
 
Base class for all joints. 
Definition: Joint.hh:50
 
Wrench information from a joint. 
Definition: JointWrench.hh:39
 
An angle and related functions. 
Definition: Angle.hh:53
 
SimTK::MobilizedBody mobod
Use isValid() if we used a mobilizer Set when we build the Simbody model. 
Definition: SimbodyJoint.hh:174
 
bool physicsInitialized
Definition: SimbodyJoint.hh:188
 
bool mustBreakLoopHere
Force Simbody to break a loop by using a weld constraint. 
Definition: SimbodyJoint.hh:137
 
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:77
 
A Time class, can be used to hold wall- or sim-time. 
Definition: Time.hh:44