donghong_ding_base.hpp
Go to the documentation of this file.
1 #ifndef RAM_PATH_PLANNING_DONGHONG_DINGBASE_HPP
2 #define RAM_PATH_PLANNING_DONGHONG_DINGBASE_HPP
3 
4 #include <future>
5 #include <mutex>
6 
8 #include <ram_msgs/AdditiveManufacturingTrajectory.h>
9 
11 
12 #include <vtkCenterOfMass.h>
13 #include <vtkCleanPolyData.h>
14 #include <vtkDecimatePolylineFilter.h>
15 #include <vtkLine.h>
16 #include <vtkPlane.h>
17 #include <vtkPolyData.h>
18 #include <vtkPolygon.h>
19 #include <vtkSmartPointer.h>
21 
22 namespace ram_path_planning
23 {
24 template<class ActionSpec>
25  class DonghongDingBase : public PathPlanningAlgorithm<ActionSpec>
26  {
27  public:
28  // Polygon (possibly multiple contours)
29  // At the end: the polygon must contain exactly 1 contour
30  typedef vtkSmartPointer<vtkPolyData> Polygon;
31  typedef std::vector<Polygon> PolygonVector;
32  typedef std::vector<PolygonVector> Layer;
33 
34  DonghongDingBase(const std::string name,
35  const std::string description,
36  const std::string service_name);
37 
38  virtual ~DonghongDingBase()=0; // Pure virtual function
39 
41  const int current_progrress_value,
42  const int next_progress_value,
43  std::vector<Layer> &layers,
44  ram_msgs::AdditiveManufacturingTrajectory &msg);
45 
47  const int current_progrress_value,
48  const int next_progress_value,
49  const Layer &current_layer,
50  ram_msgs::AdditiveManufacturingTrajectory &msg,
51  const double number_of_layers,
52  const double height_between_layers,
53  const std::array<double, 3> offset_direction = {0, 0, 1});
54  protected:
55  double normal_vector_[3]; //Normal vector to slicing plane. [0,0,1] in YAML files
56  const double calculation_tol_ = 1e-6; // In meters
57 
58  double deposited_material_width_; // In meters
59 
60  /*
61  * angle in the interval [-PI , PI]
62  * angleBetweenVectors(x,y) != angleBetweenVectors(y,x)
63  */
64  double angleBetweenVectors(const double v1[3],
65  const double v2[3]);
66 
67  void computeNormal(vtkPoints *p,
68  double *n);
69 
70  bool offsetPolygonContour(const Polygon poly_data,
71  const double deposited_material_width);
72 
73  bool intersectionBetweenContours(const Polygon poly_data);
74 
75  void identifyRelationships(const Polygon poly_data,
76  std::vector<int> &level,
77  std::vector<int> &father);
78 
79  bool organizePolygonContoursInLayer(const Polygon poly_data,
80  const std::vector<int> level,
81  const std::vector<int> father,
82  Layer &layer);
83 
84  bool removeDuplicatePoints(const Polygon poly_data,
85  const double tolerance = 1e-6);
86 
87  bool mergeColinearEdges(const Polygon poly_data,
88  const double tolerance = 1e-6);
89 
91  const int current_progrress_value,
92  const int next_progress_value,
93  std::vector<Layer> &layers,
94  ram_msgs::AdditiveManufacturingTrajectory &msg,
95  const unsigned first_layer);
96 
97  void divideInLayersWithOnePolygon(std::vector<Layer> &layers,
98  ram_msgs::AdditiveManufacturingTrajectory &msg,
99  const unsigned first_layer);
100 
101  };
102 
103 }
104 
105 //include the implementation
107 
108 #endif
double angleBetweenVectors(const double v1[3], const double v2[3])
void identifyRelationships(const Polygon poly_data, std::vector< int > &level, std::vector< int > &father)
bool mergeColinearEdges(const Polygon poly_data, const double tolerance=1e-6)
void connectYamlLayers(actionlib::ServerGoalHandle< ActionSpec > &gh, const int current_progrress_value, const int next_progress_value, const Layer &current_layer, ram_msgs::AdditiveManufacturingTrajectory &msg, const double number_of_layers, const double height_between_layers, const std::array< double, 3 > offset_direction={0, 0, 1})
void computeNormal(vtkPoints *p, double *n)
bool organizePolygonContoursInLayer(const Polygon poly_data, const std::vector< int > level, const std::vector< int > father, Layer &layer)
bool removeDuplicatePoints(const Polygon poly_data, const double tolerance=1e-6)
std::string connectMeshLayers(actionlib::ServerGoalHandle< ActionSpec > &gh, const int current_progrress_value, const int next_progress_value, std::vector< Layer > &layers, ram_msgs::AdditiveManufacturingTrajectory &msg)
vtkSmartPointer< vtkPolyData > Polygon
std::vector< PolygonVector > Layer
bool intersectionBetweenContours(const Polygon poly_data)
bool offsetPolygonContour(const Polygon poly_data, const double deposited_material_width)
void connectLayersWithOnePolygon(actionlib::ServerGoalHandle< ActionSpec > &gh, const int current_progrress_value, const int next_progress_value, std::vector< Layer > &layers, ram_msgs::AdditiveManufacturingTrajectory &msg, const unsigned first_layer)
void divideInLayersWithOnePolygon(std::vector< Layer > &layers, ram_msgs::AdditiveManufacturingTrajectory &msg, const unsigned first_layer)
DonghongDingBase(const std::string name, const std::string description, const std::string service_name)


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