11#ifndef HPP_CORBASERVER_PROBLEM_SERVER_IDL
12#define HPP_CORBASERVER_PROBLEM_SERVER_IDL
123 out
double residualError)
158 out
double residualError)
173 (in
string constraintName, in
string joint1Name,
189 (in
string constraintName, in
string joint1Name,
196 (in
string constraintName, in
string joint1Name, in
string joint2Name,
211 (in
string constraintName, in
string joint1Name,
240 in
unsigned long index,
247 in
string function) raises (
Error);
264 in
string jointLName, in
string jointRName, in
floatSeq pointL,
283 (in
string constraintName, in
Names_t floorJoints, in
Names_t objectJoints,
299 in
string joint1Name,
300 in
string joint2Name,
322 (in
string constraintName, in
string joint1Name, in
string joint2Name,
323 in
double distance) raises (
Error);
333 (in
string constraintName, in
string joint1Name, in
Names_t objects,
334 in
double distance) raises (
Error);
344 (in
string constraintName, in
Names_t inJoints, in
Names_t outJoints)
361 out
unsigned long inputSize , out
unsigned long inputDerivativeSize,
362 out
unsigned long outputSize, out
unsigned long outputDerivativeSize)
537 in
double tolerance) raises (
Error);
545 in
double tolerance) raises (
Error);
578 out
unsigned long pathId, out
string report)
583 boolean reversePath (in
unsigned long pathId, out
unsigned long reversedPathId)
602 in
unsigned long pathId, in
boolean bothEdges)
614 void extractPath (in
unsigned long pathId, in
double start, in
double end)
Definition robots-idl.hh:388
Definition path_validations-idl.hh:118
Definition configuration_shooters-idl.hh:94
Definition _constraints-idl.hh:242
Definition robots-idl.hh:221
Definition distances-idl.hh:94
Definition constraints-idl.hh:223
Definition path_planners-idl.hh:647
Definition path_planners-idl.hh:506
Definition path_projectors-idl.hh:106
Definition path_validations-idl.hh:481
Definition paths-idl.hh:302
Definition paths-idl.hh:157
Definition path_planners-idl.hh:365
Definition steering_methods-idl.hh:106
Corba exception travelling through the Corba channel.
Definition common.idl:27
To define and solve a path planning problem.
Definition problem.idl:28
void selectPathPlanner(in string pathPlannerType)
void createConvexShapeContactConstraint(in string constraintName, in Names_t floorJoints, in Names_t objectJoints, in floatSeqSeq pts, in intSeqSeq objectTriangles, in intSeqSeq floorTriangles)
void addNumericalConstraints(in string configProjName, in Names_t constraintNames, in intSeq priorities)
core_idl::Roadmap createRoadmap(in core_idl::Distance distance, in pinocchio_idl::Device robot)
void addConfigToRoadmap(in floatSeq config)
core_idl::PathPlanner getPathPlanner()
void savePath(in core_idl::Path _path, in string filename)
void createLockedJoint(in string lockedJointName, in string jointName, in floatSeq value)
void selectSteeringMethod(in string steeringMethodType)
void setConstantRightHandSide(in string constraintName, in boolean constant)
core_idl::Constraint createConfigProjector(in pinocchio_idl::Device robot, in string name, in double threshold, in unsigned long iterations)
void edge(in unsigned long edgeId, out floatSeq q1, out floatSeq q2)
Edge at given rank.
void setParameter(in string name, in any value)
void addGoalConfig(in floatSeq dofArray)
Add goal configuration to specified problem.
void createRelativeComConstraint(in string constraintName, in string comName, in string jointLName, in floatSeq point, in boolSeq mask)
boolean generateValidConfig(in unsigned long maxIter, out floatSeq output, out double residualError)
intSeq optimizePath(in unsigned long inPathId)
double getErrorThreshold()
Get error threshold in numerical constraint resolution.
floatSeqSeq getWaypoints(in unsigned long pathId, out floatSeq times)
void setRightHandSideByName(in string constraintName, in floatSeq rhs)
void setMaxIterPathPlanning(in unsigned long iterations)
Set maximal number of iterations in path planning.
void interruptPathPlanning()
Interrupt path planning activity.
void setRightHandSideFromConfigByName(in string constraintName, in floatSeq config)
boolean selectProblem(in string name)
long numberEdges()
Number of edges.
void setDistance(in core_idl::Distance distance)
unsigned long getMaxIterProjection()
Set maximal number of iterations in numerical constraint resolution.
boolean projectPath(in unsigned long patId)
void createTransformationConstraint(in string constraintName, in string joint1Name, in string joint2Name, in Transform_ ref, in boolSeq mask)
void saveRoadmap(in string filename)
boolean directPath(in floatSeq startConfig, in floatSeq endConfig, in boolean validate, out unsigned long pathId, out string report)
boolean prepareSolveStepByStep()
void finishSolveStepByStep()
void createDistanceBetweenJointAndObjects(in string constraintName, in string joint1Name, in Names_t objects, in double distance)
void selectPathValidation(in string pathValidationType, in double tolerance)
Names_t getAvailable(in string type)
void selectDistance(in string distanceType)
long connectedComponentOfEdge(in unsigned long edgeId)
return the connected component index of the edge
core_idl::Distance createDistance(in string type, in core_idl::Problem _problem)
core_idl::SteeringMethod getSteeringMethod()
string getParameterDoc(in string name)
void erasePath(in unsigned long pathId)
core_idl::PathOptimizer createPathOptimizer(in string type, in core_idl::Problem _problem)
floatSeq getRightHandSide()
Get right hand side of constraints in config projector.
void clearRoadmap()
Clear the roadmap.
void createComBeetweenFeet(in string constraintName, in string comName, in string jointLName, in string jointRName, in floatSeq pointL, in floatSeq pointR, in string jointRefName, in floatSeq pointRef, in boolSeq mask)
void setRandomSeed(in long seed)
Set random seed of random number generator.
void addPathOptimizer(in string pathOptimizerType)
void createTransformationConstraint2(in string constraintName, in string joint1Name, in string joint2Name, in Transform_ frame1, in Transform_ frame2, in boolSeq mask)
floatSeq derivativeAtParam(in unsigned long inPathId, in unsigned long orderId, in double atDistance)
core_idl::Path loadPath(in string filename)
floatSeq getNearestConfig(in floatSeq config, in long connectedComponentId, out double distance)
floatSeq configAtParam(in unsigned long inPathId, in double atDistance)
void createOrientationConstraint(in string constraintName, in string joint1Name, in string joint2Name, in Quaternion_ p, in boolSeq mask)
core_idl::Path getPath(in unsigned long pathId)
void setErrorThreshold(in double threshold)
Set error threshold in numerical constraint resolution.
void createDistanceBetweenJointConstraint(in string constraintName, in string joint1Name, in string joint2Name, in double distance)
Names_t getSelected(in string type)
void addLockedJointConstraints(in string configProjName, in Names_t lockedJointNames)
void resetProblem()
Reset the current problem.
core_idl::ConfigValidation createConfigValidation(in string type, in pinocchio_idl::Device robot)
core_idl::ConfigurationShooter createConfigurationShooter(in string type, in core_idl::Problem _problem)
void setMaxNumThreads(in unsigned short n)
core_idl::Constraint createConstraintSet(in pinocchio_idl::Device robot, in string name)
void selectPathProjector(in string pathProjectorType, in double tolerance)
void createLockedExtraDof(in string lockedDofName, in unsigned long index, in floatSeq value)
void resetGoalConstraints()
Clear goal constraints.
double getTimeOutPathPlanning()
Get time out in path planning (in seconds)
void clearPathOptimizers()
Clear the vector of path optimizers.
void setRightHandSide(in floatSeq rhs)
constraints_idl::Implicit getConstraint(in string constraintName)
void getConstraintDimensions(in string constraintName, out unsigned long inputSize, out unsigned long inputDerivativeSize, out unsigned long outputSize, out unsigned long outputDerivativeSize)
Get constraint dimensions.
boolean loadPlugin(in string pluginName)
unsigned short getMaxNumThreads()
void resetGoalConfigs()
Reset goal configurations.
core_idl::PathValidation createPathValidation(in string type, in pinocchio_idl::Device robot, in value_type parameter)
void resetConstraintMap()
core_idl::Problem getProblem()
void selectConfigurationShooter(in string configurationShooterType)
void setGoalConstraints(in Names_t constraints)
Set goal as a task.
core_idl::PathValidation getPathValidation()
long connectedComponentOfNode(in unsigned long nodeId)
return the connected component index of the node
core_idl::Problem createProblem(in pinocchio_idl::Device robot)
void setMaxIterProjection(in unsigned long iterations)
Set maximal number of iterations in numerical constraint resolution.
core_idl::Distance getDistance()
floatSeq getInitialConfig()
boolean applyConstraints(in floatSeq input, out floatSeq output, out double residualError)
void filterCollisionPairs()
boolean reversePath(in unsigned long pathId, out unsigned long reversedPathId)
void createManipulability(in string name, in string function)
void setNumericalConstraintsLastPriorityOptional(in boolean optional)
floatSeq node(in unsigned long nodeId)
long numberPaths()
Get Number of paths.
void addConfigValidation(in string configValidationType)
core_idl::Roadmap readRoadmap(in string filename, in pinocchio_idl::Device robot)
any getParameter(in string name)
void extractPath(in unsigned long pathId, in double start, in double end)
boolean optimize(in floatSeq input, out floatSeq output, out floatSeq residualError)
void setDefaultLineSearchType(in string type)
core_idl::SteeringMethod createSteeringMethod(in string type, in core_idl::Problem _problem)
void computeValueAndJacobian(in floatSeq config, out floatSeq value, out floatSeqSeq jacobian)
void createTransformationR3xSO3Constraint(in string constraintName, in string joint1Name, in string joint2Name, in Transform_ frame1, in Transform_ frame2, in boolSeq mask)
void movePathToProblem(in unsigned long pathId, in string problemName, in Names_t jointNames)
void scCreateScalarMultiply(in string outName, in double scalar, in string inName)
See hpp::constraints::ScalarMultiply.
long numberConnectedComponents()
Number of connected components.
void setInitialConfig(in floatSeq dofArray)
void appendDirectPath(in unsigned long pathId, in floatSeq config, in boolean validate)
void createPositionConstraint(in string constraintName, in string joint1Name, in string joint2Name, in floatSeq point1, in floatSeq point2, in boolSeq mask)
void createConfigurationConstraint(in string constraintName, in floatSeq goal, in floatSeq weights)
unsigned long getMaxIterPathPlanning()
Get maximal number of iterations in path planning.
void setTimeOutPathPlanning(in double timeOut)
Set time out in path planning (in seconds)
core_idl::PathPlanner createPathPlanner(in string type, in core_idl::Problem _problem, in core_idl::Roadmap roadmap)
void writeRoadmap(in string filename, in core_idl::Roadmap roadmap, in pinocchio_idl::Device robot)
unsigned long addPath(in core_idl::PathVector _path)
void setRobot(in pinocchio_idl::Device robot)
string displayConstraints()
Display the constraint in the ConfigProjector.
void addEdgeToRoadmap(in floatSeq config1, in floatSeq config2, in unsigned long pathId, in boolean bothEdges)
floatSeqSeq getGoalConfigs()
void addPassiveDofs(in string constraintName, in Names_t jointNames)
void createLockedJointWithComp(in string lockedJointName, in string jointName, in floatSeq value, in ComparisonTypes_t comp)
void loadRoadmap(in string filename)
floatSeqSeq nodesConnectedComponent(in unsigned long connectedComponentId)
pinocchio_idl::CollisionObject getObstacle(in string name)
void createIdentityConstraint(in string constraintName, in Names_t inJoints, in Names_t outJoints)
void concatenatePath(in unsigned long startId, in unsigned long endId)
floatSeqSeq nodes()
Nodes of the roadmap.
void clearConfigValidations()
Clear the vector of config validations.
double pathLength(in unsigned long inPathId)
core_idl::PathProjector createPathProjector(in string type, in core_idl::Problem robot, in value_type parameter)
boolean getConstantRightHandSide(in string constraintName)
void resetConstraints()
Reset constraints.
void setRightHandSideFromConfig(in floatSeq config)
Definition constraints.idl:17
Definition _constraints.idl:24
Definition _problem.idl:17
Implement CORBA interface `‘Obstacle’'.
Definition client.hh:46
sequence< boolean > boolSeq
Definition common.idl:30
sequence< double > floatSeq
Robot configuration is defined by a sequence of dof value.
Definition common.idl:34
double Transform_[7]
Element of SE(3) represented by a vector and a unit quaternion.
Definition common.idl:38
sequence< intSeq > intSeqSeq
Definition common.idl:32
double Quaternion_[4]
Definition common.idl:42
sequence< floatSeq > floatSeqSeq
Definition common.idl:35
sequence< string > Names_t
Sequence of names.
Definition common.idl:23
double value_type
Definition common.idl:18
sequence< ComparisonType > ComparisonTypes_t
Definition common.idl:50
sequence< long > intSeq
Definition common.idl:31