hpp::corbaServer::impl::Problem Class Reference

Implement CORBA interface ``Problem''. More...

#include <problem.impl.hh>

Inheritance diagram for hpp::corbaServer::impl::Problem:
[legend]
Collaboration diagram for hpp::corbaServer::impl::Problem:
[legend]

Public Member Functions

 Problem ()
 
void setServer (ServerPlugin *server)
 
virtual Names_tgetAvailable (const char *what) throw (hpp::Error)
 
virtual Names_tgetSelected (const char *what) throw (hpp::Error)
 
virtual void setParameter (const char *name, const Any &value) throw (Error)
 
virtual Any * getParameter (const char *name) throw (Error)
 
virtual char * getParameterDoc (const char *name) throw (Error)
 
virtual bool selectProblem (const char *problemName) throw (hpp::Error)
 
virtual void resetProblem () throw (hpp::Error)
 
virtual bool loadPlugin (const char *pluginName) throw (hpp::Error)
 
virtual void movePathToProblem (ULong pathId, const char *problemName, const Names_t &jointNames) throw (hpp::Error)
 
virtual void setMaxNumThreads (UShort n) throw (Error)
 
virtual UShort getMaxNumThreads () throw (Error)
 
virtual void setRandomSeed (const Long seed) throw (hpp::Error)
 
virtual void setInitialConfig (const hpp::floatSeq &dofArray) throw (hpp::Error)
 
virtual hpp::floatSeqgetInitialConfig () throw (hpp::Error)
 
virtual void addGoalConfig (const hpp::floatSeq &dofArray) throw (hpp::Error)
 
virtual hpp::floatSeqSeqgetGoalConfigs () throw (hpp::Error)
 
virtual void resetGoalConfigs () throw (hpp::Error)
 
virtual void createOrientationConstraint (const char *constraintName, const char *joint1Name, const char *joint2Name, const Double *p, const hpp::boolSeq &mask) throw (hpp::Error)
 
virtual void createTransformationConstraint (const char *constraintName, const char *joint1Name, const char *joint2Name, const Transform_ p, const hpp::boolSeq &mask) throw (hpp::Error)
 
virtual void createTransformationConstraint2 (const char *constraintName, const char *joint1Name, const char *joint2Name, const Transform_ frame1, const Transform_ frame2, const hpp::boolSeq &mask) throw (hpp::Error)
 
virtual void createTransformationSE3Constraint (const char *constraintName, const char *joint1Name, const char *joint2Name, const Transform_ frame1, const Transform_ frame2, const hpp::boolSeq &mask) throw (hpp::Error)
 
virtual void createLockedJoint (const char *lockedJointName, const char *jointName, const hpp::floatSeq &value) throw (hpp::Error)
 
virtual void createLockedExtraDof (const char *lockedDofName, ULong index, const hpp::floatSeq &value) throw (hpp::Error)
 
virtual void createManipulability (const char *name, const char *function) throw (hpp::Error)
 
void createRelativeComConstraint (const char *constraintName, const char *comn, const char *jointName, const floatSeq &point, const hpp::boolSeq &mask) throw (hpp::Error)
 
void createComBeetweenFeet (const char *constraintName, const char *comn, const char *jointLName, const char *jointRName, const floatSeq &pointL, const floatSeq &pointR, const char *jointRefName, const floatSeq &pRef, const hpp::boolSeq &mask) throw (hpp::Error)
 
virtual void createConvexShapeContactConstraint (const char *constraintName, const Names_t &floorJoints, const Names_t &objectJoints, const hpp::floatSeqSeq &points, const hpp::intSeqSeq &objTriangles, const hpp::intSeqSeq &floorTriangles) throw (hpp::Error)
 
void createStaticStabilityConstraint (const char *constraintName, const hpp::Names_t &jointNames, const hpp::floatSeqSeq &points, const hpp::floatSeqSeq &normals, const char *comRootJointName) throw (hpp::Error)
 
virtual void createPositionConstraint (const char *constraintName, const char *joint1Name, const char *joint2Name, const hpp::floatSeq &point1, const hpp::floatSeq &point2, const hpp::boolSeq &mask) throw (hpp::Error)
 
virtual void createConfigurationConstraint (const char *constraintName, const hpp::floatSeq &goal, const hpp::floatSeq &weights) throw (hpp::Error)
 
virtual void createDistanceBetweenJointConstraint (const char *constraintName, const char *joint1Name, const char *joint2Name, Double distance) throw (Error)
 
virtual void createDistanceBetweenJointAndObjects (const char *constraintName, const char *joint1Name, const hpp::Names_t &objects, Double distance) throw (Error)
 
virtual void createIdentityConstraint (const char *constraintName, const Names_t &inJoints, const hpp::Names_t &outJoints) throw (Error)
 
virtual bool applyConstraints (const hpp::floatSeq &input, hpp::floatSeq_out output, Double &residualError) throw (hpp::Error)
 
virtual bool optimize (const hpp::floatSeq &input, hpp::floatSeq_out output, hpp::floatSeq_out residualError) throw (hpp::Error)
 
virtual void computeValueAndJacobian (const hpp::floatSeq &config, hpp::floatSeq_out value, hpp::floatSeqSeq_out jacobian) throw (hpp::Error)
 
virtual bool generateValidConfig (ULong maxIter, hpp::floatSeq_out output, Double &residualError) throw (hpp::Error)
 
virtual void addPassiveDofs (const char *constraintName, const hpp::Names_t &dofName) throw (hpp::Error)
 
virtual void getConstraintDimensions (const char *constraintName, ULong &inputSize, ULong &inputDerivativeSize, ULong &outputSize, ULong &outputDerivativeSize) throw (hpp::Error)
 
virtual void setConstantRightHandSide (const char *constraintName, CORBA::Boolean constant) throw (hpp::Error)
 
virtual bool getConstantRightHandSide (const char *constraintName) throw (hpp::Error)
 
virtual floatSeqgetRightHandSide () throw (hpp::Error)
 
virtual void setRightHandSide (const hpp::floatSeq &rhs) throw (hpp::Error)
 
virtual void setRightHandSideFromConfig (const hpp::floatSeq &config) throw (hpp::Error)
 
virtual void setRightHandSideByName (const char *constraintName, const hpp::floatSeq &rhs) throw (hpp::Error)
 
virtual void setRightHandSideFromConfigByName (const char *constraintName, const hpp::floatSeq &config) throw (hpp::Error)
 
virtual void resetConstraints () throw (hpp::Error)
 
virtual void resetConstraintMap () throw (hpp::Error)
 
virtual void addNumericalConstraints (const char *constraintName, const hpp::Names_t &constraintNames, const hpp::intSeq &priorities) throw (Error)
 
virtual void setNumericalConstraintsLastPriorityOptional (const bool optional) throw (Error)
 
virtual void addLockedJointConstraints (const char *configProjName, const hpp::Names_t &lockedJointNames) throw (Error)
 
virtual char * displayConstraints () throw (Error)
 
virtual void filterCollisionPairs () throw (hpp::Error)
 
virtual Double getErrorThreshold () throw (Error)
 
virtual void setErrorThreshold (Double threshold) throw (Error)
 
virtual void setDefaultLineSearchType (const char *type) throw (Error)
 
virtual ULong getMaxIterProjection () throw (Error)
 
virtual void setMaxIterProjection (ULong iterations) throw (Error)
 
virtual ULong getMaxIterPathPlanning () throw (Error)
 
virtual void setMaxIterPathPlanning (ULong iterations) throw (Error)
 
virtual void setTimeOutPathPlanning (double timeOut) throw (Error)
 
virtual double getTimeOutPathPlanning () throw (Error)
 
virtual void addPathOptimizer (const char *pathOptimizerType) throw (Error)
 
virtual void clearPathOptimizers () throw (Error)
 
virtual void addConfigValidation (const char *configValidationType) throw (Error)
 
virtual void clearConfigValidations () throw (Error)
 
virtual void selectPathValidation (const char *pathValidationType, Double tolerance) throw (Error)
 
virtual void selectPathProjector (const char *pathProjectorType, Double tolerance) throw (Error)
 
virtual void selectPathPlanner (const char *pathPlannerType) throw (Error)
 
virtual void selectDistance (const char *distanceType) throw (Error)
 
virtual void selectSteeringMethod (const char *steeringMethodType) throw (Error)
 
virtual void selectConfigurationShooter (const char *configurationShooterType) throw (Error)
 
virtual bool prepareSolveStepByStep () throw (hpp::Error)
 
virtual bool executeOneStep () throw (hpp::Error)
 
virtual void finishSolveStepByStep () throw (hpp::Error)
 
virtual hpp::intSeqsolve () throw (hpp::Error)
 
virtual bool directPath (const hpp::floatSeq &startConfig, const hpp::floatSeq &endConfig, CORBA::Boolean validate, ULong &pathId, CORBA::String_out report) throw (hpp::Error)
 
virtual bool reversePath (ULong pathId, ULong &reversedPathId) throw (hpp::Error)
 
virtual void addConfigToRoadmap (const hpp::floatSeq &config) throw (hpp::Error)
 
virtual void addEdgeToRoadmap (const hpp::floatSeq &config1, const hpp::floatSeq &config2, ULong pathId, bool bothEdges) throw (hpp::Error)
 
virtual void appendDirectPath (ULong pathId, const hpp::floatSeq &config, Boolean validate) throw (hpp::Error)
 
virtual void concatenatePath (ULong startId, ULong endId) throw (hpp::Error)
 
virtual void extractPath (ULong pathId, Double start, Double end) throw (hpp::Error)
 
virtual void erasePath (ULong pathId) throw (hpp::Error)
 
virtual bool projectPath (ULong pathId) throw (hpp::Error)
 
virtual void interruptPathPlanning () throw (hpp::Error)
 
virtual Long numberPaths () throw (hpp::Error)
 
virtual hpp::intSeqoptimizePath (ULong pathId) throw (hpp::Error)
 
virtual Double pathLength (ULong pathId) throw (hpp::Error)
 
virtual hpp::floatSeqconfigAtParam (ULong pathId, Double atDistance) throw (hpp::Error)
 
virtual hpp::floatSeqderivativeAtParam (ULong pathId, ULong order, Double atDistance) throw (hpp::Error)
 
virtual hpp::floatSeqSeqgetWaypoints (ULong inPathId, floatSeq_out times) throw (hpp::Error)
 
virtual hpp::floatSeqSeqnodes () throw (hpp::Error)
 
virtual Long numberEdges () throw (hpp::Error)
 
virtual void edge (ULong edgeId, hpp::floatSeq_out q1, hpp::floatSeq_out q2) throw (hpp::Error)
 
virtual Long connectedComponentOfEdge (ULong edgeId) throw (hpp::Error)
 
virtual hpp::floatSeqnode (ULong nodeId) throw (hpp::Error)
 
virtual Long connectedComponentOfNode (ULong nodeId) throw (hpp::Error)
 
virtual Long numberNodes () throw (hpp::Error)
 
virtual Long numberConnectedComponents () throw (hpp::Error)
 
virtual hpp::floatSeqSeqnodesConnectedComponent (ULong connectedComponentId) throw (hpp::Error)
 
virtual hpp::floatSeqgetNearestConfig (const hpp::floatSeq &config, const Long connectedComponentId, hpp::core::value_type &distance) throw (hpp::Error)
 
virtual void clearRoadmap () throw (hpp::Error)
 
virtual void resetRoadmap ()
 
virtual void saveRoadmap (const char *filename) throw (hpp::Error)
 
virtual void readRoadmap (const char *filename) throw (hpp::Error)
 
virtual void scCreateScalarMultiply (const char *outName, Double scalar, const char *inName) throw (hpp::Error)
 
hpp::core_idl::Distance_ptr getDistance () throw (hpp::Error)
 
void setDistance (hpp::core_idl::Distance_ptr distance) throw (hpp::Error)
 
hpp::core_idl::Path_ptr getPath (ULong pathId) throw (Error)
 
ULong addPath (hpp::core_idl::PathVector_ptr _path) throw (Error)
 
hpp::core_idl::SteeringMethod_ptr getSteeringMethod () throw (Error)
 
hpp::core_idl::PathValidation_ptr getPathValidation () throw (Error)
 
hpp::core_idl::PathPlanner_ptr getPathPlanner () throw (Error)
 
hpp::core_idl::Problem_ptr getProblem () throw (Error)
 
hpp::constraints_idl::Implicit_ptr getConstraint (const char *name) throw (Error)
 

Detailed Description

Implement CORBA interface ``Problem''.

Constructor & Destructor Documentation

hpp::corbaServer::impl::Problem::Problem ( )

Member Function Documentation

virtual void hpp::corbaServer::impl::Problem::addConfigToRoadmap ( const hpp::floatSeq config)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::addConfigValidation ( const char *  configValidationType)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::addEdgeToRoadmap ( const hpp::floatSeq config1,
const hpp::floatSeq config2,
ULong  pathId,
bool  bothEdges 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::addGoalConfig ( const hpp::floatSeq dofArray)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::addLockedJointConstraints ( const char *  configProjName,
const hpp::Names_t lockedJointNames 
)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::addNumericalConstraints ( const char *  constraintName,
const hpp::Names_t constraintNames,
const hpp::intSeq priorities 
)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::addPassiveDofs ( const char *  constraintName,
const hpp::Names_t dofName 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

ULong hpp::corbaServer::impl::Problem::addPath ( hpp::core_idl::PathVector_ptr  _path)
throw (Error
)

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::addPathOptimizer ( const char *  pathOptimizerType)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::appendDirectPath ( ULong  pathId,
const hpp::floatSeq config,
Boolean  validate 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::applyConstraints ( const hpp::floatSeq input,
hpp::floatSeq_out  output,
Double &  residualError 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::clearConfigValidations ( )
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::clearPathOptimizers ( )
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::clearRoadmap ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::computeValueAndJacobian ( const hpp::floatSeq config,
hpp::floatSeq_out  value,
hpp::floatSeqSeq_out  jacobian 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::concatenatePath ( ULong  startId,
ULong  endId 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::floatSeq* hpp::corbaServer::impl::Problem::configAtParam ( ULong  pathId,
Double  atDistance 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Long hpp::corbaServer::impl::Problem::connectedComponentOfEdge ( ULong  edgeId)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Long hpp::corbaServer::impl::Problem::connectedComponentOfNode ( ULong  nodeId)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

void hpp::corbaServer::impl::Problem::createComBeetweenFeet ( const char *  constraintName,
const char *  comn,
const char *  jointLName,
const char *  jointRName,
const floatSeq pointL,
const floatSeq pointR,
const char *  jointRefName,
const floatSeq pRef,
const hpp::boolSeq mask 
)
throw (hpp::Error
)

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createConfigurationConstraint ( const char *  constraintName,
const hpp::floatSeq goal,
const hpp::floatSeq weights 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createConvexShapeContactConstraint ( const char *  constraintName,
const Names_t floorJoints,
const Names_t objectJoints,
const hpp::floatSeqSeq points,
const hpp::intSeqSeq objTriangles,
const hpp::intSeqSeq floorTriangles 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createDistanceBetweenJointAndObjects ( const char *  constraintName,
const char *  joint1Name,
const hpp::Names_t objects,
Double  distance 
)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createDistanceBetweenJointConstraint ( const char *  constraintName,
const char *  joint1Name,
const char *  joint2Name,
Double  distance 
)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createIdentityConstraint ( const char *  constraintName,
const Names_t inJoints,
const hpp::Names_t outJoints 
)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createLockedExtraDof ( const char *  lockedDofName,
ULong  index,
const hpp::floatSeq value 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createLockedJoint ( const char *  lockedJointName,
const char *  jointName,
const hpp::floatSeq value 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createManipulability ( const char *  name,
const char *  function 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createOrientationConstraint ( const char *  constraintName,
const char *  joint1Name,
const char *  joint2Name,
const Double *  p,
const hpp::boolSeq mask 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createPositionConstraint ( const char *  constraintName,
const char *  joint1Name,
const char *  joint2Name,
const hpp::floatSeq point1,
const hpp::floatSeq point2,
const hpp::boolSeq mask 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

void hpp::corbaServer::impl::Problem::createRelativeComConstraint ( const char *  constraintName,
const char *  comn,
const char *  jointName,
const floatSeq point,
const hpp::boolSeq mask 
)
throw (hpp::Error
)

Referenced by setRandomSeed().

void hpp::corbaServer::impl::Problem::createStaticStabilityConstraint ( const char *  constraintName,
const hpp::Names_t jointNames,
const hpp::floatSeqSeq points,
const hpp::floatSeqSeq normals,
const char *  comRootJointName 
)
throw (hpp::Error
)

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createTransformationConstraint ( const char *  constraintName,
const char *  joint1Name,
const char *  joint2Name,
const Transform_  p,
const hpp::boolSeq mask 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createTransformationConstraint2 ( const char *  constraintName,
const char *  joint1Name,
const char *  joint2Name,
const Transform_  frame1,
const Transform_  frame2,
const hpp::boolSeq mask 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::createTransformationSE3Constraint ( const char *  constraintName,
const char *  joint1Name,
const char *  joint2Name,
const Transform_  frame1,
const Transform_  frame2,
const hpp::boolSeq mask 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::floatSeq* hpp::corbaServer::impl::Problem::derivativeAtParam ( ULong  pathId,
ULong  order,
Double  atDistance 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::directPath ( const hpp::floatSeq startConfig,
const hpp::floatSeq endConfig,
CORBA::Boolean  validate,
ULong &  pathId,
CORBA::String_out  report 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual char* hpp::corbaServer::impl::Problem::displayConstraints ( )
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::edge ( ULong  edgeId,
hpp::floatSeq_out  q1,
hpp::floatSeq_out  q2 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::erasePath ( ULong  pathId)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::executeOneStep ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::extractPath ( ULong  pathId,
Double  start,
Double  end 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::filterCollisionPairs ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::finishSolveStepByStep ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::generateValidConfig ( ULong  maxIter,
hpp::floatSeq_out  output,
Double &  residualError 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Names_t* hpp::corbaServer::impl::Problem::getAvailable ( const char *  what)
throw (hpp::Error
)
virtual

Referenced by setServer().

virtual bool hpp::corbaServer::impl::Problem::getConstantRightHandSide ( const char *  constraintName)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

hpp::constraints_idl::Implicit_ptr hpp::corbaServer::impl::Problem::getConstraint ( const char *  name)
throw (Error
)

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::getConstraintDimensions ( const char *  constraintName,
ULong &  inputSize,
ULong &  inputDerivativeSize,
ULong &  outputSize,
ULong &  outputDerivativeSize 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

hpp::core_idl::Distance_ptr hpp::corbaServer::impl::Problem::getDistance ( )
throw (hpp::Error
)

Referenced by setRandomSeed().

virtual Double hpp::corbaServer::impl::Problem::getErrorThreshold ( )
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::floatSeqSeq* hpp::corbaServer::impl::Problem::getGoalConfigs ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::floatSeq* hpp::corbaServer::impl::Problem::getInitialConfig ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual ULong hpp::corbaServer::impl::Problem::getMaxIterPathPlanning ( )
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual ULong hpp::corbaServer::impl::Problem::getMaxIterProjection ( )
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual UShort hpp::corbaServer::impl::Problem::getMaxNumThreads ( )
throw (Error
)
virtual

Referenced by setServer().

virtual hpp::floatSeq* hpp::corbaServer::impl::Problem::getNearestConfig ( const hpp::floatSeq config,
const Long  connectedComponentId,
hpp::core::value_type distance 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Any* hpp::corbaServer::impl::Problem::getParameter ( const char *  name)
throw (Error
)
virtual

Referenced by setServer().

virtual char* hpp::corbaServer::impl::Problem::getParameterDoc ( const char *  name)
throw (Error
)
virtual

Referenced by setServer().

hpp::core_idl::Path_ptr hpp::corbaServer::impl::Problem::getPath ( ULong  pathId)
throw (Error
)

Referenced by setRandomSeed().

hpp::core_idl::PathPlanner_ptr hpp::corbaServer::impl::Problem::getPathPlanner ( )
throw (Error
)

Referenced by setRandomSeed().

hpp::core_idl::PathValidation_ptr hpp::corbaServer::impl::Problem::getPathValidation ( )
throw (Error
)

Referenced by setRandomSeed().

hpp::core_idl::Problem_ptr hpp::corbaServer::impl::Problem::getProblem ( )
throw (Error
)

Referenced by setRandomSeed().

virtual floatSeq* hpp::corbaServer::impl::Problem::getRightHandSide ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Names_t* hpp::corbaServer::impl::Problem::getSelected ( const char *  what)
throw (hpp::Error
)
virtual

Referenced by setServer().

hpp::core_idl::SteeringMethod_ptr hpp::corbaServer::impl::Problem::getSteeringMethod ( )
throw (Error
)

Referenced by setRandomSeed().

virtual double hpp::corbaServer::impl::Problem::getTimeOutPathPlanning ( )
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::floatSeqSeq* hpp::corbaServer::impl::Problem::getWaypoints ( ULong  inPathId,
floatSeq_out  times 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::interruptPathPlanning ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::loadPlugin ( const char *  pluginName)
throw (hpp::Error
)
virtual

Referenced by setServer().

virtual void hpp::corbaServer::impl::Problem::movePathToProblem ( ULong  pathId,
const char *  problemName,
const Names_t jointNames 
)
throw (hpp::Error
)
virtual

Referenced by setServer().

virtual hpp::floatSeq* hpp::corbaServer::impl::Problem::node ( ULong  nodeId)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::floatSeqSeq* hpp::corbaServer::impl::Problem::nodes ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::floatSeqSeq* hpp::corbaServer::impl::Problem::nodesConnectedComponent ( ULong  connectedComponentId)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Long hpp::corbaServer::impl::Problem::numberConnectedComponents ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Long hpp::corbaServer::impl::Problem::numberEdges ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Long hpp::corbaServer::impl::Problem::numberNodes ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Long hpp::corbaServer::impl::Problem::numberPaths ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::optimize ( const hpp::floatSeq input,
hpp::floatSeq_out  output,
hpp::floatSeq_out  residualError 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::intSeq* hpp::corbaServer::impl::Problem::optimizePath ( ULong  pathId)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual Double hpp::corbaServer::impl::Problem::pathLength ( ULong  pathId)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::prepareSolveStepByStep ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::projectPath ( ULong  pathId)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::readRoadmap ( const char *  filename)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::resetConstraintMap ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::resetConstraints ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::resetGoalConfigs ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::resetProblem ( )
throw (hpp::Error
)
virtual

Referenced by setServer().

virtual void hpp::corbaServer::impl::Problem::resetRoadmap ( )
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::reversePath ( ULong  pathId,
ULong &  reversedPathId 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::saveRoadmap ( const char *  filename)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::scCreateScalarMultiply ( const char *  outName,
Double  scalar,
const char *  inName 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::selectConfigurationShooter ( const char *  configurationShooterType)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::selectDistance ( const char *  distanceType)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::selectPathPlanner ( const char *  pathPlannerType)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::selectPathProjector ( const char *  pathProjectorType,
Double  tolerance 
)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::selectPathValidation ( const char *  pathValidationType,
Double  tolerance 
)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual bool hpp::corbaServer::impl::Problem::selectProblem ( const char *  problemName)
throw (hpp::Error
)
virtual

Referenced by setServer().

virtual void hpp::corbaServer::impl::Problem::selectSteeringMethod ( const char *  steeringMethodType)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setConstantRightHandSide ( const char *  constraintName,
CORBA::Boolean  constant 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setDefaultLineSearchType ( const char *  type)
throw (Error
)
virtual

Referenced by setRandomSeed().

void hpp::corbaServer::impl::Problem::setDistance ( hpp::core_idl::Distance_ptr  distance)
throw (hpp::Error
)

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setErrorThreshold ( Double  threshold)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setInitialConfig ( const hpp::floatSeq dofArray)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setMaxIterPathPlanning ( ULong  iterations)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setMaxIterProjection ( ULong  iterations)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setMaxNumThreads ( UShort  n)
throw (Error
)
virtual

Referenced by setServer().

virtual void hpp::corbaServer::impl::Problem::setNumericalConstraintsLastPriorityOptional ( const bool  optional)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setParameter ( const char *  name,
const Any &  value 
)
throw (Error
)
virtual

Referenced by setServer().

virtual void hpp::corbaServer::impl::Problem::setRandomSeed ( const Long  seed)
throw (hpp::Error
)
inlinevirtual

References addConfigToRoadmap(), addConfigValidation(), addEdgeToRoadmap(), addGoalConfig(), addLockedJointConstraints(), addNumericalConstraints(), addPassiveDofs(), addPath(), addPathOptimizer(), appendDirectPath(), applyConstraints(), clearConfigValidations(), clearPathOptimizers(), clearRoadmap(), computeValueAndJacobian(), concatenatePath(), configAtParam(), connectedComponentOfEdge(), connectedComponentOfNode(), createComBeetweenFeet(), createConfigurationConstraint(), createConvexShapeContactConstraint(), createDistanceBetweenJointAndObjects(), createDistanceBetweenJointConstraint(), createIdentityConstraint(), createLockedExtraDof(), createLockedJoint(), createManipulability(), createOrientationConstraint(), createPositionConstraint(), createRelativeComConstraint(), createStaticStabilityConstraint(), createTransformationConstraint(), createTransformationConstraint2(), createTransformationSE3Constraint(), derivativeAtParam(), directPath(), displayConstraints(), distance(), edge(), erasePath(), executeOneStep(), extractPath(), filterCollisionPairs(), finishSolveStepByStep(), generateValidConfig(), getConstantRightHandSide(), getConstraint(), getConstraintDimensions(), getDistance(), getErrorThreshold(), getGoalConfigs(), getInitialConfig(), getMaxIterPathPlanning(), getMaxIterProjection(), getNearestConfig(), getPath(), getPathPlanner(), getPathValidation(), getProblem(), getRightHandSide(), getSteeringMethod(), getTimeOutPathPlanning(), getWaypoints(), interruptPathPlanning(), node(), nodes(), nodesConnectedComponent(), numberConnectedComponents(), numberEdges(), numberNodes(), numberPaths(), optimize(), optimizePath(), pathLength(), prepareSolveStepByStep(), projectPath(), readRoadmap(), resetConstraintMap(), resetConstraints(), resetGoalConfigs(), resetRoadmap(), reversePath(), saveRoadmap(), scCreateScalarMultiply(), selectConfigurationShooter(), selectDistance(), selectPathPlanner(), selectPathProjector(), selectPathValidation(), selectSteeringMethod(), setConstantRightHandSide(), setDefaultLineSearchType(), setDistance(), setErrorThreshold(), setInitialConfig(), setMaxIterPathPlanning(), setMaxIterProjection(), setNumericalConstraintsLastPriorityOptional(), setRightHandSide(), setRightHandSideByName(), setRightHandSideFromConfig(), setRightHandSideFromConfigByName(), setTimeOutPathPlanning(), and solve().

virtual void hpp::corbaServer::impl::Problem::setRightHandSide ( const hpp::floatSeq rhs)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setRightHandSideByName ( const char *  constraintName,
const hpp::floatSeq rhs 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setRightHandSideFromConfig ( const hpp::floatSeq config)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setRightHandSideFromConfigByName ( const char *  constraintName,
const hpp::floatSeq config 
)
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().

virtual void hpp::corbaServer::impl::Problem::setTimeOutPathPlanning ( double  timeOut)
throw (Error
)
virtual

Referenced by setRandomSeed().

virtual hpp::intSeq* hpp::corbaServer::impl::Problem::solve ( )
throw (hpp::Error
)
virtual

Referenced by setRandomSeed().