hpp::model::Device Class Reference

Robot with geometric and dynamic model. More...

#include <hpp/model/device.hh>

Inheritance diagram for hpp::model::Device:

List of all members.

Public Types

enum  Computation_t {
  JOINT_POSITION = 0x0,
  JACOBIAN = 0x1,
  VELOCITY = 0x2,
  ACCELERATION = 0x4,
  COM = 0x8,
  ALL = 0Xffff
}
 Flags to select computation To optimize computation time, computations performed by method computeForwardKinematics can be selected by calling method controlComputation. More...
typedef std::pair< JointPtr_t,
JointPtr_t
CollisionPair_t
 Collision pairs between bodies.
typedef std::list
< CollisionPair_t
CollisionPairs_t

Public Member Functions

const std::string & name () const
 Get name of device.
virtual std::ostream & print (std::ostream &os) const
 Print object in a stream.
Construction, copy and destruction
virtual ~Device ()
DevicePtr_t clone () const
 Clone as a CkwsDevice.
Joints
void rootJoint (JointPtr_t joint)
 Set the root of the kinematic chain.
void rootJointPosition (const Transform3f &position)
 Set position of root joint in world frame.
JointPtr_t rootJoint () const
 Get root joint.
void registerJoint (const JointPtr_t &joint)
 Register joint in internal containers.
const JointVector_tgetJointVector () const
 Get vector of joints.
JointPtr_t getJointByName (const std::string &name) const
 Get joint by name.
JointPtr_t getJointByBodyName (const std::string &name) const
 Get joint by body name.
size_type configSize () const
 Size of configuration vectors Sum of joint dimensions and of extra configuration space dimension.
size_type numberDof () const
 Size of velocity vectors Sum of joint number of degrees of freedom and of extra configuration space dimension.
Extra configuration space
ExtraConfigSpaceextraConfigSpace ()
 Get degrees of freedom to store internal values in configurations.
const ExtraConfigSpaceextraConfigSpace () const
 Get degrees of freedom to store internal values in configurations.
void setDimensionExtraConfigSpace (const size_type &dimension)
 Set dimension of extra configuration space.
Current state
const Configuration_tcurrentConfiguration () const
 Get current configuration.
virtual bool currentConfiguration (ConfigurationIn_t configuration)
 Set current configuration.
Configuration_t neutralConfiguration () const
 Get the neutral configuration.
const vector_tcurrentVelocity () const
 Get current velocity.
void currentVelocity (vectorIn_t velocity)
 Set current velocity.
const vector_tcurrentAcceleration () const
 Get current acceleration.
void currentAcceleration (vectorIn_t acceleration)
 Set current acceleration.
Mass and center of mass
const value_typemass () const
 Get mass of robot.
const vector3_tpositionCenterOfMass () const
 Get position of center of mass.
const ComJacobian_tjacobianCenterOfMass () const
 Get Jacobian of center of mass with respect to configuration.
void addGripper (const GripperPtr_t &gripper)
 Add a gripper to the Device.
Grippers_tgrippers ()
 Return list of grippers of the Device.
const Grippers_tgrippers () const
 Return list of grippers of the Device.
Collision and distance computation
const ObjectVector_tobstacles (Request_t type) const
 Get list of obstacles.
virtual void addCollisionPairs (const JointPtr_t &joint1, const JointPtr_t &joint2, Request_t type)
 Add collision pairs between objects attached to two joints.
virtual void removeCollisionPairs (const JointPtr_t &joint1, const JointPtr_t &joint2, Request_t type)
 Remove collision pairs between objects attached to two joints.
const CollisionPairs_tcollisionPairs (Request_t type) const
 Get list of collision or distance pairs.
ObjectIterator objectIterator (Request_t type)
 Iterator over inner objects of the device.
bool collisionTest () const
 Test collision of current configuration.
void computeDistances ()
 Compute distances between pairs of objects stored in bodies.
const DistanceResults_tdistanceResults () const
 Get result of distance computations.
Forward kinematics
void controlComputation (const Computation_t &flag)
 Select computation Optimize computation time by selecting only necessary values in method computeForwardKinematics.
Computation_t computationFlag () const
 Get computation flag.
virtual void computeForwardKinematics ()
 Compute forward kinematics.

Static Public Member Functions

static DevicePtr_t create (std::string name)
 Creation of a new device.
static DevicePtr_t createCopy (const DevicePtr_t &device)
 Copy of a device.

Protected Member Functions

 Device (const std::string &name)
 Constructor.
void init (const DeviceWkPtr_t &weakPtr)
 Initialization.
void updateDistances ()
 Recompute number of distance pairs.

Friends

class Body
class Joint

Detailed Description

Robot with geometric and dynamic model.

The creation of the device is done by Device::create(const std::string name). This function returns a shared pointer to the newly created object.

See also:
Smart pointers documentation: http://www.boost.org/libs/smart_ptr/smart_ptr.htm

Member Typedef Documentation

Collision pairs between bodies.


Member Enumeration Documentation

Flags to select computation To optimize computation time, computations performed by method computeForwardKinematics can be selected by calling method controlComputation.

Enumerator:
JOINT_POSITION 
JACOBIAN 
VELOCITY 
ACCELERATION 
COM 
ALL 

Constructor & Destructor Documentation

virtual hpp::model::Device::~Device ( ) [virtual]
hpp::model::Device::Device ( const std::string &  name) [protected]

Constructor.


Member Function Documentation

virtual void hpp::model::Device::addCollisionPairs ( const JointPtr_t joint1,
const JointPtr_t joint2,
Request_t  type 
) [virtual]

Add collision pairs between objects attached to two joints.

Parameters:
joint1first joint
joint2second joint
typecollision or distance.

Define collision pair between each object of joint 1 body and each object of joint2 body.

void hpp::model::Device::addGripper ( const GripperPtr_t gripper) [inline]

Add a gripper to the Device.

Clone as a CkwsDevice.

Reimplemented in hpp::model::HumanoidRobot.

Get list of collision or distance pairs.

Parameters:
typecollision or distance.

Test collision of current configuration.

Warning:
Users should call computeForwardKinematics first.

Get computation flag.

Compute distances between pairs of objects stored in bodies.

Compute forward kinematics.

Size of configuration vectors Sum of joint dimensions and of extra configuration space dimension.

void hpp::model::Device::controlComputation ( const Computation_t flag) [inline]

Select computation Optimize computation time by selecting only necessary values in method computeForwardKinematics.

static DevicePtr_t hpp::model::Device::create ( std::string  name) [static]

Creation of a new device.

Returns:
a shared pointer to the new device
Parameters:
nameName of the device (is passed to CkkpDeviceComponent)

Referenced by hpp::model::ObjectFactory::createRobot().

static DevicePtr_t hpp::model::Device::createCopy ( const DevicePtr_t device) [static]

Copy of a device.

Returns:
A shared pointer to new device.
Parameters:
deviceDevice to be copied.

Get current acceleration.

void hpp::model::Device::currentAcceleration ( vectorIn_t  acceleration) [inline]

Set current acceleration.

Get current configuration.

virtual bool hpp::model::Device::currentConfiguration ( ConfigurationIn_t  configuration) [inline, virtual]

Set current configuration.

Returns:
True if the current configuration was modified and false if the current configuration did not change.
const vector_t& hpp::model::Device::currentVelocity ( ) const [inline]

Get current velocity.

void hpp::model::Device::currentVelocity ( vectorIn_t  velocity) [inline]

Set current velocity.

Get result of distance computations.

Get degrees of freedom to store internal values in configurations.

In some applications, it is useful to store extra variables with the configuration vector. For instance, when planning motions in state space using roadmap based methods, the velocity of the robot is stored in the nodes of the roadmap.

Get degrees of freedom to store internal values in configurations.

In some applications, it is useful to store extra variables with the configuration vector. For instance, when planning motions in state space using roadmap based methods, the velocity of the robot is stored in the nodes of the roadmap.

JointPtr_t hpp::model::Device::getJointByBodyName ( const std::string &  name) const

Get joint by body name.

Exceptions:
runtime_errorif device has no body with this name
JointPtr_t hpp::model::Device::getJointByName ( const std::string &  name) const

Get joint by name.

Parameters:
namename of the joint.
Exceptions:
runtime_errorif device has no joint with this name

Get vector of joints.

Return list of grippers of the Device.

const Grippers_t& hpp::model::Device::grippers ( ) const [inline]

Return list of grippers of the Device.

void hpp::model::Device::init ( const DeviceWkPtr_t &  weakPtr) [protected]

Initialization.

Get Jacobian of center of mass with respect to configuration.

const value_type& hpp::model::Device::mass ( ) const [inline]

Get mass of robot.

const std::string& hpp::model::Device::name ( ) const [inline]

Get name of device.

Get the neutral configuration.

Size of velocity vectors Sum of joint number of degrees of freedom and of extra configuration space dimension.

Iterator over inner objects of the device.

Parameters:
typeCollision or distance

Get list of obstacles.

Parameters:
typecollision or distance.

Get position of center of mass.

virtual std::ostream& hpp::model::Device::print ( std::ostream &  os) const [virtual]

Print object in a stream.

Register joint in internal containers.

virtual void hpp::model::Device::removeCollisionPairs ( const JointPtr_t joint1,
const JointPtr_t joint2,
Request_t  type 
) [virtual]

Remove collision pairs between objects attached to two joints.

Parameters:
joint1first joint
joint2second joint
typecollision or distance.

remove collision between each object of joint 1 body and each object of joint2 body

Set the root of the kinematic chain.

Get root joint.

Set position of root joint in world frame.

void hpp::model::Device::setDimensionExtraConfigSpace ( const size_type dimension) [inline]

Set dimension of extra configuration space.

Recompute number of distance pairs.


Friends And Related Function Documentation

friend class Body [friend]
friend class Joint [friend]
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends