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

#include <contours.hpp>

Inheritance diagram for ram_path_planning::Contours< 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

 Contours ()
 
std::string generateOneLayerTrajectory (actionlib::ServerGoalHandle< ActionSpec > &gh, const Polygon poly_data, Layer &layer, const double deposited_material_width, const std::array< double, 3 > normal_vector={0, 0, 1}, const bool use_gui=false)
 
std::string generateOneLayerTrajectory (actionlib::ServerGoalHandle< ActionSpec > &gh, const std::string yaml_file, Layer &layer, const double deposited_material_width, 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
 

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::Contours< ActionSpec >

Definition at line 9 of file contours.hpp.

Member Typedef Documentation

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

Definition at line 15 of file contours.hpp.

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

Definition at line 13 of file contours.hpp.

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

Definition at line 14 of file contours.hpp.

Constructor & Destructor Documentation

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

Definition at line 7 of file contours_imp.hpp.

Member Function Documentation

template<class ActionSpec >
std::string ram_path_planning::Contours< ActionSpec >::generateOneLayerTrajectory ( actionlib::ServerGoalHandle< ActionSpec > &  gh,
const Polygon  poly_data,
Layer layer,
const double  deposited_material_width,
const std::array< double, 3 >  normal_vector = {0, 0, 1},
const bool  use_gui = false 
)

Definition at line 16 of file contours_imp.hpp.

template<class ActionSpec >
std::string ram_path_planning::Contours< ActionSpec >::generateOneLayerTrajectory ( actionlib::ServerGoalHandle< ActionSpec > &  gh,
const std::string  yaml_file,
Layer layer,
const double  deposited_material_width,
const bool  use_gui = false 
)

Definition at line 89 of file contours_imp.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