Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane slice planner #168

Merged
merged 10 commits into from
Jun 23, 2022
Merged
Show file tree
Hide file tree
Changes from 8 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions ci
13 changes: 11 additions & 2 deletions noether_tpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,14 @@ project(${pkg_extracted_name} VERSION ${pkg_extracted_version} LANGUAGES CXX)
find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED COMPONENTS common io)

find_package(VTK REQUIRED NO_MODULE)
if(VTK_FOUND AND ("${VTK_VERSION}" VERSION_LESS 7.1))
message(FATAL_ERROR "The minimum required version of VTK is 7.1, but found ${VTK_VERSION}")
set(VTK_FOUND FALSE)
else()
include(${VTK_USE_FILE})
endif()

# Create targets if necessary
if(NOT TARGET Eigen3::Eigen)
find_package(Threads REQUIRED)
Expand All @@ -29,14 +37,15 @@ add_library(${PROJECT_NAME} SHARED
# Tool Path Planners
src/tool_path_planners/edge_planner.cpp
src/tool_path_planners/raster_planner.cpp
src/tool_path_planners/plane_slicer_raster_planner.cpp
src/tool_path_planners/direction_generators.cpp
src/tool_path_planners/origin_generators.cpp
)
target_include_directories(${PROJECT_NAME} PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")
target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${PCL_INCLUDE_DIRS})
target_link_libraries(${PROJECT_NAME} PUBLIC Eigen3::Eigen ${PCL_LIBRARIES})
target_link_libraries(${PROJECT_NAME} PUBLIC Eigen3::Eigen ${PCL_LIBRARIES} ${VTK_LIBRARIES})
target_cxx_version(${PROJECT_NAME} PUBLIC VERSION 14)
target_clang_tidy(${PROJECT_NAME}
ENABLE ${NOETHER_ENABLE_CLANG_TIDY}
Expand All @@ -55,4 +64,4 @@ if(${NOETHER_ENABLE_TESTING})
endif()

# Package configuration
configure_package(NAMESPACE noether TARGETS ${PROJECT_NAME})
configure_package(NAMESPACE noether DEPENDENCIES Eigen3 "PCL REQUIRED COMPONENTS common io" VTK TARGETS ${PROJECT_NAME})
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ class FixedDirectionGenerator : public DirectionGenerator
public:
FixedDirectionGenerator(const Eigen::Vector3d& direction);
Eigen::Vector3d generate(const pcl::PolygonMesh& mesh) const override final;
std::unique_ptr<DirectionGenerator> clone() const override final;
marip8 marked this conversation as resolved.
Show resolved Hide resolved

private:
const Eigen::Vector3d direction_;
Expand All @@ -25,6 +26,7 @@ class PrincipalAxisDirectionGenerator : public DirectionGenerator
public:
PrincipalAxisDirectionGenerator(double rotation_offset = 0.0);
Eigen::Vector3d generate(const pcl::PolygonMesh& mesh) const override final;
std::unique_ptr<DirectionGenerator> clone() const override final;

private:
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ class FixedOriginGenerator : public OriginGenerator
public:
FixedOriginGenerator(const Eigen::Vector3d& origin = Eigen::Vector3d::Zero());
Eigen::Vector3d generate(const pcl::PolygonMesh& mesh) const override final;
std::unique_ptr<OriginGenerator> clone() const override final;

private:
const Eigen::Vector3d origin_;
Expand All @@ -26,6 +27,7 @@ class FixedOriginGenerator : public OriginGenerator
struct CentroidOriginGenerator : public OriginGenerator
{
Eigen::Vector3d generate(const pcl::PolygonMesh& mesh) const override final;
std::unique_ptr<OriginGenerator> clone() const override final;
};

/**
Expand All @@ -34,6 +36,7 @@ struct CentroidOriginGenerator : public OriginGenerator
struct AABBCenterOriginGenerator : public OriginGenerator
{
Eigen::Vector3d generate(const pcl::PolygonMesh& mesh) const override final;
std::unique_ptr<OriginGenerator> clone() const override final;
};

/**
Expand All @@ -44,6 +47,7 @@ class OffsetOriginGenerator : public OriginGenerator
public:
OffsetOriginGenerator(OriginGenerator::ConstPtr&& generator, const Eigen::Vector3d& offset);
Eigen::Vector3d generate(const pcl::PolygonMesh& mesh) const override final;
std::unique_ptr<OriginGenerator> clone() const override final;

private:
const OriginGenerator::ConstPtr generator_;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
/**
* @file plane_slicer_raster_planner.h
* @copyright Copyright (c) 2021, Southwest Research Institute
*
* @par License
* Software License Agreement (Apache License)
* @par
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
* http://www.apache.org/licenses/LICENSE-2.0
* @par
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#pragma once

#include <noether_tpp/core/tool_path_modifier.h>
#include <noether_tpp/tool_path_planners/raster/raster_planner.h>

namespace noether
{
/**
* @brief An implementation of the Raster Planner using a series of parallel cutting planes.
* This implementation works best on approximately planar parts.
*/
class PlaneSlicerRasterPlanner : public RasterPlanner
{
public:
PlaneSlicerRasterPlanner(DirectionGenerator::ConstPtr dir_gen, OriginGenerator::ConstPtr origin_gen);

void setSearchRadius(const double search_radius);
void setMinSegmentSize(const double min_segment_size);

protected:
/**
* @brief Implementation of the tool path planning capability
* @param mesh
* @return
*/
ToolPaths planImpl(const pcl::PolygonMesh& mesh) const;

private:
/** @brief Minimum length of valid segment (m) */
double min_segment_size_;
/** @brief Search radius for calculating normals (m) */
double search_radius_;
};

} // namespace noether
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ struct DirectionGenerator

virtual ~DirectionGenerator() = default;
virtual Eigen::Vector3d generate(const pcl::PolygonMesh& mesh) const = 0;
virtual std::unique_ptr<DirectionGenerator> clone() const = 0;
};

/**
Expand All @@ -48,6 +49,7 @@ struct OriginGenerator

virtual ~OriginGenerator() = default;
virtual Eigen::Vector3d generate(const pcl::PolygonMesh& mesh) const = 0;
virtual std::unique_ptr<OriginGenerator> clone() const = 0;
};

/**
Expand Down Expand Up @@ -78,7 +80,6 @@ class RasterPlanner : public ToolPathPlanner
DirectionGenerator::ConstPtr dir_gen_;
OriginGenerator::ConstPtr origin_gen_;

private:
/** @brief Distance between waypoints on the same raster line (m) */
double point_spacing_;
marip8 marked this conversation as resolved.
Show resolved Hide resolved
/** @brief Distance between raster lines */
Expand Down
10 changes: 10 additions & 0 deletions noether_tpp/src/tool_path_planners/direction_generators.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,11 @@ FixedDirectionGenerator::FixedDirectionGenerator(const Eigen::Vector3d& directio

Eigen::Vector3d FixedDirectionGenerator::generate(const pcl::PolygonMesh&) const { return direction_; }

std::unique_ptr<DirectionGenerator> FixedDirectionGenerator::clone() const
{
return std::make_unique<FixedDirectionGenerator>(direction_);
}

PrincipalAxisDirectionGenerator::PrincipalAxisDirectionGenerator(double rotation_offset)
: rotation_offset_(rotation_offset)
{
Expand All @@ -30,4 +35,9 @@ Eigen::Vector3d PrincipalAxisDirectionGenerator::generate(const pcl::PolygonMesh
return Eigen::AngleAxisd(rotation_offset_, pca_vecs.col(2).normalized()) * pca_vecs.col(1).normalized();
}

std::unique_ptr<DirectionGenerator> PrincipalAxisDirectionGenerator::clone() const
{
return std::make_unique<PrincipalAxisDirectionGenerator>(rotation_offset_);
}

} // namespace noether
22 changes: 22 additions & 0 deletions noether_tpp/src/tool_path_planners/origin_generators.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,11 @@ FixedOriginGenerator::FixedOriginGenerator(const Eigen::Vector3d& origin) : orig

Eigen::Vector3d FixedOriginGenerator::generate(const pcl::PolygonMesh& mesh) const { return origin_; }

std::unique_ptr<OriginGenerator> FixedOriginGenerator::clone() const
{
return std::make_unique<FixedOriginGenerator>(origin_);
}

Eigen::Vector3d CentroidOriginGenerator::generate(const pcl::PolygonMesh& mesh) const
{
pcl::PointCloud<pcl::PointXYZ> vertices;
Expand All @@ -21,6 +26,11 @@ Eigen::Vector3d CentroidOriginGenerator::generate(const pcl::PolygonMesh& mesh)
return centroid.getArray3fMap().matrix().cast<double>();
}

std::unique_ptr<OriginGenerator> CentroidOriginGenerator::clone() const
{
return std::make_unique<CentroidOriginGenerator>();
}

Eigen::Vector3d AABBCenterOriginGenerator::generate(const pcl::PolygonMesh& mesh) const
{
pcl::PointCloud<pcl::PointXYZ> vertices;
Expand All @@ -31,6 +41,11 @@ Eigen::Vector3d AABBCenterOriginGenerator::generate(const pcl::PolygonMesh& mesh
return range / 2.0;
}

std::unique_ptr<OriginGenerator> AABBCenterOriginGenerator::clone() const
{
return std::make_unique<AABBCenterOriginGenerator>();
}

OffsetOriginGenerator::OffsetOriginGenerator(std::unique_ptr<const OriginGenerator>&& generator,
const Eigen::Vector3d& offset)
: generator_(std::move(generator)), offset_(offset)
Expand All @@ -43,4 +58,11 @@ Eigen::Vector3d OffsetOriginGenerator::generate(const pcl::PolygonMesh& mesh) co
return origin + offset_;
}

std::unique_ptr<OriginGenerator> OffsetOriginGenerator::clone() const
{
if (generator_ == nullptr)
throw std::runtime_error("OffsetOriginGenerator has nullptr sub-generator");
return std::make_unique<OffsetOriginGenerator>(generator_->clone(), offset_);
}
marip8 marked this conversation as resolved.
Show resolved Hide resolved

} // namespace noether
Loading