| Classes | |
| struct | CapRung | 
| class | CapsulatedLadderTreeRRTstar | 
| class | CapVert | 
| struct | ConstrainedSegment | 
| struct | ConstrainedSegmentPickNPlace | 
| Typedefs | |
| typedef boost::function< double(const double *, const double *)> | CostFunction | 
| Functions | |
| void | appendInTime (LadderGraph ¤t, const LadderGraph &next) | 
| bool | checkFeasibility (descartes_core::RobotModel &model, const std::vector< Eigen::Affine3d > &poses, descartes_planner::CapRung &cap_rung, descartes_planner::CapVert &cap_vert) | 
| bool | checkFeasibilityPickNPlace (descartes_core::RobotModel &model, const std::vector< std::vector< Eigen::Affine3d >> &poses, descartes_planner::CapRung &cap_rung, descartes_planner::CapVert &cap_vert) | 
| std::vector< Eigen::Vector3d > | discretizePositions (const Eigen::Vector3d &start, const Eigen::Vector3d &stop, const double ds) | 
| bool | domainDiscreteEnumerationCheck (descartes_core::RobotModel &model, descartes_planner::CapRung &cap_rung, descartes_planner::CapVert &cap_vert) | 
| LadderGraph | generateLadderGraphFromPoses (const descartes_core::RobotModel &model, const std::vector< Eigen::Affine3d > &ps, const double dt) | 
| std::vector< Eigen::Affine3d > | generateSample (const descartes_planner::CapRung &cap_rung, descartes_planner::CapVert &cap_vert) | 
| std::vector< std::vector< Eigen::Affine3d > > | generateSamplePickNPlace (const descartes_planner::CapRung &cap_rung, descartes_planner::CapVert &cap_vert) | 
| Eigen::Affine3d | makePose (const Eigen::Vector3d &position, const Eigen::Matrix3d &orientation, const double z_axis_angle) | 
| Eigen::Affine3d | makePose (const Eigen::Vector3d &position, const Eigen::Matrix3d &orientation) | 
| double | randomSampleDouble (double lower, double upper) | 
| int | randomSampleInt (int lower, int upper) | 
| LadderGraph | sampleConstrainedPaths (const descartes_core::RobotModel &model, ConstrainedSegment &segment) | 
| LadderGraph | sampleSingleConfig (const descartes_core::RobotModel &model, const std::vector< Eigen::Vector3d > &origins, const Eigen::Matrix3d &orientation, const double dt) | 
| LadderGraph | sampleSingleConfig (const descartes_core::RobotModel &model, const std::vector< Eigen::Vector3d > &origins, const double dt, const Eigen::Matrix3d &orientation, const double z_axis_angle) | 
| typedef boost::function<double(const double*, const double*)> descartes_planner::CostFunction | 
Definition at line 9 of file choreo_ladder_graph_builder.cpp.
| void descartes_planner::appendInTime | ( | LadderGraph & | current, | 
| const LadderGraph & | next | ||
| ) | 
Definition at line 190 of file choreo_ladder_graph_builder.cpp.
| bool descartes_planner::checkFeasibility | ( | descartes_core::RobotModel & | model, | 
| const std::vector< Eigen::Affine3d > & | poses, | ||
| descartes_planner::CapRung & | cap_rung, | ||
| descartes_planner::CapVert & | cap_vert | ||
| ) | 
Definition at line 10 of file pose_verification_helpers.cpp.
| bool descartes_planner::checkFeasibilityPickNPlace | ( | descartes_core::RobotModel & | model, | 
| const std::vector< std::vector< Eigen::Affine3d >> & | poses, | ||
| descartes_planner::CapRung & | cap_rung, | ||
| descartes_planner::CapVert & | cap_vert | ||
| ) | 
Definition at line 78 of file pose_verification_helpers.cpp.
| std::vector< Eigen::Vector3d > descartes_planner::discretizePositions | ( | const Eigen::Vector3d & | start, | 
| const Eigen::Vector3d & | stop, | ||
| const double | ds | ||
| ) | 
Definition at line 11 of file pose_sampling_helpers.cpp.
| bool descartes_planner::domainDiscreteEnumerationCheck | ( | descartes_core::RobotModel & | model, | 
| descartes_planner::CapRung & | cap_rung, | ||
| descartes_planner::CapVert & | cap_vert | ||
| ) | 
Definition at line 141 of file pose_verification_helpers.cpp.
| LadderGraph descartes_planner::generateLadderGraphFromPoses | ( | const descartes_core::RobotModel & | model, | 
| const std::vector< Eigen::Affine3d > & | ps, | ||
| const double | dt | ||
| ) | 
Definition at line 54 of file choreo_ladder_graph_builder.cpp.
| std::vector< Eigen::Affine3d > descartes_planner::generateSample | ( | const descartes_planner::CapRung & | cap_rung, | 
| descartes_planner::CapVert & | cap_vert | ||
| ) | 
Definition at line 89 of file pose_sampling_helpers.cpp.
| std::vector< std::vector< Eigen::Affine3d > > descartes_planner::generateSamplePickNPlace | ( | const descartes_planner::CapRung & | cap_rung, | 
| descartes_planner::CapVert & | cap_vert | ||
| ) | 
Definition at line 125 of file pose_sampling_helpers.cpp.
| Eigen::Affine3d descartes_planner::makePose | ( | const Eigen::Vector3d & | position, | 
| const Eigen::Matrix3d & | orientation, | ||
| const double | z_axis_angle | ||
| ) | 
Definition at line 35 of file pose_sampling_helpers.cpp.
| Eigen::Affine3d descartes_planner::makePose | ( | const Eigen::Vector3d & | position, | 
| const Eigen::Matrix3d & | orientation | ||
| ) | 
Definition at line 47 of file pose_sampling_helpers.cpp.
| double descartes_planner::randomSampleDouble | ( | double | lower, | 
| double | upper | ||
| ) | 
Definition at line 72 of file pose_sampling_helpers.cpp.
| int descartes_planner::randomSampleInt | ( | int | lower, | 
| int | upper | ||
| ) | 
Definition at line 56 of file pose_sampling_helpers.cpp.
| LadderGraph descartes_planner::sampleConstrainedPaths | ( | const descartes_core::RobotModel & | model, | 
| ConstrainedSegment & | segment | ||
| ) | 
Definition at line 147 of file choreo_ladder_graph_builder.cpp.
| LadderGraph descartes_planner::sampleSingleConfig | ( | const descartes_core::RobotModel & | model, | 
| const std::vector< Eigen::Vector3d > & | origins, | ||
| const Eigen::Matrix3d & | orientation, | ||
| const double | dt | ||
| ) | 
Definition at line 132 of file choreo_ladder_graph_builder.cpp.
| LadderGraph descartes_planner::sampleSingleConfig | ( | const descartes_core::RobotModel & | model, | 
| const std::vector< Eigen::Vector3d > & | origins, | ||
| const double | dt, | ||
| const Eigen::Matrix3d & | orientation, | ||
| const double | z_axis_angle | ||
| ) | 
Definition at line 116 of file choreo_ladder_graph_builder.cpp.