Abstract base class for a single axis robot joint. More...
#include <joint.h>

Public Member Functions | |
| virtual void | applyInternalWrench (double magnitude)=0 |
| virtual void | applyPassiveInternalWrenches () |
| void | cloneFrom (const Joint *original) |
| int | getChainNum () const |
| Returns the index of the chain this belongs to in the robot scheme. | |
| double | getCouplingRatio () const |
| DHTransform * | getDH () |
| double | getDisplacement () const |
| Returns the current displacement of the joint compared to the rest value. | |
| int | getDOFNum () const |
| virtual transf | getDynamicsTran () const =0 |
| double | getDynamicsVal () const |
| double | getFriction () const |
| SoTransform * | getIVTran () const |
| double | getMax () const |
| double | getMin () const |
| int | getNum () const |
| double | getOffset () const |
| double | getSpringForce () const |
| double | getSpringStiffness () |
| Returns the linear stiffness coefficient of this joint spring. | |
| transf const & | getTran () const |
| virtual transf | getTran (double jointVal) const =0 |
| virtual JointT | getType () const =0 |
| virtual double | getVal () const =0 |
| double | getVelocity () const |
| vec3 const & | getWorldAxis () const |
| virtual int | initJointFromXml (const TiXmlElement *root, int jnum)=0 |
| Joint (KinematicChain *k) | |
| void | setDraggerAttached (bool b) |
| void | setDynamicsVal (double v) |
| void | setMax (double max) |
| void | setMin (double min) |
| void | setRestValue (double r) |
| Sets the rest value of the attached joint spring. | |
| void | setSpringStiffness (double k) |
| Sets the linear stiffness coefficient of this joint spring. | |
| virtual int | setVal (double q)=0 |
| void | setVelocity (double v) |
| void | setWorldAxis (const vec3 &wa) |
| virtual | ~Joint () |
Static Public Member Functions | |
| static Matrix | jacobian (const Joint *joint, const transf &jointTran, const transf &toTarget, bool worldCoords) |
| The Jacobian relating movement of this joint to movement of a point in the world. | |
Public Attributes | |
| DynJoint * | dynJoint |
| [Temporary] this points to the DynJoint that contains this joint | |
Protected Attributes | |
| double | c |
| Joint offset. | |
| DHTransform * | DH |
| The DHTransform from this joint frame to the next. | |
| int | DOFnum |
| Index of the robot DOF this joint is connected to. | |
| bool | draggerAttached |
TRUE if an Inventor dragger is currently attached to this joint | |
| double | dynamicsVal |
| The current value of the joint computed by inverse kinematic during dynamics. | |
| double | f0 |
| Coulomb friction value (constant offset). | |
| double | f1 |
| The coefficient of viscous friction. | |
| SoTransform * | IVTran |
| A pointer to the associated Inventor transform used for joint draggers. | |
| int | jointNum |
| The number of this joint in the robot's list. | |
| double | maxVal |
| double | mCouplingRatio |
| Linear multiplier of DOF value. JointVal = mCouplingRatio * (DOFVal) + c. | |
| double | minVal |
| Joint limit. | |
| double | mK |
| double | mRestVal |
| The rest value of the joint spring. | |
| KinematicChain * | owner |
| A pointer to the kinematic chain that this joint is a part of. | |
| double | velocity |
| The current velocity of the joint (first order approximation). | |
| vec3 | worldAxis |
| Current joint axis expressed in world coordinates. | |
Abstract base class for a single axis robot joint.
A robot joint allows either translation or rotation on a single axis. It is part of a kinematic chain, which is a serial set of links and joints. Multiple joints can be defined between two links. The value of the joint is linearly related to a robot DOF value, and has its own minimum and maximum values. The joint also computes its friction value during dynamic simulation using viscous and Coulomb friction values defined in the robot configuration file. The joint can also have a spring behavior, and it computes its own spring forces based on a linear stiffness coefficient.
Definition at line 145 of file joint.h.
| Joint::Joint | ( | KinematicChain * | k | ) | [inline] |
| Joint::~Joint | ( | ) | [virtual] |
Unreferences the associated Inventor transform, and deletes the DHTransform associated with this joint.
| virtual void Joint::applyInternalWrench | ( | double | magnitude | ) | [pure virtual] |
This applies an internal wrench to this joint
Implemented in PrismaticJoint, and RevoluteJoint.
| void Joint::applyPassiveInternalWrenches | ( | ) | [virtual] |
| void Joint::cloneFrom | ( | const Joint * | original | ) |
| int Joint::getChainNum | ( | ) | const |
| double Joint::getCouplingRatio | ( | ) | const [inline] |
| DHTransform* Joint::getDH | ( | ) | [inline] |
Returns a pointer to the DHTransform associated with this joint.
| double Joint::getDisplacement | ( | ) | const [inline] |
| int Joint::getDOFNum | ( | ) | const [inline] |
| virtual transf Joint::getDynamicsTran | ( | ) | const [pure virtual] |
Returns the current joint transform as computed from IK during dynamic simulation.
Implemented in PrismaticJoint, and RevoluteJoint.
| double Joint::getDynamicsVal | ( | ) | const [inline] |
| double Joint::getFriction | ( | ) | const [inline] |
| SoTransform* Joint::getIVTran | ( | ) | const [inline] |
| double Joint::getMax | ( | ) | const [inline] |
| double Joint::getMin | ( | ) | const [inline] |
| int Joint::getNum | ( | ) | const [inline] |
| double Joint::getOffset | ( | ) | const [inline] |
| double Joint::getSpringForce | ( | ) | const |
| double Joint::getSpringStiffness | ( | ) | [inline] |
| transf const& Joint::getTran | ( | ) | const [inline] |
Returns the current value of the DHTransform associated with this joint.
| virtual transf Joint::getTran | ( | double | jointVal | ) | const [pure virtual] |
Returns the transform to the next joint frame the results from substituting jointVal for the current joint value.
Implemented in PrismaticJoint, and RevoluteJoint.
| virtual JointT Joint::getType | ( | ) | const [pure virtual] |
Return type of this joint, either REVOLUE or PRISMATIC.
Implemented in PrismaticJoint, and RevoluteJoint.
| virtual double Joint::getVal | ( | ) | const [pure virtual] |
Returns the current joint value.
Implemented in PrismaticJoint, and RevoluteJoint.
| double Joint::getVelocity | ( | ) | const [inline] |
| vec3 const& Joint::getWorldAxis | ( | ) | const [inline] |
| virtual int Joint::initJointFromXml | ( | const TiXmlElement * | root, | |
| int | jnum | |||
| ) | [pure virtual] |
Set up the joint using values from an XML DOM read from the robot configuration file.
Implemented in PrismaticJoint, and RevoluteJoint.
| Matrix Joint::jacobian | ( | const Joint * | joint, | |
| const transf & | jointTran, | |||
| const transf & | toTarget, | |||
| bool | worldCoords | |||
| ) | [static] |
The Jacobian relating movement of this joint to movement of a point in the world.
The joint Jacobian is a 6x1 matrix that relates movement of a joint (1 DOF) to movement (translation and rotation) of a point in 3D space placed at world coordinates toTarget. If worldCoords is true, the jacobian is expressed in world coordinate system; otherwise, it is expressed in the local coordinate system of the target point.
| void Joint::setDraggerAttached | ( | bool | b | ) | [inline] |
| void Joint::setDynamicsVal | ( | double | v | ) | [inline] |
| void Joint::setMax | ( | double | max | ) | [inline] |
| void Joint::setMin | ( | double | min | ) | [inline] |
| void Joint::setRestValue | ( | double | r | ) | [inline] |
| void Joint::setSpringStiffness | ( | double | k | ) | [inline] |
| virtual int Joint::setVal | ( | double | q | ) | [pure virtual] |
This sets the joint value
Implemented in PrismaticJoint, and RevoluteJoint.
| void Joint::setVelocity | ( | double | v | ) | [inline] |
| void Joint::setWorldAxis | ( | const vec3 & | wa | ) | [inline] |
DHTransform* Joint::DH [protected] |
The DHTransform from this joint frame to the next.
int Joint::DOFnum [protected] |
bool Joint::draggerAttached [protected] |
double Joint::dynamicsVal [protected] |
double Joint::f0 [protected] |
double Joint::f1 [protected] |
SoTransform* Joint::IVTran [protected] |
int Joint::jointNum [protected] |
double Joint::maxVal [protected] |
double Joint::mCouplingRatio [protected] |
double Joint::minVal [protected] |
double Joint::mK [protected] |
double Joint::mRestVal [protected] |
KinematicChain* Joint::owner [protected] |
double Joint::velocity [protected] |
vec3 Joint::worldAxis [protected] |