Noether  0.0.0
Loading...
Searching...
No Matches
noether::PlaneSlicerLegacyRasterPlanner Class Reference

Detailed Description

Implementation of the legacy PlaneSlicerRasterPlanner, which includes control over point spacing, minimum segment size, and minimum hole size.

#include <plane_slicer_legacy_raster_planner.h>

Inheritance diagram for noether::PlaneSlicerLegacyRasterPlanner:

Public Member Functions

 PlaneSlicerLegacyRasterPlanner (DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen, const double point_spacing, const double min_segment_size, const double min_hole_size)
 Constructor.
 
- Public Member Functions inherited from noether::PlaneSlicerRasterPlanner
 PlaneSlicerRasterPlanner (DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen)
 
void generateRastersBidirectionally (const bool bidirectional)
 
- Public Member Functions inherited from noether::RasterPlanner
 RasterPlanner (DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen)
 
ToolPaths plan (const pcl::PolygonMesh &mesh) const override final
 
void setLineSpacing (const double line_spacing)
 

Protected Member Functions

ToolPaths planImpl (const pcl::PolygonMesh &mesh) const
 Implementation of the tool path planning capability.
 
- Protected Member Functions inherited from noether::PlaneSlicerRasterPlanner
ToolPaths planImpl (const pcl::PolygonMesh &mesh) const
 Implementation of the tool path planning capability.
 

Protected Attributes

double point_spacing_
 
double min_segment_size_
 
double min_hole_size_
 
- Protected Attributes inherited from noether::PlaneSlicerRasterPlanner
bool bidirectional_ = true
 Flag indicating whether rasters should be generated in the direction of both the cut normal and its negation.
 
- Protected Attributes inherited from noether::RasterPlanner
DirectionGenerator::ConstPtr dir_gen_
 
OriginGenerator::ConstPtr origin_gen_
 
double line_spacing_
 Distance between raster lines.
 

Additional Inherited Members

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

Constructor & Destructor Documentation

◆ PlaneSlicerLegacyRasterPlanner()

noether::PlaneSlicerLegacyRasterPlanner::PlaneSlicerLegacyRasterPlanner ( DirectionGenerator::ConstPtr  dir_gen,
OriginGenerator::ConstPtr  origin_gen,
const double  point_spacing,
const double  min_segment_size,
const double  min_hole_size 
)
Parameters
dir_genDirection generator
origin_genOrigin generator
point_spacingDistance between waypoints on the same raster line (m)
min_segment_sizeMinimum length of valid segment (m)
min_hole_sizeMinimum size of hole in a mesh for which the planner should split a raster line that crosses over the hole into multiple segments

Member Function Documentation

◆ planImpl()

ToolPaths noether::PlaneSlicerLegacyRasterPlanner::planImpl ( const pcl::PolygonMesh &  mesh) const
protectedvirtual