choreo_ladder_graph_builder.h
Go to the documentation of this file.
1 #ifndef CHOREO_DESCARTES_GRAPH_BUILDER_H
2 #define CHOREO_DESCARTES_GRAPH_BUILDER_H
3 
4 #include "constrained_segment.h"
5 
6 #include <descartes_planner/ladder_graph.h>
7 #include <descartes_core/robot_model.h>
8 
9 #include <Eigen/Geometry>
10 
11 /*
12  * JM:
13  * So we want to represent each extrusion as a single process graph that could have many
14  * start and end points but must stay inside one configuration through the process.
15  *
16  * For the moment, we do not consider the motion planning problem
17  */
18 namespace descartes_planner
19 {
20 
21 LadderGraph sampleSingleConfig(const descartes_core::RobotModel &model,
22  const std::vector <Eigen::Vector3d> &origins,
23  const Eigen::Matrix3d &orientation,
24  const double dt);
25 
26 LadderGraph sampleSingleConfig(const descartes_core::RobotModel& model,
27  const std::vector<Eigen::Vector3d>& origins,
28  const double dt,
29  const Eigen::Matrix3d& orientation,
30  const double z_axis_angle);
31 
32 // ARCHIVED
33 // author: J. Meyer (SWRI) with some edits by Yijiang Huang (yijiangh@mit.edu)
34 // fully-sampled ladder graph from a given z-axis discretized constrained segment
35 // (so you can get an *optimal* solution in the given discretization if you perform graph search on it.)
36 // in the light of the CLT-RRT, this scheme is rarely used and is archived here.
37 LadderGraph sampleConstrainedPaths(const descartes_core::RobotModel& model, ConstrainedSegment& segment);
38 
39 // TODO: should be renamed
40 // Appends 'next' to the end of 'current' to produce a new graph
41 void appendInTime(LadderGraph& current, const LadderGraph& next);
42 
43 }
44 
45 #endif // GRAPH_BUILDER_H
void appendInTime(LadderGraph &current, 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)


choreo_descartes_planner
Author(s): Yijiang Huang , Jonathan Meyer
autogenerated on Thu Jul 18 2019 03:58:35