hpp-corbaserver 6.0.0
Corba server for Humanoid Path Planner applications
 
Loading...
Searching...
No Matches
problem.idl
Go to the documentation of this file.
1// Copyright (C) 2009, 2010 by Florent Lamiraux, Thomas Moulard, JRL.
2//
3// This file is part of the hpp-corbaserver.
4//
5// This software is provided "as is" without warranty of any kind,
6// either expressed or implied, including but not limited to the
7// implied warranties of fitness for a particular purpose.
8//
9// See the COPYING file for more information.
10
11#ifndef HPP_CORBASERVER_PROBLEM_SERVER_IDL
12#define HPP_CORBASERVER_PROBLEM_SERVER_IDL
13#include <hpp/common.idl>
22
23module hpp
24{
25 module corbaserver {
27 interface Problem
28 {
30 void setRandomSeed (in long seed) raises (Error);
31
33 void setMaxNumThreads (in unsigned short n) raises (Error);
34
36 unsigned short getMaxNumThreads () raises (Error);
37
41 Names_t getAvailable (in string type) raises (Error);
42
47 Names_t getSelected (in string type) raises (Error);
48
51 void setParameter (in string name, in any value) raises (Error);
52
55 any getParameter (in string name) raises (Error);
56
59 string getParameterDoc (in string name) raises (Error);
60
65 boolean selectProblem (in string name) raises (Error);
66
68 void resetProblem () raises (Error);
69
71 boolean loadPlugin (in string pluginName) raises (Error);
72
78 void movePathToProblem (in unsigned long pathId, in string problemName,
79 in Names_t jointNames) raises (Error);
80
83
87 void setInitialConfig (in floatSeq dofArray) raises (Error);
88
92
96 void addGoalConfig (in floatSeq dofArray) raises (Error);
97
101
103 void resetGoalConfigs () raises (Error);
104
106 void setGoalConstraints(in Names_t constraints) raises(Error);
107
110
112
115
122 boolean applyConstraints (in floatSeq input, out floatSeq output,
123 out double residualError)
124 raises (Error);
125
132 boolean optimize (in floatSeq input, out floatSeq output,
133 out floatSeq residualError)
134 raises (Error);
135
146 void computeValueAndJacobian (in floatSeq config, out floatSeq value,
147 out floatSeqSeq jacobian) raises (Error);
148
157 boolean generateValidConfig (in unsigned long maxIter, out floatSeq output,
158 out double residualError)
159 raises (Error);
160
173 (in string constraintName, in string joint1Name,
174 in string joint2Name, in Quaternion_ p,
175 in boolSeq mask) raises (Error);
176
177
189 (in string constraintName, in string joint1Name,
190 in string joint2Name, in Transform_ ref,
191 in boolSeq mask) raises (Error);
192
196 (in string constraintName, in string joint1Name, in string joint2Name,
197 in Transform_ frame1, in Transform_ frame2, in boolSeq mask) raises (Error);
198
211 (in string constraintName, in string joint1Name,
212 in string joint2Name, in Transform_ frame1, in Transform_ frame2,
213 in boolSeq mask) raises (Error);
214
219 void createLockedJoint (in string lockedJointName,
220 in string jointName,
221 in floatSeq value) raises (Error);
222
228 void createLockedJointWithComp (in string lockedJointName,
229 in string jointName,
230 in floatSeq value,
231 in ComparisonTypes_t comp) raises (Error);
232
239 void createLockedExtraDof (in string lockedDofName,
240 in unsigned long index,
241 in floatSeq value) raises (Error);
242
246 void createManipulability (in string name,
247 in string function) raises (Error);
248
263 void createComBeetweenFeet (in string constraintName, in string comName,
264 in string jointLName, in string jointRName, in floatSeq pointL,
265 in floatSeq pointR, in string jointRefName, in floatSeq pointRef,
266 in boolSeq mask)
267 raises (Error);
268
278 void createRelativeComConstraint (in string constraintName, in string comName,
279 in string jointLName, in floatSeq point, in boolSeq mask)
280 raises (Error);
281
283 (in string constraintName, in Names_t floorJoints, in Names_t objectJoints,
284 in floatSeqSeq pts, in intSeqSeq objectTriangles,
285 in intSeqSeq floorTriangles) raises (Error);
286
298 void createPositionConstraint (in string constraintName,
299 in string joint1Name,
300 in string joint2Name,
301 in floatSeq point1,
302 in floatSeq point2,
303 in boolSeq mask)
304 raises (Error);
305
308 void createConfigurationConstraint (in string constraintName,
309 in floatSeq goal,
310 in floatSeq weights)
311 raises (Error);
312
313
322 (in string constraintName, in string joint1Name, in string joint2Name,
323 in double distance) raises (Error);
324
333 (in string constraintName, in string joint1Name, in Names_t objects,
334 in double distance) raises (Error);
335
344 (in string constraintName, in Names_t inJoints, in Names_t outJoints)
345 raises (Error);
346
348 void resetConstraints () raises (Error);
349
351 void resetConstraintMap () raises (Error);
352
356 void addPassiveDofs (in string constraintName, in Names_t jointNames)
357 raises (Error);
358
360 void getConstraintDimensions (in string constraintName,
361 out unsigned long inputSize , out unsigned long inputDerivativeSize,
362 out unsigned long outputSize, out unsigned long outputDerivativeSize)
363 raises (Error);
364
371 void setConstantRightHandSide (in string constraintName,
372 in boolean constant)
373 raises (Error);
374
378 boolean getConstantRightHandSide (in string constraintName)
379 raises (Error);
380
383
388 void setRightHandSide (in floatSeq rhs) raises (Error);
389
395 void setRightHandSideFromConfig (in floatSeq config) raises (Error);
396
401 void setRightHandSideByName (in string constraintName, in floatSeq rhs)
402 raises (Error);
403
408 void setRightHandSideFromConfigByName (in string constraintName, in floatSeq config)
409 raises (Error);
410
417 void addNumericalConstraints (in string configProjName,
418 in Names_t constraintNames,
419 in intSeq priorities)
420 raises (Error);
421
426 raises (Error);
427
434 void addLockedJointConstraints (in string configProjName,
435 in Names_t lockedJointNames) raises (Error);
436
438 string displayConstraints () raises (Error);
439
441 double getErrorThreshold () raises (Error);
442
444 void setErrorThreshold (in double threshold) raises (Error);
445
446 void setDefaultLineSearchType (in string type) raises (Error);
447
449 unsigned long getMaxIterProjection () raises (Error);
450
452 void setMaxIterProjection (in unsigned long iterations) raises (Error);
453
455 unsigned long getMaxIterPathPlanning () raises (Error);
456
458 void setMaxIterPathPlanning (in unsigned long iterations) raises (Error);
459
462
464 void scCreateScalarMultiply (in string outName, in double scalar, in string inName) raises (Error);
465
467 double getTimeOutPathPlanning () raises (Error);
468
470 void setTimeOutPathPlanning (in double timeOut) raises (Error);
471
472
475
478
482 void filterCollisionPairs () raises (Error);
483
485
488
493 void selectPathPlanner (in string pathPlannerType) raises (Error);
494
499 void selectConfigurationShooter (in string configurationShooterType) raises (Error);
500
505 void selectDistance (in string distanceType) raises (Error);
506
507
512 void selectSteeringMethod (in string steeringMethodType) raises (Error);
513
517 void addPathOptimizer (in string pathOptimizerType) raises (Error);
518
520 void clearPathOptimizers () raises (Error);
521
526 void addConfigValidation (in string configValidationType) raises (Error);
527
530
536 void selectPathValidation (in string pathValidationType,
537 in double tolerance) raises (Error);
538
544 void selectPathProjector (in string pathProjectorType,
545 in double tolerance) raises (Error);
546
550 boolean prepareSolveStepByStep () raises (Error);
551
556 boolean executeOneStep () raises (Error);
557
560 void finishSolveStepByStep () raises (Error);
561
566 intSeq solve() raises (Error);
567
576 boolean directPath (in floatSeq startConfig, in floatSeq endConfig,
577 in boolean validate,
578 out unsigned long pathId, out string report)
579 raises (Error);
580
583 boolean reversePath (in unsigned long pathId, out unsigned long reversedPathId)
584 raises (Error);
585
591 void addConfigToRoadmap (in floatSeq config) raises(Error);
592
601 void addEdgeToRoadmap (in floatSeq config1, in floatSeq config2,
602 in unsigned long pathId, in boolean bothEdges)
603 raises (Error);
604
606 void appendDirectPath (in unsigned long pathId, in floatSeq config, in boolean validate)
607 raises (Error);
608
610 void concatenatePath (in unsigned long startId, in unsigned long endId)
611 raises (Error);
612
614 void extractPath (in unsigned long pathId, in double start, in double end)
615 raises (Error);
616
618 void erasePath (in unsigned long pathId)
619 raises (Error);
620
623 boolean projectPath (in unsigned long patId) raises (Error);
624
626 long numberPaths () raises (Error);
627
633 intSeq optimizePath(in unsigned long inPathId) raises (Error);
634
638 double pathLength(in unsigned long inPathId) raises (Error);
639
644 floatSeq configAtParam(in unsigned long inPathId, in double atDistance)
645 raises (Error);
646
652 floatSeq derivativeAtParam(in unsigned long inPathId, in unsigned long orderId, in double atDistance)
653 raises (Error);
654
657 floatSeqSeq getWaypoints (in unsigned long pathId, out floatSeq times) raises (Error);
658
660
663
670
673
676
677 // number of nodes in the roadmap
678 long numberNodes() raises (Error);
679
680 // return the configuration of the node nodeId
681 floatSeq node(in unsigned long nodeId) raises(Error);
682
684 long connectedComponentOfEdge(in unsigned long edgeId) raises(Error);
685
687 long connectedComponentOfNode(in unsigned long nodeId) raises(Error);
688
690 long numberEdges () raises (Error);
691
693 void edge (in unsigned long edgeId, out floatSeq q1, out floatSeq q2)
694 raises (Error);
695
698
702 floatSeqSeq nodesConnectedComponent (in unsigned long connectedComponentId)
703 raises (Error);
704
711 floatSeq getNearestConfig(in floatSeq config, in long connectedComponentId, out double distance)
712 raises (Error);
713
715 void clearRoadmap () raises (Error);
716
720 void resetRoadmap () raises (Error);
721
725 void saveRoadmap (in string filename) raises (Error);
726
731 void loadRoadmap (in string filename) raises (Error);
733
735
736 void setDistance (in core_idl::Distance distance) raises (Error);
737
738 core_idl::Path getPath (in unsigned long pathId) raises (Error);
739
740 unsigned long addPath (in core_idl::PathVector _path) raises (Error);
741
746 void savePath (in core_idl::Path _path, in string filename) raises (Error);
747
751 core_idl::Path loadPath (in string filename) raises (Error);
752
754
756
758
760
761 constraints_idl::Implicit getConstraint (in string constraintName) raises (Error);
762
764
766
770
772
780 core_idl::Roadmap readRoadmap(in string filename,
782 raises (Error);
790 void writeRoadmap(in string filename,
791 in core_idl::Roadmap roadmap,
793 raises (Error);
794
795 core_idl::PathPlanner createPathPlanner (in string type, in core_idl::Problem _problem, in core_idl::Roadmap roadmap) raises (Error);
796 core_idl::PathOptimizer createPathOptimizer (in string type, in core_idl::Problem _problem) raises (Error);
797
800 core_idl::PathProjector createPathProjector (in string type, in core_idl::Problem robot, in value_type parameter) raises (Error);
802 core_idl::Distance createDistance (in string type, in core_idl::Problem _problem) raises (Error);
803 core_idl::SteeringMethod createSteeringMethod (in string type, in core_idl::Problem _problem) raises (Error);
804
806 core_idl::Constraint createConfigProjector (in pinocchio_idl::Device robot, in string name, in double threshold, in unsigned long iterations) raises (Error);
807
809 };
810 }; // interface Problem
811}; // module hpp
812#endif
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)
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)
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()
boolean applyConstraints(in floatSeq input, out floatSeq output, out double residualError)
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 robot.py:1
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