Creation of a device, joints and bodies. More...
import"/local/robotpkg/var/tmp/robotpkg/path/hpp-corbaserver/work/hpp-corbaserver-4.1/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... | |
Names_t | getChildJointNames (in string jointName) raises (Error) |
Get child joint names excluding anchor joints This method does not work on anchor joint. 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... | |
void | jointIntegrate (in string jointName, in floatSeq speed) raises (Error) |
Integrate velocity of a joint starting from robot configuration. More... | |
floatSeqSeq | getCurrentTransformation (in string jointName) raises (Error) |
Get joint Transformation. More... | |
Transform_ | getJointPosition (in string jointName) raises (Error) |
Get joint position. 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 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... | |
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... | |
Creation of a device, joints and bodies.
void hpp::corbaserver::Robot::addObjectToJoint | ( | in string | jointName, |
in string | objectName, | ||
in Transform_ | pos | ||
) | |||
raises | ( | Error | |
) |
Attach an object to a joint.
jointName | name of the body |
objectName | name of the object |
pos | relative 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.
name | of the partial com |
jointNames | names of each ROOT of the joint trees to consider. |
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.
inPolyName | the name of the polyhedron. |
x | coordinate of the point. |
y | coordinate of the point. |
z | coordinate of the point. |
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.
inPolyName | the name of the polyhedron. |
pt1 | rank of first point in polyhedron. |
pt2 | rank of second point in polyhedron. |
pt3 | rank of third point in polyhedron. |
void hpp::corbaserver::Robot::appendJoint | ( | in string | parentJoint, |
in string | jointName, | ||
in string | jointType, | ||
in Transform_ | pos | ||
) | |||
raises | ( | Error | |
) |
Check each auto-collision pair for collision and return the result.
collide | a 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.
innerObjects | names of the objects belonging to a body |
outerObjects | names of the objects tested with inner objects, |
active | vector 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.
name | name of the box |
x,y,z | Size of the box |
void hpp::corbaserver::Robot::createCylinder | ( | in string | name, |
in double | radius, | ||
in double | length | ||
) | |||
raises | ( | Error | |
) |
Create a cylinder.
name | name of the cylinder |
radius | radius of the cylinder |
length | length of the cylinder |
void hpp::corbaserver::Robot::createPolyhedron | ( | in string | inPolyName | ) | |
raises | ( | Error | |||
) |
create an empty polyhedron.
inPolyName | name of the polyhedron. |
Error. |
void hpp::corbaserver::Robot::createRobot | ( | in string | robotName | ) | |
raises | ( | Error | |||
) |
Create an empty device.
robotName | name of the robot. |
void hpp::corbaserver::Robot::createSphere | ( | in string | name, |
in double | radius | ||
) | |||
raises | ( | Error | |
) |
Create a sphere.
name | name of the sphere |
radius | radius 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.
distances | list of distances, |
innerObjects | names of the objects belonging to a body |
outerObjects | names of the objects tested with inner objects, |
innerPoints | closest points on the body, |
outerPoints | closest points on the obstacles |
Get all joint names including anchor joints.
Get position of center of mass.
Get velocity of center of mass.
Get child joint names excluding anchor joints This method does not work on anchor joint.
long hpp::corbaserver::Robot::getConfigSize | ( | ) | ||
raises | ( | Error | ||
) |
Get size of configuration.
Get current configuration.
floatSeqSeq hpp::corbaserver::Robot::getCurrentTransformation | ( | in string | jointName | ) | |
raises | ( | Error | |||
) |
Get joint Transformation.
jointName | name of the joint |
Error | if robot is not set or it joint does not exist. |
Get current velocity.
qDot | Array of degrees of freedom |
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.
Get bounds for a joint.
jointName | name of the joint |
Referenced by hpp.corbaserver.robot.Robot::getSaturated().
Get configuration of a joint in robot configuration.
jointName | name of the joint, |
long hpp::corbaserver::Robot::getJointConfigSize | ( | in string | jointName | ) | |
raises | ( | Error | |||
) |
Get joint number config size.
jointName | name of the joint |
Error | if robot is not set or if joint does not exist. |
Get the list of objects attached to a joint.
inJointName | name of the joint. |
Get joint names in the same order as in the configuration.
long hpp::corbaserver::Robot::getJointNumberDof | ( | in string | jointName | ) | |
raises | ( | Error | |||
) |
Get joint number degrees of freedom.
jointName | name of the joint |
Error | if robot is not set or if joint does not exist. |
Get list of collision objects tested with the body attached to a joint.
inJointName | name of the joint. |
Transform_ hpp::corbaserver::Robot::getJointPosition | ( | in string | jointName | ) | |
raises | ( | Error | |||
) |
Get joint position.
jointName | name of the joint |
Error | if 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)
jointName | name of the joint |
Error | if robot is not set or if joint does not exist. |
string hpp::corbaserver::Robot::getJointType | ( | in string | jointName | ) | |
raises | ( | Error | |||
) |
Get joint type.
jointName | name of the joint, |
Get joint types in the same order as in the configuration.
Get joint velocity expressed in the world frame, at the center of the world.
jointName | name of the joint |
Error | if 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.
jointName | name of the joint |
Error | if robot is not set or if joint does not exist. |
Get link names.
jointName | name of the joint, |
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.
jointName | name of the joint |
TransformSeq hpp::corbaserver::Robot::getLinksPosition | ( | in Names_t | linkName | ) | |
raises | ( | Error | |||
) |
Get position of a list of links in world frame.
double hpp::corbaserver::Robot::getMass | ( | ) | ||
raises | ( | Error | ||
) |
Get mass of robot.
long hpp::corbaserver::Robot::getNumberDof | ( | ) | ||
raises | ( | Error | ||
) |
Get 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.
objectName | name of the object. |
cfg | Position of the obstacle. |
Error. |
string hpp::corbaserver::Robot::getParentJointName | ( | in string | jointName | ) | |
raises | ( | Error | |||
) |
Get the parent joint of a joint jointName any joint (anchor or movable).
Get position of partial center of mass.
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.
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.
validity | whether configuration is valid |
report | the reason why the config is not valid. |
void hpp::corbaserver::Robot::jointIntegrate | ( | in string | jointName, |
in floatSeq | speed | ||
) | |||
raises | ( | Error | |
) |
Integrate velocity of a joint starting from robot configuration.
jointName | name of the joint, |
speed | velocity vector of the joint |
Size of speed should fit hpp::model::Joint::numberDof.
Modify the part of the robot current configuration correponding to the joint and recompute forward kinematics
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.
robotName | Name of the robot that is constructed, |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
packageName | Name of the ROS package containing the model, |
modelName | Name of the package containing the model |
urdfSuffix | suffix 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.
robotName | Name of the robot that is constructed, |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfString | urdf string, |
srdfString | srdf 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.
robotName | Name of the robot that is constructed, |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
packageName | Name of the ROS package containing the model, |
modelName | Name of the package containing the model |
urdfSuffix | suffix 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.
robotName | Name of the robot that is constructed, |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfString | urdf string, |
srdfString | srdf string. |
void hpp::corbaserver::Robot::setAutoCollision | ( | in string | innerObject, |
in string | outerObject, | ||
in boolean | active | ||
) | |||
raises | ( | Error | |
) |
Set current configuration of specified robot,.
dofArray | Array of degrees of freedom / |
Set current velocity.
qDot | Array of degrees of freedom |
void hpp::corbaserver::Robot::setDimensionExtraConfigSpace | ( | in unsigned long | dimension | ) | |
raises | ( | Error | |||
) |
Set dimension of the extra configuration space.
dimension | dimension |
Set bounds of extra configuration variables.
inJointBound | sequence of joint dof bounds in order [v0_min,v0_max,v1_min,v1_max,...].
|
void hpp::corbaserver::Robot::setJointBounds | ( | in string | jointName, |
in floatSeq | inJointBound | ||
) | |||
raises | ( | Error | |
) |
set bounds for a joint
jointName | name of the joint |
inJointBound | sequence of joint dof bounds in order [v0_min,v0_max,v1_min,v1_max,...].
|
void hpp::corbaserver::Robot::setJointConfig | ( | in string | jointName, |
in floatSeq | config | ||
) | |||
raises | ( | Error | |
) |
Set configuration of a joint in robot configuration.
jointName | name of the joint, |
config | Configuration of the joint. |
Size of config should fit hpp::model::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.
position | constant position of the joint |
void hpp::corbaserver::Robot::setRootJointPosition | ( | in Transform_ | position | ) | |
raises | ( | Error | |||
) |
Set position of root joint in world frame.
position | constant position of the root joint in world frame in initial configuration. |