Skip to content

Commit

Permalink
Added tool to noether that allows user to toggle visibility of applie…
Browse files Browse the repository at this point in the history
…d tool path and mesh modifiers
  • Loading branch information
DavidSpielman committed Nov 15, 2023
1 parent 6b197af commit 78ac563
Show file tree
Hide file tree
Showing 5 changed files with 274 additions and 57 deletions.
22 changes: 21 additions & 1 deletion noether_gui/include/noether_gui/widgets/tpp_widget.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

#include <noether_tpp/core/types.h>
#include <QWidget>
#include <QCheckBox>
#include <vtkSmartPointer.h>

class QVTKWidget;
class vtkActor;
Expand All @@ -10,6 +12,8 @@ class vtkProp;
class vtkRenderer;
class vtkAxes;
class vtkTubeFilter;
class vtkAssembly;
class vtkPolyData;

namespace boost_plugin_loader
{
Expand Down Expand Up @@ -47,11 +51,19 @@ class TPPWidget : public QWidget
void setMeshFile(const QString& file);
void setConfigurationFile(const QString& file);

//private slots:
// void onShowOriginalMesh(const bool /*checked*/);


private:
void onLoadMesh(const bool /*checked*/);
void onLoadConfiguration(const bool /*checked*/);
void onSaveConfiguration(const bool /*checked*/);
void onPlan(const bool /*checked*/);
void onShowOriginalMesh(const bool);
void onShowModifiedMesh(const bool);
void onShowUnmodifiedToolPath(const bool);
void onShowModifiedToolPath(const bool);

Ui::TPP* ui_;
TPPPipelineWidget* pipeline_widget_;
Expand All @@ -61,11 +73,19 @@ class TPPWidget : public QWidget
vtkRenderer* renderer_;
vtkPolyDataMapper* mesh_mapper_;
vtkActor* mesh_actor_;
std::vector<vtkProp*> tool_path_actors_;

vtkPolyDataMapper* mesh_fragment_mapper_;
vtkActor* mesh_fragment_actor_;
vtkSmartPointer<vtkPolyData> combined_mesh_fragments_;

vtkAssembly* tool_path_actor_;
vtkAssembly* unmodified_tool_path_actor_;
vtkAxes* axes_;
vtkTubeFilter* tube_filter_;

std::vector<ToolPaths> tool_paths_;
// QPushButton *push_button_show_original_mesh;

};

} // namespace noether
210 changes: 179 additions & 31 deletions noether_gui/src/widgets/tpp_widget.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include <noether_gui/widgets/tpp_widget.h>
#include <noether_gui/widgets/tpp_widget.h>
#include "ui_tpp_widget.h"
#include <noether_gui/widgets/tpp_pipeline_widget.h>
#include <noether_gui/utils.h>
Expand All @@ -11,10 +11,12 @@
#include <QStandardPaths>
#include <QTextStream>
#include <yaml-cpp/yaml.h>
#include <pcl/io/ply_io.h>

// Rendering includes
#include <QVTKWidget.h>
#include <vtkAxesActor.h>
#include <vtkAssembly.h>
#include <vtkOpenGLPolyDataMapper.h>
#include <vtkOpenGLActor.h>
#include <vtkOpenGLRenderer.h>
Expand All @@ -26,6 +28,10 @@
#include <vtkTransformFilter.h>
#include <vtkTransform.h>
#include <vtkTubeFilter.h>
#include <pcl/surface/vtk_smoothing/vtk_utils.h>


#include <vtkProp3DCollection.h>

namespace noether
{
Expand All @@ -37,6 +43,11 @@ TPPWidget::TPPWidget(boost_plugin_loader::PluginLoader loader, QWidget* parent)
, renderer_(vtkOpenGLRenderer::New())
, mesh_mapper_(vtkOpenGLPolyDataMapper::New())
, mesh_actor_(vtkOpenGLActor::New())
, mesh_fragment_mapper_(vtkOpenGLPolyDataMapper::New())
, mesh_fragment_actor_(vtkOpenGLActor::New())
, combined_mesh_fragments_(vtkSmartPointer<vtkPolyData>::New())
, tool_path_actor_(vtkAssembly::New())
, unmodified_tool_path_actor_(vtkAssembly::New())
, axes_(vtkAxes::New())
, tube_filter_(vtkTubeFilter::New())
{
Expand All @@ -46,9 +57,18 @@ TPPWidget::TPPWidget(boost_plugin_loader::PluginLoader loader, QWidget* parent)
ui_->splitter->addWidget(render_widget_);

// Set up the VTK objects
renderer_->SetBackground(0.2, 0.2, 0.2);

// Original mesh mapper/actor
mesh_actor_->SetMapper(mesh_mapper_);
renderer_->AddActor(mesh_actor_);
renderer_->SetBackground(0.2, 0.2, 0.2);

// Mesh fragment mapper/actor
mesh_fragment_mapper_->SetInputData(combined_mesh_fragments_);
mesh_fragment_actor_->SetMapper(mesh_fragment_mapper_);
renderer_->AddActor(mesh_fragment_actor_);

// Tool path axis display object
axes_->SetScaleFactor(ui_->double_spin_box_axis_size->value());
tube_filter_->SetInputConnection(axes_->GetOutputPort());
tube_filter_->SetRadius(axes_->GetScaleFactor() / 10.0);
Expand All @@ -60,10 +80,20 @@ TPPWidget::TPPWidget(boost_plugin_loader::PluginLoader loader, QWidget* parent)
render_widget_->GetInteractor()->SetInteractorStyle(vtkSmartPointer<vtkInteractorStyleTrackballCamera>::New());
render_widget_->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);

// Set visibility of the actors based on the default state of the check boxes
mesh_actor_->SetVisibility(ui_->check_box_show_original_mesh->isChecked());
mesh_fragment_actor_->SetVisibility(ui_->check_box_show_modified_mesh->isChecked());
unmodified_tool_path_actor_->SetVisibility(ui_->check_box_show_original_tool_path->isChecked());
tool_path_actor_->SetVisibility(ui_->check_box_show_modified_tool_path->isChecked());

// Connect signals
connect(ui_->push_button_load_mesh, &QPushButton::clicked, this, &TPPWidget::onLoadMesh);
connect(ui_->push_button_load_configuration, &QPushButton::clicked, this, &TPPWidget::onLoadConfiguration);
connect(ui_->push_button_save_configuration, &QPushButton::clicked, this, &TPPWidget::onSaveConfiguration);
connect(ui_->check_box_show_original_mesh, &QCheckBox::clicked, this, &TPPWidget::onShowOriginalMesh);
connect(ui_->check_box_show_modified_mesh, &QCheckBox::clicked, this, &TPPWidget::onShowModifiedMesh);
connect(ui_->check_box_show_original_tool_path, &QCheckBox::clicked, this, &TPPWidget::onShowUnmodifiedToolPath);
connect(ui_->check_box_show_modified_tool_path, &QCheckBox::clicked, this, &TPPWidget::onShowModifiedToolPath);
connect(ui_->push_button_plan, &QPushButton::clicked, this, &TPPWidget::onPlan);
connect(ui_->double_spin_box_axis_size, &QDoubleSpinBox::editingFinished, this, [this]() {
axes_->SetScaleFactor(ui_->double_spin_box_axis_size->value());
Expand All @@ -78,10 +108,42 @@ TPPWidget::~TPPWidget()
renderer_->Delete();
mesh_mapper_->Delete();
mesh_actor_->Delete();
mesh_fragment_mapper_->Delete();
mesh_fragment_actor_->Delete();
tool_path_actor_->Delete();
unmodified_tool_path_actor_->Delete();
axes_->Delete();
tube_filter_->Delete();
}

void TPPWidget::onShowOriginalMesh(const bool checked)
{
mesh_actor_->SetVisibility(checked);
render_widget_->GetRenderWindow()->Render();
render_widget_->GetRenderWindow()->Render();
}

void TPPWidget::onShowModifiedMesh(const bool checked)
{
mesh_fragment_actor_->SetVisibility(checked);
render_widget_->GetRenderWindow()->Render();
render_widget_->GetRenderWindow()->Render();
}

void TPPWidget::onShowUnmodifiedToolPath(const bool checked)
{
unmodified_tool_path_actor_->SetVisibility(checked);
render_widget_->GetRenderWindow()->Render();
render_widget_->GetRenderWindow()->Render();
}

void TPPWidget::onShowModifiedToolPath(const bool checked)
{
tool_path_actor_->SetVisibility(checked);
render_widget_->GetRenderWindow()->Render();
render_widget_->GetRenderWindow()->Render();
}

std::vector<ToolPaths> TPPWidget::getToolPaths() { return tool_paths_; }

void TPPWidget::setMeshFile(const QString& file)
Expand Down Expand Up @@ -192,6 +254,69 @@ vtkSmartPointer<vtkTransform> toVTK(const Eigen::Isometry3d& mat)
return t;
}

vtkAssembly* createToolPathActors(const std::vector<ToolPaths>& tool_paths,
vtkAlgorithmOutput* waypoint_shape_output_port)
{
auto assembly = vtkAssembly::New();
for (const ToolPaths& fragment : tool_paths)
{
for (const ToolPath& tool_path : fragment)
{
for (const ToolPathSegment& segment : tool_path)
{
for (const Eigen::Isometry3d& w : segment)
{
auto transform_filter = vtkSmartPointer<vtkTransformFilter>::New();
transform_filter->SetTransform(toVTK(w));
transform_filter->SetInputConnection(waypoint_shape_output_port);

auto map = vtkSmartPointer<vtkPolyDataMapper>::New();
map->SetInputConnection(transform_filter->GetOutputPort());

auto actor = vtkSmartPointer<vtkActor>::New();
actor->SetMapper(map);

assembly->AddPart(actor);
}
}
}
}

return assembly;
}

// Function to combine two pcl::PolygonMesh instances
pcl::PolygonMesh combineMeshes(const pcl::PolygonMesh& mesh1, const pcl::PolygonMesh& mesh2) {
pcl::PolygonMesh combinedMesh;

// Combine vertices
pcl::PointCloud<pcl::PointXYZ> combinedCloud;
pcl::fromPCLPointCloud2(mesh1.cloud, combinedCloud);
pcl::PointCloud<pcl::PointXYZ> cloud2;
pcl::fromPCLPointCloud2(mesh2.cloud, cloud2);

combinedCloud += cloud2;

pcl::toPCLPointCloud2(combinedCloud, combinedMesh.cloud);

// Combine faces
// Add faces for mesh 1
combinedMesh.polygons.insert(
combinedMesh.polygons.end(), mesh1.polygons.begin(), mesh1.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;
for (auto index : polygon.vertices) {
newPolygon.vertices.push_back(index + offset);
}
combinedMesh.polygons.push_back(newPolygon);
}

return combinedMesh;
}

void TPPWidget::onPlan(const bool /*checked*/)
{
try
Expand All @@ -201,48 +326,71 @@ void TPPWidget::onPlan(const bool /*checked*/)
throw std::runtime_error("No mesh file selected");

// Load the mesh
pcl::PolygonMesh mesh;
if (pcl::io::loadPolygonFile(mesh_file, mesh) < 1)
pcl::PolygonMesh full_mesh;
if (pcl::io::loadPolygonFile(mesh_file, full_mesh) < 1)
throw std::runtime_error("Failed to load mesh from file");

const ToolPathPlannerPipeline pipeline = pipeline_widget_->createPipeline();
QApplication::setOverrideCursor(Qt::WaitCursor);
tool_paths_ = pipeline.plan(mesh);
QApplication::restoreOverrideCursor();

// Render the tool paths
std::for_each(tool_path_actors_.begin(), tool_path_actors_.end(), [this](vtkProp* actor) {
renderer_->RemoveActor(actor);
actor->Delete();
});
tool_path_actors_.clear();
// Run the mesh modifier
std::vector<pcl::PolygonMesh> meshes = pipeline.mesh_modifier->modify(full_mesh);

tool_paths_.clear();
tool_paths_.reserve(meshes.size());

for (const ToolPaths& fragment : tool_paths_)
pcl::PolygonMesh combined_mesh_fragments;
std::vector<ToolPaths> unmodified_tool_paths;
std::string file_name = "/tmp/comb_frag_mesh_test";
for(std::size_t i = 0; i < meshes.size(); ++i)
{
for (const ToolPath& tool_path : fragment)
const pcl::PolygonMesh& mesh = meshes[i];
if (i == 0)
{
for (const ToolPathSegment& segment : tool_path)
{
for (const Eigen::Isometry3d& w : segment)
{
auto transform_filter = vtkSmartPointer<vtkTransformFilter>::New();
transform_filter->SetTransform(toVTK(w));
transform_filter->SetInputConnection(tube_filter_->GetOutputPort());
combined_mesh_fragments = mesh;
}

auto map = vtkSmartPointer<vtkPolyDataMapper>::New();
map->SetInputConnection(transform_filter->GetOutputPort());
else
{
combined_mesh_fragments = combineMeshes(combined_mesh_fragments, mesh);
}

auto actor = vtkActor::New();
actor->SetMapper(map);
pcl::io::savePLYFile(file_name + std::to_string(i) + ".ply", combined_mesh_fragments);

// Plan the tool path
ToolPaths path = pipeline.planner->plan(mesh);

unmodified_tool_paths.push_back(path);
tool_paths_.push_back(pipeline.tool_path_modifier->modify(path));
}

QApplication::restoreOverrideCursor();

// Reset
{
pcl::VTKUtils::mesh2vtk(combined_mesh_fragments, combined_mesh_fragments_);
mesh_fragment_mapper_->Update();
mesh_fragment_mapper_->SetInputData(combined_mesh_fragments_);

tool_path_actors_.push_back(actor);
}
}
}
}

std::for_each(
tool_path_actors_.begin(), tool_path_actors_.end(), [this](vtkProp* actor) { renderer_->AddActor(actor); });
// Render the unmodified tool paths
{
renderer_->RemoveActor(unmodified_tool_path_actor_);
unmodified_tool_path_actor_->Delete();
unmodified_tool_path_actor_ = createToolPathActors(unmodified_tool_paths, tube_filter_->GetOutputPort());
renderer_->AddActor(unmodified_tool_path_actor_);
unmodified_tool_path_actor_->SetVisibility(ui_->check_box_show_original_tool_path->isChecked());
}

// Render the modified tool paths
{
renderer_->RemoveActor(tool_path_actor_);
tool_path_actor_->Delete();
tool_path_actor_ = createToolPathActors(tool_paths_, tube_filter_->GetOutputPort());
renderer_->AddActor(tool_path_actor_);
tool_path_actor_->SetVisibility(ui_->check_box_show_modified_tool_path->isChecked());
}

// Call render twice
render_widget_->GetRenderWindow()->Render();
Expand Down
Loading

0 comments on commit 78ac563

Please sign in to comment.