Classes | |
struct | AllCollisionsValidationReport |
Validate a configuration with respect to collision. More... | |
class | BiRRTPlanner |
Implementation of directional bi-RRT algorithm maintaining only two connected components for respectively the start and goal configurations. More... | |
struct | CollisionPathValidationReport |
Path validation report used for standard collision checking. More... | |
class | CollisionValidation |
Validate a configuration with respect to collision. More... | |
struct | CollisionValidationReport |
Validate a configuration with respect to collision. More... | |
class | ConfigProjector |
Implicit non-linear constraint. More... | |
class | ConfigurationShooter |
Abstraction of configuration shooter. More... | |
class | ConfigValidation |
Abstraction of configuration validation. More... | |
class | ConfigValidations |
Validate a configuration with respect to collision. More... | |
class | ConnectedComponent |
Connected component. More... | |
class | Constraint |
Constraint applicable to a robot configuration. More... | |
class | ConstraintSet |
Set of constraints applicable to a robot configuration. More... | |
struct | Container |
class | ContinuousValidation |
Continuous validation of a path. More... | |
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 |
Car like motion going only forward. More... | |
class | Edge |
Edge of a roadmap. More... | |
class | InterpolatedPath |
Piecewise linear interpolation between two configurations. More... | |
class | JointBoundValidation |
Validate a configuration with respect to joint bounds. More... | |
class | JointBoundValidationReport |
report returned when a configuration is not within the bounds More... | |
class | KinodynamicDistance |
This class computed the Distance between two states as the minimal time required to connect this two states with a "bang-bang" trajectory, given velocity and acceleration bounds. More... | |
class | KinodynamicOrientedPath |
This class is similar to KinodynamicPath exept that the orientation of the robot always follow the direction of the velocity. More... | |
class | KinodynamicPath |
Kino-dynamic straight path. More... | |
class | Member_lockedJoints_in_class_ProblemSolver_has_been_removed_use_member_numericalConstraints_instead |
member ProblemSolver::lockedJoints has been removed. More... | |
class | NearestNeighbor |
Optimization of the nearest neighbor search. More... | |
class | Node |
Node of a roadmap. More... | |
class | Parameter |
class | ParameterDescription |
class | Path |
Abstraction of paths: mapping from time to configuration space. More... | |
class | PathOptimizer |
Abstraction of path optimizer. More... | |
class | PathPlanner |
Path planner. More... | |
class | PathProjector |
This class projects a path using constraints. More... | |
class | PathValidation |
Abstraction of path validation. More... | |
struct | PathValidationReport |
Abstraction of path validation report. More... | |
class | PathValidations |
Validation of a path with multiple path validation methods. More... | |
class | PathVector |
Concatenation of several paths. More... | |
class | PlanAndOptimize |
Path planner and optimizer. More... | |
class | Problem |
Defines a path planning problem for one robot. More... | |
class | ProblemSolver |
Set and solve a path planning problem. More... | |
class | ProblemSolverPlugin |
Plugin mechanism to declare new features in ProblemSolver class. More... | |
class | ProblemTarget |
Problem target. More... | |
struct | projection_error |
class | ReedsSheppPath |
Car like motion. More... | |
struct | RelativeMotion |
class | Roadmap |
Roadmap built by random path planning methods Nodes are configurations, paths are collision-free paths. More... | |
class | SteeringMethod |
Steering method. More... | |
class | StraightPath |
Linear interpolation between two configurations. More... | |
class | SubchainPath |
Result of the selection of some configuration parameter of an original path. More... | |
class | TimeParameterization |
class | ValidationReport |
Abstraction of validation report for paths and configurations. More... | |
class | VisibilityPrmPlanner |
Generic implementation of visibility-PRM algorithm, based on guard nodes (which cannot see each other) and connection nodes between guards. More... | |
class | WeighedDistance |
Weighed distance between configurations. More... | |
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< BiRRTPlanner > | BiRRTPlannerPtr_t |
typedef hpp::pinocchio::Body | Body |
typedef hpp::pinocchio::BodyPtr_t | BodyPtr_t |
typedef boost::shared_ptr< CollisionValidation > | CollisionValidationPtr_t |
typedef boost::shared_ptr< CollisionValidationReport > | CollisionValidationReportPtr_t |
typedef boost::shared_ptr< AllCollisionsValidationReport > | AllCollisionsValidationReportPtr_t |
typedef pinocchio::CollisionObjectPtr_t | CollisionObjectPtr_t |
typedef pinocchio::CollisionObjectConstPtr_t | CollisionObjectConstPtr_t |
typedef pinocchio::FclCollisionObject | FclCollisionObject |
typedef FclCollisionObject * | FclCollisionObjectPtr_t |
typedef const FclCollisionObject * | FclConstCollisionObjectPtr_t |
typedef boost::shared_ptr< FclCollisionObject > | FclCollisionObjectSharePtr_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_t > | Configurations_t |
typedef Configurations_t::iterator | ConfigIterator_t |
typedef Configurations_t::const_iterator | ConfigConstIterator_t |
typedef boost::shared_ptr< ConfigurationShooter > | ConfigurationShooterPtr_t |
typedef boost::shared_ptr< ConfigProjector > | ConfigProjectorPtr_t |
typedef boost::shared_ptr< ConfigValidation > | ConfigValidationPtr_t |
typedef boost::shared_ptr< ConfigValidations > | ConfigValidationsPtr_t |
typedef boost::shared_ptr< ConnectedComponent > | ConnectedComponentPtr_t |
typedef std::set< ConnectedComponentPtr_t > | ConnectedComponents_t |
typedef boost::shared_ptr< Constraint > | ConstraintPtr_t |
typedef boost::shared_ptr< ConstraintSet > | ConstraintSetPtr_t |
typedef boost::shared_ptr< const ConstraintSet > | ConstraintSetConstPtr_t |
typedef std::deque< ConstraintPtr_t > | Constraints_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_t > | Devices_t |
typedef constraints::DifferentiableFunction | DifferentiableFunction |
typedef constraints::DifferentiableFunctionPtr_t | DifferentiableFunctionPtr_t |
typedef boost::shared_ptr< DiffusingPlanner > | DiffusingPlannerPtr_t |
typedef boost::shared_ptr< Distance > | DistancePtr_t |
typedef boost::shared_ptr< DistanceBetweenObjects > | DistanceBetweenObjectsPtr_t |
typedef pinocchio::DistanceResults_t | DistanceResults_t |
typedef Edge * | EdgePtr_t |
typedef std::list< Edge * > | Edges_t |
typedef boost::shared_ptr< ExtractedPath > | ExtractedPathPtr_t |
typedef boost::shared_ptr< SubchainPath > | SubchainPathPtr_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< JointBoundValidation > | JointBoundValidationPtr_t |
typedef boost::shared_ptr< JointBoundValidationReport > | JointBoundValidationReportPtr_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 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_type > | interval_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 Node * | NodePtr_t |
typedef std::list< NodePtr_t > | Nodes_t |
typedef std::vector< NodePtr_t > | NodeVector_t |
typedef pinocchio::ObjectVector_t | ObjectVector_t |
typedef std::vector< CollisionObjectPtr_t > | ObjectStdVector_t |
typedef std::vector< CollisionObjectConstPtr_t > | ConstObjectStdVector_t |
typedef boost::shared_ptr< Path > | PathPtr_t |
typedef boost::shared_ptr< const Path > | PathConstPtr_t |
typedef boost::shared_ptr< TimeParameterization > | TimeParameterizationPtr_t |
typedef boost::shared_ptr< PathOptimizer > | PathOptimizerPtr_t |
typedef boost::shared_ptr< PathPlanner > | PathPlannerPtr_t |
typedef boost::shared_ptr< ProblemTarget > | ProblemTargetPtr_t |
typedef boost::shared_ptr< PathVector > | PathVectorPtr_t |
typedef boost::shared_ptr< const PathVector > | PathVectorConstPtr_t |
typedef boost::shared_ptr< PlanAndOptimize > | PlanAndOptimizePtr_t |
typedef boost::shared_ptr< Problem > | ProblemPtr_t |
typedef ProblemSolver * | ProblemSolverPtr_t |
typedef boost::shared_ptr< Roadmap > | RoadmapPtr_t |
typedef boost::shared_ptr< StraightPath > | StraightPathPtr_t |
typedef boost::shared_ptr< const StraightPath > | StraightPathConstPtr_t |
typedef boost::shared_ptr< ReedsSheppPath > | ReedsSheppPathPtr_t |
typedef boost::shared_ptr< const ReedsSheppPath > | ReedsSheppPathConstPtr_t |
typedef boost::shared_ptr< DubinsPath > | DubinsPathPtr_t |
typedef boost::shared_ptr< const DubinsPath > | DubinsPathConstPtr_t |
typedef boost::shared_ptr< KinodynamicPath > | KinodynamicPathPtr_t |
typedef boost::shared_ptr< const KinodynamicPath > | KinodynamicPathConstPtr_t |
typedef boost::shared_ptr< KinodynamicOrientedPath > | KinodynamicOrientedPathPtr_t |
typedef boost::shared_ptr< const KinodynamicOrientedPath > | KinodynamicOrientedPathConstPtr_t |
typedef boost::shared_ptr< InterpolatedPath > | InterpolatedPathPtr_t |
typedef boost::shared_ptr< const InterpolatedPath > | InterpolatedPathConstPtr_t |
typedef boost::shared_ptr< SteeringMethod > | SteeringMethodPtr_t |
typedef std::vector< PathPtr_t > | Paths_t |
typedef std::vector< PathVectorPtr_t > | PathVectors_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< VisibilityPrmPlanner > | VisibilityPrmPlannerPtr_t |
typedef boost::shared_ptr< ValidationReport > | ValidationReportPtr_t |
typedef boost::shared_ptr< WeighedDistance > | WeighedDistancePtr_t |
typedef boost::shared_ptr< KinodynamicDistance > | KinodynamicDistancePtr_t |
typedef std::map< std::string, constraints::ImplicitPtr_t > | NumericalConstraintMap_t |
typedef std::map< std::string, ComparisonTypes_t > | ComparisonTypeMap_t |
typedef std::map< std::string, segments_t > | segmentsMap_t |
typedef constraints::NumericalConstraints_t | NumericalConstraints_t |
typedef std::map< std::string, CenterOfMassComputationPtr_t > | CenterOfMassComputationMap_t |
typedef std::pair< CollisionObjectConstPtr_t, CollisionObjectConstPtr_t > | CollisionPair_t |
typedef std::vector< CollisionPair_t > | CollisionPairs_t |
typedef boost::shared_ptr< ContinuousValidation > | ContinuousValidationPtr_t |
typedef NearestNeighbor * | NearestNeighborPtr_t |
typedef boost::shared_ptr< PathValidation > | PathValidationPtr_t |
typedef boost::shared_ptr< PathValidations > | PathValidationsPtr_t |
typedef boost::shared_ptr< PathValidationReport > | PathValidationReportPtr_t |
typedef boost::shared_ptr< CollisionPathValidationReport > | CollisionPathValidationReportPtr_t |
typedef std::vector< CollisionPathValidationReport > | CollisionPathValidationReports_t |
typedef boost::shared_ptr< PathProjector > | PathProjectorPtr_t |
typedef std::vector< core::vector3_t > | Shape_t |
typedef std::pair< JointPtr_t, Shape_t > | JointAndShape_t |
typedef std::list< JointAndShape_t > | JointAndShapes_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 |
typedef std::vector<std::pair < std::string, CollisionObjectPtr_t > > hpp::core::AffordanceObjects_t |
typedef boost::shared_ptr<AllCollisionsValidationReport> hpp::core::AllCollisionsValidationReportPtr_t |
typedef boost::shared_ptr<BiRRTPlanner> hpp::core::BiRRTPlannerPtr_t |
typedef Eigen::BlockIndex hpp::core::BlockIndex |
Interval of indices as (first index, number of indices)
typedef hpp::pinocchio::Body hpp::core::Body |
typedef hpp::pinocchio::BodyPtr_t hpp::core::BodyPtr_t |
typedef constraints::solver::BySubstitution hpp::core::BySubstitution |
typedef std::map<std::string, CenterOfMassComputationPtr_t> hpp::core::CenterOfMassComputationMap_t |
typedef pinocchio::CenterOfMassComputationPtr_t hpp::core::CenterOfMassComputationPtr_t |
typedef pinocchio::CollisionObjectConstPtr_t hpp::core::CollisionObjectConstPtr_t |
typedef pinocchio::CollisionObjectPtr_t hpp::core::CollisionObjectPtr_t |
typedef std::pair<CollisionObjectConstPtr_t, CollisionObjectConstPtr_t> hpp::core::CollisionPair_t |
typedef std::vector<CollisionPair_t> hpp::core::CollisionPairs_t |
typedef boost::shared_ptr<CollisionPathValidationReport> hpp::core::CollisionPathValidationReportPtr_t |
typedef std::vector<CollisionPathValidationReport> hpp::core::CollisionPathValidationReports_t |
typedef boost::shared_ptr<CollisionValidation> hpp::core::CollisionValidationPtr_t |
typedef boost::shared_ptr<CollisionValidationReport> hpp::core::CollisionValidationReportPtr_t |
typedef constraints::ComparisonType hpp::core::ComparisonType |
typedef std::map<std::string, ComparisonTypes_t> hpp::core::ComparisonTypeMap_t |
typedef constraints::ComparisonTypes_t hpp::core::ComparisonTypes_t |
typedef Configurations_t::const_iterator hpp::core::ConfigConstIterator_t |
typedef Configurations_t::iterator hpp::core::ConfigIterator_t |
typedef boost::shared_ptr<ConfigProjector> hpp::core::ConfigProjectorPtr_t |
typedef pinocchio::Configuration_t hpp::core::Configuration_t |
typedef pinocchio::ConfigurationIn_t hpp::core::ConfigurationIn_t |
typedef pinocchio::ConfigurationOut_t hpp::core::ConfigurationOut_t |
typedef pinocchio::ConfigurationPtr_t hpp::core::ConfigurationPtr_t |
typedef std::vector<ConfigurationPtr_t> hpp::core::Configurations_t |
typedef boost::function<ConfigurationShooterPtr_t (const Problem&) > hpp::core::ConfigurationShooterBuilder_t |
typedef boost::shared_ptr<ConfigurationShooter> hpp::core::ConfigurationShooterPtr_t |
typedef boost::function< ConfigValidationPtr_t (const DevicePtr_t&) > hpp::core::ConfigValidationBuilder_t |
typedef boost::shared_ptr<ConfigValidation> hpp::core::ConfigValidationPtr_t |
typedef boost::shared_ptr<ConfigValidations> hpp::core::ConfigValidationsPtr_t |
typedef boost::shared_ptr<ConnectedComponent> hpp::core::ConnectedComponentPtr_t |
typedef std::set<ConnectedComponentPtr_t> hpp::core::ConnectedComponents_t |
typedef std::vector<CollisionObjectConstPtr_t> hpp::core::ConstObjectStdVector_t |
typedef boost::shared_ptr<Constraint> hpp::core::ConstraintPtr_t |
typedef std::deque<ConstraintPtr_t> hpp::core::Constraints_t |
typedef boost::shared_ptr<const ConstraintSet> hpp::core::ConstraintSetConstPtr_t |
typedef boost::shared_ptr<ConstraintSet> hpp::core::ConstraintSetPtr_t |
typedef boost::shared_ptr<ContinuousValidation> hpp::core::ContinuousValidationPtr_t |
typedef pinocchio::Device hpp::core::Device_t |
typedef pinocchio::DevicePtr_t hpp::core::DevicePtr_t |
typedef std::deque<DevicePtr_t> hpp::core::Devices_t |
typedef pinocchio::DeviceWkPtr_t hpp::core::DeviceWkPtr_t |
typedef constraints::DifferentiableFunction hpp::core::DifferentiableFunction |
typedef constraints::DifferentiableFunctionPtr_t hpp::core::DifferentiableFunctionPtr_t |
typedef boost::shared_ptr<DiffusingPlanner> hpp::core::DiffusingPlannerPtr_t |
typedef boost::shared_ptr<DistanceBetweenObjects> hpp::core::DistanceBetweenObjectsPtr_t |
typedef boost::function<DistancePtr_t (const Problem&) > hpp::core::DistanceBuilder_t |
typedef boost::shared_ptr<Distance> hpp::core::DistancePtr_t |
typedef pinocchio::DistanceResults_t hpp::core::DistanceResults_t |
typedef boost::shared_ptr<const DubinsPath> hpp::core::DubinsPathConstPtr_t |
typedef boost::shared_ptr<DubinsPath> hpp::core::DubinsPathPtr_t |
typedef Edge* hpp::core::EdgePtr_t |
typedef std::list<Edge*> hpp::core::Edges_t |
typedef boost::shared_ptr<ExtractedPath> hpp::core::ExtractedPathPtr_t |
typedef pinocchio::FclCollisionObject hpp::core::FclCollisionObject |
typedef boost::shared_ptr<FclCollisionObject> hpp::core::FclCollisionObjectSharePtr_t |
typedef const FclCollisionObject* hpp::core::FclConstCollisionObjectPtr_t |
typedef pinocchio::HalfJointJacobian_t hpp::core::HalfJointJacobian_t |
typedef ContinuousValidation ContinuousCollisionChecking hpp::core::HPP_CORE_DEPRECATED |
typedef boost::shared_ptr<const InterpolatedPath> hpp::core::InterpolatedPathConstPtr_t |
typedef boost::shared_ptr<InterpolatedPath> hpp::core::InterpolatedPathPtr_t |
typedef std::pair<value_type, value_type> hpp::core::interval_t |
typedef pinocchio::Joint hpp::core::Joint |
typedef std::pair<JointPtr_t, Shape_t> hpp::core::JointAndShape_t |
typedef std::list<JointAndShape_t> hpp::core::JointAndShapes_t |
typedef boost::shared_ptr<JointBoundValidation> hpp::core::JointBoundValidationPtr_t |
typedef boost::shared_ptr<JointBoundValidationReport> hpp::core::JointBoundValidationReportPtr_t |
typedef pinocchio::JointConstPtr_t hpp::core::JointConstPtr_t |
typedef pinocchio::JointJacobian_t hpp::core::JointJacobian_t |
typedef pinocchio::JointPtr_t hpp::core::JointPtr_t |
typedef pinocchio::JointVector_t hpp::core::JointVector_t |
typedef KDTree* hpp::core::KDTreePtr_t |
typedef boost::shared_ptr<KinodynamicDistance> hpp::core::KinodynamicDistancePtr_t |
typedef boost::shared_ptr<const KinodynamicOrientedPath> hpp::core::KinodynamicOrientedPathConstPtr_t |
typedef boost::shared_ptr<KinodynamicOrientedPath> hpp::core::KinodynamicOrientedPathPtr_t |
typedef boost::shared_ptr<const KinodynamicPath> hpp::core::KinodynamicPathConstPtr_t |
typedef boost::shared_ptr<KinodynamicPath> hpp::core::KinodynamicPathPtr_t |
typedef constraints::LiegroupElement hpp::core::LiegroupElement |
typedef constraints::LiegroupElementRef hpp::core::LiegroupElementRef |
typedef constraints::LiegroupSpace hpp::core::LiegroupSpace |
typedef constraints::LiegroupSpacePtr_t hpp::core::LiegroupSpacePtr_t |
typedef constraints::LockedJoint hpp::core::LockedJoint |
typedef constraints::LockedJointConstPtr_t hpp::core::LockedJointConstPtr_t |
typedef constraints::LockedJointPtr_t hpp::core::LockedJointPtr_t |
typedef constraints::LockedJoints_t hpp::core::LockedJoints_t |
typedef pinocchio::matrix3_t hpp::core::matrix3_t |
typedef constraints::matrix6_t hpp::core::matrix6_t |
typedef pinocchio::matrix_t hpp::core::matrix_t |
typedef constraints::matrixIn_t hpp::core::matrixIn_t |
typedef constraints::matrixOut_t hpp::core::matrixOut_t |
typedef Node* hpp::core::NodePtr_t |
typedef std::list<NodePtr_t> hpp::core::Nodes_t |
typedef std::vector<NodePtr_t> hpp::core::NodeVector_t |
typedef std::map<std::string, constraints::ImplicitPtr_t> hpp::core::NumericalConstraintMap_t |
typedef constraints::NumericalConstraints_t hpp::core::NumericalConstraints_t |
typedef std::vector<CollisionObjectPtr_t> hpp::core::ObjectStdVector_t |
typedef pinocchio::ObjectVector_t hpp::core::ObjectVector_t |
typedef boost::shared_ptr<const Path> hpp::core::PathConstPtr_t |
typedef boost::function< PathOptimizerPtr_t (const Problem&) > hpp::core::PathOptimizerBuilder_t |
typedef boost::shared_ptr<PathOptimizer> hpp::core::PathOptimizerPtr_t |
typedef boost::function< PathPlannerPtr_t (const Problem&, const RoadmapPtr_t&) > hpp::core::PathPlannerBuilder_t |
typedef boost::shared_ptr<PathPlanner> hpp::core::PathPlannerPtr_t |
typedef boost::function<PathProjectorPtr_t (const Problem&, const value_type&) > hpp::core::PathProjectorBuilder_t |
typedef boost::shared_ptr<PathProjector> hpp::core::PathProjectorPtr_t |
typedef boost::shared_ptr<Path> hpp::core::PathPtr_t |
typedef std::vector<PathPtr_t> hpp::core::Paths_t |
typedef boost::function< PathValidationPtr_t (const DevicePtr_t&, const value_type&) > hpp::core::PathValidationBuilder_t |
typedef boost::shared_ptr<PathValidation> hpp::core::PathValidationPtr_t |
typedef boost::shared_ptr<PathValidationReport> hpp::core::PathValidationReportPtr_t |
typedef boost::shared_ptr<PathValidations> hpp::core::PathValidationsPtr_t |
typedef boost::shared_ptr<const PathVector> hpp::core::PathVectorConstPtr_t |
typedef boost::shared_ptr<PathVector> hpp::core::PathVectorPtr_t |
typedef std::vector< PathVectorPtr_t > hpp::core::PathVectors_t |
typedef boost::shared_ptr<PlanAndOptimize> hpp::core::PlanAndOptimizePtr_t |
typedef boost::shared_ptr<Problem> hpp::core::ProblemPtr_t |
typedef boost::shared_ptr<ProblemTarget> hpp::core::ProblemTargetPtr_t |
typedef boost::shared_ptr<const ReedsSheppPath> hpp::core::ReedsSheppPathConstPtr_t |
typedef boost::shared_ptr<ReedsSheppPath> hpp::core::ReedsSheppPathPtr_t |
typedef boost::shared_ptr<Roadmap> hpp::core::RoadmapPtr_t |
typedef boost::function< DevicePtr_t (const std::string&) > hpp::core::RobotBuilder_t |
typedef Eigen::Matrix<value_type, 1, Eigen::Dynamic> hpp::core::rowvector_t |
typedef constraints::segment_t hpp::core::segment_t |
typedef constraints::segments_t hpp::core::segments_t |
typedef std::map<std::string, segments_t> hpp::core::segmentsMap_t |
typedef std::vector<core::vector3_t> hpp::core::Shape_t |
typedef pinocchio::size_type hpp::core::size_type |
typedef boost::function<SteeringMethodPtr_t (const Problem&) > hpp::core::SteeringMethodBuilder_t |
typedef boost::shared_ptr<SteeringMethod> hpp::core::SteeringMethodPtr_t |
typedef boost::shared_ptr<const StraightPath> hpp::core::StraightPathConstPtr_t |
typedef boost::shared_ptr<StraightPath> hpp::core::StraightPathPtr_t |
typedef boost::shared_ptr<SubchainPath> hpp::core::SubchainPathPtr_t |
typedef boost::shared_ptr<TimeParameterization> hpp::core::TimeParameterizationPtr_t |
typedef pinocchio::Transform3f hpp::core::Transform3f |
typedef boost::shared_ptr<ValidationReport> hpp::core::ValidationReportPtr_t |
typedef pinocchio::value_type hpp::core::value_type |
typedef Eigen::Matrix<value_type, 2, 1> hpp::core::vector2_t |
typedef pinocchio::vector3_t hpp::core::vector3_t |
typedef pinocchio::vector_t hpp::core::vector_t |
typedef pinocchio::vectorIn_t hpp::core::vectorIn_t |
typedef pinocchio::vectorOut_t hpp::core::vectorOut_t |
typedef boost::shared_ptr<VisibilityPrmPlanner> hpp::core::VisibilityPrmPlannerPtr_t |
typedef boost::shared_ptr<WeighedDistance> hpp::core::WeighedDistancePtr_t |
hpp::core::HPP_PREDEF_CLASS | ( | BiRRTPlanner | ) |
hpp::core::HPP_PREDEF_CLASS | ( | CollisionValidation | ) |
hpp::core::HPP_PREDEF_CLASS | ( | CollisionValidationReport | ) |
hpp::core::HPP_PREDEF_CLASS | ( | AllCollisionsValidationReport | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ConfigurationShooter | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ConfigProjector | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ConfigValidation | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ConfigValidations | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ConnectedComponent | ) |
hpp::core::HPP_PREDEF_CLASS | ( | Constraint | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ConstraintSet | ) |
hpp::core::HPP_PREDEF_CLASS | ( | DiffusingPlanner | ) |
hpp::core::HPP_PREDEF_CLASS | ( | Distance | ) |
hpp::core::HPP_PREDEF_CLASS | ( | DistanceBetweenObjects | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ExtractedPath | ) |
hpp::core::HPP_PREDEF_CLASS | ( | SubchainPath | ) |
hpp::core::HPP_PREDEF_CLASS | ( | JointBoundValidation | ) |
hpp::core::HPP_PREDEF_CLASS | ( | Path | ) |
hpp::core::HPP_PREDEF_CLASS | ( | TimeParameterization | ) |
hpp::core::HPP_PREDEF_CLASS | ( | PathOptimizer | ) |
hpp::core::HPP_PREDEF_CLASS | ( | PathPlanner | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ProblemTarget | ) |
hpp::core::HPP_PREDEF_CLASS | ( | PathVector | ) |
hpp::core::HPP_PREDEF_CLASS | ( | PlanAndOptimize | ) |
hpp::core::HPP_PREDEF_CLASS | ( | Problem | ) |
hpp::core::HPP_PREDEF_CLASS | ( | Roadmap | ) |
hpp::core::HPP_PREDEF_CLASS | ( | SteeringMethod | ) |
hpp::core::HPP_PREDEF_CLASS | ( | StraightPath | ) |
hpp::core::HPP_PREDEF_CLASS | ( | InterpolatedPath | ) |
hpp::core::HPP_PREDEF_CLASS | ( | DubinsPath | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ReedsSheppPath | ) |
hpp::core::HPP_PREDEF_CLASS | ( | KinodynamicPath | ) |
hpp::core::HPP_PREDEF_CLASS | ( | KinodynamicOrientedPath | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ValidationReport | ) |
hpp::core::HPP_PREDEF_CLASS | ( | VisibilityPrmPlanner | ) |
hpp::core::HPP_PREDEF_CLASS | ( | WeighedDistance | ) |
hpp::core::HPP_PREDEF_CLASS | ( | KinodynamicDistance | ) |
hpp::core::HPP_PREDEF_CLASS | ( | ContinuousValidation | ) |
hpp::core::HPP_PREDEF_CLASS | ( | PathValidations | ) |
hpp::core::HPP_PREDEF_CLASS | ( | PathValidation | ) |
hpp::core::HPP_PREDEF_CLASS | ( | PathProjector | ) |