hpp-corbaserver  4.9.0
Corba server for Humanoid Path Planner applications
hpp::corbaserver::Robot Interface Reference

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

import"/home/florent/devel/release/src/hpp-corbaserver/idl/hpp/corbaserver/robot.idl";

Public Member Functions

Loading URDF files
void loadRobotModel (in string robotName, in string rootJointType, in string urdfName, in string srdfName) raises (Error)
 
void loadHumanoidModel (in string robotName, in string rootJointType, in string urdfName, in string srdfName) raises (Error)
 
void loadRobotModelFromString (in string robotName, in string rootJointType, in string urdfString, in string srdfString) raises (Error)
 
void loadHumanoidModelFromString (in string robotName, in string rootJointType, in string urdfString, in string srdfString) raises (Error)
 
Degrees of freedom
long getConfigSize () raises (Error)
 
long getNumberDof () raises (Error)
 
Joints
Names_t getJointNames () raises (Error)
 
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)
 
floatSeq getJointConfig (in string jointName) raises (Error)
 
void setJointConfig (in string jointName, in floatSeq config) raises (Error)
 
string getJointType (in string jointName) raises (Error)
 
floatSeq jointIntegrate (in floatSeq jointCfg, in string jointName, in floatSeq speed, in boolean saturate) raises (Error)
 
floatSeqSeq getCurrentTransformation (in string jointName) raises (Error)
 
Transform_ getJointPosition (in string jointName) raises (Error)
 
TransformSeq getJointsPosition (in floatSeq q, in Names_t jointNames) raises (Error)
 
floatSeq getJointVelocity (in string jointName) raises (Error)
 
floatSeq getJointVelocityInLocalFrame (in string jointName) raises (Error)
 
Transform_ getJointPositionInParentFrame (in string jointName) raises (Error)
 
Transform_ getRootJointPosition () raises (Error)
 
void setRootJointPosition (in Transform_ position) raises (Error)
 
void setJointPositionInParentFrame (in string jointName, in Transform_ position) raises (Error)
 
long getJointNumberDof (in string jointName) raises (Error)
 
long getJointConfigSize (in string jointName) raises (Error)
 
void setJointBounds (in string jointName, in floatSeq inJointBound) raises (Error)
 set bounds for a joint More...
 
floatSeq getJointBounds (in string jointName) raises (Error)
 
Transform_ getLinkPosition (in string linkName) raises (Error)
 
TransformSeq getLinksPosition (in floatSeq q, in Names_t linkName) raises (Error)
 
Names_t getLinkNames (in string jointName) raises (Error)
 
Extra configuration space
void setDimensionExtraConfigSpace (in unsigned long dimension) raises (Error)
 
unsigned long getDimensionExtraConfigSpace () raises (Error)
 
void setExtraConfigSpaceBounds (in floatSeq bounds) raises (Error)
 
Configuration
floatSeq getCurrentConfig () raises (Error)
 
floatSeq shootRandomConfig () raises (Error)
 
void setCurrentConfig (in floatSeq dofArray) raises (Error)
 
floatSeq getCurrentVelocity () raises (Error)
 
void setCurrentVelocity (in floatSeq qDot) raises (Error)
 
Bodies
Names_t getJointInnerObjects (in string jointName) raises (Error)
 
Names_t getJointOuterObjects (in string jointName) raises (Error)
 
void getObjectPosition (in string objectName, out Transform_ cfg) raises (Error)
 
Collision checking and distance computation
void isConfigValid (in floatSeq dofArray, out boolean validity, out string report) raises (Error)
 
void distancesToCollision (out floatSeq distances, out Names_t innerObjects, out Names_t outerObjects, out floatSeqSeq innerPoints, out floatSeqSeq outerPoints) raises (Error)
 
void autocollisionCheck (out boolSeq collide) raises (Error)
 
void autocollisionPairs (out Names_t innerObjects, out Names_t outerObjects, out boolSeq active) raises (Error)
 
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)
 
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...
 
pinocchio_idl::CenterOfMassComputation getCenterOfMassComputation (in string name) raises (Error)
 
Create and register robot
void createRobot (in string robotName) raises (Error)
 
void appendJoint (in string parentJoint, in string jointName, in string jointType, in Transform_ pos) raises (Error)
 
void createPolyhedron (in string inPolyName) raises (Error)
 
void createBox (in string name, in double x, in double y, in double z) raises (Error)
 
void createSphere (in string name, in double radius) raises (Error)
 
void createCylinder (in string name, in double radius, in double length) raises (Error)
 
unsigned long addPoint (in string inPolyName, in double x, in double y, in double z) raises (Error)
 
unsigned long addTriangle (in string inPolyName, in unsigned long pt1, in unsigned long pt2, in unsigned long pt3) raises (Error)
 
void addObjectToJoint (in string jointName, in string objectName, in Transform_ pos) raises (Error)
 

Detailed Description

Creation of a device, joints and bodies.

Member Function Documentation

◆ addObjectToJoint()

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

◆ addPartialCom()

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.

◆ addPoint()

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

◆ addTriangle()

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

◆ appendJoint()

void hpp::corbaserver::Robot::appendJoint ( in string  parentJoint,
in string  jointName,
in string  jointType,
in Transform_  pos 
)
raises (Error
)

◆ autocollisionCheck()

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

◆ autocollisionPairs()

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

◆ createBox()

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

◆ createCylinder()

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

◆ createPolyhedron()

void hpp::corbaserver::Robot::createPolyhedron ( in string  inPolyName)
raises (Error
)

create an empty polyhedron.

Parameters
inPolyNamename of the polyhedron.
Exceptions
Error.

◆ createRobot()

void hpp::corbaserver::Robot::createRobot ( in string  robotName)
raises (Error
)

Create an empty device

Parameters
robotNamename of the robot.

◆ createSphere()

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

◆ distancesToCollision()

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.

◆ getAllJointNames()

Names_t hpp::corbaserver::Robot::getAllJointNames ( )
raises (Error
)

Get all joint names including anchor joints.

◆ getCenterOfMass()

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

Get position of center of mass.

◆ getCenterOfMassComputation()

pinocchio_idl::CenterOfMassComputation hpp::corbaserver::Robot::getCenterOfMassComputation ( in string  name)
raises (Error
)

◆ getCenterOfMassVelocity()

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

Get velocity of center of mass.

◆ getConfigSize()

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

Get size of configuration

Returns
size of configuration

◆ getCurrentConfig()

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

Get current configuration

Returns
dofArray Array of degrees of freedom.

◆ getCurrentTransformation()

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.

◆ getCurrentVelocity()

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

Get current velocity

Parameters
qDotArray of degrees of freedom

◆ getDimensionExtraConfigSpace()

unsigned long hpp::corbaserver::Robot::getDimensionExtraConfigSpace ( )
raises (Error
)

Get the dimension of the extra configuration space

See also
hpp::pinocchio::ExtraConfigSpace

◆ getJacobianCenterOfMass()

floatSeqSeq hpp::corbaserver::Robot::getJacobianCenterOfMass ( )
raises (Error
)

Get Jacobian of the center of mass.

◆ getJacobianPartialCom()

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

Get Jacobian of the partial center of mass.

◆ getJointBounds()

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.

◆ getJointConfig()

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.

◆ getJointConfigSize()

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.

◆ getJointInnerObjects()

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.

◆ getJointNames()

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.

◆ getJointNumberDof()

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.

◆ getJointOuterObjects()

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

◆ getJointPosition()

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.

◆ getJointPositionInParentFrame()

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.

◆ getJointsPosition()

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

◆ getJointType()

string hpp::corbaserver::Robot::getJointType ( in string  jointName)
raises (Error
)

Get joint type.

Parameters
jointNamename of the joint,

◆ getJointTypes()

Names_t hpp::corbaserver::Robot::getJointTypes ( )
raises (Error
)

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

◆ getJointVelocity()

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.

◆ getJointVelocityInLocalFrame()

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.

◆ getLinkNames()

Names_t hpp::corbaserver::Robot::getLinkNames ( in string  jointName)
raises (Error
)

Get link names

Parameters
jointNamename of the joint,
Returns
names of the links.

◆ getLinkPosition()

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.

◆ getLinksPosition()

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

◆ getMass()

double hpp::corbaserver::Robot::getMass ( )
raises (Error
)

Get mass of robot.

◆ getNumberDof()

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

Get size of velocity

Returns
size of velocity

◆ getObjectPosition()

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.

◆ getParentJointName()

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)

◆ getPartialCom()

floatSeq hpp::corbaserver::Robot::getPartialCom ( in string  comName)
raises (Error
)

Get position of partial center of mass.

◆ getRobotAABB()

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

Get the aligned axes bounding box around the robot.

◆ getRobotName()

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

Get the name of the current robot.

◆ getRootJointPosition()

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.

◆ getVelocityPartialCom()

floatSeq hpp::corbaserver::Robot::getVelocityPartialCom ( in string  comName)
raises (Error
)

Get the velocity of the partial center of mass.

◆ isConfigValid()

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.

◆ jointIntegrate()

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.

◆ loadHumanoidModel()

void hpp::corbaserver::Robot::loadHumanoidModel ( in string  robotName,
in string  rootJointType,
in string  urdfName,
in string  srdfName 
)
raises (Error
)

Load humanoid robot model

Parameters
robotNameName of the robot that is constructed,
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
urdfNamename of the urdf file. It may contain "file://", or "package://" prefixes.
srdfNamename of the srdf file. It may contain "file://", or "package://" prefixes.

◆ loadHumanoidModelFromString()

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.

◆ loadRobotModel()

void hpp::corbaserver::Robot::loadRobotModel ( in string  robotName,
in string  rootJointType,
in string  urdfName,
in string  srdfName 
)
raises (Error
)

Load robot model

Parameters
robotNameName of the robot that is constructed,
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
urdfNamename of the urdf file. It may contain "file://", or "package://" prefixes.
srdfNamename of the srdf file. It may contain "file://", or "package://" prefixes.

◆ loadRobotModelFromString()

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.

◆ setAutoCollision()

void hpp::corbaserver::Robot::setAutoCollision ( in string  innerObject,
in string  outerObject,
in boolean  active 
)
raises (Error
)

◆ setCurrentConfig()

void hpp::corbaserver::Robot::setCurrentConfig ( in floatSeq  dofArray)
raises (Error
)

Set current configuration of specified robot,

Parameters
dofArrayArray of degrees of freedom /

◆ setCurrentVelocity()

void hpp::corbaserver::Robot::setCurrentVelocity ( in floatSeq  qDot)
raises (Error
)

Set current velocity

Parameters
qDotArray of degrees of freedom

◆ setDimensionExtraConfigSpace()

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

◆ setExtraConfigSpaceBounds()

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.

◆ setJointBounds()

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

◆ setJointConfig()

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

◆ setJointPositionInParentFrame()

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

◆ setRootJointPosition()

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.

◆ shootRandomConfig()

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

Shoot random configuration

Returns
dofArray Array of degrees of freedom.

The documentation for this interface was generated from the following file: