hpp::corbaserver::Robot Interface Reference

Creation of a device, joints and bodies. More...

import"/home/jmirabel/devel/demo/src/hpp-corbaserver/idl/hpp/corbaserver/robot.idl";

Public Member Functions

Loading URDF files
void loadRobotModel (in string robotName, in string rootJointType, in string packageName, in string modelName, in string urdfSuffix, in string srdfSuffix) raises (Error)
 Load robot model. More...
 
void loadHumanoidModel (in string robotName, in string rootJointType, in string packageName, in string modelName, in string urdfSuffix, in string srdfSuffix) raises (Error)
 Load humanoid robot model. More...
 
void loadRobotModelFromString (in string robotName, in string rootJointType, in string urdfString, in string srdfString) raises (Error)
 Load robot model. More...
 
void loadHumanoidModelFromString (in string robotName, in string rootJointType, in string urdfString, in string srdfString) raises (Error)
 Load humanoid robot model. More...
 
Degrees of freedom
long getConfigSize () raises (Error)
 Get size of configuration. More...
 
long getNumberDof () raises (Error)
 Get size of velocity. More...
 
Joints
Names_t getJointNames () raises (Error)
 Get joint names in the same order as in the configuration. More...
 
Names_t getJointTypes () raises (Error)
 Get joint types in the same order as in the configuration. More...
 
Names_t getAllJointNames () raises (Error)
 Get all joint names including anchor joints. More...
 
string getParentJointName (in string jointName) raises (Error)
 Get the parent joint of a joint jointName any joint (anchor or movable). More...
 
floatSeq getJointConfig (in string jointName) raises (Error)
 Get configuration of a joint in robot configuration. More...
 
void setJointConfig (in string jointName, in floatSeq config) raises (Error)
 Set configuration of a joint in robot configuration. More...
 
string getJointType (in string jointName) raises (Error)
 Get joint type. More...
 
floatSeq jointIntegrate (in floatSeq jointCfg, in string jointName, in floatSeq speed, in boolean saturate) raises (Error)
 Integrate velocity of a joint starting from joint configuration. More...
 
floatSeqSeq getCurrentTransformation (in string jointName) raises (Error)
 Get joint Transformation. More...
 
Transform_ getJointPosition (in string jointName) raises (Error)
 Get joint position. More...
 
TransformSeq getJointsPosition (in floatSeq q, in Names_t jointNames) raises (Error)
 Get position of a list of joints in world frame. More...
 
floatSeq getJointVelocity (in string jointName) raises (Error)
 Get joint velocity expressed in the world frame, at the center of the world. More...
 
floatSeq getJointVelocityInLocalFrame (in string jointName) raises (Error)
 Get joint velocity expressed in the joint frame, at the center of the joint. More...
 
Transform_ getJointPositionInParentFrame (in string jointName) raises (Error)
 Get the initial joint position (when config parameter corresponds to the identity) More...
 
Transform_ getRootJointPosition () raises (Error)
 Get position of root joint in world frame. More...
 
void setRootJointPosition (in Transform_ position) raises (Error)
 Set position of root joint in world frame. More...
 
void setJointPositionInParentFrame (in string jointName, in Transform_ position) raises (Error)
 Set the static position of joint WRT its parent. More...
 
long getJointNumberDof (in string jointName) raises (Error)
 Get joint number degrees of freedom. More...
 
long getJointConfigSize (in string jointName) raises (Error)
 Get joint number config size. More...
 
void setJointBounds (in string jointName, in floatSeq inJointBound) raises (Error)
 set bounds for a joint More...
 
floatSeq getJointBounds (in string jointName) raises (Error)
 Get bounds for a joint. More...
 
Transform_ getLinkPosition (in string linkName) raises (Error)
 Get link position in world frame. More...
 
TransformSeq getLinksPosition (in floatSeq q, in Names_t linkName) raises (Error)
 Get position of a list of links in world frame. More...
 
Names_t getLinkNames (in string jointName) raises (Error)
 Get link names. More...
 
Extra configuration space
void setDimensionExtraConfigSpace (in unsigned long dimension) raises (Error)
 Set dimension of the extra configuration space. More...
 
unsigned long getDimensionExtraConfigSpace () raises (Error)
 Get the dimension of the extra configuration space. More...
 
void setExtraConfigSpaceBounds (in floatSeq bounds) raises (Error)
 Set bounds of extra configuration variables. More...
 
Configuration
floatSeq getCurrentConfig () raises (Error)
 Get current configuration. More...
 
floatSeq shootRandomConfig () raises (Error)
 Shoot random configuration. More...
 
void setCurrentConfig (in floatSeq dofArray) raises (Error)
 Set current configuration of specified robot,. More...
 
floatSeq getCurrentVelocity () raises (Error)
 Get current velocity. More...
 
void setCurrentVelocity (in floatSeq qDot) raises (Error)
 Set current velocity. More...
 
Bodies
Names_t getJointInnerObjects (in string jointName) raises (Error)
 Get the list of objects attached to a joint. More...
 
Names_t getJointOuterObjects (in string jointName) raises (Error)
 Get list of collision objects tested with the body attached to a joint. More...
 
void getObjectPosition (in string objectName, out Transform_ cfg) raises (Error)
 Get the position of an object of the robot. More...
 
Collision checking and distance computation
void isConfigValid (in floatSeq dofArray, out boolean validity, out string report) raises (Error)
 Test the validity of a configuration. More...
 
void distancesToCollision (out floatSeq distances, out Names_t innerObjects, out Names_t outerObjects, out floatSeqSeq innerPoints, out floatSeqSeq outerPoints) raises (Error)
 Compute distances between bodies and obstacles. More...
 
void autocollisionCheck (out boolSeq collide) raises (Error)
 Check each auto-collision pair for collision and return the result. More...
 
void autocollisionPairs (out Names_t innerObjects, out Names_t outerObjects, out boolSeq active) raises (Error)
 Returns the list of auto collision pairs. More...
 
void setAutoCollision (in string innerObject, in string outerObject, in boolean active) raises (Error)
 
floatSeq getRobotAABB () raises (Error)
 Get the aligned axes bounding box around the robot. More...
 
Mass and inertia
double getMass () raises (Error)
 Get mass of robot. More...
 
floatSeq getCenterOfMass () raises (Error)
 Get position of center of mass. More...
 
floatSeq getCenterOfMassVelocity () raises (Error)
 Get velocity of center of mass. More...
 
floatSeqSeq getJacobianCenterOfMass () raises (Error)
 Get Jacobian of the center of mass. More...
 
void addPartialCom (in string comName, in Names_t jointNames) raises (Error)
 Add an object to compute a partial COM of the robot. More...
 
floatSeq getPartialCom (in string comName) raises (Error)
 Get position of partial center of mass. More...
 
floatSeqSeq getJacobianPartialCom (in string comName) raises (Error)
 Get Jacobian of the partial center of mass. More...
 
floatSeq getVelocityPartialCom (in string comName) raises (Error)
 Get the velocity of the partial center of mass. More...
 
string getRobotName () raises (Error)
 Get the name of the current robot. More...
 
Create and register robot
void createRobot (in string robotName) raises (Error)
 Create an empty device. More...
 
void appendJoint (in string parentJoint, in string jointName, in string jointType, in Transform_ pos) raises (Error)
 
void createPolyhedron (in string inPolyName) raises (Error)
 create an empty polyhedron. More...
 
void createBox (in string name, in double x, in double y, in double z) raises (Error)
 Create a box. More...
 
void createSphere (in string name, in double radius) raises (Error)
 Create a sphere. More...
 
void createCylinder (in string name, in double radius, in double length) raises (Error)
 Create a cylinder. More...
 
unsigned long addPoint (in string inPolyName, in double x, in double y, in double z) raises (Error)
 Add a point to a polyhedron. More...
 
unsigned long addTriangle (in string inPolyName, in unsigned long pt1, in unsigned long pt2, in unsigned long pt3) raises (Error)
 Add a point to a polyhedron. More...
 
void addObjectToJoint (in string jointName, in string objectName, in Transform_ pos) raises (Error)
 Attach an object to a joint. More...
 

Detailed Description

Creation of a device, joints and bodies.

Member Function Documentation

void hpp::corbaserver::Robot::addObjectToJoint ( in string  jointName,
in string  objectName,
in Transform_  pos 
)
raises (Error
)

Attach an object to a joint.

Parameters
jointNamename of the body
objectNamename of the object
posrelative position of the polyhedron in the body
void hpp::corbaserver::Robot::addPartialCom ( in string  comName,
in Names_t  jointNames 
)
raises (Error
)

Add an object to compute a partial COM of the robot.

Parameters
nameof the partial com
jointNamesnames of each ROOT of the joint trees to consider.
Note
Joints are added recursively, it is not possible so far to add a joint without addind all its children.
unsigned long hpp::corbaserver::Robot::addPoint ( in string  inPolyName,
in double  x,
in double  y,
in double  z 
)
raises (Error
)

Add a point to a polyhedron.

Parameters
inPolyNamethe name of the polyhedron.
xcoordinate of the point.
ycoordinate of the point.
zcoordinate of the point.
Returns
rank of point in polyhedron
unsigned long hpp::corbaserver::Robot::addTriangle ( in string  inPolyName,
in unsigned long  pt1,
in unsigned long  pt2,
in unsigned long  pt3 
)
raises (Error
)

Add a point to a polyhedron.

Parameters
inPolyNamethe name of the polyhedron.
pt1rank of first point in polyhedron.
pt2rank of second point in polyhedron.
pt3rank of third point in polyhedron.
Returns
rank of triangle in polyhedron
void hpp::corbaserver::Robot::appendJoint ( in string  parentJoint,
in string  jointName,
in string  jointType,
in Transform_  pos 
)
raises (Error
)
void hpp::corbaserver::Robot::autocollisionCheck ( out boolSeq  collide)
raises (Error
)

Check each auto-collision pair for collision and return the result.

Return values
collidea list of boolean corresponding to the return value of of collisionPairs
void hpp::corbaserver::Robot::autocollisionPairs ( out Names_t  innerObjects,
out Names_t  outerObjects,
out boolSeq  active 
)
raises (Error
)

Returns the list of auto collision pairs.

Return values
innerObjectsnames of the objects belonging to a body
outerObjectsnames of the objects tested with inner objects,
activevector of boolean saying whether a collision pair is active
void hpp::corbaserver::Robot::createBox ( in string  name,
in double  x,
in double  y,
in double  z 
)
raises (Error
)

Create a box.

Parameters
namename of the box
x,y,zSize of the box
void hpp::corbaserver::Robot::createCylinder ( in string  name,
in double  radius,
in double  length 
)
raises (Error
)

Create a cylinder.

Parameters
namename of the cylinder
radiusradius of the cylinder
lengthlength of the cylinder
void hpp::corbaserver::Robot::createPolyhedron ( in string  inPolyName)
raises (Error
)

create an empty polyhedron.

Parameters
inPolyNamename of the polyhedron.
Exceptions
Error.
void hpp::corbaserver::Robot::createRobot ( in string  robotName)
raises (Error
)

Create an empty device.

Parameters
robotNamename of the robot.
void hpp::corbaserver::Robot::createSphere ( in string  name,
in double  radius 
)
raises (Error
)

Create a sphere.

Parameters
namename of the sphere
radiusradius of the sphere
void hpp::corbaserver::Robot::distancesToCollision ( out floatSeq  distances,
out Names_t  innerObjects,
out Names_t  outerObjects,
out floatSeqSeq  innerPoints,
out floatSeqSeq  outerPoints 
)
raises (Error
)

Compute distances between bodies and obstacles.

Return values
distanceslist of distances,
innerObjectsnames of the objects belonging to a body
outerObjectsnames of the objects tested with inner objects,
innerPointsclosest points on the body,
outerPointsclosest points on the obstacles
Note
outer objects for a body can also be inner objects of another body.
Names_t hpp::corbaserver::Robot::getAllJointNames ( )
raises (Error
)

Get all joint names including anchor joints.

floatSeq hpp::corbaserver::Robot::getCenterOfMass ( )
raises (Error
)

Get position of center of mass.

floatSeq hpp::corbaserver::Robot::getCenterOfMassVelocity ( )
raises (Error
)

Get velocity of center of mass.

long hpp::corbaserver::Robot::getConfigSize ( )
raises (Error
)

Get size of configuration.

Returns
size of configuration
floatSeq hpp::corbaserver::Robot::getCurrentConfig ( )
raises (Error
)

Get current configuration.

Returns
dofArray Array of degrees of freedom.
floatSeqSeq hpp::corbaserver::Robot::getCurrentTransformation ( in string  jointName)
raises (Error
)

Get joint Transformation.

Parameters
jointNamename of the joint
Exceptions
Errorif robot is not set or it joint does not exist.
floatSeq hpp::corbaserver::Robot::getCurrentVelocity ( )
raises (Error
)

Get current velocity.

Parameters
qDotArray of degrees of freedom
unsigned long hpp::corbaserver::Robot::getDimensionExtraConfigSpace ( )
raises (Error
)

Get the dimension of the extra configuration space.

See also
hpp::pinocchio::ExtraConfigSpace
floatSeqSeq hpp::corbaserver::Robot::getJacobianCenterOfMass ( )
raises (Error
)

Get Jacobian of the center of mass.

floatSeqSeq hpp::corbaserver::Robot::getJacobianPartialCom ( in string  comName)
raises (Error
)

Get Jacobian of the partial center of mass.

floatSeq hpp::corbaserver::Robot::getJointBounds ( in string  jointName)
raises (Error
)

Get bounds for a joint.

Parameters
jointNamename of the joint
Returns
sequence of bounds in order [v0_min,v0_max,v1_min,v1_max,...] where vi_min, vi_max are the bounds of the i-th degree of freedom of the joint if the degree of freedom is bounded, 1, 0 otherwise.

Referenced by hpp.corbaserver.robot.Robot::getSaturated().

floatSeq hpp::corbaserver::Robot::getJointConfig ( in string  jointName)
raises (Error
)

Get configuration of a joint in robot configuration.

Parameters
jointNamename of the joint,
Returns
the segment of the robot current configuration correponding to the joint.
long hpp::corbaserver::Robot::getJointConfigSize ( in string  jointName)
raises (Error
)

Get joint number config size.

Parameters
jointNamename of the joint
Exceptions
Errorif robot is not set or if joint does not exist.
Names_t hpp::corbaserver::Robot::getJointInnerObjects ( in string  jointName)
raises (Error
)

Get the list of objects attached to a joint.

Parameters
inJointNamename of the joint.
Returns
list of names of CollisionObject attached to the body.
Names_t hpp::corbaserver::Robot::getJointNames ( )
raises (Error
)

Get joint names in the same order as in the configuration.

Note
anchor joints are not exported.
long hpp::corbaserver::Robot::getJointNumberDof ( in string  jointName)
raises (Error
)

Get joint number degrees of freedom.

Parameters
jointNamename of the joint
Exceptions
Errorif robot is not set or if joint does not exist.
Names_t hpp::corbaserver::Robot::getJointOuterObjects ( in string  jointName)
raises (Error
)

Get list of collision objects tested with the body attached to a joint.

Parameters
inJointNamename of the joint.
Returns
list of names of CollisionObject
Transform_ hpp::corbaserver::Robot::getJointPosition ( in string  jointName)
raises (Error
)

Get joint position.

Parameters
jointNamename of the joint
Exceptions
Errorif robot is not set or if joint does not exist.
Transform_ hpp::corbaserver::Robot::getJointPositionInParentFrame ( in string  jointName)
raises (Error
)

Get the initial joint position (when config parameter corresponds to the identity)

Parameters
jointNamename of the joint
Exceptions
Errorif robot is not set or if joint does not exist.
TransformSeq hpp::corbaserver::Robot::getJointsPosition ( in floatSeq  q,
in Names_t  jointNames 
)
raises (Error
)

Get position of a list of joints in world frame.

Note
This method is thread safe
string hpp::corbaserver::Robot::getJointType ( in string  jointName)
raises (Error
)

Get joint type.

Parameters
jointNamename of the joint,
Names_t hpp::corbaserver::Robot::getJointTypes ( )
raises (Error
)

Get joint types in the same order as in the configuration.

floatSeq hpp::corbaserver::Robot::getJointVelocity ( in string  jointName)
raises (Error
)

Get joint velocity expressed in the world frame, at the center of the world.

Parameters
jointNamename of the joint
Exceptions
Errorif robot is not set or if joint does not exist.
floatSeq hpp::corbaserver::Robot::getJointVelocityInLocalFrame ( in string  jointName)
raises (Error
)

Get joint velocity expressed in the joint frame, at the center of the joint.

Parameters
jointNamename of the joint
Exceptions
Errorif robot is not set or if joint does not exist.
Names_t hpp::corbaserver::Robot::getLinkNames ( in string  jointName)
raises (Error
)

Get link names.

Parameters
jointNamename of the joint,
Returns
names of the links.
Transform_ hpp::corbaserver::Robot::getLinkPosition ( in string  linkName)
raises (Error
)

Get link position in world frame.

Joints are oriented in a different way as in urdf standard since rotation and uni-dimensional translation joints act around or along their x-axis. This method returns the current position of the urdf link in world frame.

Parameters
jointNamename of the joint
Returns
position of the link in world frame.
TransformSeq hpp::corbaserver::Robot::getLinksPosition ( in floatSeq  q,
in Names_t  linkName 
)
raises (Error
)

Get position of a list of links in world frame.

Note
This method is thread safe
double hpp::corbaserver::Robot::getMass ( )
raises (Error
)

Get mass of robot.

long hpp::corbaserver::Robot::getNumberDof ( )
raises (Error
)

Get size of velocity.

Returns
size of velocity
void hpp::corbaserver::Robot::getObjectPosition ( in string  objectName,
out Transform_  cfg 
)
raises (Error
)

Get the position of an object of the robot.

Parameters
objectNamename of the object.
Return values
cfgPosition of the obstacle.
Exceptions
Error.
string hpp::corbaserver::Robot::getParentJointName ( in string  jointName)
raises (Error
)

Get the parent joint of a joint jointName any joint (anchor or movable).

Returns
the parent joint (can be an anchor joint)
floatSeq hpp::corbaserver::Robot::getPartialCom ( in string  comName)
raises (Error
)

Get position of partial center of mass.

floatSeq hpp::corbaserver::Robot::getRobotAABB ( )
raises (Error
)

Get the aligned axes bounding box around the robot.

string hpp::corbaserver::Robot::getRobotName ( )
raises (Error
)

Get the name of the current robot.

Transform_ hpp::corbaserver::Robot::getRootJointPosition ( )
raises (Error
)

Get position of root joint in world frame.

Returns
constant position of the root joint in world frame in initial configuration.
floatSeq hpp::corbaserver::Robot::getVelocityPartialCom ( in string  comName)
raises (Error
)

Get the velocity of the partial center of mass.

void hpp::corbaserver::Robot::isConfigValid ( in floatSeq  dofArray,
out boolean  validity,
out string  report 
)
raises (Error
)

Test the validity of a configuration.

Check whether current configuration of robot is valid by calling hpp::core::ConfigValidations object stored in Problem.

Return values
validitywhether configuration is valid
reportthe reason why the config is not valid.
floatSeq hpp::corbaserver::Robot::jointIntegrate ( in floatSeq  jointCfg,
in string  jointName,
in floatSeq  speed,
in boolean  saturate 
)
raises (Error
)

Integrate velocity of a joint starting from joint configuration.

Parameters
jointCfga joint configuration
jointNamename of the joint,
speedvelocity vector of the joint
saturatethe joint configuration within joint bounds.
Returns
the resulting configuration

Size of speed should fit hpp::pinocchio::Joint::numberDof.

void hpp::corbaserver::Robot::loadHumanoidModel ( in string  robotName,
in string  rootJointType,
in string  packageName,
in string  modelName,
in string  urdfSuffix,
in string  srdfSuffix 
)
raises (Error
)

Load humanoid robot model.

Parameters
robotNameName of the robot that is constructed,
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
packageNameName of the ROS package containing the model,
modelNameName of the package containing the model
urdfSuffixsuffix for urdf file,

The ros url are built as follows: "package://${packageName}/urdf/${modelName}${urdfSuffix}.urdf" "package://${packageName}/srdf/${modelName}${srdfSuffix}.srdf"

void hpp::corbaserver::Robot::loadHumanoidModelFromString ( in string  robotName,
in string  rootJointType,
in string  urdfString,
in string  srdfString 
)
raises (Error
)

Load humanoid robot model.

Parameters
robotNameName of the robot that is constructed,
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
urdfStringurdf string,
srdfStringsrdf string.
void hpp::corbaserver::Robot::loadRobotModel ( in string  robotName,
in string  rootJointType,
in string  packageName,
in string  modelName,
in string  urdfSuffix,
in string  srdfSuffix 
)
raises (Error
)

Load robot model.

Parameters
robotNameName of the robot that is constructed,
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
packageNameName of the ROS package containing the model,
modelNameName of the package containing the model
urdfSuffixsuffix for urdf file,

The ros url are built as follows: "package://${packageName}/urdf/${modelName}${urdfSuffix}.urdf" "package://${packageName}/srdf/${modelName}${srdfSuffix}.srdf"

void hpp::corbaserver::Robot::loadRobotModelFromString ( in string  robotName,
in string  rootJointType,
in string  urdfString,
in string  srdfString 
)
raises (Error
)

Load robot model.

Parameters
robotNameName of the robot that is constructed,
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
urdfStringurdf string,
srdfStringsrdf string.
void hpp::corbaserver::Robot::setAutoCollision ( in string  innerObject,
in string  outerObject,
in boolean  active 
)
raises (Error
)
void hpp::corbaserver::Robot::setCurrentConfig ( in floatSeq  dofArray)
raises (Error
)
void hpp::corbaserver::Robot::setCurrentVelocity ( in floatSeq  qDot)
raises (Error
)

Set current velocity.

Parameters
qDotArray of degrees of freedom
void hpp::corbaserver::Robot::setDimensionExtraConfigSpace ( in unsigned long  dimension)
raises (Error
)

Set dimension of the extra configuration space.

Parameters
dimensiondimension
See also
hpp::pinocchio::ExtraConfigSpace
void hpp::corbaserver::Robot::setExtraConfigSpaceBounds ( in floatSeq  bounds)
raises (Error
)

Set bounds of extra configuration variables.

Parameters
inJointBoundsequence of joint dof bounds in order [v0_min,v0_max,v1_min,v1_max,...].
  • If vi_min > vi_max, dof of rank i is not bounded.
  • If size of sequence is different from twice the number of dofs, raise error.
void hpp::corbaserver::Robot::setJointBounds ( in string  jointName,
in floatSeq  inJointBound 
)
raises (Error
)

set bounds for a joint

Parameters
jointNamename of the joint
inJointBoundsequence of joint dof bounds in order [v0_min,v0_max,v1_min,v1_max,...].
  • If vi_min > vi_max, dof of rank i is not bounded.
  • If size of sequence is different from twice the number of dofs, raise error.
Note
The roadmap must be reset after all the joints bounds has been set. See Problem::resetRoadmap
void hpp::corbaserver::Robot::setJointConfig ( in string  jointName,
in floatSeq  config 
)
raises (Error
)

Set configuration of a joint in robot configuration.

Parameters
jointNamename of the joint,
configConfiguration of the joint.

Size of config should fit hpp::pinocchio::Joint::configSize.

Modify the part of the robot current configuration correponding to the joint and recompute forward kinematics

void hpp::corbaserver::Robot::setJointPositionInParentFrame ( in string  jointName,
in Transform_  position 
)
raises (Error
)

Set the static position of joint WRT its parent.

Parameters
positionconstant position of the joint
void hpp::corbaserver::Robot::setRootJointPosition ( in Transform_  position)
raises (Error
)

Set position of root joint in world frame.

Parameters
positionconstant position of the root joint in world frame in initial configuration.
floatSeq hpp::corbaserver::Robot::shootRandomConfig ( )
raises (Error
)

Shoot random configuration.

Returns
dofArray Array of degrees of freedom.