Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ram_path_planning::DonghongDingBase< ActionSpec > Class Template Referenceabstract

#include <donghong_ding_base.hpp>

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

Public Types

typedef std::vector< PolygonVectorLayer
 
typedef vtkSmartPointer< vtkPolyData > Polygon
 
typedef std::vector< PolygonPolygonVector
 

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 &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
 

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_
 

Detailed Description

template<class ActionSpec>
class ram_path_planning::DonghongDingBase< ActionSpec >

Definition at line 25 of file donghong_ding_base.hpp.

Member Typedef Documentation

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

Definition at line 32 of file donghong_ding_base.hpp.

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

Definition at line 30 of file donghong_ding_base.hpp.

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

Definition at line 31 of file donghong_ding_base.hpp.

Constructor & Destructor Documentation

template<class ActionSpec >
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.

template<class ActionSpec >
ram_path_planning::DonghongDingBase< ActionSpec >::~DonghongDingBase ( )
pure virtual

Definition at line 16 of file donghong_ding_base_imp.hpp.

Member Function Documentation

template<class ActionSpec >
double ram_path_planning::DonghongDingBase< ActionSpec >::angleBetweenVectors ( const double  v1[3],
const double  v2[3] 
)
protected

Definition at line 261 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
void ram_path_planning::DonghongDingBase< ActionSpec >::computeNormal ( vtkPoints *  p,
double *  n 
)
protected

Definition at line 274 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
void ram_path_planning::DonghongDingBase< ActionSpec >::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 
)
protected

Definition at line 128 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
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.

template<class ActionSpec >
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.

template<class ActionSpec >
void ram_path_planning::DonghongDingBase< ActionSpec >::divideInLayersWithOnePolygon ( std::vector< Layer > &  layers,
ram_msgs::AdditiveManufacturingTrajectory &  msg,
const unsigned  first_layer 
)
protected

Definition at line 734 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
void ram_path_planning::DonghongDingBase< ActionSpec >::identifyRelationships ( const Polygon  poly_data,
std::vector< int > &  level,
std::vector< int > &  father 
)
protected

Definition at line 438 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDingBase< ActionSpec >::intersectionBetweenContours ( const Polygon  poly_data)
protected

Definition at line 384 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDingBase< ActionSpec >::mergeColinearEdges ( const Polygon  poly_data,
const double  tolerance = 1e-6 
)
protected

Definition at line 683 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDingBase< ActionSpec >::offsetPolygonContour ( const Polygon  poly_data,
const double  deposited_material_width 
)
protected

Definition at line 309 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDingBase< ActionSpec >::organizePolygonContoursInLayer ( const Polygon  poly_data,
const std::vector< int >  level,
const std::vector< int >  father,
Layer layer 
)
protected

Definition at line 505 of file donghong_ding_base_imp.hpp.

template<class ActionSpec >
bool ram_path_planning::DonghongDingBase< ActionSpec >::removeDuplicatePoints ( const Polygon  poly_data,
const double  tolerance = 1e-6 
)
protected

Definition at line 634 of file donghong_ding_base_imp.hpp.

Member Data Documentation

template<class ActionSpec >
const double ram_path_planning::DonghongDingBase< ActionSpec >::calculation_tol_ = 1e-6
protected

Definition at line 56 of file donghong_ding_base.hpp.

template<class ActionSpec >
double ram_path_planning::DonghongDingBase< ActionSpec >::deposited_material_width_
protected

Definition at line 58 of file donghong_ding_base.hpp.

template<class ActionSpec >
double ram_path_planning::DonghongDingBase< ActionSpec >::normal_vector_[3]
protected

Definition at line 55 of file donghong_ding_base.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