hpp::model::Device Class Reference

Robot with geometric and dynamic model. More...

#include <hpp/model/device.hh>

Inheritance diagram for hpp::model::Device:

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_tCollisionPair_t
 Collision pairs between bodies. More...
 
typedef std::list< CollisionPair_tCollisionPairs_t
 

Public Member Functions

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

Static Public Member Functions

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

Protected Member Functions

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

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

◆ CollisionPair_t

Collision pairs between bodies.

◆ CollisionPairs_t

Member Enumeration Documentation

◆ Computation_t

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

◆ ~Device()

virtual hpp::model::Device::~Device ( )
virtual

◆ Device()

hpp::model::Device::Device ( const std::string &  name)
protected

Constructor.

Member Function Documentation

◆ addCollisionPairs()

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.

◆ addGripper()

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

Add a gripper to the Device.

◆ clone()

DevicePtr_t hpp::model::Device::clone ( ) const

Clone as a CkwsDevice.

◆ collisionPairs()

const CollisionPairs_t& hpp::model::Device::collisionPairs ( Request_t  type) const

Get list of collision or distance pairs.

Parameters
typecollision or distance.

◆ collisionTest()

bool hpp::model::Device::collisionTest ( ) const

Test collision of current configuration.

Warning
Users should call computeForwardKinematics first.

◆ computationFlag()

Computation_t hpp::model::Device::computationFlag ( ) const
inline

Get computation flag.

References hpp::model::operator<<().

◆ computeDistances()

void hpp::model::Device::computeDistances ( )

Compute distances between pairs of objects stored in bodies.

◆ computeForwardKinematics()

virtual void hpp::model::Device::computeForwardKinematics ( )
virtual

Compute forward kinematics.

◆ configSize()

size_type hpp::model::Device::configSize ( ) const

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

◆ controlComputation()

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

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

◆ create()

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

◆ createCopy()

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.

◆ currentAcceleration() [1/2]

const vector_t& hpp::model::Device::currentAcceleration ( ) const
inline

Get current acceleration.

◆ currentAcceleration() [2/2]

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

Set current acceleration.

◆ currentConfiguration() [1/2]

const Configuration_t& hpp::model::Device::currentConfiguration ( ) const
inline

Get current configuration.

◆ currentConfiguration() [2/2]

virtual bool hpp::model::Device::currentConfiguration ( ConfigurationIn_t  configuration)
inlinevirtual

Set current configuration.

Returns
True if the current configuration was modified and false if the current configuration did not change.

◆ currentVelocity() [1/2]

const vector_t& hpp::model::Device::currentVelocity ( ) const
inline

Get current velocity.

◆ currentVelocity() [2/2]

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

Set current velocity.

◆ distanceResults()

const DistanceResults_t& hpp::model::Device::distanceResults ( ) const
inline

Get result of distance computations.

◆ extraConfigSpace() [1/2]

ExtraConfigSpace& hpp::model::Device::extraConfigSpace ( )
inline

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.

◆ extraConfigSpace() [2/2]

const ExtraConfigSpace& hpp::model::Device::extraConfigSpace ( ) const
inline

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.

◆ getJointByBodyName()

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

◆ getJointByName()

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

◆ getJointVector()

const JointVector_t& hpp::model::Device::getJointVector ( ) const

Get vector of joints.

◆ grippers() [1/2]

Grippers_t& hpp::model::Device::grippers ( )
inline

Return list of grippers of the Device.

◆ grippers() [2/2]

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

Return list of grippers of the Device.

◆ init()

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

Initialization.

◆ jacobianCenterOfMass()

const ComJacobian_t& hpp::model::Device::jacobianCenterOfMass ( ) const
inline

Get Jacobian of center of mass with respect to configuration.

◆ mass()

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

Get mass of robot.

◆ name()

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

Get name of device.

◆ neutralConfiguration()

Configuration_t hpp::model::Device::neutralConfiguration ( ) const

Get the neutral configuration.

◆ numberDof()

size_type hpp::model::Device::numberDof ( ) const

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

◆ objectIterator()

ObjectIterator hpp::model::Device::objectIterator ( Request_t  type)

Iterator over inner objects of the device.

Parameters
typeCollision or distance

◆ obstacles()

const ObjectVector_t& hpp::model::Device::obstacles ( Request_t  type) const

Get list of obstacles.

Parameters
typecollision or distance.

◆ positionCenterOfMass()

const vector3_t& hpp::model::Device::positionCenterOfMass ( ) const
inline

Get position of center of mass.

◆ print()

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

Print object in a stream.

◆ registerJoint()

void hpp::model::Device::registerJoint ( const JointPtr_t joint)

Register joint in internal containers.

◆ removeCollisionPairs()

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

◆ rootJoint() [1/2]

void hpp::model::Device::rootJoint ( JointPtr_t  joint)

Set the root of the kinematic chain.

◆ rootJoint() [2/2]

JointPtr_t hpp::model::Device::rootJoint ( ) const

Get root joint.

◆ rootJointPosition()

void hpp::model::Device::rootJointPosition ( const Transform3f position)

Set position of root joint in world frame.

◆ setDimensionExtraConfigSpace()

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

Set dimension of extra configuration space.

◆ updateDistances()

void hpp::model::Device::updateDistances ( )
protected

Recompute number of distance pairs.

Friends And Related Function Documentation

◆ Body

friend class Body
friend

◆ Joint

friend class Joint
friend