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

robot::sim::SimulatedPlatform Class Reference

Inheritance diagram for robot::sim::SimulatedPlatform:

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

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

 SimulatedPlatform ()
 SimulatedPlatform (ref< const robot::PlatformDescription > platformDescription, ref< physics::SolidSystem > solidSystem=ref< physics::SolidSystem >(0), bool dynamic=true)
virtual ~SimulatedPlatform ()
virtual String className () const
virtual void setDynamic (bool enabled)
void setSolidSystem (ref< physics::SolidSystem > solidSystem)
ref< const robot::PlatformDescriptiongetPlatformDescription () const
void construct (const base::Point3 &initialPosition, const base::Orient &initialOrientation)
ref< physics::SolidgetPlatformSolid () const
void setLeftBackWheelTorque (Real t)
 Nonholonomic platform - set the torque applied to the left back drive wheel.

void setLeftBackWheelVel (Real v, Real maxTorque=10.0)
 Nonholonomic platform - set the velocity of the left back drive wheel.

Real getLeftBackWheelVel () const
 Nonholonomic platform - get angular velocity of the left back drive wheel.

void setRightBackWheelTorque (Real t)
 Nonholonomic platform - set the torque applied to the right back drive wheel.

void setRightBackWheelVel (Real v, Real maxTorque=10.0)
 Nonholonomic platform - set the angular velocity of the right back drive wheel.

Real getRightBackWheelVel () const
 Nonholonomic platform - get angular velocity of the right back drive wheel.

void setSteeringTorque (Real t)
 Nonholonomic platform - set the torque applied by the front steering motor.

void setSteeringVel (Real v, Real maxTorque=10.0)
 Nonholonomic platform - set the angular velocity of the front steering motor.

Real getSteeringAngle () const
 Nonholonomic platform - get angle of the steering wheels.

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

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
virtual void externalize (Externalizer &e, String format="", Real version=1.0) const
 write object state to Externalizer (throws if e is in Input)

void load (ref< VFile > archive, const String &format="", Real version=1.0)
void save (ref< VFile > archive, const String &format="", Real version=1.0)

Protected Types

enum  PlatformSolids {
  Platform, LeftFrontWheel, RightFrontWheel, LeftBackWheel,
  RightBackWheel, LeftFrontWheelMount, RightFrontWheelMount, Crossbar,
  MaxPlatformSolids
}

Protected Member Functions

void updateGroupConfigurationFromPlatformSolid () const
void disableCollisions (const array< ref< physics::Collidable > > &collidables)
virtual void setName (const String &name)

Protected Attributes

ref< physics::SolidSystemsolidSystem
ref< const robot::PlatformDescriptionplatformDescr
bool dynamic
 if true, full physics is simulated; if false, the Solids that comprise the Platform aren't connected together (& only their pos/orient is significant)

array< ref< physics::Solid > > platformSolids
 Solids that comprise the platform, indexed by PlatformSolids enum.

ref< physics::SpatialGroupspatialGroup
 all the Spatials that comprise the platform (e.g. the Solids)

ref< physics::ConstraintGroupwheelConstraintGroup
ref< physics::HingeJointleftDriveHingeJoint
ref< physics::HingeJointrightDriveHingeJoint
ref< physics::HingeJointsteeringHingeJoint
ref< physics::MotorleftDriveMotor
 drive motor for left back wheel of non-holonomic mobile base

ref< physics::MotorrightDriveMotor
 drive motor for right back wheel of non-holonomic mobile base

ref< physics::MotorsteeringMotor
 steering motor for front wheels of non-holonomic mobile base

int _refCount
bool onUnreferenceEnabled

Detailed Description

A simulated robot platform created according to a supplied specification. Simulated using gfx/physics.

Definition at line 49 of file SimulatedPlatform.


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 base::Externalizable::ExternalizationType [inherited]
 

Enumeration values:
Input 
Output 
IO 

Definition at line 40 of file Externalizable.

enum robot::sim::SimulatedPlatform::PlatformSolids [protected]
 

Enumeration values:
Platform 
LeftFrontWheel 
RightFrontWheel 
LeftBackWheel 
RightBackWheel 
LeftFrontWheelMount 
RightFrontWheelMount 
Crossbar 
MaxPlatformSolids 

Definition at line 113 of file SimulatedPlatform.


Constructor & Destructor Documentation

robot::sim::SimulatedPlatform::SimulatedPlatform  ) 
 

robot::sim::SimulatedPlatform::SimulatedPlatform ref< const robot::PlatformDescription platformDescription,
ref< physics::SolidSystem solidSystem = ref< physics::SolidSystem >(0),
bool  dynamic = true
 

virtual robot::sim::SimulatedPlatform::~SimulatedPlatform  )  [virtual]
 


Member Function Documentation

virtual String robot::sim::SimulatedPlatform::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 56 of file SimulatedPlatform.

void robot::sim::SimulatedPlatform::construct const base::Point3 initialPosition,
const base::Orient initialOrientation
 

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

Implements physics::CollidableProvider.

void robot::sim::SimulatedPlatform::disableCollisions const array< ref< physics::Collidable > > &  collidables  )  [protected]
 

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.

virtual void base::Externalizable::externalize Externalizer e,
String  format = "",
Real  version = 1.0
const [virtual, inherited]
 

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

Reimplemented in physics::Box, physics::Capsule, physics::Cone, physics::Cylinder, physics::LODTerrain, physics::Polyhedron, physics::Sphere, robot::KinematicChain::Link, robot::KinematicChain, robot::ManipulatorDescription, robot::PlatformDescription, robot::RobotDescription, robot::sim::SimulatedManipulatorDescription, robot::sim::SimulatedRobotDescription, robot::sim::SimulatedSerialManipulator, robot::sim::SimulatedTool, and robot::ToolDescription.

virtual void robot::sim::SimulatedPlatform::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::SimulatedPlatform::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.

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

Reimplemented from physics::PositionableOrientable.

Real robot::sim::SimulatedPlatform::getLeftBackWheelVel  )  const
 

Nonholonomic platform - get angular velocity of the left back drive wheel.

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::SimulatedPlatform::getOrientation  )  const [virtual]
 

Implements physics::Orientable.

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

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

ref<const robot::PlatformDescription> robot::sim::SimulatedPlatform::getPlatformDescription  )  const [inline]
 

Definition at line 62 of file SimulatedPlatform.

ref<physics::Solid> robot::sim::SimulatedPlatform::getPlatformSolid  )  const [inline]
 

Definition at line 66 of file SimulatedPlatform.

References platformSolids.

virtual Point3 robot::sim::SimulatedPlatform::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.

Real robot::sim::SimulatedPlatform::getRightBackWheelVel  )  const
 

Nonholonomic platform - get angular velocity of the right back drive wheel.

Real robot::sim::SimulatedPlatform::getSteeringAngle  )  const
 

Nonholonomic platform - get angle of the steering wheels.

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().

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::SimulatedPlatform::setConfiguration const base::Transform configuration  )  [virtual]
 

Reimplemented from physics::PositionableOrientable.

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

Definition at line 58 of file SimulatedPlatform.

void robot::sim::SimulatedPlatform::setLeftBackWheelTorque Real  t  ) 
 

Nonholonomic platform - set the torque applied to the left back drive wheel.

void robot::sim::SimulatedPlatform::setLeftBackWheelVel Real  v,
Real  maxTorque = 10.0
 

Nonholonomic platform - set the velocity of the left back drive wheel.

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::SimulatedPlatform::setOrientation const Orient orient  )  [virtual]
 

Implements physics::Orientable.

virtual void robot::sim::SimulatedPlatform::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().

void robot::sim::SimulatedPlatform::setRightBackWheelTorque Real  t  ) 
 

Nonholonomic platform - set the torque applied to the right back drive wheel.

void robot::sim::SimulatedPlatform::setRightBackWheelVel Real  v,
Real  maxTorque = 10.0
 

Nonholonomic platform - set the angular velocity of the right back drive wheel.

void robot::sim::SimulatedPlatform::setSolidSystem ref< physics::SolidSystem solidSystem  )  [inline]
 

Definition at line 60 of file SimulatedPlatform.

void robot::sim::SimulatedPlatform::setSteeringTorque Real  t  ) 
 

Nonholonomic platform - set the torque applied by the front steering motor.

void robot::sim::SimulatedPlatform::setSteeringVel Real  v,
Real  maxTorque = 10.0
 

Nonholonomic platform - set the angular velocity of the front steering motor.

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.

void robot::sim::SimulatedPlatform::updateGroupConfigurationFromPlatformSolid  )  const [protected]
 


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::SimulatedPlatform::dynamic [protected]
 

if true, full physics is simulated; if false, the Solids that comprise the Platform aren't connected together (& only their pos/orient is significant)

Definition at line 111 of file SimulatedPlatform.

ref<physics::HingeJoint> robot::sim::SimulatedPlatform::leftDriveHingeJoint [protected]
 

Definition at line 129 of file SimulatedPlatform.

ref<physics::Motor> robot::sim::SimulatedPlatform::leftDriveMotor [protected]
 

drive motor for left back wheel of non-holonomic mobile base

Definition at line 132 of file SimulatedPlatform.

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<const robot::PlatformDescription> robot::sim::SimulatedPlatform::platformDescr [protected]
 

Definition at line 108 of file SimulatedPlatform.

array<ref<physics::Solid> > robot::sim::SimulatedPlatform::platformSolids [protected]
 

Solids that comprise the platform, indexed by PlatformSolids enum.

Definition at line 120 of file SimulatedPlatform.

Referenced by getPlatformSolid().

ref<physics::HingeJoint> robot::sim::SimulatedPlatform::rightDriveHingeJoint [protected]
 

Definition at line 130 of file SimulatedPlatform.

ref<physics::Motor> robot::sim::SimulatedPlatform::rightDriveMotor [protected]
 

drive motor for right back wheel of non-holonomic mobile base

Definition at line 133 of file SimulatedPlatform.

ref<physics::SolidSystem> robot::sim::SimulatedPlatform::solidSystem [protected]
 

Definition at line 107 of file SimulatedPlatform.

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

all the Spatials that comprise the platform (e.g. the Solids)

Definition at line 122 of file SimulatedPlatform.

ref<physics::HingeJoint> robot::sim::SimulatedPlatform::steeringHingeJoint [protected]
 

Definition at line 131 of file SimulatedPlatform.

ref<physics::Motor> robot::sim::SimulatedPlatform::steeringMotor [protected]
 

steering motor for front wheels of non-holonomic mobile base

Definition at line 134 of file SimulatedPlatform.

ref<physics::ConstraintGroup> robot::sim::SimulatedPlatform::wheelConstraintGroup [protected]
 

Definition at line 128 of file SimulatedPlatform.


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