Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ram_path_planning::DonghongDing< ActionSpec > Class Template Reference

#include <donghong_ding.hpp>

Inheritance diagram for ram_path_planning::DonghongDing< ActionSpec >:
Inheritance graph
[legend]

Public Types

typedef std::vector< PolygonVectorLayer
 
typedef vtkSmartPointer< vtkPolyData > Polygon
 
typedef std::vector< PolygonPolygonVector
 
- Public Types inherited from ram_path_planning::DonghongDingBase< ActionSpec >
typedef std::vector< PolygonVectorLayer
 
typedef vtkSmartPointer< vtkPolyData > Polygon
 
typedef std::vector< PolygonPolygonVector
 

Public Member Functions

 DonghongDing ()
 
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)
 
std::string generateOneLayerTrajectory (actionlib::ServerGoalHandle< ActionSpec > &gh, const int current_progrress_value, const int next_progress_value, const std::string yaml_file, Layer &layer, const double deposited_material_width, const double contours_filtering_tolerance, const double polygon_division_tolerance=M_PI/6, const bool closest_to_bisector=false, const bool use_gui=false)
 
- Public Member Functions inherited from ram_path_planning::DonghongDingBase< ActionSpec >
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 &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})
 
 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
 

Private Member Functions

bool divideInConvexPolygons (PolygonVector &polygon_source, const int polygon_position, const vtkSmartPointer< vtkPoints > split_points)
 
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 findNotch (const Polygon poly_data, vtkIdType &cell_id, vtkIdType &pos, double &angle)
 
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)
 
bool generateTrajectoryInConvexPolygon (const Polygon poly_data)
 
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)
 
double identifyZigzagDirection (const Polygon poly_data, vtkIdType &edge, vtkIdType &futhest_point)
 
bool intersectLineWithContours (const Polygon poly_data, double point_1[3], double point_2[3])
 
bool mergeConvexPolygons (PolygonVector &polygon_source, const vtkSmartPointer< vtkPoints > split_points, const vtkIdType split_line)
 
void mergeListOfPoints (const Polygon poly_data, const vtkSmartPointer< vtkPoints > left_chain, const vtkSmartPointer< vtkPoints > right_chain, const vtkSmartPointer< vtkPoints > zigzag_points)
 
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 verifyAngles (const Polygon poly_data, const vtkIdType notch_cell_id, const vtkIdType notch_pos, const vtkIdType vertex_cell_id, const vtkIdType vertex_pos)
 
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)
 

Private Attributes

bool closest_to_bisector_
 
double contours_filtering_tolerance_
 
double polygon_division_tolerance_
 
Semaphore semaphore_
 

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_
 
- Protected Member Functions inherited from ram_path_planning::DonghongDingBase< ActionSpec >
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 inherited from ram_path_planning::DonghongDingBase< ActionSpec >
const double calculation_tol_ = 1e-6
 
double deposited_material_width_
 
double normal_vector_ [3]
 

Detailed Description

template<class ActionSpec>
class ram_path_planning::DonghongDing< ActionSpec >

Definition at line 10 of file donghong_ding.hpp.

Member Typedef Documentation

template<class ActionSpec>
typedef std::vector<PolygonVector> ram_path_planning::DonghongDing< ActionSpec >::Layer

Definition at line 16 of file donghong_ding.hpp.

template<class ActionSpec>
typedef vtkSmartPointer<vtkPolyData> ram_path_planning::DonghongDing< ActionSpec >::Polygon

Definition at line 14 of file donghong_ding.hpp.

template<class ActionSpec>
typedef std::vector<Polygon> ram_path_planning::DonghongDing< ActionSpec >::PolygonVector

Definition at line 15 of file donghong_ding.hpp.

Constructor & Destructor Documentation

template<class ActionSpec >
ram_path_planning::DonghongDing< ActionSpec >::DonghongDing ( )

Definition at line 9 of file donghong_ding_imp.hpp.

Member Function Documentation

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::divideInConvexPolygons ( PolygonVector polygon_source,
const int  polygon_position,
const vtkSmartPointer< vtkPoints >  split_points 
)
private

Definition at line 509 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::findIntersectWithBisector ( const Polygon  poly_data,
const vtkIdType  notch_cell_id,
const vtkIdType  notch_pos,
vtkIdType &  vertex_cell_id,
vtkIdType &  vertex_pos,
double  vertex[3] 
)
private

Definition at line 425 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::findNotch ( const Polygon  poly_data,
vtkIdType &  cell_id,
vtkIdType &  pos,
double &  angle 
)
private

Definition at line 206 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::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 
)
private

Definition at line 335 of file donghong_ding_imp.hpp.

template<class ActionSpec >
std::string ram_path_planning::DonghongDing< ActionSpec >::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 
)

Definition at line 22 of file donghong_ding_imp.hpp.

template<class ActionSpec >
std::string ram_path_planning::DonghongDing< ActionSpec >::generateOneLayerTrajectory ( actionlib::ServerGoalHandle< ActionSpec > &  gh,
const int  current_progrress_value,
const int  next_progress_value,
const std::string  yaml_file,
Layer layer,
const double  deposited_material_width,
const double  contours_filtering_tolerance,
const double  polygon_division_tolerance = M_PI / 6,
const bool  closest_to_bisector = false,
const bool  use_gui = false 
)

Definition at line 178 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::generateTrajectoryInConvexPolygon ( const Polygon  poly_data)
private

Definition at line 1408 of file donghong_ding_imp.hpp.

template<class ActionSpec >
void ram_path_planning::DonghongDing< ActionSpec >::identifyLeftChain ( const Polygon  poly_data,
const vtkIdType  edge_id,
const vtkIdType  opposite_point_id,
const vtkSmartPointer< vtkPoints >  left_chain,
const vtkSmartPointer< vtkPoints >  right_chain 
)
private

Definition at line 855 of file donghong_ding_imp.hpp.

template<class ActionSpec >
double ram_path_planning::DonghongDing< ActionSpec >::identifyZigzagDirection ( const Polygon  poly_data,
vtkIdType &  edge,
vtkIdType &  futhest_point 
)
private

Definition at line 798 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::intersectLineWithContours ( const Polygon  poly_data,
double  point_1[3],
double  point_2[3] 
)
private

Definition at line 308 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::mergeConvexPolygons ( PolygonVector polygon_source,
const vtkSmartPointer< vtkPoints >  split_points,
const vtkIdType  split_line 
)
private

Definition at line 1198 of file donghong_ding_imp.hpp.

template<class ActionSpec >
void ram_path_planning::DonghongDing< ActionSpec >::mergeListOfPoints ( const Polygon  poly_data,
const vtkSmartPointer< vtkPoints >  left_chain,
const vtkSmartPointer< vtkPoints >  right_chain,
const vtkSmartPointer< vtkPoints >  zigzag_points 
)
private

Definition at line 1158 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::offsetLeftChain ( const Polygon  poly_data,
const vtkIdType  edge_id,
const vtkIdType  opposite_point_id,
const vtkSmartPointer< vtkPoints >  left_chain,
const vtkSmartPointer< vtkPoints >  right_chain 
)
private

Definition at line 900 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::verifyAngles ( const Polygon  poly_data,
const vtkIdType  notch_cell_id,
const vtkIdType  notch_pos,
const vtkIdType  vertex_cell_id,
const vtkIdType  vertex_pos 
)
private

Definition at line 252 of file donghong_ding_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDing< ActionSpec >::zigzagGeneration ( const Polygon  poly_data,
const vtkIdType  edge_id,
const vtkIdType  opposite_point_id,
const vtkSmartPointer< vtkPoints >  zigzag_points,
const double  deposited_material_width 
)
private

Definition at line 1062 of file donghong_ding_imp.hpp.

Member Data Documentation

template<class ActionSpec>
bool ram_path_planning::DonghongDing< ActionSpec >::closest_to_bisector_
private

Definition at line 49 of file donghong_ding.hpp.

template<class ActionSpec>
double ram_path_planning::DonghongDing< ActionSpec >::contours_filtering_tolerance_
private

Definition at line 51 of file donghong_ding.hpp.

template<class ActionSpec>
double ram_path_planning::DonghongDing< ActionSpec >::polygon_division_tolerance_
private

Definition at line 50 of file donghong_ding.hpp.

template<class ActionSpec>
Semaphore ram_path_planning::DonghongDing< ActionSpec >::semaphore_
private

Definition at line 47 of file donghong_ding.hpp.


The documentation for this class was generated from the following files:


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