Joint Class Reference
Abstract base class for a single axis robot joint.
More...
#include <joint.h>
List of all members.
Detailed Description
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 132 of file joint.h.
Constructor & Destructor Documentation
Initializes all values and pointers to zero. Joint should set up with initJoint.
Definition at line 189 of file joint.h.
Joint::~Joint |
( |
|
) |
[virtual] |
Unreferences the associated Inventor transform, and deletes the DHTransform associated with this joint.
Definition at line 113 of file joint.cpp.
Member Function Documentation
virtual void Joint::applyInternalWrench |
( |
double |
magnitude |
) |
[pure virtual] |
void Joint::applyPassiveInternalWrenches |
( |
|
) |
[virtual] |
Applies internal passive joint wrenches (such as friction or springs)
Definition at line 143 of file joint.cpp.
void Joint::cloneFrom |
( |
const Joint * |
original |
) |
|
Clones this joint from another joint
Definition at line 119 of file joint.cpp.
int Joint::getChainNum |
( |
|
) |
const |
Returns the index of the chain this belongs to in the robot scheme.
Definition at line 137 of file joint.cpp.
double Joint::getCouplingRatio |
( |
|
) |
const [inline] |
Returns the linear multiplier relating this joint value to the DOF value.
Definition at line 267 of file joint.h.
double Joint::getDisplacement |
( |
|
) |
const [inline] |
Returns the current displacement of the joint compared to the rest value.
Definition at line 250 of file joint.h.
int Joint::getDOFNum |
( |
|
) |
const [inline] |
Returns the index of the robot DOF this joint is connected to.
Definition at line 264 of file joint.h.
virtual transf Joint::getDynamicsTran |
( |
|
) |
const [pure virtual] |
double Joint::getDynamicsVal |
( |
|
) |
const [inline] |
Returns the current joint value as computed from the IK during dyanmic simulation.
Definition at line 298 of file joint.h.
double Joint::getFriction |
( |
|
) |
const [inline] |
Returns the magnitude of friction acting on this joint. This uses both viscous friction, which is proportional to the joint velocity, and Coulomb friction, which is constant.
Definition at line 287 of file joint.h.
SoTransform* Joint::getIVTran |
( |
|
) |
const [inline] |
Returns a pointer to the Inventor transform associated with this joint that is used in the joint dragger sub graph.
Definition at line 311 of file joint.h.
double Joint::getMax |
( |
|
) |
const [inline] |
Returns the maximum joint limit.
Definition at line 279 of file joint.h.
double Joint::getMin |
( |
|
) |
const [inline] |
Returns the minimum joint limit
Definition at line 276 of file joint.h.
int Joint::getNum |
( |
|
) |
const [inline] |
Returns the number of this joint in its kinematic chain
Definition at line 241 of file joint.h.
double Joint::getOffset |
( |
|
) |
const [inline] |
Returns the constant joint offset value.
Definition at line 273 of file joint.h.
double Joint::getSpringForce |
( |
|
) |
const |
Returns the spring force acting on this joint. This assumes a linear spring model, with constant stifness mK. Units are N*1.0e6 mm for torque or N*1.0e6 for force.
Assumes a linear spring with the rest value specified
Definition at line 157 of file joint.cpp.
double Joint::getSpringStiffness |
( |
|
) |
[inline] |
Returns the linear stiffness coefficient of this joint spring.
Definition at line 270 of file joint.h.
transf const& Joint::getTran |
( |
|
) |
const [inline] |
Returns the current value of the DHTransform associated with this joint.
Definition at line 301 of file joint.h.
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] |
virtual double Joint::getVal |
( |
|
) |
const [pure virtual] |
double Joint::getVelocity |
( |
|
) |
const [inline] |
Returns the current velocity of this joint (computed during dynamics).
Definition at line 282 of file joint.h.
vec3 const& Joint::getWorldAxis |
( |
|
) |
const [inline] |
Returns the current direction of the joint axis in world coordinates.
Definition at line 304 of file joint.h.
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.
Definition at line 169 of file joint.cpp.
void Joint::setDraggerAttached |
( |
bool |
b |
) |
[inline] |
Updates draggerAttached when a dragger is added or removed from this joint.
Definition at line 230 of file joint.h.
void Joint::setDynamicsVal |
( |
double |
v |
) |
[inline] |
Sets the current value of the joint (computed during dynamics).
Definition at line 223 of file joint.h.
void Joint::setMax |
( |
double |
max |
) |
[inline] |
Set the maximum joint limit.
Definition at line 211 of file joint.h.
void Joint::setMin |
( |
double |
min |
) |
[inline] |
Sets the minimum joint limit
Definition at line 208 of file joint.h.
void Joint::setRestValue |
( |
double |
r |
) |
[inline] |
Sets the rest value of the attached joint spring.
Definition at line 236 of file joint.h.
void Joint::setSpringStiffness |
( |
double |
k |
) |
[inline] |
Sets the linear stiffness coefficient of this joint spring.
Definition at line 233 of file joint.h.
virtual int Joint::setVal |
( |
double |
q |
) |
[pure virtual] |
void Joint::setVelocity |
( |
double |
v |
) |
[inline] |
Sets the current joint velocity (computed during dynamics).
Definition at line 220 of file joint.h.
void Joint::setWorldAxis |
( |
const vec3 & |
wa |
) |
[inline] |
Sets the current orientation of the joint axis in world coordinates. (computed during dynamics)
Definition at line 227 of file joint.h.
Member Data Documentation
Index of the robot DOF this joint is connected to.
Definition at line 135 of file joint.h.
TRUE
if an Inventor dragger is currently attached to this joint
Definition at line 144 of file joint.h.
The current value of the joint computed by inverse kinematic during dynamics.
Definition at line 147 of file joint.h.
[Temporary] this points to the DynJoint that contains this joint
Definition at line 185 of file joint.h.
Coulomb friction value (constant offset).
Definition at line 165 of file joint.h.
The coefficient of viscous friction.
Definition at line 162 of file joint.h.
A pointer to the associated Inventor transform used for joint draggers.
Definition at line 181 of file joint.h.
The number of this joint in the robot's list.
Definition at line 141 of file joint.h.
Linear multiplier of DOF value. JointVal = mCouplingRatio * (DOFVal) + c.
Definition at line 156 of file joint.h.
Joint spring stiffness, in N * 1.0e6 mm / rad for torque or N * 1.0e6 / mm for force. 0 if this joint has no spring.
Definition at line 169 of file joint.h.
The rest value of the joint spring.
Definition at line 172 of file joint.h.
A pointer to the kinematic chain that this joint is a part of.
Definition at line 138 of file joint.h.
The current velocity of the joint (first order approximation).
Definition at line 150 of file joint.h.
Current joint axis expressed in world coordinates.
Definition at line 175 of file joint.h.
The documentation for this class was generated from the following files:
- /opt/ros/diamondback/stacks/graspit_simulator/graspit/graspit_source/include/joint.h
- /opt/ros/diamondback/stacks/graspit_simulator/graspit/graspit_source/src/joint.cpp