Skip to content

Commit 0c1235f

Browse files
committed
Updated raster planner UIs based on changes to noether_tpp class definitions
1 parent cee80e6 commit 0c1235f

6 files changed

Lines changed: 234 additions & 158 deletions

File tree

noether_gui/include/noether_gui/widgets/tool_path_planners/raster/plane_slicer_raster_planner_widget.h

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,11 @@
44

55
class QCheckBox;
66

7+
namespace Ui
8+
{
9+
class PlaneSlicerRasterPlanner;
10+
}
11+
712
namespace noether
813
{
914
class DistanceDoubleSpinBox;
@@ -20,9 +25,7 @@ class PlaneSlicerRasterPlannerWidget : public RasterPlannerWidget
2025
void save(YAML::Node&) const override;
2126

2227
protected:
23-
DistanceDoubleSpinBox* search_radius_;
24-
DistanceDoubleSpinBox* min_segment_size_;
25-
QCheckBox* bidirectional_;
28+
Ui::PlaneSlicerRasterPlanner* ui_plane_slicer_;
2629
};
2730

2831
} // namespace noether

noether_gui/src/widgets/tool_path_planners/raster/cross_hatch_plane_slicer_raster_planner.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,10 @@
11
#include <noether_gui/widgets/tool_path_planners/raster/cross_hatch_plane_slicer_raster_planner_widget.h>
22
#include <noether_gui/widgets/angle_double_spin_box.h>
3-
#include "ui_raster_planner_widget.h"
43

54
#include <noether_tpp/serialization.h>
6-
#include <QDoubleSpinBox>
5+
#include <QFormLayout>
6+
#include <QGroupBox>
7+
#include <QLabel>
78

89
namespace noether
910
{
@@ -12,11 +13,13 @@ CrossHatchPlaneSlicerRasterPlannerWidget::CrossHatchPlaneSlicerRasterPlannerWidg
1213
QWidget* parent)
1314
: PlaneSlicerRasterPlannerWidget(factory, parent), cross_hatch_angle_(new AngleDoubleSpinBox(this))
1415
{
15-
// Search radius
16+
auto widget = new QGroupBox(this);
17+
auto form_layout = new QFormLayout(widget);
1618
cross_hatch_angle_->setMinimum(0.0);
1719
cross_hatch_angle_->setValue(M_PI_2);
1820
cross_hatch_angle_->setDecimals(3);
19-
ui_->form_layout->addRow(new QLabel("Cross Hatch Angle", this), cross_hatch_angle_);
21+
form_layout->addRow(new QLabel("Cross Hatch Angle", this), cross_hatch_angle_);
22+
layout()->addWidget(widget);
2023
}
2124

2225
void CrossHatchPlaneSlicerRasterPlannerWidget::configure(const YAML::Node& config)
Lines changed: 23 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -1,57 +1,39 @@
11
#include <noether_gui/widgets/tool_path_planners/raster/plane_slicer_raster_planner_widget.h>
2-
#include "ui_raster_planner_widget.h"
2+
#include "ui_plane_slicer_raster_planner_widget.h"
33

44
#include <noether_tpp/serialization.h>
5-
#include <QFormLayout>
6-
#include <QLabel>
7-
#include <QDoubleSpinBox>
8-
#include <QMessageBox>
9-
#include <QCheckBox>
5+
#include <QGroupBox>
6+
7+
static const std::string POINT_SPACING_KEY = "point_spacing";
8+
static const std::string MIN_HOLE_SIZE_KEY = "min_hole_size";
9+
static const std::string SEARCH_RADIUS_KEY = "search_radius";
10+
static const std::string MIN_SEGMENT_SIZE_KEY = "min_segment_size";
11+
static const std::string BIDIRECTIONAL_KEY = "bidirectional";
1012

1113
namespace noether
1214
{
1315
PlaneSlicerRasterPlannerWidget::PlaneSlicerRasterPlannerWidget(std::shared_ptr<const WidgetFactory> factory,
1416
QWidget* parent)
15-
: RasterPlannerWidget(factory, parent)
16-
, search_radius_(new DistanceDoubleSpinBox(this))
17-
, min_segment_size_(new DistanceDoubleSpinBox(this))
18-
, bidirectional_(new QCheckBox(this))
17+
: RasterPlannerWidget(factory, parent), ui_plane_slicer_(new Ui::PlaneSlicerRasterPlanner())
1918
{
20-
// Search radius
21-
search_radius_->setMinimum(0.0);
22-
search_radius_->setSingleStep(0.1);
23-
search_radius_->setValue(0.1);
24-
search_radius_->setDecimals(3);
25-
auto search_radius_label = new QLabel("Normal Radius", this);
26-
search_radius_label->setToolTip("Radius with which to estimate mesh normals");
27-
ui_->form_layout->addRow(search_radius_label, search_radius_);
28-
29-
// Min segment length
30-
min_segment_size_->setMinimum(0.0);
31-
min_segment_size_->setSingleStep(0.1);
32-
min_segment_size_->setValue(0.1);
33-
min_segment_size_->setDecimals(3);
34-
auto min_segment_label = new QLabel("Min Segment Length", this);
35-
min_segment_label->setToolTip("Tool path segments shorter than this length will not be included");
36-
ui_->form_layout->addRow(min_segment_label, min_segment_size_);
37-
38-
// Bidirectional checkbox
39-
bidirectional_->setText("Bidirectional");
40-
bidirectional_->setChecked(true);
41-
bidirectional_->setToolTip("Generate rasters in the direction of the cut plane normal and its negation");
42-
ui_->group_box_raster_planner->layout()->addWidget(bidirectional_);
19+
auto widget = new QGroupBox(this);
20+
ui_plane_slicer_->setupUi(widget);
21+
layout()->addWidget(widget);
4322
}
4423

4524
void PlaneSlicerRasterPlannerWidget::configure(const YAML::Node& config)
4625
{
4726
RasterPlannerWidget::configure(config);
48-
search_radius_->setValue(YAML::getMember<double>(config, "search_radius"));
49-
min_segment_size_->setValue(YAML::getMember<double>(config, "min_segment_size"));
27+
28+
ui_plane_slicer_->double_spin_box_point_spacing->setValue(YAML::getMember<double>(config, POINT_SPACING_KEY));
29+
ui_plane_slicer_->double_spin_box_minimum_hole_size->setValue(YAML::getMember<double>(config, MIN_HOLE_SIZE_KEY));
30+
ui_plane_slicer_->double_spin_box_search_radius->setValue(YAML::getMember<double>(config, SEARCH_RADIUS_KEY));
31+
ui_plane_slicer_->double_spin_box_min_segment_size->setValue(YAML::getMember<double>(config, MIN_SEGMENT_SIZE_KEY));
5032

5133
// Optionally get bidirectional parameter to maintain backwards compatibility
5234
try
5335
{
54-
bidirectional_->setChecked(YAML::getMember<bool>(config, "bidirectional"));
36+
ui_plane_slicer_->check_box_bidirectional->setChecked(YAML::getMember<bool>(config, BIDIRECTIONAL_KEY));
5537
}
5638
catch (const std::exception& ex)
5739
{
@@ -62,9 +44,11 @@ void PlaneSlicerRasterPlannerWidget::save(YAML::Node& config) const
6244
{
6345
config["name"] = "PlaneSlicer";
6446
RasterPlannerWidget::save(config);
65-
config["search_radius"] = search_radius_->value();
66-
config["min_segment_size"] = min_segment_size_->value();
67-
config["bidirectional"] = bidirectional_->isChecked();
47+
config[POINT_SPACING_KEY] = ui_plane_slicer_->double_spin_box_point_spacing->value();
48+
config[MIN_HOLE_SIZE_KEY] = ui_plane_slicer_->double_spin_box_minimum_hole_size->value();
49+
config[SEARCH_RADIUS_KEY] = ui_plane_slicer_->double_spin_box_search_radius->value();
50+
config[MIN_SEGMENT_SIZE_KEY] = ui_plane_slicer_->double_spin_box_min_segment_size->value();
51+
config[BIDIRECTIONAL_KEY] = ui_plane_slicer_->check_box_bidirectional->isChecked();
6852
}
6953

7054
} // namespace noether
Lines changed: 161 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,161 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<ui version="4.0">
3+
<class>PlaneSlicerRasterPlanner</class>
4+
<widget class="QWidget" name="PlaneSlicerRasterPlanner">
5+
<property name="geometry">
6+
<rect>
7+
<x>0</x>
8+
<y>0</y>
9+
<width>412</width>
10+
<height>295</height>
11+
</rect>
12+
</property>
13+
<property name="windowTitle">
14+
<string>Form</string>
15+
</property>
16+
<layout class="QFormLayout" name="formLayout">
17+
<item row="0" column="0">
18+
<widget class="QLabel" name="label_point_spacing">
19+
<property name="toolTip">
20+
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Distance between tool path waypoints on a raster line&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
21+
</property>
22+
<property name="text">
23+
<string>Point Spacing</string>
24+
</property>
25+
</widget>
26+
</item>
27+
<item row="0" column="1">
28+
<widget class="noether::DistanceDoubleSpinBox" name="double_spin_box_point_spacing">
29+
<property name="decimals">
30+
<number>3</number>
31+
</property>
32+
<property name="minimum">
33+
<double>0.000000000000000</double>
34+
</property>
35+
<property name="maximum">
36+
<double>100.000000000000000</double>
37+
</property>
38+
<property name="value">
39+
<double>0.025000000000000</double>
40+
</property>
41+
</widget>
42+
</item>
43+
<item row="1" column="0">
44+
<widget class="QLabel" name="label_min_hole_size">
45+
<property name="toolTip">
46+
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The size of the smallest hole that the tool path planner should not jump over&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
47+
</property>
48+
<property name="text">
49+
<string>Minimum Hole Size</string>
50+
</property>
51+
</widget>
52+
</item>
53+
<item row="1" column="1">
54+
<widget class="noether::DistanceDoubleSpinBox" name="double_spin_box_minimum_hole_size">
55+
<property name="decimals">
56+
<number>3</number>
57+
</property>
58+
<property name="minimum">
59+
<double>0.000000000000000</double>
60+
</property>
61+
<property name="maximum">
62+
<double>100.000000000000000</double>
63+
</property>
64+
<property name="value">
65+
<double>0.100000000000000</double>
66+
</property>
67+
</widget>
68+
</item>
69+
<item row="2" column="0">
70+
<widget class="QLabel" name="label_search_radius">
71+
<property name="toolTip">
72+
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Radius with which to estimate mesh normals&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
73+
</property>
74+
<property name="text">
75+
<string>Search Radius</string>
76+
</property>
77+
</widget>
78+
</item>
79+
<item row="2" column="1">
80+
<widget class="noether::DistanceDoubleSpinBox" name="double_spin_box_search_radius">
81+
<property name="decimals">
82+
<number>3</number>
83+
</property>
84+
<property name="singleStep">
85+
<double>0.100000000000000</double>
86+
</property>
87+
<property name="value">
88+
<double>0.100000000000000</double>
89+
</property>
90+
</widget>
91+
</item>
92+
<item row="3" column="0">
93+
<widget class="QLabel" name="label_min_segment_size">
94+
<property name="toolTip">
95+
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Tool path segments shorter than this length will not be included&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
96+
</property>
97+
<property name="text">
98+
<string>Min Segment Size</string>
99+
</property>
100+
</widget>
101+
</item>
102+
<item row="3" column="1">
103+
<widget class="noether::DistanceDoubleSpinBox" name="double_spin_box_min_segment_size">
104+
<property name="decimals">
105+
<number>3</number>
106+
</property>
107+
<property name="singleStep">
108+
<double>0.100000000000000</double>
109+
</property>
110+
<property name="value">
111+
<double>0.100000000000000</double>
112+
</property>
113+
</widget>
114+
</item>
115+
<item row="4" column="0">
116+
<widget class="QLabel" name="label">
117+
<property name="toolTip">
118+
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Generate rasters in the direction of the cut plane normal and its negation&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
119+
</property>
120+
<property name="text">
121+
<string>Bidirectional</string>
122+
</property>
123+
</widget>
124+
</item>
125+
<item row="4" column="1">
126+
<widget class="QCheckBox" name="check_box_bidirectional">
127+
<property name="sizePolicy">
128+
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
129+
<horstretch>0</horstretch>
130+
<verstretch>0</verstretch>
131+
</sizepolicy>
132+
</property>
133+
<property name="toolTip">
134+
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;&lt;br/&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
135+
</property>
136+
<property name="text">
137+
<string/>
138+
</property>
139+
<property name="checked">
140+
<bool>true</bool>
141+
</property>
142+
</widget>
143+
</item>
144+
</layout>
145+
</widget>
146+
<customwidgets>
147+
<customwidget>
148+
<class>noether::DistanceDoubleSpinBox</class>
149+
<extends>QDoubleSpinBox</extends>
150+
<header location="global">noether_gui/widgets/distance_double_spin_box.h</header>
151+
</customwidget>
152+
</customwidgets>
153+
<tabstops>
154+
<tabstop>double_spin_box_point_spacing</tabstop>
155+
<tabstop>double_spin_box_minimum_hole_size</tabstop>
156+
<tabstop>double_spin_box_search_radius</tabstop>
157+
<tabstop>double_spin_box_min_segment_size</tabstop>
158+
</tabstops>
159+
<resources/>
160+
<connections/>
161+
</ui>

noether_gui/src/widgets/tool_path_planners/raster/raster_planner_widget.cpp

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,6 @@
99
static const std::string DIRECTION_GENERATOR_KEY = "direction_generator";
1010
static const std::string ORIGIN_GENERATOR_KEY = "origin_generator";
1111
static const std::string LINE_SPACING_KEY = "line_spacing";
12-
static const std::string POINT_SPACING_KEY = "point_spacing";
13-
static const std::string MIN_HOLE_SIZE_KEY = "min_hole_size";
1412

1513
namespace noether
1614
{
@@ -73,8 +71,6 @@ RasterPlannerWidget::RasterPlannerWidget(std::shared_ptr<const WidgetFactory> fa
7371
void RasterPlannerWidget::configure(const YAML::Node& config)
7472
{
7573
ui_->double_spin_box_line_spacing->setValue(YAML::getMember<double>(config, LINE_SPACING_KEY));
76-
ui_->double_spin_box_point_spacing->setValue(YAML::getMember<double>(config, POINT_SPACING_KEY));
77-
ui_->double_spin_box_minimum_hole_size->setValue(YAML::getMember<double>(config, MIN_HOLE_SIZE_KEY));
7874

7975
// Direction generator
8076
{
@@ -136,8 +132,6 @@ void RasterPlannerWidget::save(YAML::Node& config) const
136132
}
137133

138134
config[LINE_SPACING_KEY] = ui_->double_spin_box_line_spacing->value();
139-
config[POINT_SPACING_KEY] = ui_->double_spin_box_point_spacing->value();
140-
config[MIN_HOLE_SIZE_KEY] = ui_->double_spin_box_minimum_hole_size->value();
141135
}
142136

143137
BaseWidget* RasterPlannerWidget::getDirectionGeneratorWidget() const

0 commit comments

Comments
 (0)