hpp::corbaserver::Robot Interface Reference

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

import "/local/robotpkg/var/tmp/robotpkg/path/hpp-corbaserver/work/hpp-corbaserver-3.1.0/idl/hpp/corbaserver/robot.idl";

List of all members.

Public Member Functions

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.
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.
Degrees of freedom
short getConfigSize () raises (Error)
 Get size of configuration.
short getNumberDof () raises (Error)
 Get size of velocity.
Joints
Names_t getJointNames () raises (Error)
 Get joint names in the same order as in the configuration.
Names_t getAllJointNames () raises (Error)
 Get all joint names including anchor joints.
floatSeq getComPosition () raises (Error)
 Get COM position.
Transform_ getJointPosition (in string jointName) raises (Error)
 Get joint position.
Transform_ getRootJointPosition () raises (Error)
 Get position of root joint in world frame.
void setRootJointPosition (in Transform_ position) raises (Error)
 Set position of root joint in world frame.
void setJointPosition (in string jointName, in Transform_ position) raises (Error)
 Set the static position of joint WRT its parent.
short getJointNumberDof (in string jointName) raises (Error)
 Get joint number degrees of freedom.
short getJointConfigSize (in string jointName) raises (Error)
 Get joint number config size.
void setJointBounds (in string jointName, in jointBoundSeq inJointBound) raises (Error)
 set a bound for the joint
Transform_ getLinkPosition (in string jointName) raises (Error)
 Get link position in world frame.
string getLinkName (in string jointName) raises (Error)
 Get link name.
Extra configuration space
void setDimensionExtraConfigSpace (in unsigned long dimension) raises (Error)
 Set dimension of the extra configuration space.
void setExtraConfigSpaceBounds (in jointBoundSeq bounds) raises (Error)
 Set bounds of extra configuration variables.
Configuration
floatSeq getCurrentConfig () raises (Error)
 Get current configuration.
floatSeq shootRandomConfig () raises (Error)
 Shoot random configuration.
void setCurrentConfig (in floatSeq dofArray) raises (Error)
 Set current configuration of specified robot,.
Bodies
Names_t getJointInnerObjects (in string jointName) raises (Error)
 Get the list of objects attached to a joint.
Names_t getJointOuterObjects (in string jointName) raises (Error)
 Get list of collision objects tested with the body attached to a joint.
void getObjectPosition (in string objectName, out Transform_ cfg) raises (Error)
 Get the position of an object of the robot.
Collision checking and distance computation
void collisionTest (out boolean validity) raises (Error)
 Test collision with obstacles and auto-collision.
void isConfigValid (in floatSeq dofArray, out boolean validity) raises (Error)
 Test the validity of a configuration.
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.
Mass and inertia
double getMass () raises (Error)
 Get mass of robot.
floatSeq getCenterOfMass () raises (Error)
 Get position of center of mass.
floatSeqSeq getJacobianCenterOfMass () raises (Error)
 Get Jacobian of the center of mass.
Create and register robot
void createRobot (in string robotName) raises (Error)
 Create an empty device and store it temporarily.
void createJoint (in string jointName, in string jointType, in Transform_ pos, in jointBoundSeq jointBounds) raises (Error)
 Create a new joint.
void addJoint (in string inParentName, in string inChildName) raises (Error)
 Add a child joint to a joint.
void setRobot (in string inRobotName) raises (Error)
 Add a robot to the ProblemSolver.
void setRobotRootJoint (in string inRobotName, in string inJointName) raises (Error)
 Set a joint as root joint to a robot.
void createPolyhedron (in string inPolyName) raises (Error)
 create an empty polyhedron.
void createBox (in string name, in double x, in double y, in double z) raises (Error)
 Create a box.
void createSphere (in string name, in double radius) raises (Error)
 Create a sphere.
short addPoint (in string inPolyName, in double x, in double y, in double z) raises (Error)
 Add a point to a polyhedron.
short addTriangle (in string inPolyName, in unsigned long pt1, in unsigned long pt2, in unsigned long pt3) raises (Error)
 Add a point to a polyhedron.
void addObjectToJoint (in string jointName, in string objectName, in Transform_ pos) raises (Error)
 Attach an object to a joint.
void addPartialCom (in string comName, in Names_t jointNames) raises (Error)
 Add an object to compute a partial COM of the robot.

Detailed Description

Creation of a device, joints and bodies.


Member Function Documentation

void hpp::corbaserver::Robot::addJoint ( in string  inParentName,
in string  inChildName 
) raises (Error)

Add a child joint to a joint.

Parameters:
inParentNamename of the joint to which a child is added.
inChildNamename of the child joint added to the previous one.
Exceptions:
Error.
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.
short 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
short 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::collisionTest ( out boolean  validity) raises (Error)

Test collision with obstacles and auto-collision.

Deprecated:
Use isConfigValid instead
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::createJoint ( in string  jointName,
in string  jointType,
in Transform_  pos,
in jointBoundSeq  jointBounds 
) raises (Error)

Create a new joint.

Parameters:
jointNamename of the joint,
jointTypeamong ["anchor", "SO3", "rotation", "translation"]
posinitial position of the joint
joinBoundsbounds of the joint. See setJointBounds for details.
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 and store it temporarily.

Parameters:
robotNamename of the robot. Fails if another robot is already in construction.
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::getComPosition ( ) raises (Error)

Get COM position.

Exceptions:
Errorif robot is not set
short 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::getJacobianCenterOfMass ( ) raises (Error)

Get Jacobian of the center of mass.

short 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.
short 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.
string hpp::corbaserver::Robot::getLinkName ( in string  jointName) raises (Error)

Get link name.

Parameters:
jointNamename of the joint,
Returns:
name of the link.
Transform_ hpp::corbaserver::Robot::getLinkPosition ( in string  jointName) 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.
double hpp::corbaserver::Robot::getMass ( ) raises (Error)

Get mass of robot.

short 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.
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.
void hpp::corbaserver::Robot::isConfigValid ( in floatSeq  dofArray,
out boolean  validity 
) 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
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::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::setCurrentConfig ( in floatSeq  dofArray) raises (Error)

Set current configuration of specified robot,.

Parameters:
dofArrayArray 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::model::ExtraConfigSpace
void hpp::corbaserver::Robot::setExtraConfigSpaceBounds ( in jointBoundSeq  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 jointBoundSeq  inJointBound 
) raises (Error)

set a bound for the 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::setJointPosition ( 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::setRobot ( in string  inRobotName) raises (Error)

Add a robot to the ProblemSolver.

Exceptions:
Error.
void hpp::corbaserver::Robot::setRobotRootJoint ( in string  inRobotName,
in string  inJointName 
) raises (Error)

Set a joint as root joint to a robot.

Parameters:
inRobotNamename of the robot (ChppDevice).
inJointNamename 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.