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>
|
| | PlaneSlicerLegacyRasterPlanner (DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen, const double point_spacing, const double min_segment_size, const double min_hole_size) |
| | Constructor.
|
| |
|
| PlaneSlicerRasterPlanner (DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen) |
| |
|
void | generateRastersBidirectionally (const bool bidirectional) |
| |
|
| RasterPlanner (DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen) |
| |
| ToolPaths | plan (const pcl::PolygonMesh &mesh) const override final |
| |
|
void | setLineSpacing (const double line_spacing) |
| |
|
| ToolPaths | planImpl (const pcl::PolygonMesh &mesh) const |
| | Implementation of the tool path planning capability.
|
| |
| ToolPaths | planImpl (const pcl::PolygonMesh &mesh) const |
| | Implementation of the tool path planning capability.
|
| |
|
|
double | point_spacing_ |
| |
|
double | min_segment_size_ |
| |
|
double | min_hole_size_ |
| |
|
bool | bidirectional_ = true |
| | Flag indicating whether rasters should be generated in the direction of both the cut normal and its negation.
|
| |
|
DirectionGenerator::ConstPtr | dir_gen_ |
| |
|
OriginGenerator::ConstPtr | origin_gen_ |
| |
|
double | line_spacing_ |
| | Distance between raster lines.
|
| |
◆ 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_gen | Direction generator |
| origin_gen | Origin generator |
| point_spacing | Distance between waypoints on the same raster line (m) |
| min_segment_size | Minimum length of valid segment (m) |
| 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::PlaneSlicerLegacyRasterPlanner::planImpl |
( |
const pcl::PolygonMesh & |
mesh | ) |
const |
|
protectedvirtual |