From bd54bd8dfd210e4a29076efee1e45d07b5e47863 Mon Sep 17 00:00:00 2001 From: David Spielman Date: Tue, 12 Dec 2023 13:54:11 -0600 Subject: [PATCH] Removed commented code and unecessary libraries. pcl::PolygonMesh concatenate method still needs to be investigated. --- .../include/noether_gui/widgets/tpp_widget.h | 5 +- noether_gui/src/widgets/tpp_widget.cpp | 50 +++++++------------ .../core/tool_path_planner_pipeline.h | 1 - 3 files changed, 18 insertions(+), 38 deletions(-) diff --git a/noether_gui/include/noether_gui/widgets/tpp_widget.h b/noether_gui/include/noether_gui/widgets/tpp_widget.h index fb301fad..f2e97dde 100644 --- a/noether_gui/include/noether_gui/widgets/tpp_widget.h +++ b/noether_gui/include/noether_gui/widgets/tpp_widget.h @@ -2,7 +2,6 @@ #include #include -#include #include class QVTKWidget; @@ -51,8 +50,7 @@ class TPPWidget : public QWidget void setMeshFile(const QString& file); void setConfigurationFile(const QString& file); -//private slots: -// void onShowOriginalMesh(const bool /*checked*/); + private: @@ -84,7 +82,6 @@ class TPPWidget : public QWidget vtkTubeFilter* tube_filter_; std::vector tool_paths_; -// QPushButton *push_button_show_original_mesh; }; diff --git a/noether_gui/src/widgets/tpp_widget.cpp b/noether_gui/src/widgets/tpp_widget.cpp index be9ca20c..bdc13d31 100644 --- a/noether_gui/src/widgets/tpp_widget.cpp +++ b/noether_gui/src/widgets/tpp_widget.cpp @@ -11,7 +11,6 @@ #include #include #include -#include // Rendering includes #include @@ -30,9 +29,6 @@ #include #include - -#include - namespace noether { TPPWidget::TPPWidget(boost_plugin_loader::PluginLoader loader, QWidget* parent) @@ -286,35 +282,35 @@ vtkAssembly* createToolPathActors(const std::vector& tool_paths, } // Function to combine two pcl::PolygonMesh instances -pcl::PolygonMesh combineMeshes(const pcl::PolygonMesh& mesh1, const pcl::PolygonMesh& mesh2) { - pcl::PolygonMesh combinedMesh; +pcl::PolygonMesh combineMeshes(const pcl::PolygonMesh& mesh_1, const pcl::PolygonMesh& mesh_2) { + pcl::PolygonMesh combined_mesh; // Combine vertices - pcl::PointCloud combinedCloud; - pcl::fromPCLPointCloud2(mesh1.cloud, combinedCloud); - pcl::PointCloud cloud2; - pcl::fromPCLPointCloud2(mesh2.cloud, cloud2); + pcl::PointCloud combined_cloud; + pcl::fromPCLPointCloud2(mesh_1.cloud, combined_cloud); + pcl::PointCloud cloud_2; + pcl::fromPCLPointCloud2(mesh_2.cloud, cloud_2); - combinedCloud += cloud2; + combined_cloud += cloud_2; - pcl::toPCLPointCloud2(combinedCloud, combinedMesh.cloud); + pcl::toPCLPointCloud2(combined_cloud, combined_mesh.cloud); // Combine faces // Add faces for mesh 1 - combinedMesh.polygons.insert( - combinedMesh.polygons.end(), mesh1.polygons.begin(), mesh1.polygons.end()); + combined_mesh.polygons.insert( + combined_mesh.polygons.end(), mesh_1.polygons.begin(), mesh_1.polygons.end()); // Offset the indices of the second mesh's faces to account for the combined vertices - size_t offset = mesh1.cloud.width * mesh1.cloud.height; - for (auto& polygon : mesh2.polygons) { - pcl::Vertices newPolygon; + size_t offset = mesh_1.cloud.width * mesh_1.cloud.height; + for (auto& polygon : mesh_2.polygons) { + pcl::Vertices new_polygon; for (auto index : polygon.vertices) { - newPolygon.vertices.push_back(index + offset); + new_polygon.vertices.push_back(index + offset); } - combinedMesh.polygons.push_back(newPolygon); + combined_mesh.polygons.push_back(new_polygon); } - return combinedMesh; + return combined_mesh; } void TPPWidget::onPlan(const bool /*checked*/) @@ -338,24 +334,12 @@ void TPPWidget::onPlan(const bool /*checked*/) tool_paths_.clear(); tool_paths_.reserve(meshes.size()); - pcl::PolygonMesh combined_mesh_fragments; std::vector unmodified_tool_paths; - std::string file_name = "/tmp/comb_frag_mesh_test"; for(std::size_t i = 0; i < meshes.size(); ++i) { const pcl::PolygonMesh& mesh = meshes[i]; - if (i == 0) - { - combined_mesh_fragments = mesh; - } - - else - { - combined_mesh_fragments = combineMeshes(combined_mesh_fragments, mesh); - } - - pcl::io::savePLYFile(file_name + std::to_string(i) + ".ply", combined_mesh_fragments); + combined_mesh_fragments = combineMeshes(combined_mesh_fragments, mesh); // Plan the tool path ToolPaths path = pipeline.planner->plan(mesh); diff --git a/noether_tpp/include/noether_tpp/core/tool_path_planner_pipeline.h b/noether_tpp/include/noether_tpp/core/tool_path_planner_pipeline.h index 05b470df..f1491687 100644 --- a/noether_tpp/include/noether_tpp/core/tool_path_planner_pipeline.h +++ b/noether_tpp/include/noether_tpp/core/tool_path_planner_pipeline.h @@ -44,7 +44,6 @@ class ToolPathPlannerPipeline ToolPathModifier::ConstPtr tool_path_modifier; -private: };