Noether
0.0.0
|
A specification of the tool path planner for covering surfaces in repeating, evenly spaced path lines. More...
#include <raster_planner.h>
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. | |
Additional Inherited Members | |
Public Types inherited from noether::ToolPathPlanner | |
using | Ptr = std::unique_ptr< ToolPathPlanner > |
using | ConstPtr = std::unique_ptr< const ToolPathPlanner > |
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.
|
finaloverridevirtual |
Implements noether::ToolPathPlanner.
|
protectedpure virtual |
Implementation of the tool path planning capability.
Implemented in noether::PlaneSlicerRasterPlanner.