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

Namespaces

 configurationShooter
 
 continuousValidation
 
 distance
 
 nearestNeighbor
 
 parser
 
 path
 
 pathOptimization
 
 pathPlanner
 
 pathProjector
 
 pathValidation
 
 plugin
 
 problemTarget
 
 steeringMethod
 
 timeParameterization
 

Classes

struct  AllCollisionsValidationReport
 
class  BiRRTPlanner
 
struct  CollisionPathValidationReport
 Path validation report used for standard collision checking. More...
 
class  CollisionValidation
 
struct  CollisionValidationReport
 
class  ConfigProjector
 
class  ConfigurationShooter
 
class  ConfigValidation
 
class  ConfigValidations
 
class  ConnectedComponent
 
class  Constraint
 
class  ConstraintSet
 
struct  Container
 
class  ContinuousValidation
 
class  DiffusingPlanner
 Generic implementation of RRT algorithm. More...
 
class  Distance
 Abstract class for distance between configurations. More...
 
class  DistanceBetweenObjects
 Computation of distances between pairs of objects. More...
 
class  DubinsPath
 
class  Edge
 
class  InterpolatedPath
 
class  JointBoundValidation
 
class  JointBoundValidationReport
 report returned when a configuration is not within the bounds More...
 
class  KinodynamicDistance
 
class  KinodynamicOrientedPath
 
class  KinodynamicPath
 
class  Member_lockedJoints_in_class_ProblemSolver_has_been_removed_use_member_numericalConstraints_instead
 
class  NearestNeighbor
 Optimization of the nearest neighbor search. More...
 
class  Node
 
class  ObstacleUser
 Stores a set of obstacles (movable or static). More...
 
class  ObstacleUserInterface
 
class  ObstacleUserVector
 
class  Parameter
 
class  ParameterDescription
 
class  Path
 
class  PathOptimizer
 
class  PathPlanner
 
class  PathProjector
 This class projects a path using constraints. More...
 
class  PathValidation
 
struct  PathValidationReport
 
class  PathValidations
 
class  PathVector
 Concatenation of several paths. More...
 
class  PlanAndOptimize
 
class  Problem
 
class  ProblemSolver
 
class  ProblemSolverPlugin
 Plugin mechanism to declare new features in ProblemSolver class. More...
 
class  ProblemTarget
 
struct  projection_error
 
struct  ProjectionError
 Handles projection errors when evaluating a path. More...
 
class  ReedsSheppPath
 
struct  RelativeMotion
 
class  Roadmap
 
class  SteeringMethod
 
class  StraightPath
 
class  SubchainPath
 
class  TimeParameterization
 
class  ValidationReport
 
class  VisibilityPrmPlanner
 
class  WeighedDistance
 

Typedefs

typedef configurationShooter::Uniform BasicConfigurationShooter
 
typedef configurationShooter::UniformPtr_t BasicConfigurationShooterPtr_t
 
typedef constraints::solver::BySubstitution BySubstitution
 
typedef constraints::ComparisonTypes_t ComparisonTypes_t
 
typedef constraints::ComparisonType ComparisonType
 
typedef boost::shared_ptr< BiRRTPlannerBiRRTPlannerPtr_t
 
typedef hpp::pinocchio::Body Body
 
typedef hpp::pinocchio::BodyPtr_t BodyPtr_t
 
typedef boost::shared_ptr< CollisionValidationCollisionValidationPtr_t
 
typedef boost::shared_ptr< CollisionValidationReportCollisionValidationReportPtr_t
 
typedef boost::shared_ptr< AllCollisionsValidationReportAllCollisionsValidationReportPtr_t
 
typedef pinocchio::CollisionObjectPtr_t CollisionObjectPtr_t
 
typedef pinocchio::CollisionObjectConstPtr_t CollisionObjectConstPtr_t
 
typedef pinocchio::FclCollisionObject FclCollisionObject
 
typedef FclCollisionObjectFclCollisionObjectPtr_t
 
typedef const FclCollisionObjectFclConstCollisionObjectPtr_t
 
typedef boost::shared_ptr< FclCollisionObjectFclCollisionObjectSharePtr_t
 
typedef pinocchio::Configuration_t Configuration_t
 
typedef pinocchio::ConfigurationIn_t ConfigurationIn_t
 
typedef pinocchio::ConfigurationOut_t ConfigurationOut_t
 
typedef pinocchio::ConfigurationPtr_t ConfigurationPtr_t
 
typedef std::vector< ConfigurationPtr_tConfigurations_t
 
typedef Configurations_t::iterator ConfigIterator_t
 
typedef Configurations_t::const_iterator ConfigConstIterator_t
 
typedef boost::shared_ptr< ConfigurationShooterConfigurationShooterPtr_t
 
typedef boost::shared_ptr< ConfigProjectorConfigProjectorPtr_t
 
typedef boost::shared_ptr< ConfigValidationConfigValidationPtr_t
 
typedef boost::shared_ptr< ConfigValidationsConfigValidationsPtr_t
 
typedef boost::shared_ptr< ConnectedComponentConnectedComponentPtr_t
 
typedef std::set< ConnectedComponentPtr_tConnectedComponents_t
 
typedef boost::shared_ptr< ConstraintConstraintPtr_t
 
typedef boost::shared_ptr< ConstraintSetConstraintSetPtr_t
 
typedef boost::shared_ptr< const ConstraintSetConstraintSetConstPtr_t
 
typedef std::deque< ConstraintPtr_tConstraints_t
 
typedef pinocchio::Device Device_t
 
typedef pinocchio::DevicePtr_t DevicePtr_t
 
typedef pinocchio::DeviceWkPtr_t DeviceWkPtr_t
 
typedef pinocchio::CenterOfMassComputationPtr_t CenterOfMassComputationPtr_t
 
typedef std::deque< DevicePtr_tDevices_t
 
typedef constraints::DifferentiableFunction DifferentiableFunction
 
typedef constraints::DifferentiableFunctionPtr_t DifferentiableFunctionPtr_t
 
typedef boost::shared_ptr< DiffusingPlannerDiffusingPlannerPtr_t
 
typedef boost::shared_ptr< DistanceDistancePtr_t
 
typedef boost::shared_ptr< DistanceBetweenObjectsDistanceBetweenObjectsPtr_t
 
typedef pinocchio::DistanceResults_t DistanceResults_t
 
typedef EdgeEdgePtr_t
 
typedef std::list< Edge * > Edges_t
 
typedef boost::shared_ptr< ExtractedPath > ExtractedPathPtr_t
 
typedef boost::shared_ptr< SubchainPathSubchainPathPtr_t
 
typedef pinocchio::JointJacobian_t JointJacobian_t
 
typedef pinocchio::Joint Joint
 
typedef pinocchio::JointConstPtr_t JointConstPtr_t
 
typedef pinocchio::JointPtr_t JointPtr_t
 
typedef boost::shared_ptr< JointBoundValidationJointBoundValidationPtr_t
 
typedef boost::shared_ptr< JointBoundValidationReportJointBoundValidationReportPtr_t
 
typedef pinocchio::HalfJointJacobian_t HalfJointJacobian_t
 
typedef pinocchio::JointVector_t JointVector_t
 
typedef KDTree * KDTreePtr_t
 
typedef constraints::LockedJoint LockedJoint
 
typedef constraints::LockedJointPtr_t LockedJointPtr_t
 
typedef constraints::LockedJointConstPtr_t LockedJointConstPtr_t
 
typedef constraints::LockedJoints_t LockedJoints_t
 
typedef pinocchio::matrix_t matrix_t
 
typedef pinocchio::matrix3_t matrix3_t
 
typedef constraints::matrix6_t matrix6_t
 
typedef pinocchio::vector3_t vector3_t
 
typedef constraints::matrixIn_t matrixIn_t
 
typedef constraints::matrixOut_t matrixOut_t
 
typedef constraints::LiegroupElement LiegroupElement
 
typedef constraints::LiegroupElementRef LiegroupElementRef
 
typedef pinocchio::LiegroupElementConstRef LiegroupElementConstRef
 
typedef constraints::LiegroupSpace LiegroupSpace
 
typedef constraints::LiegroupSpacePtr_t LiegroupSpacePtr_t
 
typedef pinocchio::size_type size_type
 
typedef pinocchio::value_type value_type
 
typedef std::pair< value_type, value_typeinterval_t
 
typedef Eigen::BlockIndex BlockIndex
 Interval of indices as (first index, number of indices) More...
 
typedef constraints::segment_t segment_t
 
typedef constraints::segments_t segments_t
 
typedef NodeNodePtr_t
 
typedef std::list< NodePtr_tNodes_t
 
typedef std::vector< NodePtr_tNodeVector_t
 
typedef pinocchio::ObjectVector_t ObjectVector_t
 
typedef std::vector< CollisionObjectPtr_tObjectStdVector_t
 
typedef std::vector< CollisionObjectConstPtr_tConstObjectStdVector_t
 
typedef boost::shared_ptr< PathPathPtr_t
 
typedef boost::shared_ptr< const PathPathConstPtr_t
 
typedef boost::shared_ptr< TimeParameterizationTimeParameterizationPtr_t
 
typedef boost::shared_ptr< PathOptimizerPathOptimizerPtr_t
 
typedef boost::shared_ptr< PathPlannerPathPlannerPtr_t
 
typedef boost::shared_ptr< ProblemTargetProblemTargetPtr_t
 
typedef boost::shared_ptr< PathVectorPathVectorPtr_t
 
typedef boost::shared_ptr< const PathVectorPathVectorConstPtr_t
 
typedef boost::shared_ptr< PlanAndOptimizePlanAndOptimizePtr_t
 
typedef boost::shared_ptr< ProblemProblemPtr_t
 
typedef ProblemSolverProblemSolverPtr_t
 
typedef boost::shared_ptr< RoadmapRoadmapPtr_t
 
typedef boost::shared_ptr< StraightPathStraightPathPtr_t
 
typedef boost::shared_ptr< const StraightPathStraightPathConstPtr_t
 
typedef boost::shared_ptr< ReedsSheppPathReedsSheppPathPtr_t
 
typedef boost::shared_ptr< const ReedsSheppPathReedsSheppPathConstPtr_t
 
typedef boost::shared_ptr< DubinsPathDubinsPathPtr_t
 
typedef boost::shared_ptr< const DubinsPathDubinsPathConstPtr_t
 
typedef boost::shared_ptr< KinodynamicPathKinodynamicPathPtr_t
 
typedef boost::shared_ptr< const KinodynamicPathKinodynamicPathConstPtr_t
 
typedef boost::shared_ptr< KinodynamicOrientedPathKinodynamicOrientedPathPtr_t
 
typedef boost::shared_ptr< const KinodynamicOrientedPathKinodynamicOrientedPathConstPtr_t
 
typedef boost::shared_ptr< InterpolatedPathInterpolatedPathPtr_t
 
typedef boost::shared_ptr< const InterpolatedPathInterpolatedPathConstPtr_t
 
typedef boost::shared_ptr< SteeringMethodSteeringMethodPtr_t
 
typedef std::vector< PathPtr_tPaths_t
 
typedef std::vector< PathVectorPtr_tPathVectors_t
 
typedef pinocchio::Transform3f Transform3f
 
typedef Eigen::Matrix< value_type, 2, 1 > vector2_t
 
typedef pinocchio::vector_t vector_t
 
typedef pinocchio::vectorIn_t vectorIn_t
 
typedef pinocchio::vectorOut_t vectorOut_t
 
typedef Eigen::Matrix< value_type, 1, Eigen::Dynamic > rowvector_t
 
typedef boost::shared_ptr< VisibilityPrmPlannerVisibilityPrmPlannerPtr_t
 
typedef boost::shared_ptr< ValidationReportValidationReportPtr_t
 
typedef boost::shared_ptr< WeighedDistanceWeighedDistancePtr_t
 
typedef boost::shared_ptr< KinodynamicDistanceKinodynamicDistancePtr_t
 
typedef std::map< std::string, constraints::ImplicitPtr_tNumericalConstraintMap_t
 
typedef std::map< std::string, ComparisonTypes_tComparisonTypeMap_t
 
typedef std::map< std::string, segments_tsegmentsMap_t
 
typedef constraints::NumericalConstraints_t NumericalConstraints_t
 
typedef std::map< std::string, CenterOfMassComputationPtr_tCenterOfMassComputationMap_t
 
typedef std::pair< CollisionObjectConstPtr_t, CollisionObjectConstPtr_tCollisionPair_t
 
typedef std::vector< CollisionPair_tCollisionPairs_t
 
typedef boost::shared_ptr< ContinuousValidationContinuousValidationPtr_t
 
typedef NearestNeighborNearestNeighborPtr_t
 
typedef boost::shared_ptr< PathValidationPathValidationPtr_t
 
typedef boost::shared_ptr< PathValidationsPathValidationsPtr_t
 
typedef boost::shared_ptr< PathValidationReportPathValidationReportPtr_t
 
typedef boost::shared_ptr< CollisionPathValidationReportCollisionPathValidationReportPtr_t
 
typedef std::vector< CollisionPathValidationReportCollisionPathValidationReports_t
 
typedef boost::shared_ptr< PathProjectorPathProjectorPtr_t
 
typedef std::vector< core::vector3_tShape_t
 
typedef std::pair< JointPtr_t, Shape_tJointAndShape_t
 
typedef std::list< JointAndShape_tJointAndShapes_t
 
typedef constraints::Implicit NumericalConstraint HPP_CORE_DEPRECATED
 
typedef boost::function< DevicePtr_t(const std::string &) > RobotBuilder_t
 
typedef boost::function< PathOptimizerPtr_t(const Problem &) > PathOptimizerBuilder_t
 
typedef boost::function< PathPlannerPtr_t(const Problem &, const RoadmapPtr_t &) > PathPlannerBuilder_t
 
typedef boost::function< PathValidationPtr_t(const DevicePtr_t &, const value_type &) > PathValidationBuilder_t
 
typedef boost::function< ConfigValidationPtr_t(const DevicePtr_t &) > ConfigValidationBuilder_t
 
typedef boost::function< PathProjectorPtr_t(const Problem &, const value_type &) > PathProjectorBuilder_t
 
typedef boost::function< ConfigurationShooterPtr_t(const Problem &) > ConfigurationShooterBuilder_t
 
typedef boost::function< DistancePtr_t(const Problem &) > DistanceBuilder_t
 
typedef boost::function< SteeringMethodPtr_t(const Problem &) > SteeringMethodBuilder_t
 
typedef std::vector< std::pair< std::string, CollisionObjectPtr_t > > AffordanceObjects_t
 
typedef vector3_t AffordanceConfig_t
 
typedef steeringMethod::Straight SteeringMethodStraight
 
typedef steeringMethod::StraightPtr_t SteeringMethodStraightPtr_t
 

Functions

std::ostream & operator<< (std::ostream &os, const Constraint &constraint)
 
template<>
void ContinuousValidation::add< ContinuousValidation::AddObstacle > (const ContinuousValidation::AddObstacle &delegate)
 
template<>
void ContinuousValidation::reset< ContinuousValidation::AddObstacle > ()
 
template<>
void ContinuousValidation::add< ContinuousValidation::Initialize > (const ContinuousValidation::Initialize &delegate)
 
template<>
void ContinuousValidation::reset< ContinuousValidation::Initialize > ()
 
 HPP_PREDEF_CLASS (BiRRTPlanner)
 
 HPP_PREDEF_CLASS (CollisionValidation)
 
 HPP_PREDEF_CLASS (CollisionValidationReport)
 
 HPP_PREDEF_CLASS (AllCollisionsValidationReport)
 
 HPP_PREDEF_CLASS (ConfigurationShooter)
 
 HPP_PREDEF_CLASS (ConfigProjector)
 
 HPP_PREDEF_CLASS (ConfigValidation)
 
 HPP_PREDEF_CLASS (ConfigValidations)
 
 HPP_PREDEF_CLASS (ConnectedComponent)
 
 HPP_PREDEF_CLASS (Constraint)
 
 HPP_PREDEF_CLASS (ConstraintSet)
 
 HPP_PREDEF_CLASS (DiffusingPlanner)
 
 HPP_PREDEF_CLASS (Distance)
 
 HPP_PREDEF_CLASS (DistanceBetweenObjects)
 
 HPP_PREDEF_CLASS (ExtractedPath)
 
 HPP_PREDEF_CLASS (SubchainPath)
 
 HPP_PREDEF_CLASS (JointBoundValidation)
 
 HPP_PREDEF_CLASS (Path)
 
 HPP_PREDEF_CLASS (TimeParameterization)
 
 HPP_PREDEF_CLASS (PathOptimizer)
 
 HPP_PREDEF_CLASS (PathPlanner)
 
 HPP_PREDEF_CLASS (ProblemTarget)
 
 HPP_PREDEF_CLASS (PathVector)
 
 HPP_PREDEF_CLASS (PlanAndOptimize)
 
 HPP_PREDEF_CLASS (Problem)
 
 HPP_PREDEF_CLASS (Roadmap)
 
 HPP_PREDEF_CLASS (SteeringMethod)
 
 HPP_PREDEF_CLASS (StraightPath)
 
 HPP_PREDEF_CLASS (InterpolatedPath)
 
 HPP_PREDEF_CLASS (DubinsPath)
 
 HPP_PREDEF_CLASS (ReedsSheppPath)
 
 HPP_PREDEF_CLASS (KinodynamicPath)
 
 HPP_PREDEF_CLASS (KinodynamicOrientedPath)
 
 HPP_PREDEF_CLASS (ValidationReport)
 
 HPP_PREDEF_CLASS (VisibilityPrmPlanner)
 
 HPP_PREDEF_CLASS (WeighedDistance)
 
 HPP_PREDEF_CLASS (KinodynamicDistance)
 
 HPP_PREDEF_CLASS (ContinuousValidation)
 
 HPP_PREDEF_CLASS (PathValidations)
 
 HPP_PREDEF_CLASS (PathValidation)
 
 HPP_PREDEF_CLASS (PathProjector)
 
std::ostream & operator<< (std::ostream &os, const Node &n)
 
std::ostream & operator<< (std::ostream &os, const Path &path)
 
std::ostream & operator<< (std::ostream &os, const Roadmap &r)
 
std::ostream & operator<< (std::ostream &os, const ValidationReport &report)
 

Typedef Documentation

◆ AffordanceConfig_t

◆ AffordanceObjects_t

typedef std::vector<std::pair < std::string, CollisionObjectPtr_t > > hpp::core::AffordanceObjects_t

◆ AllCollisionsValidationReportPtr_t

◆ BiRRTPlannerPtr_t

typedef boost::shared_ptr<BiRRTPlanner> hpp::core::BiRRTPlannerPtr_t

◆ BlockIndex

Interval of indices as (first index, number of indices)

◆ Body

◆ BodyPtr_t

◆ BySubstitution

◆ CenterOfMassComputationMap_t

◆ CenterOfMassComputationPtr_t

◆ CollisionObjectConstPtr_t

◆ CollisionObjectPtr_t

◆ CollisionPair_t

◆ CollisionPairs_t

◆ CollisionPathValidationReportPtr_t

◆ CollisionPathValidationReports_t

◆ CollisionValidationPtr_t

◆ CollisionValidationReportPtr_t

◆ ComparisonType

◆ ComparisonTypeMap_t

typedef std::map<std::string, ComparisonTypes_t> hpp::core::ComparisonTypeMap_t

◆ ComparisonTypes_t

◆ ConfigConstIterator_t

typedef Configurations_t::const_iterator hpp::core::ConfigConstIterator_t

◆ ConfigIterator_t

typedef Configurations_t::iterator hpp::core::ConfigIterator_t

◆ ConfigProjectorPtr_t

◆ Configuration_t

◆ ConfigurationIn_t

◆ ConfigurationOut_t

◆ ConfigurationPtr_t

◆ Configurations_t

◆ ConfigurationShooterBuilder_t

◆ ConfigurationShooterPtr_t

◆ ConfigValidationBuilder_t

◆ ConfigValidationPtr_t

◆ ConfigValidationsPtr_t

◆ ConnectedComponentPtr_t

◆ ConnectedComponents_t

◆ ConstObjectStdVector_t

◆ ConstraintPtr_t

typedef boost::shared_ptr<Constraint> hpp::core::ConstraintPtr_t

◆ Constraints_t

◆ ConstraintSetConstPtr_t

typedef boost::shared_ptr<const ConstraintSet> hpp::core::ConstraintSetConstPtr_t

◆ ConstraintSetPtr_t

typedef boost::shared_ptr<ConstraintSet> hpp::core::ConstraintSetPtr_t

◆ ContinuousValidationPtr_t

◆ Device_t

◆ DevicePtr_t

◆ Devices_t

typedef std::deque<DevicePtr_t> hpp::core::Devices_t

◆ DeviceWkPtr_t

typedef pinocchio::DeviceWkPtr_t hpp::core::DeviceWkPtr_t

◆ DifferentiableFunction

◆ DifferentiableFunctionPtr_t

◆ DiffusingPlannerPtr_t

◆ DistanceBetweenObjectsPtr_t

◆ DistanceBuilder_t

typedef boost::function<DistancePtr_t (const Problem&) > hpp::core::DistanceBuilder_t

◆ DistancePtr_t

typedef boost::shared_ptr<Distance> hpp::core::DistancePtr_t

◆ DistanceResults_t

◆ DubinsPathConstPtr_t

typedef boost::shared_ptr<const DubinsPath> hpp::core::DubinsPathConstPtr_t

◆ DubinsPathPtr_t

typedef boost::shared_ptr<DubinsPath> hpp::core::DubinsPathPtr_t

◆ EdgePtr_t

◆ Edges_t

typedef std::list<Edge*> hpp::core::Edges_t

◆ ExtractedPathPtr_t

typedef boost::shared_ptr<ExtractedPath> hpp::core::ExtractedPathPtr_t

◆ FclCollisionObject

◆ FclCollisionObjectPtr_t

◆ FclCollisionObjectSharePtr_t

◆ FclConstCollisionObjectPtr_t

◆ HalfJointJacobian_t

◆ HPP_CORE_DEPRECATED

typedef ContinuousValidation ContinuousCollisionChecking hpp::core::HPP_CORE_DEPRECATED

◆ InterpolatedPathConstPtr_t

typedef boost::shared_ptr<const InterpolatedPath> hpp::core::InterpolatedPathConstPtr_t

◆ InterpolatedPathPtr_t

◆ interval_t

◆ Joint

◆ JointAndShape_t

◆ JointAndShapes_t

◆ JointBoundValidationPtr_t

◆ JointBoundValidationReportPtr_t

◆ JointConstPtr_t

◆ JointJacobian_t

◆ JointPtr_t

◆ JointVector_t

◆ KDTreePtr_t

typedef KDTree* hpp::core::KDTreePtr_t

◆ KinodynamicDistancePtr_t

◆ KinodynamicOrientedPathConstPtr_t

◆ KinodynamicOrientedPathPtr_t

◆ KinodynamicPathConstPtr_t

typedef boost::shared_ptr<const KinodynamicPath> hpp::core::KinodynamicPathConstPtr_t

◆ KinodynamicPathPtr_t

◆ LiegroupElement

◆ LiegroupElementConstRef

◆ LiegroupElementRef

◆ LiegroupSpace

◆ LiegroupSpacePtr_t

◆ LockedJoint

◆ LockedJointConstPtr_t

◆ LockedJointPtr_t

◆ LockedJoints_t

◆ matrix3_t

◆ matrix6_t

◆ matrix_t

◆ matrixIn_t

◆ matrixOut_t

◆ NearestNeighborPtr_t

◆ NodePtr_t

◆ Nodes_t

typedef std::list<NodePtr_t> hpp::core::Nodes_t

◆ NodeVector_t

typedef std::vector<NodePtr_t> hpp::core::NodeVector_t

◆ NumericalConstraintMap_t

◆ NumericalConstraints_t

◆ ObjectStdVector_t

◆ ObjectVector_t

◆ PathConstPtr_t

typedef boost::shared_ptr<const Path> hpp::core::PathConstPtr_t

◆ PathOptimizerBuilder_t

typedef boost::function< PathOptimizerPtr_t (const Problem&) > hpp::core::PathOptimizerBuilder_t

◆ PathOptimizerPtr_t

typedef boost::shared_ptr<PathOptimizer> hpp::core::PathOptimizerPtr_t

◆ PathPlannerBuilder_t

typedef boost::function< PathPlannerPtr_t (const Problem&, const RoadmapPtr_t&) > hpp::core::PathPlannerBuilder_t

◆ PathPlannerPtr_t

typedef boost::shared_ptr<PathPlanner> hpp::core::PathPlannerPtr_t

◆ PathProjectorBuilder_t

typedef boost::function<PathProjectorPtr_t (const Problem&, const value_type&) > hpp::core::PathProjectorBuilder_t

◆ PathProjectorPtr_t

typedef boost::shared_ptr<PathProjector> hpp::core::PathProjectorPtr_t

◆ PathPtr_t

typedef boost::shared_ptr<Path> hpp::core::PathPtr_t

◆ Paths_t

typedef std::vector<PathPtr_t> hpp::core::Paths_t

◆ PathValidationBuilder_t

◆ PathValidationPtr_t

typedef boost::shared_ptr<PathValidation> hpp::core::PathValidationPtr_t

◆ PathValidationReportPtr_t

◆ PathValidationsPtr_t

◆ PathVectorConstPtr_t

typedef boost::shared_ptr<const PathVector> hpp::core::PathVectorConstPtr_t

◆ PathVectorPtr_t

typedef boost::shared_ptr<PathVector> hpp::core::PathVectorPtr_t

◆ PathVectors_t

typedef std::vector< PathVectorPtr_t > hpp::core::PathVectors_t

◆ PlanAndOptimizePtr_t

◆ ProblemPtr_t

typedef boost::shared_ptr<Problem> hpp::core::ProblemPtr_t

◆ ProblemSolverPtr_t

◆ ProblemTargetPtr_t

typedef boost::shared_ptr<ProblemTarget> hpp::core::ProblemTargetPtr_t

◆ ReedsSheppPathConstPtr_t

typedef boost::shared_ptr<const ReedsSheppPath> hpp::core::ReedsSheppPathConstPtr_t

◆ ReedsSheppPathPtr_t

typedef boost::shared_ptr<ReedsSheppPath> hpp::core::ReedsSheppPathPtr_t

◆ RoadmapPtr_t

typedef boost::shared_ptr<Roadmap> hpp::core::RoadmapPtr_t

◆ RobotBuilder_t

typedef boost::function< DevicePtr_t (const std::string&) > hpp::core::RobotBuilder_t

◆ rowvector_t

typedef Eigen::Matrix<value_type, 1, Eigen::Dynamic> hpp::core::rowvector_t

◆ segment_t

◆ segments_t

◆ segmentsMap_t

typedef std::map<std::string, segments_t> hpp::core::segmentsMap_t

◆ Shape_t

typedef std::vector<core::vector3_t> hpp::core::Shape_t

Plane polygon represented by its vertices Used to model contact surfaces for manipulation applications

◆ size_type

◆ SteeringMethodBuilder_t

◆ SteeringMethodPtr_t

typedef boost::shared_ptr<SteeringMethod> hpp::core::SteeringMethodPtr_t

◆ SteeringMethodStraight

◆ SteeringMethodStraightPtr_t

◆ StraightPathConstPtr_t

typedef boost::shared_ptr<const StraightPath> hpp::core::StraightPathConstPtr_t

◆ StraightPathPtr_t

typedef boost::shared_ptr<StraightPath> hpp::core::StraightPathPtr_t

◆ SubchainPathPtr_t

typedef boost::shared_ptr<SubchainPath> hpp::core::SubchainPathPtr_t

◆ TimeParameterizationPtr_t

◆ Transform3f

◆ ValidationReportPtr_t

◆ value_type

◆ vector2_t

typedef Eigen::Matrix<value_type, 2, 1> hpp::core::vector2_t

◆ vector3_t

◆ vector_t

◆ vectorIn_t

◆ vectorOut_t

◆ VisibilityPrmPlannerPtr_t

◆ WeighedDistancePtr_t

Function Documentation

◆ ContinuousValidation::add< ContinuousValidation::AddObstacle >()

◆ ContinuousValidation::add< ContinuousValidation::Initialize >()

◆ ContinuousValidation::reset< ContinuousValidation::AddObstacle >()

◆ ContinuousValidation::reset< ContinuousValidation::Initialize >()

◆ HPP_PREDEF_CLASS() [1/41]

hpp::core::HPP_PREDEF_CLASS ( BiRRTPlanner  )

◆ HPP_PREDEF_CLASS() [2/41]

hpp::core::HPP_PREDEF_CLASS ( CollisionValidation  )

◆ HPP_PREDEF_CLASS() [3/41]

hpp::core::HPP_PREDEF_CLASS ( CollisionValidationReport  )

◆ HPP_PREDEF_CLASS() [4/41]

hpp::core::HPP_PREDEF_CLASS ( AllCollisionsValidationReport  )

◆ HPP_PREDEF_CLASS() [5/41]

hpp::core::HPP_PREDEF_CLASS ( ConfigurationShooter  )

◆ HPP_PREDEF_CLASS() [6/41]

hpp::core::HPP_PREDEF_CLASS ( ConfigProjector  )

◆ HPP_PREDEF_CLASS() [7/41]

hpp::core::HPP_PREDEF_CLASS ( ConfigValidation  )

◆ HPP_PREDEF_CLASS() [8/41]

hpp::core::HPP_PREDEF_CLASS ( ConfigValidations  )

◆ HPP_PREDEF_CLASS() [9/41]

hpp::core::HPP_PREDEF_CLASS ( ConnectedComponent  )

◆ HPP_PREDEF_CLASS() [10/41]

hpp::core::HPP_PREDEF_CLASS ( Constraint  )

◆ HPP_PREDEF_CLASS() [11/41]

hpp::core::HPP_PREDEF_CLASS ( ConstraintSet  )

◆ HPP_PREDEF_CLASS() [12/41]

hpp::core::HPP_PREDEF_CLASS ( DiffusingPlanner  )

◆ HPP_PREDEF_CLASS() [13/41]

hpp::core::HPP_PREDEF_CLASS ( Distance  )

◆ HPP_PREDEF_CLASS() [14/41]

hpp::core::HPP_PREDEF_CLASS ( DistanceBetweenObjects  )

◆ HPP_PREDEF_CLASS() [15/41]

hpp::core::HPP_PREDEF_CLASS ( ExtractedPath  )

◆ HPP_PREDEF_CLASS() [16/41]

hpp::core::HPP_PREDEF_CLASS ( SubchainPath  )

◆ HPP_PREDEF_CLASS() [17/41]

hpp::core::HPP_PREDEF_CLASS ( JointBoundValidation  )

◆ HPP_PREDEF_CLASS() [18/41]

hpp::core::HPP_PREDEF_CLASS ( Path  )

◆ HPP_PREDEF_CLASS() [19/41]

hpp::core::HPP_PREDEF_CLASS ( TimeParameterization  )

◆ HPP_PREDEF_CLASS() [20/41]

hpp::core::HPP_PREDEF_CLASS ( PathOptimizer  )

◆ HPP_PREDEF_CLASS() [21/41]

hpp::core::HPP_PREDEF_CLASS ( PathPlanner  )

◆ HPP_PREDEF_CLASS() [22/41]

hpp::core::HPP_PREDEF_CLASS ( ProblemTarget  )

◆ HPP_PREDEF_CLASS() [23/41]

hpp::core::HPP_PREDEF_CLASS ( PathVector  )

◆ HPP_PREDEF_CLASS() [24/41]

hpp::core::HPP_PREDEF_CLASS ( PlanAndOptimize  )

◆ HPP_PREDEF_CLASS() [25/41]

hpp::core::HPP_PREDEF_CLASS ( Problem  )

◆ HPP_PREDEF_CLASS() [26/41]

hpp::core::HPP_PREDEF_CLASS ( Roadmap  )

◆ HPP_PREDEF_CLASS() [27/41]

hpp::core::HPP_PREDEF_CLASS ( SteeringMethod  )

◆ HPP_PREDEF_CLASS() [28/41]

hpp::core::HPP_PREDEF_CLASS ( StraightPath  )

◆ HPP_PREDEF_CLASS() [29/41]

hpp::core::HPP_PREDEF_CLASS ( InterpolatedPath  )

◆ HPP_PREDEF_CLASS() [30/41]

hpp::core::HPP_PREDEF_CLASS ( DubinsPath  )

◆ HPP_PREDEF_CLASS() [31/41]

hpp::core::HPP_PREDEF_CLASS ( ReedsSheppPath  )

◆ HPP_PREDEF_CLASS() [32/41]

hpp::core::HPP_PREDEF_CLASS ( KinodynamicPath  )

◆ HPP_PREDEF_CLASS() [33/41]

hpp::core::HPP_PREDEF_CLASS ( KinodynamicOrientedPath  )

◆ HPP_PREDEF_CLASS() [34/41]

hpp::core::HPP_PREDEF_CLASS ( ValidationReport  )

◆ HPP_PREDEF_CLASS() [35/41]

hpp::core::HPP_PREDEF_CLASS ( VisibilityPrmPlanner  )

◆ HPP_PREDEF_CLASS() [36/41]

hpp::core::HPP_PREDEF_CLASS ( WeighedDistance  )

◆ HPP_PREDEF_CLASS() [37/41]

hpp::core::HPP_PREDEF_CLASS ( KinodynamicDistance  )

◆ HPP_PREDEF_CLASS() [38/41]

hpp::core::HPP_PREDEF_CLASS ( ContinuousValidation  )

◆ HPP_PREDEF_CLASS() [39/41]

hpp::core::HPP_PREDEF_CLASS ( PathValidations  )

◆ HPP_PREDEF_CLASS() [40/41]

hpp::core::HPP_PREDEF_CLASS ( PathValidation  )

◆ HPP_PREDEF_CLASS() [41/41]

hpp::core::HPP_PREDEF_CLASS ( PathProjector  )