import"/local/robotpkg/var/tmp/robotpkg/wip/py-hpp-rbprm-corba/work/hpp-rbprm-corba-4.8.0/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl";
Public Member Functions | |
void | loadRobotRomModel (in string romRobotName, in string rootJointType, in string packageName, in string modelName, in string urdfSuffix, in string srdfSuffix) 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. More... | |
void | loadRobotCompleteModel (in string trunkRobotName, in string rootJointType, in string packageName, in string modelName, in string urdfSuffix, in string srdfSuffix) raises (Error) |
Create a RbprmDevice for the root of the robot. More... | |
void | loadFullBodyRobot (in string trunkRobotName, in string rootJointType, in string packageName, in string modelName, in string urdfSuffix, in string srdfSuffix, in string selectedProblem) raises (Error) |
Create a RbprmFullBody object The device automatically has an anchor joint called "base_joint" as root joint. More... | |
void | loadFullBodyRobotFromExistingRobot () raises (Error) |
Create a RbprmFullBody object The device automatically has an anchor joint called "base_joint" as root joint. More... | |
void | selectFullBody (in string name) raises (Error) |
void | setStaticStability (in boolean staticStability) raises (Error) |
set a boolean in rbprmFullBody if true, the acceleration doesn't account for the stability check More... | |
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) |
Set Rom constraints for the configuration shooter a configuration will only be valid if all roms indicated are colliding with the environment. More... | |
void | initNewProblemSolver () raises (Error) |
Called if several problem solvers are used is colliding with the environment. More... | |
void | 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.) More... | |
void | boundSO3 (in floatSeq limitszyx) raises (Error) |
Sets limits on robot orientation, described according to Euler's ZYX rotation order. More... | |
double | projectStateToCOM (in unsigned short stateId, in floatSeq com, in unsigned short max_num_sample) raises (Error) |
Project a state into a COM. More... | |
short | cloneState (in unsigned short stateId) raises (Error) |
Clone a state. More... | |
double | projectStateToRoot (in unsigned short stateId, in floatSeq root, in floatSeq offset) raises (Error) |
Project a state into a given root position and orientation. More... | |
double | setConfigAtState (in unsigned short stateId, in floatSeq config) raises (Error) |
Project a state into a COM. More... | |
short | createState (in floatSeq configuration, in Names_t contactLimbs) raises (Error) |
Create a state and push it to the state array. More... | |
floatSeq | getSampleConfig (in string sampleName, in unsigned long sampleId) raises (Error) |
Get Sample configuration by its id. More... | |
floatSeq | getSamplePosition (in string sampleName, in unsigned long sampleId) raises (Error) |
Get the end effector position of a given limb configuration. More... | |
floatSeqSeq | getEffectorPosition (in string limbName, in floatSeq dofArray) raises (Error) |
Get the end effector position for a given configuration, assuming z normal. More... | |
unsigned short | getNumSamples (in string limbName) raises (Error) |
Get the end effector position of a given limb configuration. More... | |
floatSeq | getOctreeNodeIds (in string limbName) raises (Error) |
Get the number of octree nodes for a limb database. More... | |
double | getSampleValue (in string limbName, in string valueName, in unsigned long sampleId) raises (Error) |
Get the sample value for a given analysis. More... | |
double | 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 More... | |
floatSeq | generateContacts (in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration, in double robustnessThreshold) raises (Error) |
Generate all possible contact in a given configuration. More... | |
short | 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. More... | |
floatSeq | generateGroundContact (in Names_t contactLimbs) raises (Error) |
Generate an autocollision free configuration with limbs in contact with the ground. More... | |
floatSeq | 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. More... | |
floatSeqSeq | 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. More... | |
short | 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. More... | |
floatSeq | getSamplesIdsInOctreeNode (in string name, in double octreeNodeId) raises (Error) |
get Ids of limb in an octree cell More... | |
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) |
A limb must consist in a simple kinematic chain, where every node has only one child. More... | |
void | addNonContactingLimb (in string id, in string limb, in string effector, in unsigned long samples) raises (Error) |
Add a limb not used for contact generation. More... | |
void | 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. More... | |
void | setStartState (in floatSeq dofArray, in Names_t contactLimbs) raises (Error) |
Set the start state of a contact generation problem. More... | |
void | setStartStateId (in unsigned short stateId) raises (Error) |
Set the start state of a contact generation problem. More... | |
void | setEndStateId (in unsigned short stateId) raises (Error) |
Set the end state of a contact generation problem. More... | |
floatSeq | computeContactForConfig (in floatSeq dofArray, in string limbName) raises (Error) |
Compute effector contact points and normals for a given configuration in local coordinates. More... | |
void | setEndState (in floatSeq dofArray, in Names_t contactLimbs) raises (Error) |
Set the end state of a contact generation problem environment, ordered by their efficiency. More... | |
floatSeqSeq | 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. More... | |
floatSeqSeq | 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. More... | |
floatSeqSeq | 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. More... | |
floatSeqSeq | 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. More... | |
floatSeqSeq | 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. More... | |
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) |
Provided a path has already been computed, interpolates it and generates the statically stable constact configurations along it. More... | |
floatSeqSeq | 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. More... | |
floatSeqSeq | getContactCone (in unsigned short stateId, in double friction) raises (Error) |
returns the CWC of the robot at a given state More... | |
floatSeqSeq | getContactIntermediateCone (in unsigned short stateId, in double friction) raises (Error) |
returns the CWC of the robot between two states More... | |
short | 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. More... | |
short | 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. More... | |
short | 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. More... | |
short | generateCurveTraj (in floatSeqSeq coefficients) raises (Error) |
Create a trajectory corresponding to a bezier curve. More... | |
short | generateCurveTrajParts (in floatSeqSeq coefficients, in floatSeq partitions) raises (Error) |
Create a trajectory corresponding to a bezier curve. More... | |
short | 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. More... | |
short | 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. More... | |
short | configToPath (in floatSeqSeq configs) raises (Error) |
Linear interpolation of many configurations into a path. More... | |
short | 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. More... | |
floatSeq | 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. More... | |
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) |
Provided a path has already been computed and interpolated, generate a continuous path between three indicated states. More... | |
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) |
Provided a path has already been computed and interpolated, generate a continuous path between three indicated states. More... | |
floatSeq | 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. More... | |
floatSeq | 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. More... | |
floatSeqSeq | 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) More... | |
floatSeq | 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. More... | |
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) |
Provided a path has already been computed and interpolated, generate a continuous path between two indicated states. More... | |
short | 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. More... | |
floatSeq | 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. More... | |
floatSeq | getConfigAtState (in unsigned short state) raises (Error) |
Retrieve the configuration at a given state between two indicated states. More... | |
short | isLimbInContact (in string limbname, in unsigned short state1) raises (Error) |
short | 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. More... | |
short | computeIntermediary (in unsigned short state1, in unsigned short state2) raises (Error) |
Generate intermediary state. More... | |
short | getNumStates () raises (Error) |
Compute the number of computed states. More... | |
void | saveComputedStates (in string filename) raises (Error) |
Saves the last computed states by the function interpolate in a filename. More... | |
void | saveLimbDatabase (in string limbname, in string filename) raises (Error) |
Saves a sample database into a file Raises an ifthe file could not be opened. More... | |
floatSeqSeq | getOctreeBoxes (in string limbname, in floatSeq dofArray) raises (Error) |
returns the size and transforms of all boxes of the octree for a limb More... | |
floatSeq | getOctreeBox (in string limbname, in double sampleId) raises (Error) |
returns the size and transforms of all boxes of the octree for a limb More... | |
floatSeq | getOctreeTransform (in string limbname, in floatSeq dofArray) raises (Error) |
returns octree transform for a given robot configuration More... | |
double | isStateBalanced (in unsigned short state) raises (Error) |
returns whether a state is in static equilibrium More... | |
short | isConfigBalanced (in floatSeq config, in Names_t contacts, in double robustnessTreshold, in floatSeq CoM) raises (Error) |
returns octree transform for a given robot configuration More... | |
void | runSampleAnalysis (in string analysis, in double isstatic) raises (Error) |
run and store an analysis on all limb databases More... | |
floatSeq | runLimbSampleAnalysis (in string limbname, in string analysis, in double isstatic) raises (Error) |
run and store an analysis on a limb database More... | |
floatSeq | evaluateConfig (in floatSeq configuration, in floatSeq direction) raises (Error) |
void | dumpProfile (in string logFile) raises (Error) |
if the preprocessor variable PROFILE is active dump the profiling data into a logFile More... | |
double | getTimeAtState (in unsigned short stateId) raises (Error) |
return the time at the given state index More... | |
Names_t | getContactsVariations (in unsigned short stateIdFrom, in unsigned short stateIdTo) raises (Error) |
return the contacts variation between two states More... | |
Names_t | 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. More... | |
floatSeqSeq | 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. More... | |
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) |
tries to add a new contact to the state if the limb is already in contact, replace the previous contact. More... | |
short | 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 More... | |
floatSeq | 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. More... | |
Names_t | 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. More... | |
floatSeqSeqSeq | getEffectorTrajectoryWaypoints (in unsigned short pathId, in string effectorName) raises (Error) |
Return the waypoints of the bezier curve for a given pathIndex and effector name. More... | |
floatSeqSeq | getPathAsBezier (in unsigned short pathId) raises (Error) |
Return the waypoints of the bezier curve at given index. More... | |
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) |
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.
id | user given name of the new limb |
limb | robot joint corresponding to the root of the limb (ex a shoulder or ankle joint) |
effector | robot joint corresponding to the effector of the limb (ex a hand or foot joint) |
offset | contact point of the effector, expressed as an offset from the joint root |
normal | normal 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 |
x | half width of the rectangle surface contact of the effector |
y | half length of the rectangle surface contact of the effector |
samples | number of samples to generate for the limb (a typical value is 10000) |
heuristicName | heuristic used to bias sample selection |
resolution | resolution of the octree used to store the samples (a typical value is 0.01 meters) |
contactType | whether the contact is punctual ("_3_DOF") or surfacic ("_6_DOF") |
disableEffectorCollision | whether collision detection should be disabled for the end effector bones |
limbOffset | the offset between the limb joint and it's link |
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
databasepath | filepath to the database |
id | user given name of the new limb |
heuristicName | heuristic used to bias sample selection |
loadValues | whether other values computed for the limb database should be loaded |
disableEffectorCollision | whether collision detection should be disabled for the end effector bones |
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.
state | State considered |
limbName | name of the considered limb to create contact with |
p | 3d position of the point |
n | 3d normal of the contact location center |
max_num_sample | number 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) |
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.
id | user given name of the new limb |
limb | robot joint corresponding to the root of the limb (ex a shoulder or ankle joint) |
effector | robot joint corresponding to the effector of the limb (ex a hand or foot joint) |
samples | number of samples to generate for the limb (a typical value is 10000) |
boolean hpp::corbaserver::rbprm::RbprmBuilder::areKinematicsConstraintsVerified | ( | in floatSeq | point | ) | |
raises | ( | Error | |||
) |
boolean hpp::corbaserver::rbprm::RbprmBuilder::areKinematicsConstraintsVerifiedForState | ( | in unsigned short | stateFrom, |
in floatSeq | point | ||
) | |||
raises | ( | Error | |
) |
Sets limits on robot orientation, described according to Euler's ZYX rotation order.
limitszyx | 6D 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] |
short hpp::corbaserver::rbprm::RbprmBuilder::cloneState | ( | in unsigned short | stateId | ) | |
raises | ( | Error | |||
) |
Clone a state.
stateId | target state |
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.
stateId | normalized step for generation along the path (ie the path has a length of 1). |
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.
dofArray | configuration of the robot |
limbName | ids of the limb in contact |
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.
stateId | normalized step for generation along the path (ie the path has a length of 1). |
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.
stateId | iD of the considered state |
isIntermediate | whether the intermediate state should be considerred rather than this one |
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.
stateId | normalized step for generation along the path (ie the path has a length of 1). |
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.
stateId | normalized step for generation along the path (ie the path has a length of 1). |
short hpp::corbaserver::rbprm::RbprmBuilder::computeIntermediary | ( | in unsigned short | state1, |
in unsigned short | state2 | ||
) | |||
raises | ( | Error | |
) |
Generate intermediary state.
state1 | initial state considered |
state2 | target state considered |
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.
limbname | name of the considered limb |
configuration | considered configuration of the robot |
p | target position |
n | target normal |
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.
state1 | index of first state. |
state2 | index of second state. |
comPath | index of the path considered of the com path |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
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.
state1 | index of first state. |
rootPositions1 | com positions to track for 1st phase |
rootPositions1 | com positions to track for 2nd phase |
rootPositions1 | com positions to track for 3rd phase |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
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.
state1 | index of first state. |
state2 | index of end state. |
rootPositions1 | com positions to track for 1st phase |
rootPositions1 | com positions to track for 2nd phase |
rootPositions1 | com positions to track for 3rd phase |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
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)
state1 | index of the first state |
state2 | index of the second state |
rootPositions1 | com positions to track |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
short hpp::corbaserver::rbprm::RbprmBuilder::configToPath | ( | in floatSeqSeq | configs | ) | |
raises | ( | Error | |||
) |
Linear interpolation of many configurations into a path.
configs | list of configurations |
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.
q | configuration |
names | list of effectors in contact |
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
logFile | name of the file where to dump the profiling data |
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.
state1 | index of first state. |
rootPositions1 | com positions to track for 1st phase |
rootPositions1 | com positions to track for 2nd phase |
rootPositions1 | com positions to track for 3rd phase |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
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.
state1 | index of first state. |
rootPositions1 | com positions to track for 1st phase |
rootPositions1 | com positions to track for 2nd phase |
rootPositions1 | com positions to track for 3rd phase |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
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.
state1 | index of first state. |
state2 | index of end state. |
rootPositions1 | com positions to track for 1st phase |
rootPositions1 | com positions to track for 2nd phase |
rootPositions1 | com positions to track for 3rd phase |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
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)
state1 | index of the first state |
state2 | index of the second state |
rootPositions1 | com positions to track |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
floatSeq hpp::corbaserver::rbprm::RbprmBuilder::evaluateConfig | ( | in floatSeq | configuration, |
in floatSeq | direction | ||
) | |||
raises | ( | Error | |
) |
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
positions | array of positions |
velocities | array of velocities |
accelerations | array of accelerations |
dt | time between two points |
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.
dofArray | initial configuration of the robot |
direction | desired direction of motion for the robot |
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.
currentState | Id of the considered state |
name | name of the limb used to create a contact |
direction | desired direction of motion for the robot |
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
coefficients | array of positions |
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
coefficients | array of positions |
partitions | array of positions |
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)
state1 | index of the first state |
state2 | index of the second state |
rootPositions1 | com positions to track |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
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
state1 | index of first state. |
state2 | index of end state. |
rootPositions | com positions to track |
floatSeq hpp::corbaserver::rbprm::RbprmBuilder::generateGroundContact | ( | in Names_t | contactLimbs | ) | |
raises | ( | Error | |||
) |
Generate an autocollision free configuration with limbs in contact with the ground.
contactLimbs | name of the limbs to project in contact |
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
positions | array of positions |
q1 | quaternion of 1st rotation |
q2 | quaternion of 2nd rotation |
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.
dofArray | initial configuration of the robot |
direction | desired direction of motion for the robot |
return a list of all the limbs names
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.
configuration | : root configuration |
limbName | : name of the considered limb |
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.
state | index of first state. |
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
stateId | The considered state |
friction | The friction coefficient |
floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getContactIntermediateCone | ( | in unsigned short | stateId, |
in double | friction | ||
) | |||
raises | ( | Error | |
) |
returns the CWC of the robot between two states
stateId | The considered state |
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.
name | name of the considered limb |
dofArray | considered configuration of the robot |
direction | desired direction of motion for the robot |
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.
name | name of the considered limb |
dofArray | considered configuration of the robot |
direction | desired direction of motion for the robot |
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.
configuration | : root configuration |
limbName | : name of the considered limb |
Names_t hpp::corbaserver::rbprm::RbprmBuilder::getContactsVariations | ( | in unsigned short | stateIdFrom, |
in unsigned short | stateIdTo | ||
) | |||
raises | ( | Error | |
) |
return the contacts variation between two states
stateIdFrom | : index of the first state |
stateIdTo | : index of the second state |
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
state1 | from state |
state2 | destination state |
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.
limbName | name of the limb from which to retrieve a sample |
dofArray | configuration of the robot |
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.
pathId | : index of the path, the same index as the wholeBody path stored in problem-solver |
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.
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) |
unsigned short hpp::corbaserver::rbprm::RbprmBuilder::getNumSamples | ( | in string | limbName | ) | |
raises | ( | Error | |||
) |
Get the end effector position of a given limb configuration.
limbName | name of the limb from which to retrieve a sample |
short hpp::corbaserver::rbprm::RbprmBuilder::getNumStates | ( | ) | ||
raises | ( | Error | ||
) |
Compute the number of computed states.
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
limbname | name of the considered limb |
dofArray | considered configuration of the robot |
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
limbname | name of the considered limb |
dofArray | considered configuration of the robot |
floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getOctreeNodeIds | ( | in string | limbName | ) | |
raises | ( | Error | |||
) |
Get the number of octree nodes for a limb database.
limbName | name of the limb from which to retrieve octree number |
floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getOctreeTransform | ( | in string | limbname, |
in floatSeq | dofArray | ||
) | |||
raises | ( | Error | |
) |
returns octree transform for a given robot configuration
limbname | name of the considered limb |
dofArray | considered configuration of the robot |
floatSeqSeq hpp::corbaserver::rbprm::RbprmBuilder::getPathAsBezier | ( | in unsigned short | pathId | ) | |
raises | ( | Error | |||
) |
Return the waypoints of the bezier curve at given index.
pathId | the path index |
floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getSampleConfig | ( | in string | sampleName, |
in unsigned long | sampleId | ||
) | |||
raises | ( | Error | |
) |
Get Sample configuration by its id.
sampleName | name of the limb from which to retrieve a sample |
sampleId | id of the desired samples |
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.
sampleName | name of the limb from which to retrieve a sample |
sampleId | id of the desired samples |
floatSeq hpp::corbaserver::rbprm::RbprmBuilder::getSamplesIdsInOctreeNode | ( | in string | name, |
in double | octreeNodeId | ||
) | |||
raises | ( | Error | |
) |
get Ids of limb in an octree cell
name | name of the considered limb |
octreeNodeId | considered configuration of the robot |
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.
limbName | name of the limb from which to retrieve a sample |
valueName | name of the analytic measure desired |
sampleId | id of the considered sample |
double hpp::corbaserver::rbprm::RbprmBuilder::getTimeAtState | ( | in unsigned short | stateId | ) | |
raises | ( | Error | |||
) |
return the time at the given state index
stateId | index of the state |
void hpp::corbaserver::rbprm::RbprmBuilder::initNewProblemSolver | ( | ) | ||
raises | ( | Error | ||
) |
Called if several problem solvers are used is colliding with the environment.
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.
timestep | normalized step for generation along the path (ie the path has a length of 1). |
path | path computed. |
robustnessTreshold | minimum value of the static equilibrium robustness criterion required to accept the configuration (0 by default). |
filterStates | If 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 |
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.
timestep | normalized step for generation along the path (ie the path has a length of 1). |
path | path computed. |
robustnessTreshold | minimum value of the static equilibrium robustness criterion required to accept the configuration (0 by default). |
filterStates | If 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 |
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
config | configuration tested on the robot |
contacts | name of the limbs in contact |
robustnessTreshold | robustness treshold used |
CoM | optional, if specified use this CoM position instead of the one computed from the configuration |
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 | |
) |
short hpp::corbaserver::rbprm::RbprmBuilder::isLimbInContact | ( | in string | limbname, |
in unsigned short | state1 | ||
) | |||
raises | ( | Error | |
) |
limb | name of the limb for which the request aplies |
state1 | current state considered |
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.
limb | name of the limb for which the request aplies |
state1 | current state considered |
floatSeq hpp::corbaserver::rbprm::RbprmBuilder::isReachableFromState | ( | in unsigned short | stateFrom, |
in unsigned short | stateTo, | ||
in boolean | useIntermediateState | ||
) | |||
raises | ( | Error | |
) |
double hpp::corbaserver::rbprm::RbprmBuilder::isStateBalanced | ( | in unsigned short | state | ) | |
raises | ( | Error | |||
) |
returns whether a state is in static equilibrium
state | id of the state |
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.
state1 | index of first state. |
state2 | index of second state. |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
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.
state1 | index of first state. |
state2 | index of second state. |
path | index of the path considered for the generation |
numOptimizations | Number of iterations of the shortcut algorithm to apply between each states |
void hpp::corbaserver::rbprm::RbprmBuilder::loadFullBodyRobot | ( | in string | trunkRobotName, |
in string | rootJointType, | ||
in string | packageName, | ||
in string | modelName, | ||
in string | urdfSuffix, | ||
in string | srdfSuffix, | ||
in string | selectedProblem | ||
) | |||
raises | ( | Error | |
) |
Create a RbprmFullBody object The device automatically has an anchor joint called "base_joint" as root joint.
trunkRobotName | the name of the robot trunk used for collision. |
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::rbprm::RbprmBuilder::loadFullBodyRobotFromExistingRobot | ( | ) | ||
raises | ( | Error | ||
) |
Create a RbprmFullBody object The device automatically has an anchor joint called "base_joint" as root joint.
void hpp::corbaserver::rbprm::RbprmBuilder::loadRobotCompleteModel | ( | in string | trunkRobotName, |
in string | rootJointType, | ||
in string | packageName, | ||
in string | modelName, | ||
in string | urdfSuffix, | ||
in string | srdfSuffix | ||
) | |||
raises | ( | Error | |
) |
Create a RbprmDevice for the root of the robot.
The device automatically has an anchor joint called "base_joint" as root joint.
trunkRobotName | the name of the robot trunk used for collision. |
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::rbprm::RbprmBuilder::loadRobotRomModel | ( | in string | romRobotName, |
in string | rootJointType, | ||
in string | packageName, | ||
in string | modelName, | ||
in string | urdfSuffix, | ||
in string | srdfSuffix | ||
) | |||
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.
romRobotName | the name of the robot range of motion. Load robot model |
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"
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.
stateId | target state |
com | target com |
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.
stateId | target state |
root | the root configuration (size 7) |
offset | specific point to be projected in root frame. If different than 0 root orientation is ignored |
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.
state | index of first state. |
targetCom | 3D vector for the com position |
max_num_sample | number of samples that can be used at worst before failing |
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
state | State considered |
limbName | name of the considered limb to create contact with |
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
limbname | name of the limb to perform the analysis to |
analysis | name of the analysis existing if analysis ="all", all tests are run. |
isstatic | 1 is becomes new static value of database, 0 otherwise |
void hpp::corbaserver::rbprm::RbprmBuilder::runSampleAnalysis | ( | in string | analysis, |
in double | isstatic | ||
) | |||
raises | ( | Error | |
) |
run and store an analysis on all limb databases
analysis | name of the analysis existing if analysis ="all", all tests are run. |
isstatic | 1 is becomes new static value of database, 0 otherwise |
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.
filename | name of the file used to save the contacts. |
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.
limbname | name of the limb used to save the samples. |
filename | name of the file used to save the samples. |
void hpp::corbaserver::rbprm::RbprmBuilder::selectFullBody | ( | in string | name | ) | |
raises | ( | Error | |||
) |
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.)
affordances | a list of affordances accepted for validation of given Rom |
double hpp::corbaserver::rbprm::RbprmBuilder::setConfigAtState | ( | in unsigned short | stateId, |
in floatSeq | config | ||
) | |||
raises | ( | Error | |
) |
Project a state into a COM.
stateId | target state |
com | target com |
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.
dofArray | end configuration of the robot |
contactLimbs | ids of the limb in contact for the state |
void hpp::corbaserver::rbprm::RbprmBuilder::setEndStateId | ( | in unsigned short | stateId | ) | |
raises | ( | Error | |||
) |
Set the end state of a contact generation problem.
stateId | : the id of the state, in fullBody |
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.
void hpp::corbaserver::rbprm::RbprmBuilder::setPostureWeights | ( | in floatSeq | postureWeights | ) | |
raises | ( | Error | |||
) |
set the weights used when computing a postural task
void hpp::corbaserver::rbprm::RbprmBuilder::setReferenceConfig | ( | in floatSeq | referenceConfig | ) | |
raises | ( | Error | |||
) |
set a reference configuration in fullBody
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
void hpp::corbaserver::rbprm::RbprmBuilder::setStartState | ( | in floatSeq | dofArray, |
in Names_t | contactLimbs | ||
) | |||
raises | ( | Error | |
) |
Set the start state of a contact generation problem.
dofArray | start configuration of the robot |
contactLimbs | ids of the limb in contact for the state |
void hpp::corbaserver::rbprm::RbprmBuilder::setStartStateId | ( | in unsigned short | stateId | ) | |
raises | ( | Error | |||
) |
Set the start state of a contact generation problem.
stateId | : the id of the state, in fullBody |
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
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
positions | array of positions |
boolean hpp::corbaserver::rbprm::RbprmBuilder::toggleNonContactingLimb | ( | in string | limbname | ) | |
raises | ( | Error | |||
) |
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.