1 #ifndef RAM_PATH_PLANNING_DONGHONG_DINGBASE_HPP 2 #define RAM_PATH_PLANNING_DONGHONG_DINGBASE_HPP 8 #include <ram_msgs/AdditiveManufacturingTrajectory.h> 12 #include <vtkCenterOfMass.h> 13 #include <vtkCleanPolyData.h> 14 #include <vtkDecimatePolylineFilter.h> 17 #include <vtkPolyData.h> 18 #include <vtkPolygon.h> 19 #include <vtkSmartPointer.h> 24 template<
class ActionSpec>
30 typedef vtkSmartPointer<vtkPolyData>
Polygon;
32 typedef std::vector<PolygonVector>
Layer;
35 const std::string description,
36 const std::string service_name);
41 const int current_progrress_value,
42 const int next_progress_value,
43 std::vector<Layer> &layers,
44 ram_msgs::AdditiveManufacturingTrajectory &msg);
47 const int current_progrress_value,
48 const int next_progress_value,
49 const Layer ¤t_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});
71 const double deposited_material_width);
76 std::vector<int> &level,
77 std::vector<int> &father);
80 const std::vector<int> level,
81 const std::vector<int> father,
85 const double tolerance = 1e-6);
88 const double tolerance = 1e-6);
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);
98 ram_msgs::AdditiveManufacturingTrajectory &msg,
99 const unsigned first_layer);
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)
std::vector< Polygon > PolygonVector
virtual ~DonghongDingBase()=0
void connectYamlLayers(actionlib::ServerGoalHandle< ActionSpec > &gh, const int current_progrress_value, const int next_progress_value, const Layer ¤t_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
double deposited_material_width_
bool intersectionBetweenContours(const Polygon poly_data)
const double calculation_tol_
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)