1 #ifndef CHOREO_DESCARTES_GRAPH_BUILDER_H 2 #define CHOREO_DESCARTES_GRAPH_BUILDER_H 6 #include <descartes_planner/ladder_graph.h> 7 #include <descartes_core/robot_model.h> 9 #include <Eigen/Geometry> 22 const std::vector <Eigen::Vector3d> &origins,
23 const Eigen::Matrix3d &orientation,
27 const std::vector<Eigen::Vector3d>& origins,
29 const Eigen::Matrix3d& orientation,
30 const double z_axis_angle);
41 void appendInTime(LadderGraph& current,
const LadderGraph& next);
45 #endif // GRAPH_BUILDER_H
void appendInTime(LadderGraph ¤t, const LadderGraph &next)
LadderGraph sampleSingleConfig(const descartes_core::RobotModel &model, const std::vector< Eigen::Vector3d > &origins, const Eigen::Matrix3d &orientation, const double dt)
LadderGraph sampleConstrainedPaths(const descartes_core::RobotModel &model, ConstrainedSegment &segment)