hpp-rbprm-corba  4.10.0
Corba server for reachability based planning
hpp::corbaserver::rbprm::RbprmBuilder Interface Reference

import"/local/robotpkg/var/tmp/robotpkg/wip/py-hpp-rbprm-corba/work/hpp-rbprm-corba-4.10.0/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl";

Public Member Functions

void loadRobotRomModel (in string robotName, in string rootJointType, in string urdfName) raises (Error)
 
void loadRobotCompleteModel (in string robotName, in string rootJointType, in string urdfName, in string srdfName) raises (Error)
 Create a RbprmDevice for the root of the robot. More...
 
void loadFullBodyRobot (in string robotName, in string rootJointType, in string urdfName, in string srdfName, in string selectedProblem) raises (Error)
 
void loadFullBodyRobotFromExistingRobot () raises (Error)
 
void selectFullBody (in string name) raises (Error)
 
void setStaticStability (in boolean staticStability) raises (Error)
 
void setReferenceConfig (in floatSeq referenceConfig) raises (Error)
 set a reference configuration in fullBody More...
 
void setPostureWeights (in floatSeq postureWeights) raises (Error)
 set the weights used when computing a postural task More...
 
void usePosturalTaskContactCreation (in boolean use) raises (Error)
 If true, optimize the orientation of all the newly created contact using a postural task. More...
 
void setReferenceEndEffector (in string romName, in floatSeq ref) raises (Error)
 set a reference position of the end effector for the given ROM More...
 
void setFilter (in Names_t roms) raises (Error)
 
void initNewProblemSolver () raises (Error)
 
void setAffordanceFilter (in string romName, in Names_t affordances) raises (Error)
 
void boundSO3 (in floatSeq limitszyx) raises (Error)
 
double projectStateToCOM (in unsigned short stateId, in floatSeq com, in unsigned short max_num_sample) raises (Error)
 
short cloneState (in unsigned short stateId) raises (Error)
 
double projectStateToRoot (in unsigned short stateId, in floatSeq root, in floatSeq offset) raises (Error)
 
double setConfigAtState (in unsigned short stateId, in floatSeq config) raises (Error)
 
short createState (in floatSeq configuration, in Names_t contactLimbs) raises (Error)
 
floatSeq getSampleConfig (in string sampleName, in unsigned long sampleId) raises (Error)
 
floatSeq getSamplePosition (in string sampleName, in unsigned long sampleId) raises (Error)
 
floatSeqSeq getEffectorPosition (in string limbName, in floatSeq dofArray) raises (Error)
 
unsigned short getNumSamples (in string limbName) raises (Error)
 
floatSeq getOctreeNodeIds (in string limbName) raises (Error)
 
double getSampleValue (in string limbName, in string valueName, in unsigned long sampleId) raises (Error)
 
double getEffectorDistance (in unsigned short state1, in unsigned short state2) raises (Error)
 
floatSeq generateContacts (in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration, in double robustnessThreshold) raises (Error)
 
short generateStateInContact (in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration, in double robustnessThreshold) raises (Error)
 
floatSeq generateGroundContact (in Names_t contactLimbs) raises (Error)
 
floatSeq getContactSamplesIds (in string name, in floatSeq dofArray, in floatSeq direction) raises (Error)
 
floatSeqSeq getContactSamplesProjected (in string name, in floatSeq dofArray, in floatSeq direction, in unsigned short numSamples) raises (Error)
 
short generateContactState (in unsigned short currentState, in string name, in floatSeq direction) raises (Error)
 
floatSeq getSamplesIdsInOctreeNode (in string name, in double octreeNodeId) raises (Error)
 
void addLimb (in string id, in string limb, in string effector, in floatSeq offset, in floatSeq normal, in double x, in double y, in unsigned long samples, in string heuristicName, in double resolution, in string contactType, in double disableEffectorCollision, in double grasp, in floatSeq limbOffset, in string kinematicConstraintsPath, in double kinematicConstraintsMin) raises (Error)
 
void addNonContactingLimb (in string id, in string limb, in string effector, in unsigned long samples) raises (Error)
 
void addLimbDatabase (in string databasepath, in string id, in string heuristicName, in double loadValues, in double disableEffectorCollision, in double grasp) raises (Error)
 
void setStartState (in floatSeq dofArray, in Names_t contactLimbs) raises (Error)
 
void setStartStateId (in unsigned short stateId) raises (Error)
 
void setEndStateId (in unsigned short stateId) raises (Error)
 
floatSeq computeContactForConfig (in floatSeq dofArray, in string limbName) raises (Error)
 
void setEndState (in floatSeq dofArray, in Names_t contactLimbs) raises (Error)
 
floatSeqSeq computeContactPoints (in unsigned short stateId) raises (Error)
 
floatSeqSeq computeContactPointsForLimb (in unsigned short stateId, in string limbname) raises (Error)
 
floatSeqSeq computeContactPointsAtStateForLimb (in unsigned short stateId, in unsigned short isIntermediate, in string limbname) raises (Error)
 
floatSeqSeq computeCenterOfContactAtStateForLimb (in unsigned short cId, in unsigned short isIntermediate, in string limbName) raises (Error)
 
floatSeqSeq computeContactPointsAtState (in unsigned short stateId, in unsigned short isIntermediate) raises (Error)
 
floatSeqSeq interpolate (in double timestep, in double path, in double robustnessTreshold, in unsigned short filterStates, in boolean testReachability, in boolean quasiStatic, in boolean erasePreviousStates) raises (Error)
 
floatSeqSeq interpolateConfigs (in floatSeqSeq configs, in double robustnessTreshold, in unsigned short filterStates, in boolean testReachability, in boolean quasiStatic, in boolean erasePreviousStates) raises (Error)
 
floatSeqSeq getContactCone (in unsigned short stateId, in double friction) raises (Error)
 
floatSeqSeq getContactIntermediateCone (in unsigned short stateId, in double friction) raises (Error)
 
short generateRootPath (in floatSeqSeq rootPositions, in floatSeq q1, in floatSeq q2) raises (Error)
 
short generateComTraj (in floatSeqSeq positions, in floatSeqSeq velocities, in floatSeqSeq accelerations, in double dt) raises (Error)
 
short straightPath (in floatSeqSeq positions) raises (Error)
 
short generateCurveTraj (in floatSeqSeq coefficients) raises (Error)
 
short generateCurveTrajParts (in floatSeqSeq coefficients, in floatSeq partitions) raises (Error)
 
short limbRRT (in unsigned short state1, in unsigned short state2, in unsigned short numOptimizations) raises (Error)
 
short limbRRTFromRootPath (in unsigned short state1, in unsigned short state2, in unsigned short path, in unsigned short numOptimizations) raises (Error)
 
short configToPath (in floatSeqSeq configs) raises (Error)
 
short comRRT (in unsigned short state1, in unsigned short state2, in unsigned short comPath, in unsigned short numOptimizations) raises (Error)
 
floatSeq comRRTFromPos (in unsigned short state1, in unsigned short comTraj1, in unsigned short comTraj2, in unsigned short comTraj3, in unsigned short numOptimizations) raises (Error)
 
floatSeq comRRTFromPosBetweenState (in unsigned short state1, in unsigned short state2, in unsigned short comTraj1, in unsigned short comTraj2, in unsigned short comTraj3, in unsigned short numOptimizations) raises (Error)
 
floatSeq effectorRRTFromPosBetweenState (in unsigned short state1, in unsigned short state2, in unsigned short comTraj1, in unsigned short comTraj2, in unsigned short comTraj3, in unsigned short numOptimizations) raises (Error)
 
floatSeq effectorRRT (in unsigned short state1, in unsigned short comTraj1, in unsigned short comTraj2, in unsigned short comTraj3, in unsigned short numOptimizations) raises (Error)
 
floatSeq effectorRRTOnePhase (in unsigned short state1, in unsigned short state2, in unsigned short comTraj, in unsigned short numOptimizations) raises (Error)
 
floatSeqSeq generateEffectorBezierArray (in unsigned short state1, in unsigned short state2, in unsigned short comTraj, in unsigned short numOptimizations) raises (Error)
 
floatSeq comRRTOnePhase (in unsigned short state1, in unsigned short state2, in unsigned short comTraj, in unsigned short numOptimizations) raises (Error)
 
floatSeq effectorRRTFromPath (in unsigned short state1, in unsigned short refPath, in double path_from, in double path_to, in unsigned short comTraj1, in unsigned short comTraj2, in unsigned short comTraj3, in unsigned short numOptimizations, in Names_t trackedEffectors) raises (Error)
 
short generateEndEffectorBezier (in unsigned short state1, in unsigned short state2, in unsigned short comTraj) raises (Error)
 
floatSeq projectToCom (in unsigned short state, in floatSeq targetCom, in unsigned short max_num_sample) raises (Error)
 
floatSeq getConfigAtState (in unsigned short state) raises (Error)
 
short isLimbInContact (in string limbname, in unsigned short state1) raises (Error)
 
short isLimbInContactIntermediary (in string limbname, in unsigned short state1) raises (Error)
 
short computeIntermediary (in unsigned short state1, in unsigned short state2) raises (Error)
 
short getNumStates () raises (Error)
 
void saveComputedStates (in string filename) raises (Error)
 
void saveLimbDatabase (in string limbname, in string filename) raises (Error)
 
floatSeqSeq getOctreeBoxes (in string limbname, in floatSeq dofArray) raises (Error)
 
floatSeq getOctreeBox (in string limbname, in double sampleId) raises (Error)
 
floatSeq getOctreeTransform (in string limbname, in floatSeq dofArray) raises (Error)
 
double isStateBalanced (in unsigned short state) raises (Error)
 
short isConfigBalanced (in floatSeq config, in Names_t contacts, in double robustnessTreshold, in floatSeq CoM) raises (Error)
 
void runSampleAnalysis (in string analysis, in double isstatic) raises (Error)
 
floatSeq runLimbSampleAnalysis (in string limbname, in string analysis, in double isstatic) raises (Error)
 
floatSeq evaluateConfig (in floatSeq configuration, in floatSeq direction) raises (Error)
 
void dumpProfile (in string logFile) raises (Error)
 
double getTimeAtState (in unsigned short stateId) raises (Error)
 
Names_t getContactsVariations (in unsigned short stateIdFrom, in unsigned short stateIdTo) raises (Error)
 
Names_t getCollidingObstacleAtConfig (in floatSeq configuration, in string limbName) raises (Error)
 
floatSeqSeq getContactSurfacesAtConfig (in floatSeq configuration, in string limbName) raises (Error)
 
Names_t getAllLimbsNames () raises (Error)
 return a list of all the limbs names More...
 
short addNewContact (in unsigned short stateId, in string limbName, in floatSeq position, in floatSeq normal, in unsigned short max_num_sample, in boolean lockOtherJoints, in floatSeq rotation) raises (Error)
 
short removeContact (in unsigned short stateId, in string limbName) raises (Error)
 
floatSeq computeTargetTransform (in string limbname, in floatSeq configuration, in floatSeq p, in floatSeq n) raises (Error)
 
Names_t getEffectorsTrajectoriesNames (in unsigned short pathId) raises (Error)
 
floatSeqSeqSeq getEffectorTrajectoryWaypoints (in unsigned short pathId, in string effectorName) raises (Error)
 
floatSeqSeq getPathAsBezier (in unsigned short pathId) raises (Error)
 
boolean toggleNonContactingLimb (in string limbname) raises (Error)
 
boolean areKinematicsConstraintsVerified (in floatSeq point) raises (Error)
 
boolean areKinematicsConstraintsVerifiedForState (in unsigned short stateFrom, in floatSeq point) raises (Error)
 
floatSeq isReachableFromState (in unsigned short stateFrom, in unsigned short stateTo, in boolean useIntermediateState) raises (Error)
 
floatSeq isDynamicallyReachableFromState (in unsigned short stateFrom, in unsigned short stateTo, in boolean addPathPerPhase, in floatSeq timings, in short numPointsPerPhase) raises (Error)
 

Member Function Documentation

◆ addLimb()

void hpp::corbaserver::rbprm::RbprmBuilder::addLimb ( in string  id,
in string  limb,
in string  effector,
in floatSeq  offset,
in floatSeq  normal,
in double  x,
in double  y,
in unsigned long  samples,
in string  heuristicName,
in double  resolution,
in string  contactType,
in double  disableEffectorCollision,
in double  grasp,
in floatSeq  limbOffset,
in string  kinematicConstraintsPath,
in double  kinematicConstraintsMin 
)
raises (Error
)

A limb must consist in a simple kinematic chain, where every node has only one child

Parameters
iduser given name of the new limb
limbrobot joint corresponding to the root of the limb (ex a shoulder or ankle joint)
effectorrobot joint corresponding to the effector of the limb (ex a hand or foot joint)
offsetcontact point of the effector, expressed as an offset from the joint root
normalnormal vector to consider for contact creation. For instance for a foot, typically normal is aligned with the -z vertical axis, to create a contact with the plant of the robot
xhalf width of the rectangle surface contact of the effector
yhalf length of the rectangle surface contact of the effector
samplesnumber of samples to generate for the limb (a typical value is 10000)
heuristicNameheuristic used to bias sample selection
resolutionresolution of the octree used to store the samples (a typical value is 0.01 meters)
contactTypewhether the contact is punctual ("_3_DOF") or surfacic ("_6_DOF")
disableEffectorCollisionwhether collision detection should be disabled for the end effector bones
limbOffsetthe offset between the limb joint and it's link

◆ addLimbDatabase()

void hpp::corbaserver::rbprm::RbprmBuilder::addLimbDatabase ( in string  databasepath,
in string  id,
in string  heuristicName,
in double  loadValues,
in double  disableEffectorCollision,
in double  grasp 
)
raises (Error
)

Specifies a subchain of the robot as a limb, which can be used to create contacts. A limb must consist in a simple kinematic chain, where every node has only one child

Parameters
databasepathfilepath to the database
iduser given name of the new limb
heuristicNameheuristic used to bias sample selection
loadValueswhether other values computed for the limb database should be loaded
disableEffectorCollisionwhether collision detection should be disabled for the end effector bones

◆ addNewContact()

short hpp::corbaserver::rbprm::RbprmBuilder::addNewContact ( in unsigned short  stateId,
in string  limbName,
in floatSeq  position,
in floatSeq  normal,
in unsigned short  max_num_sample,
in boolean  lockOtherJoints,
in floatSeq  rotation 
)
raises (Error
)

tries to add a new contact to the state if the limb is already in contact, replace the previous contact. Only considers kinematic limitations. collision and equilibrium are NOT considered.

Parameters
stateState considered
limbNamename of the considered limb to create contact with
p3d position of the point
n3d normal of the contact location center
max_num_samplenumber of times it will try to randomly sample a configuration before failing
lockOtherJoints: if True, the values of all the joints exepct the ones of 'limbName' are constrained to be constant. This only affect the first projection, if max_num_sample > 0 and the first projection was unsuccessfull, the parameter is ignored
rotation: desired rotation of the end-effector in contact, expressed as Quaternion (x,y,z,w). If different from zero, the normal is ignored. Otherwise the rotation is automatically computed from the normal (with one axis of freedom)
Returns
(success,NState) whether the creation was successful, as well as the new state

◆ addNonContactingLimb()

void hpp::corbaserver::rbprm::RbprmBuilder::addNonContactingLimb ( in string  id,
in string  limb,
in string  effector,
in unsigned long  samples 
)
raises (Error
)

Add a limb not used for contact generation

Parameters
iduser given name of the new limb
limbrobot joint corresponding to the root of the limb (ex a shoulder or ankle joint)
effectorrobot joint corresponding to the effector of the limb (ex a hand or foot joint)
samplesnumber of samples to generate for the limb (a typical value is 10000)

◆ areKinematicsConstraintsVerified()

boolean hpp::corbaserver::rbprm::RbprmBuilder::areKinematicsConstraintsVerified ( in floatSeq  point)
raises (Error
)

◆ areKinematicsConstraintsVerifiedForState()

boolean hpp::corbaserver::rbprm::RbprmBuilder::areKinematicsConstraintsVerifiedForState ( in unsigned short  stateFrom,
in floatSeq  point 
)
raises (Error
)

◆ boundSO3()

void hpp::corbaserver::rbprm::RbprmBuilder::boundSO3 ( in floatSeq  limitszyx)
raises (Error
)

Sets limits on robot orientation, described according to Euler's ZYX rotation order

Parameters
limitszyx6D vector with the lower and upperBound for each rotation axis in sequence expressed in gradients [z_inf, z_sup, y_inf, y_sup, x_inf, x_sup]

◆ cloneState()

short hpp::corbaserver::rbprm::RbprmBuilder::cloneState ( in unsigned short  stateId)
raises (Error
)

Clone a state

Parameters
stateIdtarget state
Returns
stateId of the cloned state

◆ computeCenterOfContactAtStateForLimb()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::computeCenterOfContactAtStateForLimb ( in unsigned short  cId,
in unsigned short  isIntermediate,
in string  limbName 
)
raises (Error
)

Provided a discrete contact sequence has already been computed, computes the position of the contact center and the normal

Parameters
stateIdnormalized step for generation along the path (ie the path has a length of 1).
Returns
2 3D vector : the first is the position the second is the normal

◆ computeContactForConfig()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::computeContactForConfig ( in floatSeq  dofArray,
in string  limbName 
)
raises (Error
)

Compute effector contact points and normals for a given configuration in local coordinates

Parameters
dofArrayconfiguration of the robot
limbNameids of the limb in contact

◆ computeContactPoints()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::computeContactPoints ( in unsigned short  stateId)
raises (Error
)

Provided a discrete contact sequence has already been computed, computes all the contact positions and normals for a given state, the next one, and the intermediate between them.

Parameters
stateIdnormalized step for generation along the path (ie the path has a length of 1).
Returns
list of 2 or 3 lists of 6d vectors [pox, poy, posz, nprmalx, normaly, normalz]

◆ computeContactPointsAtState()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::computeContactPointsAtState ( in unsigned short  stateId,
in unsigned short  isIntermediate 
)
raises (Error
)

Provided a discrete contact sequence has already been computed, computes all the contact positions and normals for a given state

Parameters
stateIdiD of the considered state
isIntermediatewhether the intermediate state should be considerred rather than this one
Returns
list of 6d vectors [pox, poy, posz, nprmalx, normaly, normalz]

◆ computeContactPointsAtStateForLimb()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::computeContactPointsAtStateForLimb ( in unsigned short  stateId,
in unsigned short  isIntermediate,
in string  limbname 
)
raises (Error
)

Provided a discrete contact sequence has already been computed, computes all the contact positions and normals for a given state

Parameters
stateIdnormalized step for generation along the path (ie the path has a length of 1).
Returns
list of 6d vectors [pox, poy, posz, nprmalx, normaly, normalz]

◆ computeContactPointsForLimb()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::computeContactPointsForLimb ( in unsigned short  stateId,
in string  limbname 
)
raises (Error
)

Provided a discrete contact sequence has already been computed, computes all the contact positions and normals for a given state, the next one, and the intermediate between them.

Parameters
stateIdnormalized step for generation along the path (ie the path has a length of 1).
Returns
list of 2 or 3 lists of 6d vectors [pox, poy, posz, nprmalx, normaly, normalz]

◆ computeIntermediary()

short hpp::corbaserver::rbprm::RbprmBuilder::computeIntermediary ( in unsigned short  state1,
in unsigned short  state2 
)
raises (Error
)

Generate intermediary state

Parameters
state1initial state considered
state2target state considered
Returns
whether the limb is in contact at this state

◆ computeTargetTransform()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::computeTargetTransform ( in string  limbname,
in floatSeq  configuration,
in floatSeq  p,
in floatSeq  n 
)
raises (Error
)

Computes the closest projection matrix that will bring a limb's effector from its current configuration to a specified location

Parameters
limbnamename of the considered limb
configurationconsidered configuration of the robot
ptarget position
ntarget normal
Returns
7D Transform of effector in contact (position + quaternion)

◆ comRRT()

short hpp::corbaserver::rbprm::RbprmBuilder::comRRT ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  comPath,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. The states do not need to be consecutive, but increasing in Id. Will fail if the index of the states do not exist The path of the COM of thr robot and limbs not considered by the contact transitions between two states is assumed to be already computed, and registered in the solver under the id specified by the user. It must be valid in the sense of the active PathValidation.

Parameters
state1index of first state.
state2index of second state.
comPathindex of the path considered of the com path
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ comRRTFromPos()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::comRRTFromPos ( in unsigned short  state1,
in unsigned short  comTraj1,
in unsigned short  comTraj2,
in unsigned short  comTraj3,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. The states do need to be consecutive. Will fail if the index of the states do not exist The path of the COM of thr robot and limbs not considered by the contact transitions between two states is assumed to be already computed, and registered in the solver under the id specified by the user. It must be valid in the sense of the active PathValidation.

Parameters
state1index of first state.
rootPositions1com positions to track for 1st phase
rootPositions1com positions to track for 2nd phase
rootPositions1com positions to track for 3rd phase
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ comRRTFromPosBetweenState()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::comRRTFromPosBetweenState ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  comTraj1,
in unsigned short  comTraj2,
in unsigned short  comTraj3,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between three indicated states. The states do not need to be consecutive. Will fail if the index of the states do not exist The path of the COM of thr robot and limbs not considered by the contact transitions between two states is assumed to be already computed, and registered in the solver under the id specified by the user. It must be valid in the sense of the active PathValidation.

Parameters
state1index of first state.
state2index of end state.
rootPositions1com positions to track for 1st phase
rootPositions1com positions to track for 2nd phase
rootPositions1com positions to track for 3rd phase
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ comRRTOnePhase()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::comRRTOnePhase ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  comTraj,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. The states need to be consecutive with no contact variation between them (the free limbs can move, but there should be no contact creation/break)

Parameters
state1index of the first state
state2index of the second state
rootPositions1com positions to track
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ configToPath()

short hpp::corbaserver::rbprm::RbprmBuilder::configToPath ( in floatSeqSeq  configs)
raises (Error
)

Linear interpolation of many configurations into a path

Parameters
configslist of configurations
Returns
id of the root path computed

◆ createState()

short hpp::corbaserver::rbprm::RbprmBuilder::createState ( in floatSeq  configuration,
in Names_t  contactLimbs 
)
raises (Error
)

Create a state and push it to the state array

Parameters
qconfiguration
nameslist of effectors in contact
Returns
stateId

◆ dumpProfile()

void hpp::corbaserver::rbprm::RbprmBuilder::dumpProfile ( in string  logFile)
raises (Error
)

if the preprocessor variable PROFILE is active dump the profiling data into a logFile

Parameters
logFilename of the file where to dump the profiling data

◆ effectorRRT()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::effectorRRT ( in unsigned short  state1,
in unsigned short  comTraj1,
in unsigned short  comTraj2,
in unsigned short  comTraj3,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. The states do not need to be consecutive, but increasing in Id. Will fail if the index of the states do not exist The path of the COM of thr robot and limbs not considered by the contact transitions between two states is assumed to be already computed, and registered in the solver under the id specified by the user. It must be valid in the sense of the active PathValidation.

Parameters
state1index of first state.
rootPositions1com positions to track for 1st phase
rootPositions1com positions to track for 2nd phase
rootPositions1com positions to track for 3rd phase
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ effectorRRTFromPath()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::effectorRRTFromPath ( in unsigned short  state1,
in unsigned short  refPath,
in double  path_from,
in double  path_to,
in unsigned short  comTraj1,
in unsigned short  comTraj2,
in unsigned short  comTraj3,
in unsigned short  numOptimizations,
in Names_t  trackedEffectors 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. The states do not need to be consecutive, but increasing in Id. Will fail if the index of the states do not exist The path of the COM of thr robot and limbs not considered by the contact transitions between two states is assumed to be already computed, and registered in the solver under the id specified by the user. It must be valid in the sense of the active PathValidation.

Parameters
state1index of first state.
rootPositions1com positions to track for 1st phase
rootPositions1com positions to track for 2nd phase
rootPositions1com positions to track for 3rd phase
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ effectorRRTFromPosBetweenState()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::effectorRRTFromPosBetweenState ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  comTraj1,
in unsigned short  comTraj2,
in unsigned short  comTraj3,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between three indicated states. The states do not need to be consecutive. Will fail if the index of the states do not exist The path of the COM of thr robot and limbs not considered by the contact transitions between two states is assumed to be already computed, and registered in the solver under the id specified by the user. It must be valid in the sense of the active PathValidation.

Parameters
state1index of first state.
state2index of end state.
rootPositions1com positions to track for 1st phase
rootPositions1com positions to track for 2nd phase
rootPositions1com positions to track for 3rd phase
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ effectorRRTOnePhase()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::effectorRRTOnePhase ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  comTraj,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. The states need to be consecutive with no contact variation between them (the free limbs can move, but there should be no contact creation/break)

Parameters
state1index of the first state
state2index of the second state
rootPositions1com positions to track
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ evaluateConfig()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::evaluateConfig ( in floatSeq  configuration,
in floatSeq  direction 
)
raises (Error
)

◆ generateComTraj()

short hpp::corbaserver::rbprm::RbprmBuilder::generateComTraj ( in floatSeqSeq  positions,
in floatSeqSeq  velocities,
in floatSeqSeq  accelerations,
in double  dt 
)
raises (Error
)

Create a com trajectory given list of positions, velocities and accelerations accelerations list contains one less element because it does not have an initial state. a set of 3d key points The path is composed of n+1 integrations between the n positions. The resulting path is added to the problem solver

Parameters
positionsarray of positions
velocitiesarray of velocities
accelerationsarray of accelerations
dttime between two points
Returns
id of the root path computed

◆ generateContacts()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::generateContacts ( in floatSeq  dofArray,
in floatSeq  direction,
in floatSeq  acceleration,
in double  robustnessThreshold 
)
raises (Error
)

Generate all possible contact in a given configuration

Parameters
dofArrayinitial configuration of the robot
directiondesired direction of motion for the robot
Returns
transformed configuration for which all possible contacts have been created

◆ generateContactState()

short hpp::corbaserver::rbprm::RbprmBuilder::generateContactState ( in unsigned short  currentState,
in string  name,
in floatSeq  direction 
)
raises (Error
)

Given a contact state and a limb, tries to generate a new contact, and returns the id of the new State if successful

Parameters
currentStateId of the considered state
namename of the limb used to create a contact
directiondesired direction of motion for the robot
Returns
id of the new contact state if successful, -1 otherwise

◆ generateCurveTraj()

short hpp::corbaserver::rbprm::RbprmBuilder::generateCurveTraj ( in floatSeqSeq  coefficients)
raises (Error
)

Create a trajectory corresponding to a bezier curve. The coefficients give the order of the spline

Parameters
coefficientsarray of positions
Returns
id of the path computed

◆ generateCurveTrajParts()

short hpp::corbaserver::rbprm::RbprmBuilder::generateCurveTrajParts ( in floatSeqSeq  coefficients,
in floatSeq  partitions 
)
raises (Error
)

Create a trajectory corresponding to a bezier curve. The coefficients give the order of the spline

Parameters
coefficientsarray of positions
partitionsarray of positions
Returns
id of the path computed

◆ generateEffectorBezierArray()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::generateEffectorBezierArray ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  comTraj,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate an array of bezier curves, with varying weightRRT (see effector-rrt.cc::fitBezier)

Parameters
state1index of the first state
state2index of the second state
rootPositions1com positions to track
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ generateEndEffectorBezier()

short hpp::corbaserver::rbprm::RbprmBuilder::generateEndEffectorBezier ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  comTraj 
)
raises (Error
)

compute and add a trajectory for the end effector between the 2 states represented as a bezier curve. Do not check the kinematic feasability of this trajectory

Parameters
state1index of first state.
state2index of end state.
rootPositionscom positions to track

◆ generateGroundContact()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::generateGroundContact ( in Names_t  contactLimbs)
raises (Error
)

Generate an autocollision free configuration with limbs in contact with the ground

Parameters
contactLimbsname of the limbs to project in contact
Returns
a sampled contact configuration

◆ generateRootPath()

short hpp::corbaserver::rbprm::RbprmBuilder::generateRootPath ( in floatSeqSeq  rootPositions,
in floatSeq  q1,
in floatSeq  q2 
)
raises (Error
)

Create a path for the root given a set of 3d key points The path is composed of n+1 linear interpolations between the n positions. The rotation is linearly interpolated as well, between a start and a goal rotation. The resulting path is added to the problem solver

Parameters
positionsarray of positions
q1quaternion of 1st rotation
q2quaternion of 2nd rotation
Returns
id of the root path computed

◆ generateStateInContact()

short hpp::corbaserver::rbprm::RbprmBuilder::generateStateInContact ( in floatSeq  dofArray,
in floatSeq  direction,
in floatSeq  acceleration,
in double  robustnessThreshold 
)
raises (Error
)

Generate all possible contact in a given configuration and add the state in fullBody

Parameters
dofArrayinitial configuration of the robot
directiondesired direction of motion for the robot
Returns
the Id of the new state

◆ getAllLimbsNames()

Names_t hpp::corbaserver::rbprm::RbprmBuilder::getAllLimbsNames ( )
raises (Error
)

return a list of all the limbs names

◆ getCollidingObstacleAtConfig()

Names_t hpp::corbaserver::rbprm::RbprmBuilder::getCollidingObstacleAtConfig ( in floatSeq  configuration,
in string  limbName 
)
raises (Error
)

For a given limb, returns the names of all the contact surfaces in collisions with the limb's reachable workspace

Parameters
configuration: root configuration
limbName: name of the considered limb

◆ getConfigAtState()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getConfigAtState ( in unsigned short  state)
raises (Error
)

Retrieve the configuration at a given state between two indicated states. The states do not need to be consecutive, but increasing in Id. Will fail if the index of the state does not exist.

Parameters
stateindex of first state.
Returns
projected configuration

◆ getContactCone()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getContactCone ( in unsigned short  stateId,
in double  friction 
)
raises (Error
)

returns the CWC of the robot at a given state

Parameters
stateIdThe considered state
frictionThe friction coefficient
Returns
H matrix, such that H w <= h. h is added as the last column

◆ getContactIntermediateCone()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getContactIntermediateCone ( in unsigned short  stateId,
in double  friction 
)
raises (Error
)

returns the CWC of the robot between two states

Parameters
stateIdThe considered state
Returns
H matrix, such that H w <= h. h is added as the last column

◆ getContactSamplesIds()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getContactSamplesIds ( in string  name,
in floatSeq  dofArray,
in floatSeq  direction 
)
raises (Error
)

Given a configuration and a limb, returns the id of all samples potentially in contact with the environment, ordered by their efficiency

Parameters
namename of the considered limb
dofArrayconsidered configuration of the robot
directiondesired direction of motion for the robot
Returns
transformed configuration for which all possible contacts have been created

◆ getContactSamplesProjected()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getContactSamplesProjected ( in string  name,
in floatSeq  dofArray,
in floatSeq  direction,
in unsigned short  numSamples 
)
raises (Error
)

Given a configuration and a limb, returns the id of all samples potentially in contact with the environment, ordered by their efficiency

Parameters
namename of the considered limb
dofArrayconsidered configuration of the robot
directiondesired direction of motion for the robot
Returns
transformed configuration for which all possible contacts have been created

◆ getContactSurfacesAtConfig()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getContactSurfacesAtConfig ( in floatSeq  configuration,
in string  limbName 
)
raises (Error
)

For a given limb, return all the intersections between the limb reachable workspace and a contact surface

Parameters
configuration: root configuration
limbName: name of the considered limb

◆ getContactsVariations()

Names_t hpp::corbaserver::rbprm::RbprmBuilder::getContactsVariations ( in unsigned short  stateIdFrom,
in unsigned short  stateIdTo 
)
raises (Error
)

return the contacts variation between two states

Parameters
stateIdFrom: index of the first state
stateIdTo: index of the second state

◆ getEffectorDistance()

double hpp::corbaserver::rbprm::RbprmBuilder::getEffectorDistance ( in unsigned short  state1,
in unsigned short  state2 
)
raises (Error
)

compute the distance between all effectors replaced between two states does not account for contact not present in both states

Parameters
state1from state
state2destination state
Returns
the value computed for the given sample and analytics

◆ getEffectorPosition()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getEffectorPosition ( in string  limbName,
in floatSeq  dofArray 
)
raises (Error
)

Get the end effector position for a given configuration, assuming z normal

Parameters
limbNamename of the limb from which to retrieve a sample
dofArrayconfiguration of the robot
Returns
world position of the limb end effector given the current robot configuration. array of size 4, where each entry is the position of a corner of the contact surface

◆ getEffectorsTrajectoriesNames()

Names_t hpp::corbaserver::rbprm::RbprmBuilder::getEffectorsTrajectoriesNames ( in unsigned short  pathId)
raises (Error
)

Return the names of all the effector for which a trajectory have been computed for a given path index.

Parameters
pathId: index of the path, the same index as the wholeBody path stored in problem-solver
Returns
the list of all the end-effector (joint names) for which a trajectory have been defined

◆ getEffectorTrajectoryWaypoints()

floatSeqSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getEffectorTrajectoryWaypoints ( in unsigned short  pathId,
in string  effectorName 
)
raises (Error
)

Return the waypoints of the bezier curve for a given pathIndex and effector name

Parameters
pathId: index of the path, the same index as the wholeBody path stored in problem-solver
effectorName: the name of the desired effector (Joint name)
Returns
A list with the length of the curve at the first index and then the waypoints of the bezier curve followed by this end effector Throw an error if there is no trajectory computed for the given id/name

◆ getNumSamples()

unsigned short hpp::corbaserver::rbprm::RbprmBuilder::getNumSamples ( in string  limbName)
raises (Error
)

Get the end effector position of a given limb configuration

Parameters
limbNamename of the limb from which to retrieve a sample
Returns
number of samples generated for the limb

◆ getNumStates()

short hpp::corbaserver::rbprm::RbprmBuilder::getNumStates ( )
raises (Error
)

Compute the number of computed states

Returns
the number of computed states

◆ getOctreeBox()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getOctreeBox ( in string  limbname,
in double  sampleId 
)
raises (Error
)

returns the size and transforms of all boxes of the octree for a limb

Parameters
limbnamename of the considered limb
dofArrayconsidered configuration of the robot
Returns
transformed configuration for which all possible contacts have been created

◆ getOctreeBoxes()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getOctreeBoxes ( in string  limbname,
in floatSeq  dofArray 
)
raises (Error
)

returns the size and transforms of all boxes of the octree for a limb

Parameters
limbnamename of the considered limb
dofArrayconsidered configuration of the robot
Returns
transformed configuration for which all possible contacts have been created

◆ getOctreeNodeIds()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getOctreeNodeIds ( in string  limbName)
raises (Error
)

Get the number of octree nodes for a limb database

Parameters
limbNamename of the limb from which to retrieve octree number
Returns
ids of the nodes in the octree

◆ getOctreeTransform()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getOctreeTransform ( in string  limbname,
in floatSeq  dofArray 
)
raises (Error
)

returns octree transform for a given robot configuration

Parameters
limbnamename of the considered limb
dofArrayconsidered configuration of the robot
Returns
size 7 position + quaternion of the octree root

◆ getPathAsBezier()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getPathAsBezier ( in unsigned short  pathId)
raises (Error
)

Return the waypoints of the bezier curve at given index

Parameters
pathIdthe path index
Returns
a list of lenght degree+ 2 : the first item is the time of the curve, the others are the waypoints

◆ getSampleConfig()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getSampleConfig ( in string  sampleName,
in unsigned long  sampleId 
)
raises (Error
)

Get Sample configuration by its id

Parameters
sampleNamename of the limb from which to retrieve a sample
sampleIdid of the desired samples
Returns
dofArray Array of degrees of freedom corresponding to the current configuration of the robot , to which the desired limb configuration has been assigned.

◆ getSamplePosition()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getSamplePosition ( in string  sampleName,
in unsigned long  sampleId 
)
raises (Error
)

Get the end effector position of a given limb configuration

Parameters
sampleNamename of the limb from which to retrieve a sample
sampleIdid of the desired samples
Returns
world position of the limb end effector given the current robot configuration and the and the selected sample

◆ getSamplesIdsInOctreeNode()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getSamplesIdsInOctreeNode ( in string  name,
in double  octreeNodeId 
)
raises (Error
)

get Ids of limb in an octree cell

Parameters
namename of the considered limb
octreeNodeIdconsidered configuration of the robot
Returns
list of ids in the cell

◆ getSampleValue()

double hpp::corbaserver::rbprm::RbprmBuilder::getSampleValue ( in string  limbName,
in string  valueName,
in unsigned long  sampleId 
)
raises (Error
)

Get the sample value for a given analysis

Parameters
limbNamename of the limb from which to retrieve a sample
valueNamename of the analytic measure desired
sampleIdid of the considered sample
Returns
the value computed for the given sample and analytics

◆ getTimeAtState()

double hpp::corbaserver::rbprm::RbprmBuilder::getTimeAtState ( in unsigned short  stateId)
raises (Error
)

return the time at the given state index

Parameters
stateIdindex of the state

◆ initNewProblemSolver()

void hpp::corbaserver::rbprm::RbprmBuilder::initNewProblemSolver ( )
raises (Error
)

Called if several problem solvers are used is colliding with the environment.

◆ interpolate()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::interpolate ( in double  timestep,
in double  path,
in double  robustnessTreshold,
in unsigned short  filterStates,
in boolean  testReachability,
in boolean  quasiStatic,
in boolean  erasePreviousStates 
)
raises (Error
)

Provided a path has already been computed, interpolates it and generates the statically stable constact configurations along it. setStartState and setEndState must have been called prior to this function. If these conditions are not met an error is raised.

Parameters
timestepnormalized step for generation along the path (ie the path has a length of 1).
pathpath computed.
robustnessTresholdminimum value of the static equilibrium robustness criterion required to accept the configuration (0 by default).
filterStatesIf different than 0, the resulting state list will be filtered to remove unnecessary states
testReachability: if true, check each contact transition with our reachability criterion
quasiStatic: if True, use our reachability criterion with the quasiStatic constraint

◆ interpolateConfigs()

floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::interpolateConfigs ( in floatSeqSeq  configs,
in double  robustnessTreshold,
in unsigned short  filterStates,
in boolean  testReachability,
in boolean  quasiStatic,
in boolean  erasePreviousStates 
)
raises (Error
)

Provided a path has already been computed, interpolates it and generates the statically stable constact configurations along it. setStartState and setEndState must have been called prior to this function. If these conditions are not met an error is raised.

Parameters
timestepnormalized step for generation along the path (ie the path has a length of 1).
pathpath computed.
robustnessTresholdminimum value of the static equilibrium robustness criterion required to accept the configuration (0 by default).
filterStatesIf different than 0, the resulting state list will be filtered to remove unnecessary states
testReachability: if true, check each contact transition with our reachability criterion
quasiStatic: if True, use our reachability criterion with the quasiStatic constraint
erasePreviousStates: if True, the method override the current state list in fullBody, otherwise it append the results

◆ isConfigBalanced()

short hpp::corbaserver::rbprm::RbprmBuilder::isConfigBalanced ( in floatSeq  config,
in Names_t  contacts,
in double  robustnessTreshold,
in floatSeq  CoM 
)
raises (Error
)

returns octree transform for a given robot configuration

Parameters
configconfiguration tested on the robot
contactsname of the limbs in contact
robustnessTresholdrobustness treshold used
CoMoptional, if specified use this CoM position instead of the one computed from the configuration
Returns
whether the configuration is quasi-statically balanced

◆ isDynamicallyReachableFromState()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::isDynamicallyReachableFromState ( in unsigned short  stateFrom,
in unsigned short  stateTo,
in boolean  addPathPerPhase,
in floatSeq  timings,
in short  numPointsPerPhase 
)
raises (Error
)

◆ isLimbInContact()

short hpp::corbaserver::rbprm::RbprmBuilder::isLimbInContact ( in string  limbname,
in unsigned short  state1 
)
raises (Error
)
Parameters
limbname of the limb for which the request aplies
state1current state considered
Returns
whether the limb is in contact at this state

◆ isLimbInContactIntermediary()

short hpp::corbaserver::rbprm::RbprmBuilder::isLimbInContactIntermediary ( in string  limbname,
in unsigned short  state1 
)
raises (Error
)

Is limb in contact during the motion from the current state to the next one

Parameters
limbname of the limb for which the request aplies
state1current state considered
Returns
whether the limb is in contact at this state

◆ isReachableFromState()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::isReachableFromState ( in unsigned short  stateFrom,
in unsigned short  stateTo,
in boolean  useIntermediateState 
)
raises (Error
)

◆ isStateBalanced()

double hpp::corbaserver::rbprm::RbprmBuilder::isStateBalanced ( in unsigned short  state)
raises (Error
)

returns whether a state is in static equilibrium

Parameters
stateid of the state

◆ limbRRT()

short hpp::corbaserver::rbprm::RbprmBuilder::limbRRT ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. The states do not need to be consecutive, but increasing in Id. Will fail if the index of the states do not exist The path of the root and limbs not considered by the contact transitions between two states are computed using the current active steering method, and considered to be valid in the sense of the active PathValidation.

Parameters
state1index of first state.
state2index of second state.
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ limbRRTFromRootPath()

short hpp::corbaserver::rbprm::RbprmBuilder::limbRRTFromRootPath ( in unsigned short  state1,
in unsigned short  state2,
in unsigned short  path,
in unsigned short  numOptimizations 
)
raises (Error
)

Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. The states do not need to be consecutive, but increasing in Id. Will fail if the index of the states do not exist The path of the root and limbs not considered by the contact transitions between two states is assumed to be already computed, and registered in the solver under the id specified by the user. It must be valid in the sense of the active PathValidation.

Parameters
state1index of first state.
state2index of second state.
pathindex of the path considered for the generation
numOptimizationsNumber of iterations of the shortcut algorithm to apply between each states
Returns
id of the root path computed

◆ loadFullBodyRobot()

void hpp::corbaserver::rbprm::RbprmBuilder::loadFullBodyRobot ( in string  robotName,
in string  rootJointType,
in string  urdfName,
in string  srdfName,
in string  selectedProblem 
)
raises (Error
)

Load fullbody robot model

Create a RbprmFullBody object The device automatically has an anchor joint called "base_joint" as root joint.

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.

◆ loadFullBodyRobotFromExistingRobot()

void hpp::corbaserver::rbprm::RbprmBuilder::loadFullBodyRobotFromExistingRobot ( )
raises (Error
)

Create a RbprmFullBody object The device automatically has an anchor joint called "base_joint" as root joint.

◆ loadRobotCompleteModel()

void hpp::corbaserver::rbprm::RbprmBuilder::loadRobotCompleteModel ( in string  robotName,
in string  rootJointType,
in string  urdfName,
in string  srdfName 
)
raises (Error
)

Create a RbprmDevice for the root of the robot.

The device automatically has an anchor joint called "base_joint" as root joint.

Parameters
robotNamethe name of the robot trunk used for collision,
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.

◆ loadRobotRomModel()

void hpp::corbaserver::rbprm::RbprmBuilder::loadRobotRomModel ( in string  robotName,
in string  rootJointType,
in string  urdfName 
)
raises (Error
)

Create a Device for the ROM of the robot This function can be called several times to include several ROMs (one for each limb) The device automatically has an anchor joint called "base_joint" as root joint.

Parameters
robotNamethe name of the robot range of motion,
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
urdfNamename of the urdf file. It may contain "file://", or "package://" prefixes.

◆ projectStateToCOM()

double hpp::corbaserver::rbprm::RbprmBuilder::projectStateToCOM ( in unsigned short  stateId,
in floatSeq  com,
in unsigned short  max_num_sample 
)
raises (Error
)

Project a state into a COM

Parameters
stateIdtarget state
comtarget com

◆ projectStateToRoot()

double hpp::corbaserver::rbprm::RbprmBuilder::projectStateToRoot ( in unsigned short  stateId,
in floatSeq  root,
in floatSeq  offset 
)
raises (Error
)

Project a state into a given root position and orientation

Parameters
stateIdtarget state
rootthe root configuration (size 7)
offsetspecific point to be projected in root frame. If different than 0 root orientation is ignored

◆ projectToCom()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::projectToCom ( in unsigned short  state,
in floatSeq  targetCom,
in unsigned short  max_num_sample 
)
raises (Error
)

Project a given state into a given COM position between two indicated states. The states do not need to be consecutive, but increasing in Id. Will fail if the index of the state does not exist.

Parameters
stateindex of first state.
targetCom3D vector for the com position
max_num_samplenumber of samples that can be used at worst before failing
Returns
projected configuration

◆ removeContact()

short hpp::corbaserver::rbprm::RbprmBuilder::removeContact ( in unsigned short  stateId,
in string  limbName 
)
raises (Error
)

removes a contact from the state if the limb is not already in contact, does nothing

Parameters
stateState considered
limbNamename of the considered limb to create contact with
Returns
stateId of the state without the contact

◆ runLimbSampleAnalysis()

floatSeq hpp::corbaserver::rbprm::RbprmBuilder::runLimbSampleAnalysis ( in string  limbname,
in string  analysis,
in double  isstatic 
)
raises (Error
)

run and store an analysis on a limb database

Parameters
limbnamename of the limb to perform the analysis to
analysisname of the analysis existing if analysis ="all", all tests are run.
isstatic1 is becomes new static value of database, 0 otherwise
Returns
min and max values obtained

◆ runSampleAnalysis()

void hpp::corbaserver::rbprm::RbprmBuilder::runSampleAnalysis ( in string  analysis,
in double  isstatic 
)
raises (Error
)

run and store an analysis on all limb databases

Parameters
analysisname of the analysis existing if analysis ="all", all tests are run.
isstatic1 is becomes new static value of database, 0 otherwise

◆ saveComputedStates()

void hpp::corbaserver::rbprm::RbprmBuilder::saveComputedStates ( in string  filename)
raises (Error
)

Saves the last computed states by the function interpolate in a filename. Raises an error if interpolate has not been called, or the file could not be opened.

Parameters
filenamename of the file used to save the contacts.

◆ saveLimbDatabase()

void hpp::corbaserver::rbprm::RbprmBuilder::saveLimbDatabase ( in string  limbname,
in string  filename 
)
raises (Error
)

Saves a sample database into a file Raises an ifthe file could not be opened.

Parameters
limbnamename of the limb used to save the samples.
filenamename of the file used to save the samples.

◆ selectFullBody()

void hpp::corbaserver::rbprm::RbprmBuilder::selectFullBody ( in string  name)
raises (Error
)

◆ setAffordanceFilter()

void hpp::corbaserver::rbprm::RbprmBuilder::setAffordanceFilter ( in string  romName,
in Names_t  affordances 
)
raises (Error
)

Set Rom surface constraints for the configuration shooter a Rom configuration will only be valid it collides with a surface that forms a given affordance (support, lean, etc.)

Parameters
affordancesa list of affordances accepted for
validation of given Rom

◆ setConfigAtState()

double hpp::corbaserver::rbprm::RbprmBuilder::setConfigAtState ( in unsigned short  stateId,
in floatSeq  config 
)
raises (Error
)

Project a state into a COM

Parameters
stateIdtarget state
comtarget com

◆ setEndState()

void hpp::corbaserver::rbprm::RbprmBuilder::setEndState ( in floatSeq  dofArray,
in Names_t  contactLimbs 
)
raises (Error
)

Set the end state of a contact generation problem environment, ordered by their efficiency

Parameters
dofArrayend configuration of the robot
contactLimbsids of the limb in contact for the state

◆ setEndStateId()

void hpp::corbaserver::rbprm::RbprmBuilder::setEndStateId ( in unsigned short  stateId)
raises (Error
)

Set the end state of a contact generation problem

Parameters
stateId: the id of the state, in fullBody

◆ setFilter()

void hpp::corbaserver::rbprm::RbprmBuilder::setFilter ( in Names_t  roms)
raises (Error
)

Set Rom constraints for the configuration shooter a configuration will only be valid if all roms indicated are colliding with the environment. If no roms are indicated, a configuration will be valid if any rom is colliding with the environment.

◆ setPostureWeights()

void hpp::corbaserver::rbprm::RbprmBuilder::setPostureWeights ( in floatSeq  postureWeights)
raises (Error
)

set the weights used when computing a postural task

◆ setReferenceConfig()

void hpp::corbaserver::rbprm::RbprmBuilder::setReferenceConfig ( in floatSeq  referenceConfig)
raises (Error
)

set a reference configuration in fullBody

◆ setReferenceEndEffector()

void hpp::corbaserver::rbprm::RbprmBuilder::setReferenceEndEffector ( in string  romName,
in floatSeq  ref 
)
raises (Error
)

set a reference position of the end effector for the given ROM

◆ setStartState()

void hpp::corbaserver::rbprm::RbprmBuilder::setStartState ( in floatSeq  dofArray,
in Names_t  contactLimbs 
)
raises (Error
)

Set the start state of a contact generation problem

Parameters
dofArraystart configuration of the robot
contactLimbsids of the limb in contact for the state

◆ setStartStateId()

void hpp::corbaserver::rbprm::RbprmBuilder::setStartStateId ( in unsigned short  stateId)
raises (Error
)

Set the start state of a contact generation problem

Parameters
stateId: the id of the state, in fullBody

◆ setStaticStability()

void hpp::corbaserver::rbprm::RbprmBuilder::setStaticStability ( in boolean  staticStability)
raises (Error
)

set a boolean in rbprmFullBody if true, the acceleration doesn't account for the stability check

◆ straightPath()

short hpp::corbaserver::rbprm::RbprmBuilder::straightPath ( in floatSeqSeq  positions)
raises (Error
)

Create a linear path given list of positions The path is composed of n+1 integrations between the n positions. The resulting path is added to the problem solver

Parameters
positionsarray of positions
Returns
id of the root path computed

◆ toggleNonContactingLimb()

boolean hpp::corbaserver::rbprm::RbprmBuilder::toggleNonContactingLimb ( in string  limbname)
raises (Error
)

◆ usePosturalTaskContactCreation()

void hpp::corbaserver::rbprm::RbprmBuilder::usePosturalTaskContactCreation ( in boolean  use)
raises (Error
)

If true, optimize the orientation of all the newly created contact using a postural task.


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