Skip to content
Merged
Show file tree
Hide file tree
Changes from all 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
3 changes: 1 addition & 2 deletions noether_gui/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,7 @@ add_library(
src/widgets/tool_path_modifiers/biased_tool_drag_orientation_modifier_widget.cpp
src/widgets/tool_path_modifiers/uniform_orientation_modifier_widget.cpp
src/widgets/tool_path_modifiers/offset_modifier_widget.cpp
src/widgets/tool_path_modifiers/uniform_spacing_spline_modifier_widget.cpp
src/widgets/tool_path_modifiers/uniform_spacing_linear_modifier_widget.cpp
src/widgets/tool_path_modifiers/uniform_spacing_modifier_widget.cpp
# Mesh Modifiers
src/widgets/mesh_modifiers/euclidean_clustering_modifier_widget.cpp
src/widgets/mesh_modifiers/face_subdivision_modifier_widget.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,23 +2,26 @@

#include <noether_gui/widgets.h>

namespace noether
namespace Ui
{
class DistanceDoubleSpinBox;
class UniformSpacing;
}

namespace noether
{
/**
* @ingroup gui_widgets_tool_path_modifiers
*/
class UniformSpacingLinearModifierWidget : public BaseWidget
class UniformSpacingModifierWidget : public BaseWidget
{
public:
UniformSpacingLinearModifierWidget(QWidget* parent = nullptr);
UniformSpacingModifierWidget(QWidget* parent = nullptr);

void configure(const YAML::Node& config) override;
void save(YAML::Node& config) const override;

protected:
DistanceDoubleSpinBox* point_spacing_;
Ui::UniformSpacing* ui_;
};

} // namespace noether

This file was deleted.

6 changes: 2 additions & 4 deletions noether_gui/src/plugins.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@
#include <noether_gui/widgets/tool_path_modifiers/linear_departure_modifier_widget.h>
#include <noether_gui/widgets/tool_path_modifiers/minimum_segment_length_modifier_widget.h>
#include <noether_gui/widgets/tool_path_modifiers/offset_modifier_widget.h>
#include <noether_gui/widgets/tool_path_modifiers/uniform_spacing_spline_modifier_widget.h>
#include <noether_gui/widgets/tool_path_modifiers/uniform_spacing_linear_modifier_widget.h>
#include <noether_gui/widgets/tool_path_modifiers/uniform_spacing_modifier_widget.h>
#include <noether_gui/widgets/tool_path_modifiers/spline_extrapolation_modifier_widget.h>
// Mesh Modifiers
#include <noether_gui/widgets/mesh_modifiers/euclidean_clustering_modifier_widget.h>
Expand Down Expand Up @@ -121,8 +120,7 @@ EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(LinearDepartureToolPathModifierWi
EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(MinimumSegmentLengthToolPathModifierWidget, MinimumSegmentLength)
EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(ConcatenateModifierWidget, Concatenate)
EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(OffsetModifierWidget, Offset)
EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(UniformSpacingSplineModifierWidget, UniformSpacingSpline)
EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(UniformSpacingLinearModifierWidget, UniformSpacingLinear)
EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(UniformSpacingModifierWidget, UniformSpacing)
EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(SplineExtrapolationToolPathModifierWidget, SplineExtrapolation)

} // namespace noether
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include <noether_gui/widgets/tool_path_modifiers/uniform_spacing_modifier_widget.h>
#include "ui_uniform_spacing_modifier_widget.h"
#include <noether_gui/widgets/distance_double_spin_box.h>

#include <noether_tpp/serialization.h>

namespace noether
{
UniformSpacingModifierWidget::UniformSpacingModifierWidget(QWidget* parent)
: BaseWidget(parent), ui_(new Ui::UniformSpacing())
{
ui_->setupUi(this);
}

void UniformSpacingModifierWidget::configure(const YAML::Node& config)
{
ui_->point_spacing->setValue(YAML::getMember<double>(config, "point_spacing"));
ui_->spline_degree->setValue(YAML::getMember<int>(config, "spline_degree"));
ui_->include_endpoints->setChecked(YAML::getMember<bool>(config, "include_endpoints"));
}

void UniformSpacingModifierWidget::save(YAML::Node& config) const
{
config["name"] = "UniformSpacing";
config["point_spacing"] = ui_->point_spacing->value();
config["spline_degree"] = ui_->spline_degree->value();
config["include_endpoints"] = ui_->include_endpoints->isChecked();
}

} // namespace noether
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>UniformSpacing</class>
<widget class="QWidget" name="UniformSpacing">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>347</width>
<height>226</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QFormLayout" name="formLayout">
<item row="0" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>Point spacing</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="noether::DistanceDoubleSpinBox" name="point_spacing">
<property name="decimals">
<number>3</number>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
<property name="value">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Spline degree</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QSpinBox" name="spline_degree">
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>3</number>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QCheckBox" name="include_endpoints">
<property name="text">
<string>Include endpoints</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>noether::DistanceDoubleSpinBox</class>
<extends>QDoubleSpinBox</extends>
<header location="global">noether_gui/widgets/distance_double_spin_box.h</header>
</customwidget>
</customwidgets>
<tabstops>
<tabstop>point_spacing</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>

This file was deleted.

6 changes: 3 additions & 3 deletions noether_tpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,9 @@ add_library(
${PROJECT_NAME} SHARED
# Core
src/core/tool_path_planner_pipeline.cpp
src/utils.cpp
src/plugin_interface.cpp
src/splines.cpp
src/utils.cpp
# Mesh Modifiers
src/mesh_modifiers/subset_extraction/subset_extractor.cpp
src/mesh_modifiers/subset_extraction/extruded_polygon_subset_extractor.cpp
Expand Down Expand Up @@ -89,8 +90,7 @@ add_library(
src/tool_path_modifiers/tool_drag_orientation_modifier.cpp
src/tool_path_modifiers/uniform_orientation_modifier.cpp
src/tool_path_modifiers/offset_modifier.cpp
src/tool_path_modifiers/uniform_spacing_spline_modifier.cpp
src/tool_path_modifiers/uniform_spacing_linear_modifier.cpp
src/tool_path_modifiers/uniform_spacing_modifier.cpp
# Tool Path Planners
src/tool_path_planners/multi_tool_path_planner.cpp
src/tool_path_planners/edge/edge_planner.cpp
Expand Down
67 changes: 67 additions & 0 deletions noether_tpp/include/noether_tpp/splines.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
#pragma once

#include <unsupported/Eigen/Splines>
#include <Eigen/Dense>

namespace noether
{
/**
* @details Samples the input spline at the given spline parameter to create a 6-DoF pose, where the x-axis is aligned
* with the first derivative of the spline.
* @param spline
* @param u Spline parameter (on [0, 1]) at which to sample the spline
* @param ref_z Reference z-axis for use in computing the pose orientation
* @return
*/
Eigen::Isometry3d sample(const Eigen::Spline3d& spline, const double u, const Eigen::Vector3d& ref_z);

/**
* @details Computes the lengths (m) of each polynomial span of the spline. This method applies Simpson's composite 3/8
* rule to numerically integrate the first derivative of each polynomial segment of the spline to compute the distance
* @param spline
* @return Vector of lengths (m) of each polynomial span of the spline (size `n_knots - 1`)
*/
std::vector<double> computeSpanLengths(const Eigen::Spline3d& spline);

/**
* @details Computes the distances (m) along the spline to each knot. This method performs a cumulative sum of the span
* lengths (given by computeSpanLengths) to return the total distance (m) along the spline to each knot
* @param spline
* @return Vector of distances (m) to each knot in the spline (size `n_knots`)
*/
std::vector<double> computeKnotDistances(const Eigen::Spline3d& spline);

/**
* @details Computes the length (m) of the input spline. This method sums the length of all polynomial spans of the
* spline, given by computeSpanLengths
* @param spline
* @return
*/
double computeLength(const Eigen::Spline3d& spline);

/**
* @details Computes the spline parameter at a specific distance along on the spline
* @param spline
* @param dist Distance (m) along spline. When this value is negative, or greater than the length of the spline the
* first/last polynomial segment will be extrapolated.
* @param tol Error tolerance (m) with which to calculate the distance
* @return
*/
double computeSplineParameterAtDistance(const Eigen::Spline3d& spline, const double dist, const double tol = 1.0e-4);

/**
* @details Computes equidistant knot points along a spline. If the endpoints of the spline are included, the remaining
* equally spaced points will be centered in between them.
* @param spline
* @param knot_spacing Spacing (m) between knots on the spline
* @param include_endpoints Flag to indicate that the spline parameters for the endpoints of the spline (i.e., 0 and 1)
* should be included in the output
* @param tol Error tolerance (m) for calculating the distance along the spline
* @return Vector of spline parameters that are equally spaced in distance along the spline
*/
std::vector<double> computeEquidistantKnots(const Eigen::Spline3d& spline,
const double knot_spacing,
const bool include_endpoints = false,
const double tol = 1.0e-4);

} // namespace noether

This file was deleted.

Loading
Loading