An implementation of the Raster Planner using a series of parallel cutting planes.
More...
This implementation works best on approximately planar parts. The direction generator defines the direction of the raster cut. The cut normal (i.e., the raster step direction) is defined by the cross product of the cut direction and the smallest principal axis of the mesh.
#include <plane_slicer_raster_planner.h>
|
| PlaneSlicerRasterPlanner (DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen) |
|
void | setSearchRadius (const double search_radius) |
|
void | setMinSegmentSize (const double min_segment_size) |
|
void | generateRastersBidirectionally (const bool bidirectional) |
|
| 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) |
|
|
ToolPaths | planImpl (const pcl::PolygonMesh &mesh) const |
| Implementation of the tool path planning capability.
|
|
|
bool | bidirectional_ = true |
| Flag indicating whether rasters should be generated in the direction of both the cut normal and its negation.
|
|
double | min_segment_size_ |
| Minimum length of valid segment (m)
|
|
double | search_radius_ |
| Search radius for calculating normals (m)
|
|
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.
|
|
◆ planImpl()
ToolPaths noether::PlaneSlicerRasterPlanner::planImpl |
( |
const pcl::PolygonMesh & |
mesh | ) |
const |
|
protectedvirtual |