Skip to content

Commit e77d0d5

Browse files
authored
Merge pull request #120 from marip8/update/tool-path-planner-documentation
Tool path planner documentation and clean-up
2 parents a55f733 + 017cc78 commit e77d0d5

File tree

9 files changed

+19
-22
lines changed

9 files changed

+19
-22
lines changed

path_sequence_planner/include/path_sequence_planner/path_sequence_planner.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,9 @@ namespace path_sequence_planner
2727
class PathSequencePlanner
2828
{
2929
public:
30+
PathSequencePlanner() = default;
31+
virtual ~PathSequencePlanner() = default;
32+
3033
/** @brief linkPaths Connects all of the paths_ into a single path and flips paths as necessary */
3134
virtual void linkPaths() = 0;
3235

@@ -40,7 +43,7 @@ class PathSequencePlanner
4043
* @brief getPaths Get the list of paths currently stored (some paths may be flipped after linking)
4144
* @return The set of paths currently stored
4245
*/
43-
virtual tool_path_planner::ToolPaths getPaths() = 0;
46+
virtual tool_path_planner::ToolPaths getPaths() const = 0;
4447

4548
/**
4649
* @brief getIndices Get the list of path indices denoting the order in which paths should be executed

path_sequence_planner/include/path_sequence_planner/simple_path_sequence_planner.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ class SimplePathSequencePlanner : public PathSequencePlanner
3131

3232
void setPaths(tool_path_planner::ToolPaths paths) override;
3333

34-
tool_path_planner::ToolPaths getPaths() override;
34+
tool_path_planner::ToolPaths getPaths() const override;
3535

3636
std::vector<std::size_t> getIndices() const override;
3737

path_sequence_planner/src/simple_path_sequence_planner.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ void SimplePathSequencePlanner::setPaths(tool_path_planner::ToolPaths paths)
1717
indices_.clear();
1818
}
1919

20-
tool_path_planner::ToolPaths SimplePathSequencePlanner::getPaths() { return paths_; }
20+
tool_path_planner::ToolPaths SimplePathSequencePlanner::getPaths() const { return paths_; }
2121

2222
std::vector<std::size_t> SimplePathSequencePlanner::getIndices() const { return indices_; }
2323

tool_path_planner/include/tool_path_planner/eigen_value_edge_generator.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,6 @@ class EigenValueEdgeGenerator : public PathGenerator
102102
};
103103

104104
EigenValueEdgeGenerator() = default;
105-
virtual ~EigenValueEdgeGenerator() = default;
106105

107106
/**
108107
* @brief Set the generator configuration

tool_path_planner/include/tool_path_planner/halfedge_edge_generator.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,6 @@ class HalfedgeEdgeGenerator : public PathGenerator
6969
};
7070

7171
HalfedgeEdgeGenerator() = default;
72-
virtual ~HalfedgeEdgeGenerator() = default;
7372

7473
/**
7574
* @brief Set the generator configuration

tool_path_planner/include/tool_path_planner/path_generator.h

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,12 @@
1313

1414
namespace tool_path_planner
1515
{
16-
using ToolPathSegment = std::vector<Eigen::Isometry3d>;
16+
/** @brief A set of contiguous waypoints that lie on the same line created by a "slice" through a surface */
17+
using ToolPathSegment = std::vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d>>;
18+
/** @brief A set of tool path segments that lie on the same line created by a tool path "slice",
19+
* but are not connected (e.g. due to a hole in the mesh) */
1720
using ToolPath = std::vector<ToolPathSegment>;
21+
/** @brief A set of tool paths (i.e. rasters) generated by various different slices through a surface */
1822
using ToolPaths = std::vector<ToolPath>;
1923

2024
struct ToolPathSegmentData

tool_path_planner/include/tool_path_planner/plane_slicer_raster_generator.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,6 @@ class PlaneSlicerRasterGenerator : public PathGenerator
126126
};
127127

128128
PlaneSlicerRasterGenerator() = default;
129-
virtual ~PlaneSlicerRasterGenerator() = default;
130129

131130
/**
132131
* @brief Set the generator configuration

tool_path_planner/include/tool_path_planner/surface_walk_raster_generator.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,6 @@ class SurfaceWalkRasterGenerator : public PathGenerator
134134
jv["generate_extra_rasters"].asBool() :
135135
DEFAULT_GENERATE_EXTRA_RASTERS;
136136
return true;
137-
return true;
138137
}
139138

140139
bool fromJson(const std::string& jv_string)
@@ -162,7 +161,6 @@ class SurfaceWalkRasterGenerator : public PathGenerator
162161
};
163162

164163
SurfaceWalkRasterGenerator() = default;
165-
virtual ~SurfaceWalkRasterGenerator() = default;
166164

167165
/**
168166
* @brief Set the generator configuration

tool_path_planner/src/plane_slicer_raster_generator.cpp

Lines changed: 8 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -88,15 +88,15 @@ static vtkSmartPointer<vtkTransform> toVtkMatrix(const Eigen::Affine3d& t)
8888

8989
double computeLength(const vtkSmartPointer<vtkPoints>& points)
9090
{
91-
std::size_t num_points = points->GetNumberOfPoints();
91+
const vtkIdType num_points = points->GetNumberOfPoints();
9292
double total_length = 0.0;
9393
if (num_points < 2)
9494
{
9595
return total_length;
9696
}
9797

9898
Eigen::Vector3d p0, pf;
99-
for (std::size_t i = 1; i < num_points; i++)
99+
for (vtkIdType i = 1; i < num_points; i++)
100100
{
101101
points->GetPoint(i - 1, p0.data());
102102
points->GetPoint(i, pf.data());
@@ -124,11 +124,10 @@ static vtkSmartPointer<vtkPoints> applyParametricSpline(const vtkSmartPointer<vt
124124
new_points->InsertNextPoint(pt_prev.data());
125125

126126
// adding remaining points by evaluating spline
127-
double incr = point_spacing / total_length;
128-
std::size_t num_points = std::ceil(total_length / point_spacing) + 1;
127+
std::size_t num_points = static_cast<std::size_t>(std::ceil(total_length / point_spacing) + 1);
129128
double du[9];
130129
Eigen::Vector3d u, pt;
131-
for (std::size_t i = 1; i < num_points; i++)
130+
for (unsigned i = 1; i < num_points; i++)
132131
{
133132
double interv = static_cast<double>(i) / static_cast<double>(num_points - 1);
134133
interv = interv > 1.0 ? 1.0 : interv;
@@ -276,7 +275,7 @@ static void mergeRasterSegments(const vtkSmartPointer<vtkPoints>& points,
276275
{
277276
CONSOLE_BRIDGE_logDebug("Merged segment %lu onto segment %lu", j, i);
278277
current_list = merged_list;
279-
merged_list_ids.push_back(j);
278+
merged_list_ids.push_back(static_cast<vtkIdType>(j));
280279
seek_adjacent = true;
281280
continue;
282281
}
@@ -286,7 +285,7 @@ static void mergeRasterSegments(const vtkSmartPointer<vtkPoints>& points,
286285
{
287286
CONSOLE_BRIDGE_logDebug("Merged segment %lu onto segment %lu", j, i);
288287
current_list = merged_list;
289-
merged_list_ids.push_back(j);
288+
merged_list_ids.push_back(static_cast<vtkIdType>(j));
290289
seek_adjacent = true;
291290
continue;
292291
}
@@ -562,7 +561,7 @@ boost::optional<ToolPaths> PlaneSlicerRasterGenerator::generate()
562561

563562
// collect rasters and set direction
564563
raster_data->Update();
565-
std::size_t num_slices = raster_data->GetTotalNumberOfInputConnections();
564+
vtkIdType num_slices = raster_data->GetTotalNumberOfInputConnections();
566565
std::vector<RasterConstructData> rasters_data_vec;
567566
std::vector<IDVec> raster_ids;
568567
boost::optional<Vector3d> ref_dir;
@@ -575,7 +574,6 @@ boost::optional<ToolPaths> PlaneSlicerRasterGenerator::generate()
575574
vtkIdType* indices;
576575
vtkIdType num_points;
577576
vtkIdType num_lines = raster_lines->GetNumberOfLines();
578-
vtkPoints* points = raster_lines->GetPoints();
579577
vtkCellArray* cells = raster_lines->GetLines();
580578

581579
CONSOLE_BRIDGE_logDebug("%s raster %i has %i lines and %i points",
@@ -727,13 +725,10 @@ bool PlaneSlicerRasterGenerator::insertNormals(const double search_radius, vtkSm
727725
// compute normal average
728726
normal_vect = Eigen::Vector3d::Zero();
729727
std::size_t num_normals = 0;
730-
for (std::size_t p = 0; p < id_list->GetNumberOfIds(); p++)
728+
for (auto p = 0; p < id_list->GetNumberOfIds(); p++)
731729
{
732730
Eigen::Vector3d temp_normal, query_point, closest_point;
733731
vtkIdType p_id = id_list->GetId(p);
734-
vtkIdType cell_id;
735-
int sub_index;
736-
double dist;
737732

738733
if (p_id < 0)
739734
{

0 commit comments

Comments
 (0)