Main Page | Namespace List | Class Hierarchy | Alphabetical List | Class List | File List | Namespace Members | Class Members | File Members | Related Pages

robot::sim::SimulatedTool Class Reference

Inheritance diagram for robot::sim::SimulatedTool:

Inheritance graph
[legend]
Collaboration diagram for robot::sim::SimulatedTool:

Collaboration graph
[legend]
List of all members.

Public Types

typedef std::bitset< sizeof(Int)*8 CollidableFlags )
typedef Int CollidableFlag
enum  ExternalizationType { Input = 1, Output = 2, IO = 3 }

Public Member Functions

 SimulatedTool (ref< const robot::ToolDescription > toolDescription, const base::Point3 &initialPosition, const base::Orient &initialOrientation, ref< physics::SolidSystem > solidSystem, bool dynamic=true)
virtual String className () const
virtual void setDynamic (bool enabled)
virtual void setSolidSystem (ref< physics::SolidSystem > solidSystem)
ref< const robot::ToolDescriptiongetToolDescription () const
ref< physics::SolidgetFirstLinkSolid () const
 < get the Solid for first link

ref< physics::CollidablegetFirstLinkCollidable () const
 < get the Collidable associated with the first link

ref< physics::CollidablegetFirstLinkProximitySensorCollidable () const
 < get the Collidable associated with the first link's proximity sensor

void setJointForce (Int j, Real f)
 Set the force (torque for revolute joints) of joint j (first joint j=1).

void setJointVel (Int j, Real v, Real maxForce=10.0)
 Set the velocity (ang. velocity for revolute joints) of joint j (first joint j=1).

void setJointPos (Int j, Real p)
 Set the position (angle for revolute joints) of joint j (first joint j=1).

Real getJointPos (Int j) const
 Get the current theta* angle (revolute) or position d (prismatic) of the joint.

Real getJointVel (Int j) const
 Get the current joint velocity (ang. velocity for revolute joints).

void attachTo (ref< physics::Solid > manipEESolid)
 attach the base Solid to the specified solid - this is the first joint

void detatch ()
 detatch base Solid

Real getClosestObjectDistance (Int link) const
 get distance to closest object detected by proximity sensors on the link

Vector3 getClosestObjectDirection (Int link) const
 get the direction vector to the closest object detected by proximity sensors on the link

Real getClosestObjectSensorPosition (Int link) const
 get the distance along the link x-axis of the proximity sensor that detected the closest object to the link

virtual void setPosition (const Point3 &pos)
virtual Point3 getPosition () const
virtual void setOrientation (const Orient &orient)
virtual Orient getOrientation () const
virtual void setConfiguration (const base::Transform &configuration)
virtual base::Transform getConfiguration () const
virtual ref< physics::CollidablecreateCollidable (CollidableFlags flags=0)
virtual bool formatSupported (const String format, Real version=1.0, ExternalizationType type=IO) const
 query if specific format is supported (for input, output or both)

virtual void externalize (base::Externalizer &e, const String format="", Real version=1.0)
 read or write object state to Externalizer

void externalize (base::Externalizer &e, const String format="", Real version=1.0) const
 write object state to Externalizer (throws if e is in Input)

virtual void setPositionOrientation (const Point3 &pos, const Orient &orient)
virtual void setPosition2D (const base::Point2 &p, Real theta)
 set the 2D (x,y,theta) position (theta is rot. angle about Z-axis)

virtual base::Point2 getPosition2D () const
 get the 2D (x,y) position

Real getOrientation2D () const
 get the 2D angle theta (rot. angle about Z-axis)

virtual const String & getName () const
virtual bool isSameKindAs (const ReferencedObject &) const
virtual bool isSameKindAs (const Object &) const
void reference () const
bool unreference () const
const int referenceCount () const
void enableOnUnreferenceCall (bool enabled)
virtual void onUnreference () const
void load (ref< VFile > archive, const String &format="", Real version=1.0)
void save (ref< VFile > archive, const String &format="", Real version=1.0)

Static Public Attributes

const Real maxDist

Protected Types

enum  CollidableClasses { SensorCollidableClass = 1 }

Protected Member Functions

 SimulatedTool (const SimulatedTool &st)
void construct (const base::Point3 &initialPosition, const base::Orient &initialOrientation)
 construct an approximation of the tool from the D-H parameters (best we can do)

TransformInfo computeLinkTransforms (const Transform &mountTransform, const base::Vector &q) const
 compute transform information for chain

virtual void createLinks (const array< base::Dimension3 > &linkDims)
 create the Solids for each link and assemble them into a Spatial tree (and add them to solidSystem)

virtual void positionLinks (const TransformInfo &transformInfo)
 position the links

virtual void disableCollisions (const array< ref< physics::Collidable > > &collidables, const array< ref< physics::Collidable > > &proximityCollidables)
virtual void attachJoints (const TransformInfo &transformInfo)
virtual void handleCollision (ref< physics::CollisionState > collisionState)
 called from ProximityCollisionResponseHandler::handleCollision()

virtual array< base::Dimension3computeLinkDimensions (const array< Real > &linkRadii)
virtual void setName (const String &name)

Protected Attributes

ref< const robot::ToolDescriptiontoolDescr
ref< physics::SolidfirstSolid
 Solid for the first link.

ref< physics::SolidendSolid
 Solid for the tool end-effector.

base::Transform firstLinkSolidToMount
 transform from origin of first link Solid to mount origin

ref< physics::SpatialTransformmountSpatial
 Spatial who's configuration is that of the tool's mount point.

ref< physics::SpatialGroupspatialGroup
 a group containing the Solids

bool attached
 is this tool attached to the end-effector of a manipulator?

ref< physics::ConstraintGroupmountConstraintGroup
 group that holds the joint attaching the tool to the manipulator end-effector (valid if attached is true)

KinematicChain chain
ref< physics::SolidSystemsolidSystem
bool dynamic
 true for a dynamic simulation, fasle for static (no force/torque or velocity control, just position control)

array< ref< physics::SpatialGroup > > linkGroups
 a group for each link (which contains the link Solid and the group for the next link)

array< ref< physics::Solid > > links
 Solids for each link.

array< ref< physics::Joint > > joints
 Joint attaching each pair of consecutive links (dynamic simulation only).

array< Real > linkLengths
 Length of each link corresponding with links[].

array< ref< physics::Collidable > > collidables
 collidables for each link Solid

array< ref< physics::Collidable > > proximityCollidables
 collidables for each link's proximity sensor

base::Vector q
 current joint parameters (static simulation only)

ref< physics::CollidableGroupproximityCollidableGroup
array< ProximityData > linkProximity
array< Real > linkProximitySurfPosition
 dist from link axis of proximity sensor (i.e. on link sufrace)

int _refCount
bool onUnreferenceEnabled

Friends

class SimulatedRobot
class base::Serializable::SerializableDerivedInstantiator< SimulatedTool >
class ProximityCollisionResponseHandler

Detailed Description

Represents a simulated manipulator tool according to a supplied D-H parameter specification. Simulated using gfx/physics.

Definition at line 54 of file SimulatedTool.


Member Typedef Documentation

typedef Int physics::CollidableProvider::CollidableFlag [inherited]
 

Definition at line 45 of file CollidableProvider.

typedef std::bitset<sizeof(Int)*8 physics::CollidableProvider::CollidableFlags) [inherited]
 

Definition at line 44 of file CollidableProvider.


Member Enumeration Documentation

enum robot::sim::SimulatedKinematicChain::CollidableClasses [protected, inherited]
 

Enumeration values:
SensorCollidableClass 

Definition at line 177 of file SimulatedKinematicChain.

enum base::Externalizable::ExternalizationType [inherited]
 

Enumeration values:
Input 
Output 
IO 

Definition at line 40 of file Externalizable.


Constructor & Destructor Documentation

robot::sim::SimulatedTool::SimulatedTool ref< const robot::ToolDescription toolDescription,
const base::Point3 initialPosition,
const base::Orient initialOrientation,
ref< physics::SolidSystem solidSystem,
bool  dynamic = true
 

robot::sim::SimulatedTool::SimulatedTool const SimulatedTool st  )  [inline, protected]
 

Definition at line 146 of file SimulatedTool.

References Unimplemented.


Member Function Documentation

virtual void robot::sim::SimulatedTool::attachJoints const TransformInfo &  transformInfo  )  [protected, virtual]
 

Implements robot::sim::SimulatedKinematicChain.

void robot::sim::SimulatedTool::attachTo ref< physics::Solid manipEESolid  ) 
 

attach the base Solid to the specified solid - this is the first joint

virtual String robot::sim::SimulatedTool::className  )  const [inline, virtual]
 

return the name of the object's class type. Must be defined by derived classes.

Implements base::Object.

Definition at line 66 of file SimulatedTool.

virtual array<base::Dimension3> robot::sim::SimulatedKinematicChain::computeLinkDimensions const array< Real > &  linkRadii  )  [protected, virtual, inherited]
 

compute the dimensions of each link's Solid based on the KinematicChain and fill in linkLengths[1..dof]

Reimplemented in robot::sim::SimulatedSerialManipulator.

TransformInfo robot::sim::SimulatedTool::computeLinkTransforms const Transform mountTransform,
const base::Vector q
const [protected]
 

compute transform information for chain

void robot::sim::SimulatedTool::construct const base::Point3 initialPosition,
const base::Orient initialOrientation
[protected, virtual]
 

construct an approximation of the tool from the D-H parameters (best we can do)

Implements robot::sim::SimulatedKinematicChain.

virtual ref<physics::Collidable> robot::sim::SimulatedTool::createCollidable CollidableFlags  flags = 0  )  [virtual]
 

Implements physics::CollidableProvider.

virtual void robot::sim::SimulatedTool::createLinks const array< base::Dimension3 > &  linkDims  )  [protected, virtual]
 

create the Solids for each link and assemble them into a Spatial tree (and add them to solidSystem)

Implements robot::sim::SimulatedKinematicChain.

void robot::sim::SimulatedTool::detatch  ) 
 

detatch base Solid

virtual void robot::sim::SimulatedTool::disableCollisions const array< ref< physics::Collidable > > &  collidables,
const array< ref< physics::Collidable > > &  proximityCollidables
[protected, virtual]
 

Implements robot::sim::SimulatedKinematicChain.

void base::Referenced::enableOnUnreferenceCall bool  enabled  )  [inline, inherited]
 

If enabled, each call to unreference() will also call virtual method onUnreference()

Definition at line 115 of file Referenced.

References base::Referenced::onUnreferenceEnabled.

void robot::sim::SimulatedTool::externalize base::Externalizer e,
const String  format = "",
Real  version = 1.0
const [inline, virtual]
 

write object state to Externalizer (throws if e is in Input)

Reimplemented from base::Externalizable.

Definition at line 142 of file SimulatedTool.

virtual void robot::sim::SimulatedTool::externalize base::Externalizer e,
const String  format = "",
Real  version = 1.0
[virtual]
 

read or write object state to Externalizer

Implements base::Externalizable.

virtual bool robot::sim::SimulatedTool::formatSupported const String  format,
Real  version = 1.0,
ExternalizationType  type = IO
const [virtual]
 

query if specific format is supported (for input, output or both)

Implements base::Externalizable.

Vector3 robot::sim::SimulatedTool::getClosestObjectDirection Int  link  )  const [virtual]
 

get the direction vector to the closest object detected by proximity sensors on the link

Implements robot::sim::SimulatedKinematicChain.

Real robot::sim::SimulatedTool::getClosestObjectDistance Int  link  )  const [virtual]
 

get distance to closest object detected by proximity sensors on the link

Implements robot::sim::SimulatedKinematicChain.

Real robot::sim::SimulatedTool::getClosestObjectSensorPosition Int  link  )  const [virtual]
 

get the distance along the link x-axis of the proximity sensor that detected the closest object to the link

Implements robot::sim::SimulatedKinematicChain.

virtual base::Transform robot::sim::SimulatedTool::getConfiguration  )  const [virtual]
 

Reimplemented from physics::PositionableOrientable.

ref<physics::Collidable> robot::sim::SimulatedTool::getFirstLinkCollidable  )  const [inline]
 

< get the Collidable associated with the first link

Definition at line 78 of file SimulatedTool.

References Assert.

ref<physics::Collidable> robot::sim::SimulatedTool::getFirstLinkProximitySensorCollidable  )  const [inline]
 

< get the Collidable associated with the first link's proximity sensor

Definition at line 81 of file SimulatedTool.

References Assert.

ref<physics::Solid> robot::sim::SimulatedTool::getFirstLinkSolid  )  const [inline]
 

< get the Solid for first link

Definition at line 75 of file SimulatedTool.

References firstSolid.

Real robot::sim::SimulatedTool::getJointPos Int  j  )  const [virtual]
 

Get the current theta* angle (revolute) or position d (prismatic) of the joint.

*NB: the angle is relative to the theta home position.

Implements robot::sim::SimulatedKinematicChain.

Real robot::sim::SimulatedTool::getJointVel Int  j  )  const [virtual]
 

Get the current joint velocity (ang. velocity for revolute joints).

Implements robot::sim::SimulatedKinematicChain.

virtual const String& base::Named::getName  )  const [inline, virtual, inherited]
 

Definition at line 44 of file Named.

References base::String.

Referenced by physics::Collidable::findNamed(), physics::operator<<(), robot::ToolDescription::operator=(), robot::RobotDescription::operator=(), robot::PlatformDescription::operator=(), robot::ManipulatorDescription::operator=(), base::Named::operator=(), and robot::ManipulatorDescription::operator==().

virtual Orient robot::sim::SimulatedTool::getOrientation  )  const [virtual]
 

Implements physics::Orientable.

Real physics::PositionableOrientable::getOrientation2D  )  const [inherited]
 

get the 2D angle theta (rot. angle about Z-axis)

virtual Point3 robot::sim::SimulatedTool::getPosition  )  const [virtual]
 

Implements physics::Positionable.

virtual base::Point2 physics::PositionableOrientable::getPosition2D  )  const [inline, virtual, inherited]
 

get the 2D (x,y) position

Definition at line 72 of file PositionableOrientable.

References physics::Positionable::getPosition(), base::Point2, base::Point3, base::Vector3::x, and base::Vector3::y.

ref<const robot::ToolDescription> robot::sim::SimulatedTool::getToolDescription  )  const [inline]
 

Definition at line 73 of file SimulatedTool.

References toolDescr.

virtual void robot::sim::SimulatedTool::handleCollision ref< physics::CollisionState collisionState  )  [protected, virtual]
 

called from ProximityCollisionResponseHandler::handleCollision()

Implements robot::sim::SimulatedKinematicChain.

virtual bool base::Object::isSameKindAs const Object  )  const [inline, virtual, inherited]
 

Definition at line 47 of file Object.

virtual bool base::ReferencedObject::isSameKindAs const ReferencedObject  )  const [inline, virtual, inherited]
 

Definition at line 52 of file ReferencedObject.

void base::Externalizable::load ref< VFile archive,
const String format = "",
Real  version = 1.0
[inherited]
 

virtual void base::Referenced::onUnreference  )  const [inline, virtual, inherited]
 

Called by unreference() if enabled via enableOnUnreferenceCall(true). Typically overridden in subclasses that wish to know about unreference() calls - for example to handle manually breaking cyclic references

Reimplemented in robot::control::ControllableAdaptor::AdaptorControlInterface, and robot::control::ControllableAdaptor.

Definition at line 121 of file Referenced.

Referenced by base::Referenced::unreference().

virtual void robot::sim::SimulatedTool::positionLinks const TransformInfo &  transformInfo  )  [protected, virtual]
 

position the links

Implements robot::sim::SimulatedKinematicChain.

void base::Referenced::reference  )  const [inline, inherited]
 

Increment the reference count by one, indicating that this object has another pointer which is referencing it.

Definition at line 65 of file Referenced.

References base::Referenced::_refCount.

const int base::Referenced::referenceCount  )  const [inline, inherited]
 

Return the number pointers currently referencing this object.

Definition at line 112 of file Referenced.

References base::Referenced::_refCount.

Referenced by robot::control::ControllableAdaptor::AdaptorControlInterface::onUnreference().

void base::Externalizable::save ref< VFile archive,
const String format = "",
Real  version = 1.0
[inherited]
 

virtual void robot::sim::SimulatedTool::setConfiguration const base::Transform configuration  )  [virtual]
 

Reimplemented from physics::PositionableOrientable.

virtual void robot::sim::SimulatedTool::setDynamic bool  enabled  )  [inline, virtual]
 

Reimplemented from robot::sim::SimulatedKinematicChain.

Definition at line 68 of file SimulatedTool.

void robot::sim::SimulatedTool::setJointForce Int  j,
Real  f
[virtual]
 

Set the force (torque for revolute joints) of joint j (first joint j=1).

Implements robot::sim::SimulatedKinematicChain.

void robot::sim::SimulatedTool::setJointPos Int  j,
Real  p
[virtual]
 

Set the position (angle for revolute joints) of joint j (first joint j=1).

NB: This will instantaneously move the joint to the specified angle - which obviously is not physically realistic. Consequently, for dynamic simulations, this can cause large forces in the system and possibly numerical instability in the simulation. It is intended for non-dynamic simulations. NB: the angle is relative to the theta home position.

Implements robot::sim::SimulatedKinematicChain.

void robot::sim::SimulatedTool::setJointVel Int  j,
Real  v,
Real  maxForce = 10.0
[virtual]
 

Set the velocity (ang. velocity for revolute joints) of joint j (first joint j=1).

NB: As the simulation is force controlled, this will set the target velocity

Implements robot::sim::SimulatedKinematicChain.

virtual void base::Named::setName const String name  )  [inline, protected, virtual, inherited]
 

Reimplemented in physics::Collidable, physics::Solid, and robot::sim::BasicEnvironment::Obstacle.

Definition at line 47 of file Named.

References base::String.

Referenced by robot::control::ControllableAdaptor::AdaptorControlInterface::AdaptorControlInterface(), robot::control::kinematics::BetaFormConstraints::BetaFormConstraint::BetaFormConstraint(), robot::control::kinematics::IKORController::EEPositionControlInterface::EEPositionControlInterface(), robot::control::kinematics::IKOR::JointLimitBetaConstraint::JointLimitBetaConstraint(), robot::control::kinematics::IKORController::LinkPositionsControlInterface::LinkPositionsControlInterface(), robot::ToolDescription::operator=(), robot::RobotDescription::operator=(), robot::PlatformDescription::operator=(), robot::ManipulatorDescription::operator=(), base::Named::operator=(), robot::control::ManipulatorPIDPositionController::PositionInterface::PositionInterface(), robot::RobotDescription::set(), robot::PlatformDescription::set(), robot::ManipulatorDescription::set(), and physics::Solid::setName().

virtual void robot::sim::SimulatedTool::setOrientation const Orient orient  )  [virtual]
 

Implements physics::Orientable.

virtual void robot::sim::SimulatedTool::setPosition const Point3 pos  )  [virtual]
 

Implements physics::Positionable.

virtual void physics::PositionableOrientable::setPosition2D const base::Point2 p,
Real  theta
[virtual, inherited]
 

set the 2D (x,y,theta) position (theta is rot. angle about Z-axis)

virtual void physics::PositionableOrientable::setPositionOrientation const Point3 pos,
const Orient orient
[inline, virtual, inherited]
 

Definition at line 48 of file PositionableOrientable.

References base::Point3, and physics::PositionableOrientable::setConfiguration().

virtual void robot::sim::SimulatedTool::setSolidSystem ref< physics::SolidSystem solidSystem  )  [inline, virtual]
 

Reimplemented from robot::sim::SimulatedKinematicChain.

Definition at line 70 of file SimulatedTool.

bool base::Referenced::unreference  )  const [inline, inherited]
 

Decrement the reference count by one, indicating that a pointer to this object is referencing it. If the refence count goes to zero, it is assumed that this object is nolonger referenced and is automatically deleted.

Definition at line 81 of file Referenced.

References base::Referenced::_refCount, Exception, base::Referenced::onUnreference(), and base::Referenced::onUnreferenceEnabled.


Friends And Related Function Documentation

friend class base::Serializable::SerializableDerivedInstantiator< SimulatedTool > [friend]
 

Definition at line 182 of file SimulatedTool.

friend class ProximityCollisionResponseHandler [friend, inherited]
 

Reimplemented in robot::sim::SimulatedSerialManipulator.

Definition at line 196 of file SimulatedKinematicChain.

friend class SimulatedRobot [friend]
 

Reimplemented from robot::sim::SimulatedKinematicChain.

Definition at line 181 of file SimulatedTool.


Member Data Documentation

int base::Referenced::_refCount [mutable, protected, inherited]
 

Definition at line 136 of file Referenced.

Referenced by base::Referenced::reference(), base::Referenced::referenceCount(), base::Referenced::Referenced(), base::Referenced::unreference(), and base::Referenced::~Referenced().

bool robot::sim::SimulatedTool::attached [protected]
 

is this tool attached to the end-effector of a manipulator?

Definition at line 177 of file SimulatedTool.

KinematicChain robot::sim::SimulatedKinematicChain::chain [protected, inherited]
 

Definition at line 109 of file SimulatedKinematicChain.

array<ref<physics::Collidable> > robot::sim::SimulatedKinematicChain::collidables [protected, inherited]
 

collidables for each link Solid

Definition at line 150 of file SimulatedKinematicChain.

bool robot::sim::SimulatedKinematicChain::dynamic [protected, inherited]
 

true for a dynamic simulation, fasle for static (no force/torque or velocity control, just position control)

Definition at line 113 of file SimulatedKinematicChain.

ref<physics::Solid> robot::sim::SimulatedTool::endSolid [protected]
 

Solid for the tool end-effector.

Definition at line 173 of file SimulatedTool.

base::Transform robot::sim::SimulatedTool::firstLinkSolidToMount [protected]
 

transform from origin of first link Solid to mount origin

Definition at line 174 of file SimulatedTool.

ref<physics::Solid> robot::sim::SimulatedTool::firstSolid [protected]
 

Solid for the first link.

Definition at line 172 of file SimulatedTool.

Referenced by getFirstLinkSolid().

array<ref<physics::Joint> > robot::sim::SimulatedKinematicChain::joints [protected, inherited]
 

Joint attaching each pair of consecutive links (dynamic simulation only).

Definition at line 148 of file SimulatedKinematicChain.

array<ref<physics::SpatialGroup> > robot::sim::SimulatedKinematicChain::linkGroups [protected, inherited]
 

a group for each link (which contains the link Solid and the group for the next link)

Reimplemented in robot::sim::SimulatedSerialManipulator.

Definition at line 145 of file SimulatedKinematicChain.

array<Real> robot::sim::SimulatedKinematicChain::linkLengths [protected, inherited]
 

Length of each link corresponding with links[].

Definition at line 149 of file SimulatedKinematicChain.

array< ProximityData > robot::sim::SimulatedKinematicChain::linkProximity [protected, inherited]
 

Definition at line 191 of file SimulatedKinematicChain.

array< Real > robot::sim::SimulatedKinematicChain::linkProximitySurfPosition [protected, inherited]
 

dist from link axis of proximity sensor (i.e. on link sufrace)

Definition at line 193 of file SimulatedKinematicChain.

array<ref<physics::Solid> > robot::sim::SimulatedKinematicChain::links [protected, inherited]
 

Solids for each link.

Definition at line 147 of file SimulatedKinematicChain.

const Real robot::sim::SimulatedKinematicChain::maxDist [static, inherited]
 

Definition at line 94 of file SimulatedKinematicChain.

ref<physics::ConstraintGroup> robot::sim::SimulatedTool::mountConstraintGroup [protected]
 

group that holds the joint attaching the tool to the manipulator end-effector (valid if attached is true)

Definition at line 178 of file SimulatedTool.

ref<physics::SpatialTransform> robot::sim::SimulatedTool::mountSpatial [protected]
 

Spatial who's configuration is that of the tool's mount point.

Definition at line 175 of file SimulatedTool.

bool base::Referenced::onUnreferenceEnabled [protected, inherited]
 

Definition at line 137 of file Referenced.

Referenced by base::Referenced::enableOnUnreferenceCall(), base::Referenced::Referenced(), and base::Referenced::unreference().

ref<physics::CollidableGroup> robot::sim::SimulatedKinematicChain::proximityCollidableGroup [protected, inherited]
 

Definition at line 179 of file SimulatedKinematicChain.

array<ref<physics::Collidable> > robot::sim::SimulatedKinematicChain::proximityCollidables [protected, inherited]
 

collidables for each link's proximity sensor

Definition at line 151 of file SimulatedKinematicChain.

base::Vector robot::sim::SimulatedKinematicChain::q [mutable, protected, inherited]
 

current joint parameters (static simulation only)

Definition at line 153 of file SimulatedKinematicChain.

ref<physics::SolidSystem> robot::sim::SimulatedKinematicChain::solidSystem [protected, inherited]
 

Definition at line 110 of file SimulatedKinematicChain.

ref<physics::SpatialGroup> robot::sim::SimulatedTool::spatialGroup [protected]
 

a group containing the Solids

Definition at line 176 of file SimulatedTool.

ref<const robot::ToolDescription> robot::sim::SimulatedTool::toolDescr [protected]
 

Definition at line 148 of file SimulatedTool.

Referenced by getToolDescription().


The documentation for this class was generated from the following file:
Generated on Thu Jul 29 16:43:32 2004 for OpenSim by doxygen 1.3.6