Skip to content

Commit

Permalink
Merge pull request #120 from marip8/update/tool-path-planner-document…
Browse files Browse the repository at this point in the history
…ation

Tool path planner documentation and clean-up
  • Loading branch information
marip8 authored Dec 11, 2020
2 parents a55f733 + 017cc78 commit e77d0d5
Show file tree
Hide file tree
Showing 9 changed files with 19 additions and 22 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@ namespace path_sequence_planner
class PathSequencePlanner
{
public:
PathSequencePlanner() = default;
virtual ~PathSequencePlanner() = default;

/** @brief linkPaths Connects all of the paths_ into a single path and flips paths as necessary */
virtual void linkPaths() = 0;

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

/**
* @brief getIndices Get the list of path indices denoting the order in which paths should be executed
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class SimplePathSequencePlanner : public PathSequencePlanner

void setPaths(tool_path_planner::ToolPaths paths) override;

tool_path_planner::ToolPaths getPaths() override;
tool_path_planner::ToolPaths getPaths() const override;

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

Expand Down
2 changes: 1 addition & 1 deletion path_sequence_planner/src/simple_path_sequence_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ void SimplePathSequencePlanner::setPaths(tool_path_planner::ToolPaths paths)
indices_.clear();
}

tool_path_planner::ToolPaths SimplePathSequencePlanner::getPaths() { return paths_; }
tool_path_planner::ToolPaths SimplePathSequencePlanner::getPaths() const { return paths_; }

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,6 @@ class EigenValueEdgeGenerator : public PathGenerator
};

EigenValueEdgeGenerator() = default;
virtual ~EigenValueEdgeGenerator() = default;

/**
* @brief Set the generator configuration
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@ class HalfedgeEdgeGenerator : public PathGenerator
};

HalfedgeEdgeGenerator() = default;
virtual ~HalfedgeEdgeGenerator() = default;

/**
* @brief Set the generator configuration
Expand Down
6 changes: 5 additions & 1 deletion tool_path_planner/include/tool_path_planner/path_generator.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,12 @@

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

struct ToolPathSegmentData
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,6 @@ class PlaneSlicerRasterGenerator : public PathGenerator
};

PlaneSlicerRasterGenerator() = default;
virtual ~PlaneSlicerRasterGenerator() = default;

/**
* @brief Set the generator configuration
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,6 @@ class SurfaceWalkRasterGenerator : public PathGenerator
jv["generate_extra_rasters"].asBool() :
DEFAULT_GENERATE_EXTRA_RASTERS;
return true;
return true;
}

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

SurfaceWalkRasterGenerator() = default;
virtual ~SurfaceWalkRasterGenerator() = default;

/**
* @brief Set the generator configuration
Expand Down
21 changes: 8 additions & 13 deletions tool_path_planner/src/plane_slicer_raster_generator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,15 +88,15 @@ static vtkSmartPointer<vtkTransform> toVtkMatrix(const Eigen::Affine3d& t)

double computeLength(const vtkSmartPointer<vtkPoints>& points)
{
std::size_t num_points = points->GetNumberOfPoints();
const vtkIdType num_points = points->GetNumberOfPoints();
double total_length = 0.0;
if (num_points < 2)
{
return total_length;
}

Eigen::Vector3d p0, pf;
for (std::size_t i = 1; i < num_points; i++)
for (vtkIdType i = 1; i < num_points; i++)
{
points->GetPoint(i - 1, p0.data());
points->GetPoint(i, pf.data());
Expand Down Expand Up @@ -124,11 +124,10 @@ static vtkSmartPointer<vtkPoints> applyParametricSpline(const vtkSmartPointer<vt
new_points->InsertNextPoint(pt_prev.data());

// adding remaining points by evaluating spline
double incr = point_spacing / total_length;
std::size_t num_points = std::ceil(total_length / point_spacing) + 1;
std::size_t num_points = static_cast<std::size_t>(std::ceil(total_length / point_spacing) + 1);
double du[9];
Eigen::Vector3d u, pt;
for (std::size_t i = 1; i < num_points; i++)
for (unsigned i = 1; i < num_points; i++)
{
double interv = static_cast<double>(i) / static_cast<double>(num_points - 1);
interv = interv > 1.0 ? 1.0 : interv;
Expand Down Expand Up @@ -276,7 +275,7 @@ static void mergeRasterSegments(const vtkSmartPointer<vtkPoints>& points,
{
CONSOLE_BRIDGE_logDebug("Merged segment %lu onto segment %lu", j, i);
current_list = merged_list;
merged_list_ids.push_back(j);
merged_list_ids.push_back(static_cast<vtkIdType>(j));
seek_adjacent = true;
continue;
}
Expand All @@ -286,7 +285,7 @@ static void mergeRasterSegments(const vtkSmartPointer<vtkPoints>& points,
{
CONSOLE_BRIDGE_logDebug("Merged segment %lu onto segment %lu", j, i);
current_list = merged_list;
merged_list_ids.push_back(j);
merged_list_ids.push_back(static_cast<vtkIdType>(j));
seek_adjacent = true;
continue;
}
Expand Down Expand Up @@ -562,7 +561,7 @@ boost::optional<ToolPaths> PlaneSlicerRasterGenerator::generate()

// collect rasters and set direction
raster_data->Update();
std::size_t num_slices = raster_data->GetTotalNumberOfInputConnections();
vtkIdType num_slices = raster_data->GetTotalNumberOfInputConnections();
std::vector<RasterConstructData> rasters_data_vec;
std::vector<IDVec> raster_ids;
boost::optional<Vector3d> ref_dir;
Expand All @@ -575,7 +574,6 @@ boost::optional<ToolPaths> PlaneSlicerRasterGenerator::generate()
vtkIdType* indices;
vtkIdType num_points;
vtkIdType num_lines = raster_lines->GetNumberOfLines();
vtkPoints* points = raster_lines->GetPoints();
vtkCellArray* cells = raster_lines->GetLines();

CONSOLE_BRIDGE_logDebug("%s raster %i has %i lines and %i points",
Expand Down Expand Up @@ -727,13 +725,10 @@ bool PlaneSlicerRasterGenerator::insertNormals(const double search_radius, vtkSm
// compute normal average
normal_vect = Eigen::Vector3d::Zero();
std::size_t num_normals = 0;
for (std::size_t p = 0; p < id_list->GetNumberOfIds(); p++)
for (auto p = 0; p < id_list->GetNumberOfIds(); p++)
{
Eigen::Vector3d temp_normal, query_point, closest_point;
vtkIdType p_id = id_list->GetId(p);
vtkIdType cell_id;
int sub_index;
double dist;

if (p_id < 0)
{
Expand Down

0 comments on commit e77d0d5

Please sign in to comment.