donghong_ding.hpp
Go to the documentation of this file.
1 #ifndef RAM_PATH_PLANNING_DONGHONG_DING_HPP
2 #define RAM_PATH_PLANNING_DONGHONG_DING_HPP
3 
6 
7 namespace ram_path_planning
8 {
9 template<class ActionSpec>
10  class DonghongDing : public DonghongDingBase<ActionSpec>
11  {
12  public:
13 
14  typedef vtkSmartPointer<vtkPolyData> Polygon;
15  typedef std::vector<Polygon> PolygonVector;
16  typedef std::vector<PolygonVector> Layer;
17 
18  DonghongDing();
19 
20  std::string generateOneLayerTrajectory(
22  const int current_progrress_value,
23  const int next_progress_value,
24  const Polygon poly_data,
25  Layer &layer,
26  const double deposited_material_width,
27  const double contours_filtering_tolerance,
28  const std::array<double, 3> normal_vector = {0, 0, 1},
29  const double polygon_division_tolerance = M_PI / 6,
30  const bool closest_to_bisector = false,
31  const bool use_gui = false);
32 
33  std::string generateOneLayerTrajectory(
35  const int current_progrress_value,
36  const int next_progress_value,
37  const std::string yaml_file,
38  Layer &layer,
39  const double deposited_material_width,
40  const double contours_filtering_tolerance,
41  const double polygon_division_tolerance = M_PI / 6,
42  const bool closest_to_bisector = false,
43  const bool use_gui = false);
44 
45  private:
46 
48 
50  double polygon_division_tolerance_; // In radians
51  double contours_filtering_tolerance_; // In meters
52 
53  bool findNotch(const Polygon poly_data,
54  vtkIdType &cell_id,
55  vtkIdType &pos,
56  double &angle);
57 
58  bool verifyAngles(const Polygon poly_data,
59  const vtkIdType notch_cell_id,
60  const vtkIdType notch_pos,
61  const vtkIdType vertex_cell_id,
62  const vtkIdType vertex_pos);
63 
64  bool intersectLineWithContours(const Polygon poly_data,
65  double point_1[3],
66  double point_2[3]);
67 
68  bool findVertex(const Polygon poly_data,
69  const vtkIdType notch_cell_id,
70  const vtkIdType notch_pos,
71  vtkIdType &vertex_cell_id,
72  vtkIdType &vertex_pos,
73  const double notch_angle);
74 
75  bool findIntersectWithBisector(const Polygon poly_data,
76  const vtkIdType notch_cell_id,
77  const vtkIdType notch_pos,
78  vtkIdType &vertex_cell_id,
79  vtkIdType &vertex_pos,
80  double vertex[3]);
81 
82  bool divideInConvexPolygons(PolygonVector &polygon_source,
83  const int polygon_position,
84  const vtkSmartPointer<vtkPoints> split_points);
85 
86  double identifyZigzagDirection(const Polygon poly_data,
87  vtkIdType &edge,
88  vtkIdType &futhest_point);
89 
90  void identifyLeftChain(const Polygon poly_data,
91  const vtkIdType edge_id,
92  const vtkIdType opposite_point_id,
93  const vtkSmartPointer<vtkPoints> left_chain,
94  const vtkSmartPointer<vtkPoints> right_chain);
95 
96  bool offsetLeftChain(const Polygon poly_data,
97  const vtkIdType edge_id,
98  const vtkIdType opposite_point_id,
99  const vtkSmartPointer<vtkPoints> left_chain,
100  const vtkSmartPointer<vtkPoints> right_chain);
101 
102  bool zigzagGeneration(const Polygon poly_data,
103  const vtkIdType edge_id,
104  const vtkIdType opposite_point_id,
105  const vtkSmartPointer<vtkPoints> zigzag_points,
106  const double deposited_material_width);
107 
108  void mergeListOfPoints(const Polygon poly_data,
109  const vtkSmartPointer<vtkPoints> left_chain,
110  const vtkSmartPointer<vtkPoints> right_chain,
111  const vtkSmartPointer<vtkPoints> zigzag_points);
112 
113  bool mergeConvexPolygons(PolygonVector &polygon_source,
114  const vtkSmartPointer<vtkPoints> split_points,
115  const vtkIdType split_line);
116 
117  bool generateTrajectoryInConvexPolygon(const Polygon poly_data);
118 
119  };
120 
121 }
122 
123 //include the implementation
125 #endif
bool findIntersectWithBisector(const Polygon poly_data, const vtkIdType notch_cell_id, const vtkIdType notch_pos, vtkIdType &vertex_cell_id, vtkIdType &vertex_pos, double vertex[3])
bool divideInConvexPolygons(PolygonVector &polygon_source, const int polygon_position, const vtkSmartPointer< vtkPoints > split_points)
vtkSmartPointer< vtkPolyData > Polygon
bool offsetLeftChain(const Polygon poly_data, const vtkIdType edge_id, const vtkIdType opposite_point_id, const vtkSmartPointer< vtkPoints > left_chain, const vtkSmartPointer< vtkPoints > right_chain)
bool intersectLineWithContours(const Polygon poly_data, double point_1[3], double point_2[3])
std::vector< PolygonVector > Layer
double identifyZigzagDirection(const Polygon poly_data, vtkIdType &edge, vtkIdType &futhest_point)
bool zigzagGeneration(const Polygon poly_data, const vtkIdType edge_id, const vtkIdType opposite_point_id, const vtkSmartPointer< vtkPoints > zigzag_points, const double deposited_material_width)
bool verifyAngles(const Polygon poly_data, const vtkIdType notch_cell_id, const vtkIdType notch_pos, const vtkIdType vertex_cell_id, const vtkIdType vertex_pos)
std::vector< Polygon > PolygonVector
bool generateTrajectoryInConvexPolygon(const Polygon poly_data)
void mergeListOfPoints(const Polygon poly_data, const vtkSmartPointer< vtkPoints > left_chain, const vtkSmartPointer< vtkPoints > right_chain, const vtkSmartPointer< vtkPoints > zigzag_points)
bool mergeConvexPolygons(PolygonVector &polygon_source, const vtkSmartPointer< vtkPoints > split_points, const vtkIdType split_line)
void identifyLeftChain(const Polygon poly_data, const vtkIdType edge_id, const vtkIdType opposite_point_id, const vtkSmartPointer< vtkPoints > left_chain, const vtkSmartPointer< vtkPoints > right_chain)
bool findNotch(const Polygon poly_data, vtkIdType &cell_id, vtkIdType &pos, double &angle)
bool use_gui
std::string generateOneLayerTrajectory(actionlib::ServerGoalHandle< ActionSpec > &gh, const int current_progrress_value, const int next_progress_value, const Polygon poly_data, Layer &layer, const double deposited_material_width, const double contours_filtering_tolerance, const std::array< double, 3 > normal_vector={0, 0, 1}, const double polygon_division_tolerance=M_PI/6, const bool closest_to_bisector=false, const bool use_gui=false)
bool findVertex(const Polygon poly_data, const vtkIdType notch_cell_id, const vtkIdType notch_pos, vtkIdType &vertex_cell_id, vtkIdType &vertex_pos, const double notch_angle)


ram_path_planning
Author(s): Andres Campos - Institut Maupertuis
autogenerated on Mon Jun 10 2019 14:50:03