hpp-core  4.9.0
Implement basic classes for canonical path planning for kinematic chains.
hpp::core::Problem Class Reference

#include <hpp/core/problem.hh>

Collaboration diagram for hpp::core::Problem:

Public Member Functions

 Problem ()
 
virtual ~Problem ()
 
virtual void checkProblem () const
 Check that problem is well formulated. More...
 
const ParametergetParameter (const std::string &name) const
 
void setParameter (const std::string &name, const Parameter &value)
 
Problem definition
const DevicePtr_trobot () const
 return shared pointer to robot. More...
 
const ConfigurationPtr_tinitConfig () const
 Get shared pointer to initial configuration. More...
 
void initConfig (const ConfigurationPtr_t &inConfig)
 Set initial configuration. More...
 
void target (const ProblemTargetPtr_t &target)
 Set the target. More...
 
const ProblemTargetPtr_ttarget () const
 Get the target. More...
 
const Configurations_tgoalConfigs () const
 Get number of goal configuration. More...
 
void addGoalConfig (const ConfigurationPtr_t &config)
 Add goal configuration. More...
 
void resetGoalConfigs ()
 Reset the set of goal configurations. More...
 
Steering method and distance function
void steeringMethod (const SteeringMethodPtr_t &sm)
 
SteeringMethodPtr_t steeringMethod () const
 Get steering method. More...
 
void distance (const DistancePtr_t &distance)
 Set distance between configurations. More...
 
const DistancePtr_tdistance () const
 Get distance between configuration. More...
 
Configuration validation
void configValidation (const ConfigValidationsPtr_t &configValidations)
 
const ConfigValidationsPtr_tconfigValidations () const
 Get configuration validation methods. More...
 
void resetConfigValidations ()
 
void clearConfigValidations ()
 
void addConfigValidation (const ConfigValidationPtr_t &configValidation)
 Add a config validation method. More...
 
Path validation

Set path validation method

virtual void pathValidation (const PathValidationPtr_t &pathValidation)
 
PathValidationPtr_t pathValidation () const
 Get path validation method. More...
 
Configuration shooter

Set configuration shooter method

void configurationShooter (const ConfigurationShooterPtr_t &configurationShooter)
 
ConfigurationShooterPtr_t configurationShooter () const
 Get path validation method. More...
 
Path projector

Set path projector method

void pathProjector (const PathProjectorPtr_t &pathProjector)
 
PathProjectorPtr_t pathProjector () const
 Get path projector method. More...
 
Constraints applicable to the robot
void constraints (const ConstraintSetPtr_t &constraints)
 
const ConstraintSetPtr_tconstraints () const
 Get constraint set. More...
 
Obstacles
void addObstacle (const CollisionObjectPtr_t &object)
 
void removeObstacleFromJoint (const JointPtr_t &joint, const CollisionObjectConstPtr_t &obstacle)
 
void filterCollisionPairs ()
 
const ObjectStdVector_tcollisionObstacles () const
 Vector of objects considered for collision detection. More...
 
void collisionObstacles (const ObjectStdVector_t &collisionObstacles)
 Set the vector of objects considered for collision detection. More...
 

Static Public Member Functions

static ProblemPtr_t create (DevicePtr_t robot)
 
static void declareParameter (const ParameterDescription &desc)
 
static const Container< ParameterDescription > & parameterDescriptions ()
 Get all the parameter descriptions. More...
 
static const ParameterDescriptionparameterDescription (const std::string &name)
 Access one parameter description. More...
 

Public Attributes

Container< Parameterparameters
 

Protected Member Functions

 Problem (DevicePtr_t robot)
 
void init (ProblemWkPtr_t wkPtr)
 

Detailed Description

Defines a path planning problem for one robot. A path planning problem is defined by

  • a robot: instance of class hpp::pinocchio::Device,
  • a set of obstacles: a list of hpp::pinocchio::CollisionObject,
  • initial and goal configurations,
  • a SteeringMethod to handle the robot dynamics, Additional objects are stored in this object:
  • a method to validate paths,
  • a set of methods to validate configurations. Default methods are collision checking and joint bound checking.

Constructor & Destructor Documentation

◆ Problem() [1/2]

hpp::core::Problem::Problem ( )

Constructor without argument

Warning
do not use this constructor. It is necessary to define std::pairs <Problem, OtherType>.

◆ ~Problem()

virtual hpp::core::Problem::~Problem ( )
virtual

◆ Problem() [2/2]

hpp::core::Problem::Problem ( DevicePtr_t  robot)
protected

Create a path planning problem.

Parameters
robotrobot associated to the path planning problem.

Member Function Documentation

◆ addConfigValidation()

void hpp::core::Problem::addConfigValidation ( const ConfigValidationPtr_t configValidation)

Add a config validation method.

◆ addGoalConfig()

void hpp::core::Problem::addGoalConfig ( const ConfigurationPtr_t config)

Add goal configuration.

◆ addObstacle()

void hpp::core::Problem::addObstacle ( const CollisionObjectPtr_t object)

Add obstacle to the list.

Parameters
objecta new object.

◆ checkProblem()

virtual void hpp::core::Problem::checkProblem ( ) const
virtual

Check that problem is well formulated.

◆ clearConfigValidations()

void hpp::core::Problem::clearConfigValidations ( )

◆ collisionObstacles() [1/2]

const ObjectStdVector_t& hpp::core::Problem::collisionObstacles ( ) const

Vector of objects considered for collision detection.

◆ collisionObstacles() [2/2]

void hpp::core::Problem::collisionObstacles ( const ObjectStdVector_t collisionObstacles)

Set the vector of objects considered for collision detection.

◆ configurationShooter() [1/2]

void hpp::core::Problem::configurationShooter ( const ConfigurationShooterPtr_t configurationShooter)

◆ configurationShooter() [2/2]

ConfigurationShooterPtr_t hpp::core::Problem::configurationShooter ( ) const
inline

Get path validation method.

◆ configValidation()

void hpp::core::Problem::configValidation ( const ConfigValidationsPtr_t configValidations)
inline

Set configuration validation methods Before starting tos solve a path planning problem, the initial and goal configurations are checked for validity.

◆ configValidations()

const ConfigValidationsPtr_t& hpp::core::Problem::configValidations ( ) const
inline

Get configuration validation methods.

◆ constraints() [1/2]

void hpp::core::Problem::constraints ( const ConstraintSetPtr_t constraints)
inline

Set constraint set

Parameters
constraintsa set of constraints If problem contains a steering method, constraints are passed to the steering method.

◆ constraints() [2/2]

const ConstraintSetPtr_t& hpp::core::Problem::constraints ( ) const
inline

Get constraint set.

◆ create()

static ProblemPtr_t hpp::core::Problem::create ( DevicePtr_t  robot)
static

Create a path planning problem.

Parameters
robotrobot associated to the path planning problem.

◆ declareParameter()

static void hpp::core::Problem::declareParameter ( const ParameterDescription desc)
static

Declare a parameter In shared library, use the following snippet in your cc file:

Problem::declareParameter (ParameterDescription (
"name",
"doc",
Parameter(value)));

◆ distance() [1/2]

void hpp::core::Problem::distance ( const DistancePtr_t distance)
inline

Set distance between configurations.

◆ distance() [2/2]

const DistancePtr_t& hpp::core::Problem::distance ( ) const
inline

Get distance between configuration.

◆ filterCollisionPairs()

void hpp::core::Problem::filterCollisionPairs ( )

Build matrix of relative motions between joints

Loop over constraints in the current constraint set (see Problem::constraints) and for each LockedJoint and each constraints::RelativeTransformation, fill a matrix the column and rows represent joints and the values are the following

  • RelativeMotionType::Constrained when the two joints are rigidly fixed by the constraint,
  • RelativeMotionType::Parameterized when the two joints are rigidly fixed by the constraint, the relative position is a parameter constant along path, but that can change for different paths,
  • RelativeMotionType::Unconstrained when the two joints are not rigidly fixed by the constraint.
Note
the matrix is passed to the current configuration validation instance (Problem::configValidation) and to the current path validation instance (Problem::pathValidation).

◆ getParameter()

const Parameter& hpp::core::Problem::getParameter ( const std::string &  name) const
inline

Get a parameter named name.

Parameters
nameof the parameter.

◆ goalConfigs()

const Configurations_t& hpp::core::Problem::goalConfigs ( ) const

Get number of goal configuration.

◆ init()

void hpp::core::Problem::init ( ProblemWkPtr_t  wkPtr)
protected

◆ initConfig() [1/2]

const ConfigurationPtr_t& hpp::core::Problem::initConfig ( ) const
inline

Get shared pointer to initial configuration.

◆ initConfig() [2/2]

void hpp::core::Problem::initConfig ( const ConfigurationPtr_t inConfig)

Set initial configuration.

◆ parameterDescription()

static const ParameterDescription& hpp::core::Problem::parameterDescription ( const std::string &  name)
static

Access one parameter description.

◆ parameterDescriptions()

static const Container<ParameterDescription>& hpp::core::Problem::parameterDescriptions ( )
static

Get all the parameter descriptions.

◆ pathProjector() [1/2]

void hpp::core::Problem::pathProjector ( const PathProjectorPtr_t pathProjector)
inline

◆ pathProjector() [2/2]

PathProjectorPtr_t hpp::core::Problem::pathProjector ( ) const
inline

Get path projector method.

◆ pathValidation() [1/2]

virtual void hpp::core::Problem::pathValidation ( const PathValidationPtr_t pathValidation)
virtual

◆ pathValidation() [2/2]

PathValidationPtr_t hpp::core::Problem::pathValidation ( ) const
inline

Get path validation method.

◆ removeObstacleFromJoint()

void hpp::core::Problem::removeObstacleFromJoint ( const JointPtr_t joint,
const CollisionObjectConstPtr_t obstacle 
)

Remove a collision pair between a joint and an obstacle

Parameters
jointthat holds the inner objects,
obstacleto remove.

◆ resetConfigValidations()

void hpp::core::Problem::resetConfigValidations ( )

◆ resetGoalConfigs()

void hpp::core::Problem::resetGoalConfigs ( )

Reset the set of goal configurations.

◆ robot()

const DevicePtr_t& hpp::core::Problem::robot ( ) const
inline

return shared pointer to robot.

◆ setParameter()

void hpp::core::Problem::setParameter ( const std::string &  name,
const Parameter value 
)

Set a parameter named name.

Parameters
nameof the parameter.
valuevalue of the parameter
Exceptions
std::invalid_argumentif a parameter exists but has a different type.

◆ steeringMethod() [1/2]

void hpp::core::Problem::steeringMethod ( const SteeringMethodPtr_t sm)
inline

Set steering method

Parameters
smsteering method. If problem contains constraints they are passed to the steering method.

◆ steeringMethod() [2/2]

SteeringMethodPtr_t hpp::core::Problem::steeringMethod ( ) const
inline

Get steering method.

◆ target() [1/2]

void hpp::core::Problem::target ( const ProblemTargetPtr_t target)
inline

Set the target.

◆ target() [2/2]

const ProblemTargetPtr_t& hpp::core::Problem::target ( ) const
inline

Get the target.

Member Data Documentation

◆ parameters

Container< Parameter > hpp::core::Problem::parameters

The documentation for this class was generated from the following file: