Noether  0.0.0
Loading...
Searching...
No Matches
noether::RasterPlanner Class Referenceabstract

A specification of the tool path planner for covering surfaces in repeating, evenly spaced path lines. More...

#include <raster_planner.h>

Inheritance diagram for noether::RasterPlanner:

Public Member Functions

 RasterPlanner (DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen)
 
ToolPaths plan (const pcl::PolygonMesh &mesh) const override final
 
void setPointSpacing (const double point_spacing)
 
void setLineSpacing (const double line_spacing)
 
void setMinHoleSize (const double min_hole_size)
 

Protected Member Functions

virtual ToolPaths planImpl (const pcl::PolygonMesh &mesh) const =0
 Implementation of the tool path planning capability.
 

Protected Attributes

DirectionGenerator::ConstPtr dir_gen_
 
OriginGenerator::ConstPtr origin_gen_
 
double point_spacing_
 Distance between waypoints on the same raster line (m)
 
double line_spacing_
 Distance between raster lines.
 
double min_hole_size_
 Minimum size of hole in a mesh for which the planner should split a raster line that crosses over the hole into multiple segments.
 

Additional Inherited Members

- Public Types inherited from noether::ToolPathPlanner
using Ptr = std::unique_ptr< ToolPathPlanner >
 
using ConstPtr = std::unique_ptr< const ToolPathPlanner >
 

Detailed Description

A specification of the tool path planner for covering surfaces in repeating, evenly spaced path lines.

By default, a raster planner will produce a path with all points having a consistent orientation, lines which all travel in the same direction across the surface, and the traversal between lines will be in a consistent direction and order.

Member Function Documentation

◆ plan()

ToolPaths noether::RasterPlanner::plan ( const pcl::PolygonMesh &  mesh) const
finaloverridevirtual

◆ planImpl()

virtual ToolPaths noether::RasterPlanner::planImpl ( const pcl::PolygonMesh &  mesh) const
protectedpure virtual

Implementation of the tool path planning capability.

Implemented in noether::PlaneSlicerRasterPlanner.