hpp-corbaserver
6.0.0
Corba server for Humanoid Path Planner applications
|
#include <hpp/corbaserver/problem-idl.hh>
Public Member Functions | |
void | setRandomSeed (::CORBA::Long seed) |
void | setMaxNumThreads (::CORBA::UShort n) |
::CORBA::UShort | getMaxNumThreads () |
Names_t * | getAvailable (const char *type) |
Names_t * | getSelected (const char *type) |
void | setParameter (const char *name, const ::CORBA::Any &value) |
::CORBA::Any * | getParameter (const char *name) |
char * | getParameterDoc (const char *name) |
::CORBA::Boolean | selectProblem (const char *name) |
void | resetProblem () |
::CORBA::Boolean | loadPlugin (const char *pluginName) |
void | movePathToProblem (::CORBA::ULong pathId, const char *problemName, const ::hpp::Names_t &jointNames) |
void | setInitialConfig (const ::hpp::floatSeq &dofArray) |
floatSeq * | getInitialConfig () |
void | addGoalConfig (const ::hpp::floatSeq &dofArray) |
floatSeqSeq * | getGoalConfigs () |
void | resetGoalConfigs () |
void | setGoalConstraints (const ::hpp::Names_t &constraints) |
void | resetGoalConstraints () |
::CORBA::Boolean | applyConstraints (const ::hpp::floatSeq &input, ::hpp::floatSeq_out output, ::CORBA::Double &residualError) |
::CORBA::Boolean | optimize (const ::hpp::floatSeq &input, ::hpp::floatSeq_out output, ::hpp::floatSeq_out residualError) |
void | computeValueAndJacobian (const ::hpp::floatSeq &config, ::hpp::floatSeq_out value, ::hpp::floatSeqSeq_out jacobian) |
::CORBA::Boolean | generateValidConfig (::CORBA::ULong maxIter, ::hpp::floatSeq_out output, ::CORBA::Double &residualError) |
void | createOrientationConstraint (const char *constraintName, const char *joint1Name, const char *joint2Name, const ::hpp::Quaternion_ p, const ::hpp::boolSeq &mask) |
void | createTransformationConstraint (const char *constraintName, const char *joint1Name, const char *joint2Name, const ::hpp::Transform_ ref, const ::hpp::boolSeq &mask) |
void | createTransformationR3xSO3Constraint (const char *constraintName, const char *joint1Name, const char *joint2Name, const ::hpp::Transform_ frame1, const ::hpp::Transform_ frame2, const ::hpp::boolSeq &mask) |
void | createTransformationConstraint2 (const char *constraintName, const char *joint1Name, const char *joint2Name, const ::hpp::Transform_ frame1, const ::hpp::Transform_ frame2, const ::hpp::boolSeq &mask) |
void | createLockedJoint (const char *lockedJointName, const char *jointName, const ::hpp::floatSeq &value) |
void | createLockedJointWithComp (const char *lockedJointName, const char *jointName, const ::hpp::floatSeq &value, const ::hpp::ComparisonTypes_t &comp) |
void | createLockedExtraDof (const char *lockedDofName, ::CORBA::ULong index, const ::hpp::floatSeq &value) |
void | createManipulability (const char *name, const char *function) |
void | createComBeetweenFeet (const char *constraintName, const char *comName, const char *jointLName, const char *jointRName, const ::hpp::floatSeq &pointL, const ::hpp::floatSeq &pointR, const char *jointRefName, const ::hpp::floatSeq &pointRef, const ::hpp::boolSeq &mask) |
void | createRelativeComConstraint (const char *constraintName, const char *comName, const char *jointLName, const ::hpp::floatSeq &point, const ::hpp::boolSeq &mask) |
void | createConvexShapeContactConstraint (const char *constraintName, const ::hpp::Names_t &floorJoints, const ::hpp::Names_t &objectJoints, const ::hpp::floatSeqSeq &pts, const ::hpp::intSeqSeq &objectTriangles, const ::hpp::intSeqSeq &floorTriangles) |
void | createPositionConstraint (const char *constraintName, const char *joint1Name, const char *joint2Name, const ::hpp::floatSeq &point1, const ::hpp::floatSeq &point2, const ::hpp::boolSeq &mask) |
void | createConfigurationConstraint (const char *constraintName, const ::hpp::floatSeq &goal, const ::hpp::floatSeq &weights) |
void | createDistanceBetweenJointConstraint (const char *constraintName, const char *joint1Name, const char *joint2Name, ::CORBA::Double distance) |
void | createDistanceBetweenJointAndObjects (const char *constraintName, const char *joint1Name, const ::hpp::Names_t &objects, ::CORBA::Double distance) |
void | createIdentityConstraint (const char *constraintName, const ::hpp::Names_t &inJoints, const ::hpp::Names_t &outJoints) |
void | resetConstraints () |
void | resetConstraintMap () |
void | addPassiveDofs (const char *constraintName, const ::hpp::Names_t &jointNames) |
void | getConstraintDimensions (const char *constraintName, ::CORBA::ULong &inputSize, ::CORBA::ULong &inputDerivativeSize, ::CORBA::ULong &outputSize, ::CORBA::ULong &outputDerivativeSize) |
void | setConstantRightHandSide (const char *constraintName, ::CORBA::Boolean constant) |
::CORBA::Boolean | getConstantRightHandSide (const char *constraintName) |
floatSeq * | getRightHandSide () |
void | setRightHandSide (const ::hpp::floatSeq &rhs) |
void | setRightHandSideFromConfig (const ::hpp::floatSeq &config) |
void | setRightHandSideByName (const char *constraintName, const ::hpp::floatSeq &rhs) |
void | setRightHandSideFromConfigByName (const char *constraintName, const ::hpp::floatSeq &config) |
void | addNumericalConstraints (const char *configProjName, const ::hpp::Names_t &constraintNames, const ::hpp::intSeq &priorities) |
void | setNumericalConstraintsLastPriorityOptional (::CORBA::Boolean optional) |
void | addLockedJointConstraints (const char *configProjName, const ::hpp::Names_t &lockedJointNames) |
char * | displayConstraints () |
::CORBA::Double | getErrorThreshold () |
void | setErrorThreshold (::CORBA::Double threshold) |
void | setDefaultLineSearchType (const char *type) |
::CORBA::ULong | getMaxIterProjection () |
void | setMaxIterProjection (::CORBA::ULong iterations) |
::CORBA::ULong | getMaxIterPathPlanning () |
void | setMaxIterPathPlanning (::CORBA::ULong iterations) |
void | scCreateScalarMultiply (const char *outName, ::CORBA::Double scalar, const char *inName) |
::CORBA::Double | getTimeOutPathPlanning () |
void | setTimeOutPathPlanning (::CORBA::Double timeOut) |
void | filterCollisionPairs () |
void | selectPathPlanner (const char *pathPlannerType) |
void | selectConfigurationShooter (const char *configurationShooterType) |
void | selectDistance (const char *distanceType) |
void | selectSteeringMethod (const char *steeringMethodType) |
void | addPathOptimizer (const char *pathOptimizerType) |
void | clearPathOptimizers () |
void | addConfigValidation (const char *configValidationType) |
void | clearConfigValidations () |
void | selectPathValidation (const char *pathValidationType, ::CORBA::Double tolerance) |
void | selectPathProjector (const char *pathProjectorType, ::CORBA::Double tolerance) |
::CORBA::Boolean | prepareSolveStepByStep () |
::CORBA::Boolean | executeOneStep () |
void | finishSolveStepByStep () |
intSeq * | solve () |
::CORBA::Boolean | directPath (const ::hpp::floatSeq &startConfig, const ::hpp::floatSeq &endConfig, ::CORBA::Boolean validate, ::CORBA::ULong &pathId, ::CORBA::String_out report) |
::CORBA::Boolean | reversePath (::CORBA::ULong pathId, ::CORBA::ULong &reversedPathId) |
void | addConfigToRoadmap (const ::hpp::floatSeq &config) |
void | addEdgeToRoadmap (const ::hpp::floatSeq &config1, const ::hpp::floatSeq &config2, ::CORBA::ULong pathId, ::CORBA::Boolean bothEdges) |
void | appendDirectPath (::CORBA::ULong pathId, const ::hpp::floatSeq &config, ::CORBA::Boolean validate) |
void | concatenatePath (::CORBA::ULong startId, ::CORBA::ULong endId) |
void | extractPath (::CORBA::ULong pathId, ::CORBA::Double start, ::CORBA::Double end) |
void | erasePath (::CORBA::ULong pathId) |
::CORBA::Boolean | projectPath (::CORBA::ULong patId) |
::CORBA::Long | numberPaths () |
intSeq * | optimizePath (::CORBA::ULong inPathId) |
::CORBA::Double | pathLength (::CORBA::ULong inPathId) |
floatSeq * | configAtParam (::CORBA::ULong inPathId, ::CORBA::Double atDistance) |
floatSeq * | derivativeAtParam (::CORBA::ULong inPathId, ::CORBA::ULong orderId, ::CORBA::Double atDistance) |
floatSeqSeq * | getWaypoints (::CORBA::ULong pathId, ::hpp::floatSeq_out times) |
void | interruptPathPlanning () |
floatSeqSeq * | nodes () |
::CORBA::Long | numberNodes () |
floatSeq * | node (::CORBA::ULong nodeId) |
::CORBA::Long | connectedComponentOfEdge (::CORBA::ULong edgeId) |
::CORBA::Long | connectedComponentOfNode (::CORBA::ULong nodeId) |
::CORBA::Long | numberEdges () |
void | edge (::CORBA::ULong edgeId, ::hpp::floatSeq_out q1, ::hpp::floatSeq_out q2) |
::CORBA::Long | numberConnectedComponents () |
floatSeqSeq * | nodesConnectedComponent (::CORBA::ULong connectedComponentId) |
floatSeq * | getNearestConfig (const ::hpp::floatSeq &config, ::CORBA::Long connectedComponentId, ::CORBA::Double &distance) |
void | clearRoadmap () |
void | resetRoadmap () |
void | saveRoadmap (const char *filename) |
void | loadRoadmap (const char *filename) |
core_idl::Distance_ptr | getDistance () |
void | setDistance (::hpp::core_idl::Distance_ptr distance) |
core_idl::Path_ptr | getPath (::CORBA::ULong pathId) |
::CORBA::ULong | addPath (::hpp::core_idl::PathVector_ptr path) |
void | savePath (::hpp::core_idl::Path_ptr path, const char *filename) |
core_idl::Path_ptr | loadPath (const char *filename) |
core_idl::SteeringMethod_ptr | getSteeringMethod () |
core_idl::PathValidation_ptr | getPathValidation () |
core_idl::PathPlanner_ptr | getPathPlanner () |
core_idl::Problem_ptr | getProblem () |
constraints_idl::Implicit_ptr | getConstraint (const char *constraintName) |
void | setRobot (::hpp::pinocchio_idl::Device_ptr robot) |
pinocchio_idl::CollisionObject_ptr | getObstacle (const char *name) |
core_idl::Problem_ptr | createProblem (::hpp::pinocchio_idl::Device_ptr robot) |
core_idl::Roadmap_ptr | createRoadmap (::hpp::core_idl::Distance_ptr distance, ::hpp::pinocchio_idl::Device_ptr robot) |
core_idl::Roadmap_ptr | readRoadmap (const char *filename, ::hpp::pinocchio_idl::Device_ptr robot) |
void | writeRoadmap (const char *filename, ::hpp::core_idl::Roadmap_ptr roadmap, ::hpp::pinocchio_idl::Device_ptr robot) |
core_idl::PathPlanner_ptr | createPathPlanner (const char *type, ::hpp::core_idl::Problem_ptr problem, ::hpp::core_idl::Roadmap_ptr roadmap) |
core_idl::PathOptimizer_ptr | createPathOptimizer (const char *type, ::hpp::core_idl::Problem_ptr problem) |
core_idl::ConfigValidation_ptr | createConfigValidation (const char *type, ::hpp::pinocchio_idl::Device_ptr robot) |
core_idl::PathValidation_ptr | createPathValidation (const char *type, ::hpp::pinocchio_idl::Device_ptr robot, ::hpp::value_type parameter) |
core_idl::PathProjector_ptr | createPathProjector (const char *type, ::hpp::core_idl::Problem_ptr robot, ::hpp::value_type parameter) |
core_idl::ConfigurationShooter_ptr | createConfigurationShooter (const char *type, ::hpp::core_idl::Problem_ptr problem) |
core_idl::Distance_ptr | createDistance (const char *type, ::hpp::core_idl::Problem_ptr problem) |
core_idl::SteeringMethod_ptr | createSteeringMethod (const char *type, ::hpp::core_idl::Problem_ptr problem) |
core_idl::Constraint_ptr | createConstraintSet (::hpp::pinocchio_idl::Device_ptr robot, const char *name) |
core_idl::Constraint_ptr | createConfigProjector (::hpp::pinocchio_idl::Device_ptr robot, const char *name, ::CORBA::Double threshold, ::CORBA::ULong iterations) |
_objref_Problem () | |
_objref_Problem (omniIOR *, omniIdentity *) | |
void | deleteThis () |
::CORBA::Boolean | deleteIfExpired () |
void | persistantStorage (::CORBA::Boolean persistant) |
pinocchio_idl::Device_ptr | robot () |
void | setInitConfig (const ::hpp::floatSeq &init) |
floatSeq * | getInitConfig () |
void | addGoalConfig (const ::hpp::floatSeq &goal) |
void | resetGoalConfigs () |
Constraint_ptr | getConstraints () |
void | setConstraints (::hpp::core_idl::Constraint_ptr constraints) |
Distance_ptr | getDistance () |
void | setDistance (::hpp::core_idl::Distance_ptr d) |
SteeringMethod_ptr | getSteeringMethod () |
void | setSteeringMethod (::hpp::core_idl::SteeringMethod_ptr d) |
PathValidation_ptr | getPathValidation () |
void | setPathValidation (::hpp::core_idl::PathValidation_ptr d) |
PathProjector_ptr | getPathProjector () |
void | setPathProjector (::hpp::core_idl::PathProjector_ptr p) |
ConfigValidation_ptr | getConfigValidations () |
void | clearConfigValidations () |
void | addConfigValidation (::hpp::core_idl::ConfigValidation_ptr cfgValidation) |
ConfigurationShooter_ptr | getConfigurationShooter () |
void | setConfigurationShooter (::hpp::core_idl::ConfigurationShooter_ptr d) |
void | filterCollisionPairs () |
void | setSecurityMargins (const ::hpp::floatSeqSeq &margins) |
void | addObstacle (::hpp::pinocchio_idl::CollisionObject_ptr object) |
void | setParameter (const char *name, const ::CORBA::Any &value) |
::CORBA::Any * | getParameter (const char *name) |
_objref_Problem () | |
_objref_Problem (omniIOR *, omniIdentity *) | |
Protected Member Functions | |
virtual | ~_objref_Problem () |
virtual | ~_objref_Problem () |
Friends | |
class | Problem |
|
inline |
_objref_Problem::_objref_Problem | ( | omniIOR * | , |
omniIdentity * | |||
) |
|
protectedvirtual |
|
inline |
_objref_Problem::_objref_Problem | ( | omniIOR * | , |
omniIdentity * | |||
) |
|
protectedvirtual |
void _objref_Problem::addConfigToRoadmap | ( | const ::hpp::floatSeq & | config | ) |
void _objref_Problem::addConfigValidation | ( | ::hpp::core_idl::ConfigValidation_ptr | cfgValidation | ) |
void _objref_Problem::addConfigValidation | ( | const char * | configValidationType | ) |
void _objref_Problem::addEdgeToRoadmap | ( | const ::hpp::floatSeq & | config1, |
const ::hpp::floatSeq & | config2, | ||
::CORBA::ULong | pathId, | ||
::CORBA::Boolean | bothEdges | ||
) |
void _objref_Problem::addGoalConfig | ( | const ::hpp::floatSeq & | dofArray | ) |
void _objref_Problem::addGoalConfig | ( | const ::hpp::floatSeq & | goal | ) |
void _objref_Problem::addLockedJointConstraints | ( | const char * | configProjName, |
const ::hpp::Names_t & | lockedJointNames | ||
) |
void _objref_Problem::addNumericalConstraints | ( | const char * | configProjName, |
const ::hpp::Names_t & | constraintNames, | ||
const ::hpp::intSeq & | priorities | ||
) |
void _objref_Problem::addObstacle | ( | ::hpp::pinocchio_idl::CollisionObject_ptr | object | ) |
void _objref_Problem::addPassiveDofs | ( | const char * | constraintName, |
const ::hpp::Names_t & | jointNames | ||
) |
::CORBA::ULong _objref_Problem::addPath | ( | ::hpp::core_idl::PathVector_ptr | path | ) |
void _objref_Problem::addPathOptimizer | ( | const char * | pathOptimizerType | ) |
void _objref_Problem::appendDirectPath | ( | ::CORBA::ULong | pathId, |
const ::hpp::floatSeq & | config, | ||
::CORBA::Boolean | validate | ||
) |
::CORBA::Boolean _objref_Problem::applyConstraints | ( | const ::hpp::floatSeq & | input, |
::hpp::floatSeq_out | output, | ||
::CORBA::Double & | residualError | ||
) |
void _objref_Problem::clearConfigValidations | ( | ) |
void _objref_Problem::clearConfigValidations | ( | ) |
void _objref_Problem::clearPathOptimizers | ( | ) |
void _objref_Problem::clearRoadmap | ( | ) |
void _objref_Problem::computeValueAndJacobian | ( | const ::hpp::floatSeq & | config, |
::hpp::floatSeq_out | value, | ||
::hpp::floatSeqSeq_out | jacobian | ||
) |
void _objref_Problem::concatenatePath | ( | ::CORBA::ULong | startId, |
::CORBA::ULong | endId | ||
) |
floatSeq* _objref_Problem::configAtParam | ( | ::CORBA::ULong | inPathId, |
::CORBA::Double | atDistance | ||
) |
::CORBA::Long _objref_Problem::connectedComponentOfEdge | ( | ::CORBA::ULong | edgeId | ) |
::CORBA::Long _objref_Problem::connectedComponentOfNode | ( | ::CORBA::ULong | nodeId | ) |
void _objref_Problem::createComBeetweenFeet | ( | const char * | constraintName, |
const char * | comName, | ||
const char * | jointLName, | ||
const char * | jointRName, | ||
const ::hpp::floatSeq & | pointL, | ||
const ::hpp::floatSeq & | pointR, | ||
const char * | jointRefName, | ||
const ::hpp::floatSeq & | pointRef, | ||
const ::hpp::boolSeq & | mask | ||
) |
core_idl::Constraint_ptr _objref_Problem::createConfigProjector | ( | ::hpp::pinocchio_idl::Device_ptr | robot, |
const char * | name, | ||
::CORBA::Double | threshold, | ||
::CORBA::ULong | iterations | ||
) |
void _objref_Problem::createConfigurationConstraint | ( | const char * | constraintName, |
const ::hpp::floatSeq & | goal, | ||
const ::hpp::floatSeq & | weights | ||
) |
core_idl::ConfigurationShooter_ptr _objref_Problem::createConfigurationShooter | ( | const char * | type, |
::hpp::core_idl::Problem_ptr | problem | ||
) |
core_idl::ConfigValidation_ptr _objref_Problem::createConfigValidation | ( | const char * | type, |
::hpp::pinocchio_idl::Device_ptr | robot | ||
) |
core_idl::Constraint_ptr _objref_Problem::createConstraintSet | ( | ::hpp::pinocchio_idl::Device_ptr | robot, |
const char * | name | ||
) |
void _objref_Problem::createConvexShapeContactConstraint | ( | const char * | constraintName, |
const ::hpp::Names_t & | floorJoints, | ||
const ::hpp::Names_t & | objectJoints, | ||
const ::hpp::floatSeqSeq & | pts, | ||
const ::hpp::intSeqSeq & | objectTriangles, | ||
const ::hpp::intSeqSeq & | floorTriangles | ||
) |
core_idl::Distance_ptr _objref_Problem::createDistance | ( | const char * | type, |
::hpp::core_idl::Problem_ptr | problem | ||
) |
void _objref_Problem::createDistanceBetweenJointAndObjects | ( | const char * | constraintName, |
const char * | joint1Name, | ||
const ::hpp::Names_t & | objects, | ||
::CORBA::Double | distance | ||
) |
void _objref_Problem::createDistanceBetweenJointConstraint | ( | const char * | constraintName, |
const char * | joint1Name, | ||
const char * | joint2Name, | ||
::CORBA::Double | distance | ||
) |
void _objref_Problem::createIdentityConstraint | ( | const char * | constraintName, |
const ::hpp::Names_t & | inJoints, | ||
const ::hpp::Names_t & | outJoints | ||
) |
void _objref_Problem::createLockedExtraDof | ( | const char * | lockedDofName, |
::CORBA::ULong | index, | ||
const ::hpp::floatSeq & | value | ||
) |
void _objref_Problem::createLockedJoint | ( | const char * | lockedJointName, |
const char * | jointName, | ||
const ::hpp::floatSeq & | value | ||
) |
void _objref_Problem::createLockedJointWithComp | ( | const char * | lockedJointName, |
const char * | jointName, | ||
const ::hpp::floatSeq & | value, | ||
const ::hpp::ComparisonTypes_t & | comp | ||
) |
void _objref_Problem::createManipulability | ( | const char * | name, |
const char * | function | ||
) |
void _objref_Problem::createOrientationConstraint | ( | const char * | constraintName, |
const char * | joint1Name, | ||
const char * | joint2Name, | ||
const ::hpp::Quaternion_ | p, | ||
const ::hpp::boolSeq & | mask | ||
) |
core_idl::PathOptimizer_ptr _objref_Problem::createPathOptimizer | ( | const char * | type, |
::hpp::core_idl::Problem_ptr | problem | ||
) |
core_idl::PathPlanner_ptr _objref_Problem::createPathPlanner | ( | const char * | type, |
::hpp::core_idl::Problem_ptr | problem, | ||
::hpp::core_idl::Roadmap_ptr | roadmap | ||
) |
core_idl::PathProjector_ptr _objref_Problem::createPathProjector | ( | const char * | type, |
::hpp::core_idl::Problem_ptr | robot, | ||
::hpp::value_type | parameter | ||
) |
core_idl::PathValidation_ptr _objref_Problem::createPathValidation | ( | const char * | type, |
::hpp::pinocchio_idl::Device_ptr | robot, | ||
::hpp::value_type | parameter | ||
) |
void _objref_Problem::createPositionConstraint | ( | const char * | constraintName, |
const char * | joint1Name, | ||
const char * | joint2Name, | ||
const ::hpp::floatSeq & | point1, | ||
const ::hpp::floatSeq & | point2, | ||
const ::hpp::boolSeq & | mask | ||
) |
core_idl::Problem_ptr _objref_Problem::createProblem | ( | ::hpp::pinocchio_idl::Device_ptr | robot | ) |
void _objref_Problem::createRelativeComConstraint | ( | const char * | constraintName, |
const char * | comName, | ||
const char * | jointLName, | ||
const ::hpp::floatSeq & | point, | ||
const ::hpp::boolSeq & | mask | ||
) |
core_idl::Roadmap_ptr _objref_Problem::createRoadmap | ( | ::hpp::core_idl::Distance_ptr | distance, |
::hpp::pinocchio_idl::Device_ptr | robot | ||
) |
core_idl::SteeringMethod_ptr _objref_Problem::createSteeringMethod | ( | const char * | type, |
::hpp::core_idl::Problem_ptr | problem | ||
) |
void _objref_Problem::createTransformationConstraint | ( | const char * | constraintName, |
const char * | joint1Name, | ||
const char * | joint2Name, | ||
const ::hpp::Transform_ | ref, | ||
const ::hpp::boolSeq & | mask | ||
) |
void _objref_Problem::createTransformationConstraint2 | ( | const char * | constraintName, |
const char * | joint1Name, | ||
const char * | joint2Name, | ||
const ::hpp::Transform_ | frame1, | ||
const ::hpp::Transform_ | frame2, | ||
const ::hpp::boolSeq & | mask | ||
) |
void _objref_Problem::createTransformationR3xSO3Constraint | ( | const char * | constraintName, |
const char * | joint1Name, | ||
const char * | joint2Name, | ||
const ::hpp::Transform_ | frame1, | ||
const ::hpp::Transform_ | frame2, | ||
const ::hpp::boolSeq & | mask | ||
) |
::CORBA::Boolean _objref_Problem::deleteIfExpired | ( | ) |
void _objref_Problem::deleteThis | ( | ) |
floatSeq* _objref_Problem::derivativeAtParam | ( | ::CORBA::ULong | inPathId, |
::CORBA::ULong | orderId, | ||
::CORBA::Double | atDistance | ||
) |
::CORBA::Boolean _objref_Problem::directPath | ( | const ::hpp::floatSeq & | startConfig, |
const ::hpp::floatSeq & | endConfig, | ||
::CORBA::Boolean | validate, | ||
::CORBA::ULong & | pathId, | ||
::CORBA::String_out | report | ||
) |
char* _objref_Problem::displayConstraints | ( | ) |
void _objref_Problem::edge | ( | ::CORBA::ULong | edgeId, |
::hpp::floatSeq_out | q1, | ||
::hpp::floatSeq_out | q2 | ||
) |
void _objref_Problem::erasePath | ( | ::CORBA::ULong | pathId | ) |
::CORBA::Boolean _objref_Problem::executeOneStep | ( | ) |
void _objref_Problem::extractPath | ( | ::CORBA::ULong | pathId, |
::CORBA::Double | start, | ||
::CORBA::Double | end | ||
) |
void _objref_Problem::filterCollisionPairs | ( | ) |
void _objref_Problem::filterCollisionPairs | ( | ) |
void _objref_Problem::finishSolveStepByStep | ( | ) |
::CORBA::Boolean _objref_Problem::generateValidConfig | ( | ::CORBA::ULong | maxIter, |
::hpp::floatSeq_out | output, | ||
::CORBA::Double & | residualError | ||
) |
Names_t* _objref_Problem::getAvailable | ( | const char * | type | ) |
ConfigurationShooter_ptr _objref_Problem::getConfigurationShooter | ( | ) |
ConfigValidation_ptr _objref_Problem::getConfigValidations | ( | ) |
::CORBA::Boolean _objref_Problem::getConstantRightHandSide | ( | const char * | constraintName | ) |
constraints_idl::Implicit_ptr _objref_Problem::getConstraint | ( | const char * | constraintName | ) |
void _objref_Problem::getConstraintDimensions | ( | const char * | constraintName, |
::CORBA::ULong & | inputSize, | ||
::CORBA::ULong & | inputDerivativeSize, | ||
::CORBA::ULong & | outputSize, | ||
::CORBA::ULong & | outputDerivativeSize | ||
) |
Constraint_ptr _objref_Problem::getConstraints | ( | ) |
core_idl::Distance_ptr _objref_Problem::getDistance | ( | ) |
Distance_ptr _objref_Problem::getDistance | ( | ) |
::CORBA::Double _objref_Problem::getErrorThreshold | ( | ) |
floatSeqSeq* _objref_Problem::getGoalConfigs | ( | ) |
floatSeq* _objref_Problem::getInitConfig | ( | ) |
floatSeq* _objref_Problem::getInitialConfig | ( | ) |
::CORBA::ULong _objref_Problem::getMaxIterPathPlanning | ( | ) |
::CORBA::ULong _objref_Problem::getMaxIterProjection | ( | ) |
::CORBA::UShort _objref_Problem::getMaxNumThreads | ( | ) |
floatSeq* _objref_Problem::getNearestConfig | ( | const ::hpp::floatSeq & | config, |
::CORBA::Long | connectedComponentId, | ||
::CORBA::Double & | distance | ||
) |
pinocchio_idl::CollisionObject_ptr _objref_Problem::getObstacle | ( | const char * | name | ) |
::CORBA::Any* _objref_Problem::getParameter | ( | const char * | name | ) |
::CORBA::Any* _objref_Problem::getParameter | ( | const char * | name | ) |
char* _objref_Problem::getParameterDoc | ( | const char * | name | ) |
core_idl::Path_ptr _objref_Problem::getPath | ( | ::CORBA::ULong | pathId | ) |
core_idl::PathPlanner_ptr _objref_Problem::getPathPlanner | ( | ) |
PathProjector_ptr _objref_Problem::getPathProjector | ( | ) |
core_idl::PathValidation_ptr _objref_Problem::getPathValidation | ( | ) |
PathValidation_ptr _objref_Problem::getPathValidation | ( | ) |
core_idl::Problem_ptr _objref_Problem::getProblem | ( | ) |
floatSeq* _objref_Problem::getRightHandSide | ( | ) |
Names_t* _objref_Problem::getSelected | ( | const char * | type | ) |
core_idl::SteeringMethod_ptr _objref_Problem::getSteeringMethod | ( | ) |
SteeringMethod_ptr _objref_Problem::getSteeringMethod | ( | ) |
::CORBA::Double _objref_Problem::getTimeOutPathPlanning | ( | ) |
floatSeqSeq* _objref_Problem::getWaypoints | ( | ::CORBA::ULong | pathId, |
::hpp::floatSeq_out | times | ||
) |
void _objref_Problem::interruptPathPlanning | ( | ) |
core_idl::Path_ptr _objref_Problem::loadPath | ( | const char * | filename | ) |
::CORBA::Boolean _objref_Problem::loadPlugin | ( | const char * | pluginName | ) |
void _objref_Problem::loadRoadmap | ( | const char * | filename | ) |
void _objref_Problem::movePathToProblem | ( | ::CORBA::ULong | pathId, |
const char * | problemName, | ||
const ::hpp::Names_t & | jointNames | ||
) |
floatSeq* _objref_Problem::node | ( | ::CORBA::ULong | nodeId | ) |
floatSeqSeq* _objref_Problem::nodes | ( | ) |
floatSeqSeq* _objref_Problem::nodesConnectedComponent | ( | ::CORBA::ULong | connectedComponentId | ) |
::CORBA::Long _objref_Problem::numberConnectedComponents | ( | ) |
::CORBA::Long _objref_Problem::numberEdges | ( | ) |
::CORBA::Long _objref_Problem::numberNodes | ( | ) |
::CORBA::Long _objref_Problem::numberPaths | ( | ) |
::CORBA::Boolean _objref_Problem::optimize | ( | const ::hpp::floatSeq & | input, |
::hpp::floatSeq_out | output, | ||
::hpp::floatSeq_out | residualError | ||
) |
intSeq* _objref_Problem::optimizePath | ( | ::CORBA::ULong | inPathId | ) |
::CORBA::Double _objref_Problem::pathLength | ( | ::CORBA::ULong | inPathId | ) |
void _objref_Problem::persistantStorage | ( | ::CORBA::Boolean | persistant | ) |
::CORBA::Boolean _objref_Problem::prepareSolveStepByStep | ( | ) |
::CORBA::Boolean _objref_Problem::projectPath | ( | ::CORBA::ULong | patId | ) |
core_idl::Roadmap_ptr _objref_Problem::readRoadmap | ( | const char * | filename, |
::hpp::pinocchio_idl::Device_ptr | robot | ||
) |
void _objref_Problem::resetConstraintMap | ( | ) |
void _objref_Problem::resetConstraints | ( | ) |
void _objref_Problem::resetGoalConfigs | ( | ) |
void _objref_Problem::resetGoalConfigs | ( | ) |
void _objref_Problem::resetGoalConstraints | ( | ) |
void _objref_Problem::resetProblem | ( | ) |
void _objref_Problem::resetRoadmap | ( | ) |
::CORBA::Boolean _objref_Problem::reversePath | ( | ::CORBA::ULong | pathId, |
::CORBA::ULong & | reversedPathId | ||
) |
pinocchio_idl::Device_ptr _objref_Problem::robot | ( | ) |
void _objref_Problem::savePath | ( | ::hpp::core_idl::Path_ptr | path, |
const char * | filename | ||
) |
void _objref_Problem::saveRoadmap | ( | const char * | filename | ) |
void _objref_Problem::scCreateScalarMultiply | ( | const char * | outName, |
::CORBA::Double | scalar, | ||
const char * | inName | ||
) |
void _objref_Problem::selectConfigurationShooter | ( | const char * | configurationShooterType | ) |
void _objref_Problem::selectDistance | ( | const char * | distanceType | ) |
void _objref_Problem::selectPathPlanner | ( | const char * | pathPlannerType | ) |
void _objref_Problem::selectPathProjector | ( | const char * | pathProjectorType, |
::CORBA::Double | tolerance | ||
) |
void _objref_Problem::selectPathValidation | ( | const char * | pathValidationType, |
::CORBA::Double | tolerance | ||
) |
::CORBA::Boolean _objref_Problem::selectProblem | ( | const char * | name | ) |
void _objref_Problem::selectSteeringMethod | ( | const char * | steeringMethodType | ) |
void _objref_Problem::setConfigurationShooter | ( | ::hpp::core_idl::ConfigurationShooter_ptr | d | ) |
void _objref_Problem::setConstantRightHandSide | ( | const char * | constraintName, |
::CORBA::Boolean | constant | ||
) |
void _objref_Problem::setConstraints | ( | ::hpp::core_idl::Constraint_ptr | constraints | ) |
void _objref_Problem::setDefaultLineSearchType | ( | const char * | type | ) |
void _objref_Problem::setDistance | ( | ::hpp::core_idl::Distance_ptr | d | ) |
void _objref_Problem::setDistance | ( | ::hpp::core_idl::Distance_ptr | distance | ) |
void _objref_Problem::setErrorThreshold | ( | ::CORBA::Double | threshold | ) |
void _objref_Problem::setGoalConstraints | ( | const ::hpp::Names_t & | constraints | ) |
void _objref_Problem::setInitConfig | ( | const ::hpp::floatSeq & | init | ) |
void _objref_Problem::setInitialConfig | ( | const ::hpp::floatSeq & | dofArray | ) |
void _objref_Problem::setMaxIterPathPlanning | ( | ::CORBA::ULong | iterations | ) |
void _objref_Problem::setMaxIterProjection | ( | ::CORBA::ULong | iterations | ) |
void _objref_Problem::setMaxNumThreads | ( | ::CORBA::UShort | n | ) |
void _objref_Problem::setNumericalConstraintsLastPriorityOptional | ( | ::CORBA::Boolean | optional | ) |
void _objref_Problem::setParameter | ( | const char * | name, |
const ::CORBA::Any & | value | ||
) |
void _objref_Problem::setParameter | ( | const char * | name, |
const ::CORBA::Any & | value | ||
) |
void _objref_Problem::setPathProjector | ( | ::hpp::core_idl::PathProjector_ptr | p | ) |
void _objref_Problem::setPathValidation | ( | ::hpp::core_idl::PathValidation_ptr | d | ) |
void _objref_Problem::setRandomSeed | ( | ::CORBA::Long | seed | ) |
void _objref_Problem::setRightHandSide | ( | const ::hpp::floatSeq & | rhs | ) |
void _objref_Problem::setRightHandSideByName | ( | const char * | constraintName, |
const ::hpp::floatSeq & | rhs | ||
) |
void _objref_Problem::setRightHandSideFromConfig | ( | const ::hpp::floatSeq & | config | ) |
void _objref_Problem::setRightHandSideFromConfigByName | ( | const char * | constraintName, |
const ::hpp::floatSeq & | config | ||
) |
void _objref_Problem::setRobot | ( | ::hpp::pinocchio_idl::Device_ptr | robot | ) |
void _objref_Problem::setSecurityMargins | ( | const ::hpp::floatSeqSeq & | margins | ) |
void _objref_Problem::setSteeringMethod | ( | ::hpp::core_idl::SteeringMethod_ptr | d | ) |
void _objref_Problem::setTimeOutPathPlanning | ( | ::CORBA::Double | timeOut | ) |
intSeq* _objref_Problem::solve | ( | ) |
void _objref_Problem::writeRoadmap | ( | const char * | filename, |
::hpp::core_idl::Roadmap_ptr | roadmap, | ||
::hpp::pinocchio_idl::Device_ptr | robot | ||
) |
|
friend |