#include <donghong_ding_base.hpp>
Public Types | |
typedef std::vector< PolygonVector > | Layer |
typedef vtkSmartPointer< vtkPolyData > | Polygon |
typedef std::vector< Polygon > | PolygonVector |
Public Member Functions | |
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) |
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}) |
DonghongDingBase (const std::string name, const std::string description, const std::string service_name) | |
virtual | ~DonghongDingBase ()=0 |
Public Member Functions inherited from ram_path_planning::PathPlanningAlgorithm< ActionSpec > | |
PathPlanningAlgorithm (const std::string name, const std::string description, const std::string service_name) | |
bool | publishPercentageDone (const unsigned percentage, actionlib::ServerGoalHandle< ActionSpec > &gh) |
bool | publishStatusDone (const std::string progress_msg, actionlib::ServerGoalHandle< ActionSpec > &gh) |
bool | publishStatusPercentageDone (const std::string progress_msg, const unsigned percentage, actionlib::ServerGoalHandle< ActionSpec > &gh) |
virtual | ~PathPlanningAlgorithm ()=0 |
Protected Member Functions | |
double | angleBetweenVectors (const double v1[3], const double v2[3]) |
void | computeNormal (vtkPoints *p, double *n) |
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) |
void | identifyRelationships (const Polygon poly_data, std::vector< int > &level, std::vector< int > &father) |
bool | intersectionBetweenContours (const Polygon poly_data) |
bool | mergeColinearEdges (const Polygon poly_data, const double tolerance=1e-6) |
bool | offsetPolygonContour (const Polygon poly_data, const double deposited_material_width) |
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) |
Protected Attributes | |
const double | calculation_tol_ = 1e-6 |
double | deposited_material_width_ |
double | normal_vector_ [3] |
Additional Inherited Members | |
Public Attributes inherited from ram_path_planning::PathPlanningAlgorithm< ActionSpec > | |
const std::string | description_ |
const std::string | name_ |
const std::string | service_name_ |
Definition at line 25 of file donghong_ding_base.hpp.
typedef std::vector<PolygonVector> ram_path_planning::DonghongDingBase< ActionSpec >::Layer |
Definition at line 32 of file donghong_ding_base.hpp.
typedef vtkSmartPointer<vtkPolyData> ram_path_planning::DonghongDingBase< ActionSpec >::Polygon |
Definition at line 30 of file donghong_ding_base.hpp.
typedef std::vector<Polygon> ram_path_planning::DonghongDingBase< ActionSpec >::PolygonVector |
Definition at line 31 of file donghong_ding_base.hpp.
ram_path_planning::DonghongDingBase< ActionSpec >::DonghongDingBase | ( | const std::string | name, |
const std::string | description, | ||
const std::string | service_name | ||
) |
Definition at line 8 of file donghong_ding_base_imp.hpp.
|
pure virtual |
Definition at line 16 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 261 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 274 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 128 of file donghong_ding_base_imp.hpp.
std::string ram_path_planning::DonghongDingBase< ActionSpec >::connectMeshLayers | ( | actionlib::ServerGoalHandle< ActionSpec > & | gh, |
const int | current_progrress_value, | ||
const int | next_progress_value, | ||
std::vector< Layer > & | layers, | ||
ram_msgs::AdditiveManufacturingTrajectory & | msg | ||
) |
Definition at line 22 of file donghong_ding_base_imp.hpp.
void ram_path_planning::DonghongDingBase< ActionSpec >::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} |
||
) |
Definition at line 60 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 734 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 438 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 384 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 683 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 309 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 505 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 634 of file donghong_ding_base_imp.hpp.
|
protected |
Definition at line 56 of file donghong_ding_base.hpp.
|
protected |
Definition at line 58 of file donghong_ding_base.hpp.
|
protected |
Definition at line 55 of file donghong_ding_base.hpp.