hpp-core
4.9.0
Implement basic classes for canonical path planning for kinematic chains.
|
#include <vector>
#include <map>
#include <deque>
#include <list>
#include <set>
#include <hpp/util/pointer.hh>
#include <hpp/constraints/fwd.hh>
#include <hpp/core/config.hh>
#include <hpp/core/deprecated.hh>
Go to the source code of this file.
Classes | |
class | hpp::core::path::Spline< _PolynomeBasis, _Order > |
Typedefs | |
typedef constraints::ComparisonTypes_t | hpp::core::ComparisonTypes_t |
typedef constraints::ComparisonType | hpp::core::ComparisonType |
typedef boost::shared_ptr< BiRRTPlanner > | hpp::core::BiRRTPlannerPtr_t |
typedef hpp::pinocchio::Body | hpp::core::Body |
typedef hpp::pinocchio::BodyPtr_t | hpp::core::BodyPtr_t |
typedef boost::shared_ptr< CollisionValidation > | hpp::core::CollisionValidationPtr_t |
typedef boost::shared_ptr< CollisionValidationReport > | hpp::core::CollisionValidationReportPtr_t |
typedef boost::shared_ptr< AllCollisionsValidationReport > | hpp::core::AllCollisionsValidationReportPtr_t |
typedef pinocchio::CollisionObjectPtr_t | hpp::core::CollisionObjectPtr_t |
typedef pinocchio::CollisionObjectConstPtr_t | hpp::core::CollisionObjectConstPtr_t |
typedef pinocchio::FclCollisionObject | hpp::core::FclCollisionObject |
typedef FclCollisionObject * | hpp::core::FclCollisionObjectPtr_t |
typedef const FclCollisionObject * | hpp::core::FclConstCollisionObjectPtr_t |
typedef boost::shared_ptr< FclCollisionObject > | hpp::core::FclCollisionObjectSharePtr_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 Configurations_t::iterator | hpp::core::ConfigIterator_t |
typedef Configurations_t::const_iterator | hpp::core::ConfigConstIterator_t |
typedef boost::shared_ptr< ConfigurationShooter > | hpp::core::ConfigurationShooterPtr_t |
typedef boost::shared_ptr< ConfigProjector > | hpp::core::ConfigProjectorPtr_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 boost::shared_ptr< Constraint > | hpp::core::ConstraintPtr_t |
typedef boost::shared_ptr< ConstraintSet > | hpp::core::ConstraintSetPtr_t |
typedef boost::shared_ptr< const ConstraintSet > | hpp::core::ConstraintSetConstPtr_t |
typedef std::deque< ConstraintPtr_t > | hpp::core::Constraints_t |
typedef pinocchio::Device | hpp::core::Device_t |
typedef pinocchio::DevicePtr_t | hpp::core::DevicePtr_t |
typedef pinocchio::DeviceWkPtr_t | hpp::core::DeviceWkPtr_t |
typedef pinocchio::CenterOfMassComputationPtr_t | hpp::core::CenterOfMassComputationPtr_t |
typedef std::deque< DevicePtr_t > | hpp::core::Devices_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< Distance > | hpp::core::DistancePtr_t |
typedef boost::shared_ptr< DistanceBetweenObjects > | hpp::core::DistanceBetweenObjectsPtr_t |
typedef pinocchio::DistanceResults_t | hpp::core::DistanceResults_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 boost::shared_ptr< SubchainPath > | hpp::core::SubchainPathPtr_t |
typedef pinocchio::JointJacobian_t | hpp::core::JointJacobian_t |
typedef pinocchio::Joint | hpp::core::Joint |
typedef pinocchio::JointConstPtr_t | hpp::core::JointConstPtr_t |
typedef pinocchio::JointPtr_t | hpp::core::JointPtr_t |
typedef boost::shared_ptr< JointBoundValidation > | hpp::core::JointBoundValidationPtr_t |
typedef boost::shared_ptr< JointBoundValidationReport > | hpp::core::JointBoundValidationReportPtr_t |
typedef pinocchio::HalfJointJacobian_t | hpp::core::HalfJointJacobian_t |
typedef pinocchio::JointVector_t | hpp::core::JointVector_t |
typedef KDTree * | hpp::core::KDTreePtr_t |
typedef constraints::LockedJoint | hpp::core::LockedJoint |
typedef constraints::LockedJointPtr_t | hpp::core::LockedJointPtr_t |
typedef constraints::LockedJointConstPtr_t | hpp::core::LockedJointConstPtr_t |
typedef constraints::LockedJoints_t | hpp::core::LockedJoints_t |
typedef pinocchio::matrix_t | hpp::core::matrix_t |
typedef pinocchio::matrix3_t | hpp::core::matrix3_t |
typedef constraints::matrix6_t | hpp::core::matrix6_t |
typedef pinocchio::vector3_t | hpp::core::vector3_t |
typedef constraints::matrixIn_t | hpp::core::matrixIn_t |
typedef constraints::matrixOut_t | hpp::core::matrixOut_t |
typedef constraints::LiegroupElement | hpp::core::LiegroupElement |
typedef constraints::LiegroupElementRef | hpp::core::LiegroupElementRef |
typedef pinocchio::LiegroupElementConstRef | hpp::core::LiegroupElementConstRef |
typedef constraints::LiegroupSpace | hpp::core::LiegroupSpace |
typedef constraints::LiegroupSpacePtr_t | hpp::core::LiegroupSpacePtr_t |
typedef pinocchio::size_type | hpp::core::size_type |
typedef pinocchio::value_type | hpp::core::value_type |
typedef std::pair< value_type, value_type > | hpp::core::interval_t |
typedef Eigen::BlockIndex | hpp::core::BlockIndex |
Interval of indices as (first index, number of indices) More... | |
typedef constraints::segment_t | hpp::core::segment_t |
typedef constraints::segments_t | hpp::core::segments_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 pinocchio::ObjectVector_t | hpp::core::ObjectVector_t |
typedef std::vector< CollisionObjectPtr_t > | hpp::core::ObjectStdVector_t |
typedef std::vector< CollisionObjectConstPtr_t > | hpp::core::ConstObjectStdVector_t |
typedef boost::shared_ptr< Path > | hpp::core::PathPtr_t |
typedef boost::shared_ptr< const Path > | hpp::core::PathConstPtr_t |
typedef boost::shared_ptr< TimeParameterization > | hpp::core::TimeParameterizationPtr_t |
typedef boost::shared_ptr< PathOptimizer > | hpp::core::PathOptimizerPtr_t |
typedef boost::shared_ptr< PathPlanner > | hpp::core::PathPlannerPtr_t |
typedef boost::shared_ptr< ProblemTarget > | hpp::core::ProblemTargetPtr_t |
typedef boost::shared_ptr< PathVector > | hpp::core::PathVectorPtr_t |
typedef boost::shared_ptr< const PathVector > | hpp::core::PathVectorConstPtr_t |
typedef boost::shared_ptr< PlanAndOptimize > | hpp::core::PlanAndOptimizePtr_t |
typedef boost::shared_ptr< Problem > | hpp::core::ProblemPtr_t |
typedef ProblemSolver * | hpp::core::ProblemSolverPtr_t |
typedef boost::shared_ptr< Roadmap > | hpp::core::RoadmapPtr_t |
typedef boost::shared_ptr< StraightPath > | hpp::core::StraightPathPtr_t |
typedef boost::shared_ptr< const StraightPath > | hpp::core::StraightPathConstPtr_t |
typedef boost::shared_ptr< ReedsSheppPath > | hpp::core::ReedsSheppPathPtr_t |
typedef boost::shared_ptr< const ReedsSheppPath > | hpp::core::ReedsSheppPathConstPtr_t |
typedef boost::shared_ptr< DubinsPath > | hpp::core::DubinsPathPtr_t |
typedef boost::shared_ptr< const DubinsPath > | hpp::core::DubinsPathConstPtr_t |
typedef boost::shared_ptr< KinodynamicPath > | hpp::core::KinodynamicPathPtr_t |
typedef boost::shared_ptr< const KinodynamicPath > | hpp::core::KinodynamicPathConstPtr_t |
typedef boost::shared_ptr< KinodynamicOrientedPath > | hpp::core::KinodynamicOrientedPathPtr_t |
typedef boost::shared_ptr< const KinodynamicOrientedPath > | hpp::core::KinodynamicOrientedPathConstPtr_t |
typedef boost::shared_ptr< InterpolatedPath > | hpp::core::InterpolatedPathPtr_t |
typedef boost::shared_ptr< const InterpolatedPath > | hpp::core::InterpolatedPathConstPtr_t |
typedef boost::shared_ptr< SteeringMethod > | hpp::core::SteeringMethodPtr_t |
typedef std::vector< PathPtr_t > | hpp::core::Paths_t |
typedef std::vector< PathVectorPtr_t > | hpp::core::PathVectors_t |
typedef pinocchio::Transform3f | hpp::core::Transform3f |
typedef Eigen::Matrix< value_type, 2, 1 > | hpp::core::vector2_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 Eigen::Matrix< value_type, 1, Eigen::Dynamic > | hpp::core::rowvector_t |
typedef boost::shared_ptr< VisibilityPrmPlanner > | hpp::core::VisibilityPrmPlannerPtr_t |
typedef boost::shared_ptr< ValidationReport > | hpp::core::ValidationReportPtr_t |
typedef boost::shared_ptr< WeighedDistance > | hpp::core::WeighedDistancePtr_t |
typedef boost::shared_ptr< KinodynamicDistance > | hpp::core::KinodynamicDistancePtr_t |
typedef std::map< std::string, constraints::ImplicitPtr_t > | hpp::core::NumericalConstraintMap_t |
typedef std::map< std::string, ComparisonTypes_t > | hpp::core::ComparisonTypeMap_t |
typedef std::map< std::string, segments_t > | hpp::core::segmentsMap_t |
typedef constraints::NumericalConstraints_t | hpp::core::NumericalConstraints_t |
typedef std::map< std::string, CenterOfMassComputationPtr_t > | hpp::core::CenterOfMassComputationMap_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< Hermite > | hpp::core::path::HermitePtr_t |
typedef boost::shared_ptr< const Hermite > | hpp::core::path::HermiteConstPtr_t |
typedef boost::shared_ptr< ContinuousValidation > | hpp::core::ContinuousValidationPtr_t |
typedef boost::shared_ptr< Dichotomy > | hpp::core::continuousValidation::DichotomyPtr_t |
typedef boost::shared_ptr< Progressive > | hpp::core::continuousValidation::ProgressivePtr_t |
typedef boost::shared_ptr< BodyPairCollision > | hpp::core::continuousValidation::BodyPairCollisionPtr_t |
typedef std::vector< BodyPairCollisionPtr_t > | hpp::core::continuousValidation::BodyPairCollisions_t |
typedef boost::shared_ptr< IntervalValidation > | hpp::core::continuousValidation::IntervalValidationPtr_t |
typedef std::vector< IntervalValidationPtr_t > | hpp::core::continuousValidation::IntervalValidations_t |
typedef boost::shared_ptr< SolidSolidCollision > | hpp::core::continuousValidation::SolidSolidCollisionPtr_t |
typedef boost::shared_ptr< ReedsShepp > | hpp::core::distance::ReedsSheppPtr_t |
typedef NearestNeighbor * | hpp::core::NearestNeighborPtr_t |
typedef KDTree * | hpp::core::nearestNeighbor::KDTreePtr_t |
typedef Basic * | hpp::core::nearestNeighbor::BasicPtr_t |
typedef boost::shared_ptr< RandomShortcut > | hpp::core::pathOptimization::RandomShortcutPtr_t |
typedef boost::shared_ptr< SimpleShortcut > | hpp::core::pathOptimization::SimpleShortcutPtr_t |
typedef boost::shared_ptr< Cost > | hpp::core::pathOptimization::CostPtr_t |
typedef boost::shared_ptr< GradientBased > | hpp::core::pathOptimization::GradientBasedPtr_t |
typedef boost::shared_ptr< PathLength > | hpp::core::pathOptimization::PathLengthPtr_t |
typedef boost::shared_ptr< PartialShortcut > | hpp::core::pathOptimization::PartialShortcutPtr_t |
typedef boost::shared_ptr< SimpleTimeParameterization > | hpp::core::pathOptimization::SimpleTimeParameterizationPtr_t |
typedef boost::shared_ptr< ConfigOptimization > | hpp::core::pathOptimization::ConfigOptimizationPtr_t |
typedef boost::shared_ptr< kPrmStar > | hpp::core::pathPlanner::kPrmStarPtr_t |
typedef boost::shared_ptr< PathValidation > | hpp::core::PathValidationPtr_t |
typedef boost::shared_ptr< PathValidations > | hpp::core::PathValidationsPtr_t |
typedef boost::shared_ptr< Discretized > | hpp::core::pathValidation::DiscretizedPtr_t |
typedef boost::shared_ptr< PathValidationReport > | hpp::core::PathValidationReportPtr_t |
typedef boost::shared_ptr< CollisionPathValidationReport > | hpp::core::CollisionPathValidationReportPtr_t |
typedef std::vector< CollisionPathValidationReport > | hpp::core::CollisionPathValidationReports_t |
typedef boost::shared_ptr< PathProjector > | hpp::core::PathProjectorPtr_t |
typedef boost::shared_ptr< Global > | hpp::core::pathProjector::GlobalPtr_t |
typedef boost::shared_ptr< Dichotomy > | hpp::core::pathProjector::DichotomyPtr_t |
typedef boost::shared_ptr< Progressive > | hpp::core::pathProjector::ProgressivePtr_t |
typedef boost::shared_ptr< RecursiveHermite > | hpp::core::pathProjector::RecursiveHermitePtr_t |
typedef boost::shared_ptr< Interpolated > | hpp::core::steeringMethod::InterpolatedPtr_t |
typedef boost::shared_ptr< ReedsShepp > | hpp::core::steeringMethod::ReedsSheppPtr_t |
typedef boost::shared_ptr< Kinodynamic > | hpp::core::steeringMethod::KinodynamicPtr_t |
typedef boost::shared_ptr< GoalConfigurations > | hpp::core::problemTarget::GoalConfigurationsPtr_t |
typedef boost::shared_ptr< TaskTarget > | hpp::core::problemTarget::TaskTargetPtr_t |
typedef boost::shared_ptr< Uniform > | hpp::core::configurationShooter::UniformPtr_t |
typedef boost::shared_ptr< Gaussian > | hpp::core::configurationShooter::GaussianPtr_t |
typedef std::vector< core::vector3_t > | hpp::core::Shape_t |
typedef std::pair< JointPtr_t, Shape_t > | hpp::core::JointAndShape_t |
typedef std::list< JointAndShape_t > | hpp::core::JointAndShapes_t |
typedef constraints::Implicit NumericalConstraint | hpp::core::HPP_CORE_DEPRECATED |