hpp-corbaserver
4.9.0
Corba server for Humanoid Path Planner applications
|
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) |
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.
pinocchio_idl::CenterOfMassComputation hpp::corbaserver::Robot::getCenterOfMassComputation | ( | in string | name | ) | |
raises | ( | Error | |||
) |
Get velocity of center of mass.
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 |
unsigned long hpp::corbaserver::Robot::getDimensionExtraConfigSpace | ( | ) | ||
raises | ( | Error | ||
) |
Get the dimension of the extra configuration space
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 |
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. |
TransformSeq hpp::corbaserver::Robot::getJointsPosition | ( | in floatSeq | q, |
in Names_t | jointNames | ||
) | |||
raises | ( | Error | |
) |
Get position of a list of joints in world frame
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 floatSeq | q, |
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. |
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
jointCfg | a joint configuration |
jointName | name of the joint, |
speed | velocity vector of the joint |
saturate | the joint configuration within joint bounds. |
Size of speed should fit hpp::pinocchio::Joint::numberDof.
void hpp::corbaserver::Robot::loadHumanoidModel | ( | in string | robotName, |
in string | rootJointType, | ||
in string | urdfName, | ||
in string | srdfName | ||
) | |||
raises | ( | Error | |
) |
Load humanoid robot model
robotName | Name of the robot that is constructed, |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfName | name of the urdf file. It may contain "file://", or "package://" prefixes. |
srdfName | name of the srdf file. It may contain "file://", or "package://" prefixes. |
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 | urdfName, | ||
in string | srdfName | ||
) | |||
raises | ( | Error | |
) |
Load robot model
robotName | Name of the robot that is constructed, |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfName | name of the urdf file. It may contain "file://", or "package://" prefixes. |
srdfName | name of the srdf file. It may contain "file://", or "package://" prefixes. |
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::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
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. |
Shoot random configuration