Skip to content

Commit

Permalink
Plane slice planner (#168)
Browse files Browse the repository at this point in the history
* Raster Planner: Port of Plane Slicer

* Update plane slice planner port

* Handle empty toolpaths

* Ran clang-format

* Replace tool_path_planner version of plane slice raster planner with noether_tpp version

* Added CI directory symlink

* Export dependencies of noether_tpp

* Add Eigen3::Eigen target for Xenial compatibility

* Remove unneeded clone function

* Removed unused headers

Co-authored-by: David Merz, Jr <[email protected]>
Co-authored-by: Tyler Marr <[email protected]>
  • Loading branch information
3 people authored Jun 23, 2022
1 parent afa3319 commit bdda731
Show file tree
Hide file tree
Showing 9 changed files with 815 additions and 706 deletions.
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
@@ -0,0 +1,52 @@
/**
* @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/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 @@ -78,7 +78,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_;
/** @brief Distance between raster lines */
Expand Down
Loading

0 comments on commit bdda731

Please sign in to comment.