donghong_ding.cpp
Go to the documentation of this file.
2 
3 namespace ram_qt_guis
4 {
5 
7 
8 {
9  setObjectName("DonghongDingAlgorithm");
10 
11  main_layout_ = new QVBoxLayout(this);
12 
13  QHBoxLayout *file = new QHBoxLayout;
14  QPushButton *file_explorer = new QPushButton;
15  file_explorer->setText("...");
16  file_explorer->setMaximumSize(30, 30);
17  file_ = new QLineEdit;
18  connect(file_, SIGNAL(textChanged(QString)), this, SLOT(fileChanged()));
19  file->addWidget(file_);
20  file->addWidget(file_explorer);
21  connect(file_explorer, SIGNAL(released()), this, SLOT(browseFiles()));
22 
23  number_of_layers_ = new QSpinBox;
24  number_of_layers_->setRange(1, 10000);
25  QHBoxLayout *number_of_layers_layout = new QHBoxLayout;
26  number_of_layers_layout->addWidget(new QLabel("Number of layers:"));
27  number_of_layers_layout->addWidget(number_of_layers_);
28  number_of_layers_widget_ = new QWidget;
29  number_of_layers_widget_->setLayout(number_of_layers_layout);
30 
31  height_between_layers_ = new QDoubleSpinBox;
32  height_between_layers_->setRange(0.001, 1000);
33  height_between_layers_->setSuffix(" mm");
34  height_between_layers_->setSingleStep(0.1);
35  height_between_layers_->setDecimals(3);
36 
37  QHBoxLayout *height_between_layers_layout = new QHBoxLayout;
38  height_between_layers_layout->addWidget(new QLabel("Height between layers:"));
39  height_between_layers_layout->addWidget(height_between_layers_);
40 
41  deposited_material_width_ = new QDoubleSpinBox;
42  deposited_material_width_->setRange(0.001, 1000);
43  deposited_material_width_->setSuffix(" mm");
44  deposited_material_width_->setSingleStep(0.1);
45  deposited_material_width_->setDecimals(3);
46 
47  QHBoxLayout *deposited_material_width_layout = new QHBoxLayout;
48  deposited_material_width_layout->addWidget(new QLabel("Deposited material width:"));
49  deposited_material_width_layout->addWidget(deposited_material_width_);
50 
51  contours_filtering_tolerance_ = new QDoubleSpinBox;
52  contours_filtering_tolerance_->setRange(0, 100);
53  contours_filtering_tolerance_->setSuffix(" mm");
54  contours_filtering_tolerance_->setSingleStep(0.01);
55  contours_filtering_tolerance_->setDecimals(3);
56  QHBoxLayout *contours_filtering_tolerance_layout = new QHBoxLayout;
57  contours_filtering_tolerance_layout->addWidget(new QLabel("Contours filtering tolerance:"));
58  contours_filtering_tolerance_layout->addWidget(contours_filtering_tolerance_);
59 
60  slicing_direction_x_ = new QDoubleSpinBox;
61  slicing_direction_x_->setRange(-20000, 20000);
62  slicing_direction_x_->setSingleStep(0.01);
63  slicing_direction_x_->setDecimals(3);
64  slicing_direction_x_->setMaximumWidth(80);
65  slicing_direction_x_->setSizePolicy(QSizePolicy::Maximum, QSizePolicy::Maximum);
66 
67  slicing_direction_y_ = new QDoubleSpinBox;
68  slicing_direction_y_->setMinimum(slicing_direction_x_->minimum());
69  slicing_direction_y_->setMaximum(slicing_direction_x_->maximum());
70  slicing_direction_y_->setSingleStep(slicing_direction_x_->singleStep());
71  slicing_direction_y_->setDecimals(slicing_direction_x_->decimals());
72  slicing_direction_y_->setMaximumWidth(slicing_direction_x_->maximumWidth());
73  slicing_direction_y_->setSizePolicy(slicing_direction_x_->sizePolicy());
74 
75  slicing_direction_z_ = new QDoubleSpinBox;
76  slicing_direction_z_->setMinimum(slicing_direction_x_->minimum());
77  slicing_direction_z_->setMaximum(slicing_direction_x_->maximum());
78  slicing_direction_z_->setSingleStep(slicing_direction_x_->singleStep());
79  slicing_direction_z_->setDecimals(slicing_direction_x_->decimals());
80  slicing_direction_z_->setMaximumWidth(slicing_direction_x_->maximumWidth());
81  slicing_direction_z_->setSizePolicy(slicing_direction_x_->sizePolicy());
82 
83  QHBoxLayout* vector_layout = new QHBoxLayout;
84  vector_layout->addWidget(new QLabel("X"));
85  vector_layout->addWidget(slicing_direction_x_);
86  vector_layout->addStretch(1);
87  vector_layout->addWidget(new QLabel("Y"));
88  vector_layout->addWidget(slicing_direction_y_);
89  vector_layout->addStretch(1);
90  vector_layout->addWidget(new QLabel("Z"));
91  vector_layout->addWidget(slicing_direction_z_);
92  QVBoxLayout *slicing_direction_layout = new QVBoxLayout;
93  slicing_direction_layout->addWidget(new QLabel("Slicing direction:"));
94  slicing_direction_layout->addLayout(vector_layout);
95  slicing_direction_widget_ = new QWidget;
96  slicing_direction_widget_->setLayout(slicing_direction_layout);
97 
98  // Main layout
99  main_layout_->addWidget(new QLabel("YAML or mesh file:"));
100  main_layout_->addLayout(file);
102  main_layout_->addLayout(height_between_layers_layout);
103  main_layout_->addLayout(deposited_material_width_layout);
104  main_layout_->addLayout(contours_filtering_tolerance_layout);
106 
107  //
108  connect(file_, SIGNAL(textChanged(QString)), this, SIGNAL(valueChanged()));
109  connect(number_of_layers_, SIGNAL(valueChanged(int)), this, SIGNAL(valueChanged()));
110  connect(height_between_layers_, SIGNAL(valueChanged(double)), this, SIGNAL(valueChanged()));
111  connect(deposited_material_width_, SIGNAL(valueChanged(double)), this, SIGNAL(valueChanged()));
112  connect(contours_filtering_tolerance_, SIGNAL(valueChanged(double)), this, SIGNAL(valueChanged()));
113  connect(slicing_direction_x_, SIGNAL(valueChanged(double)), this, SIGNAL(valueChanged()));
114  connect(slicing_direction_y_, SIGNAL(valueChanged(double)), this, SIGNAL(valueChanged()));
115  connect(slicing_direction_z_, SIGNAL(valueChanged(double)), this, SIGNAL(valueChanged()));
116 
117 }
118 
120 {
121 }
122 
124 {
125  QString file_dir("");
126  {
127  QFileInfo file(file_->text());
128  if (!file_->text().isEmpty() && file.dir().exists())
129  file_dir = file.dir().path();
130  else
131  {
132  std::string path = ros::package::getPath("ram_path_planning");
133  file_dir = QString::fromStdString(path);
134  }
135  }
136 
137  QFileDialog browser;
138  browser.setOption(QFileDialog::DontUseNativeDialog, true);
139  QString file_path = browser.getOpenFileName(
140  this, tr("Choose YAML or mesh file"), file_dir,
141  tr("YAML and mesh files (*.yaml *.YAML *.yml *.YML *.ply *.PLY *.stl *.STL *.obj *.OBJ)"));
142  if (file_path != "")
143  file_->setText(file_path);
144 }
145 
147 {
148  std::string file_extension(fileExtension(file_->text().toStdString()));
149  if (!strcasecmp(file_extension.c_str(), "yaml") || !strcasecmp(file_extension.c_str(), "yml"))
150  // YAML
151  {
152  number_of_layers_widget_->setEnabled(true);
153  slicing_direction_widget_->setEnabled(false);
154  }
155  else if (!strcasecmp(file_extension.c_str(), "ply") || !strcasecmp(file_extension.c_str(), "stl")
156  || !strcasecmp(file_extension.c_str(), "obj"))
157  // Mesh
158  {
159  number_of_layers_widget_->setEnabled(false);
160  slicing_direction_widget_->setEnabled(true);
161  }
162  else
163  // Enable everything
164  {
165  number_of_layers_widget_->setEnabled(true);
166  slicing_direction_widget_->setEnabled(true);
167  }
168 }
169 
171 {
172  QString tmp_str("");
173  int tmp_int(0);
174  float tmp_float(0.01);
175 
176  if (config.mapGetString(objectName() + "file", &tmp_str))
177  file_->setText(tmp_str);
178 
179  if (config.mapGetInt(objectName() + "number_of_layers", &tmp_int))
180  number_of_layers_->setValue(tmp_int);
181 
182  if (config.mapGetFloat(objectName() + "height_between_layers", &tmp_float))
183  height_between_layers_->setValue(tmp_float);
184  else
186 
187  if (config.mapGetFloat(objectName() + "deposited_material_width", &tmp_float))
188  deposited_material_width_->setValue(tmp_float);
189  else
191 
192  if (config.mapGetFloat(objectName() + "contours_filtering_tolerance", &tmp_float))
193  contours_filtering_tolerance_->setValue(tmp_float);
194  else
196 
197  if (config.mapGetFloat(objectName() + "slicing_direction_x", &tmp_float))
198  slicing_direction_x_->setValue(tmp_float);
199  else
201 
202  if (config.mapGetFloat(objectName() + "slicing_direction_y", &tmp_float))
203  slicing_direction_y_->setValue(tmp_float);
204  else
206 
207  if (config.mapGetFloat(objectName() + "slicing_direction_z", &tmp_float))
208  slicing_direction_z_->setValue(tmp_float);
209  else
211 }
212 
214  {
215  config.mapSetValue(objectName() + "file", file_->text());
216  config.mapSetValue(objectName() + "number_of_layers", number_of_layers_->value());
217  config.mapSetValue(objectName() + "height_between_layers", height_between_layers_->value());
218  config.mapSetValue(objectName() + "deposited_material_width", deposited_material_width_->value());
219  config.mapSetValue(objectName() + "contours_filtering_tolerance", contours_filtering_tolerance_->value());
220  config.mapSetValue(objectName() + "slicing_direction_x", slicing_direction_x_->value());
221  config.mapSetValue(objectName() + "slicing_direction_y", slicing_direction_y_->value());
222  config.mapSetValue(objectName() + "slicing_direction_z", slicing_direction_z_->value());
223 }
224 
225 std::string DonghongDingWidget::fillGoal(ram_path_planning::DonghongDingGoal &goal)
226 {
227  if (file_->text().isEmpty())
228  return "File name is not specified.";
229 
230  goal.file = file_->text().toStdString();
231  goal.number_of_layers = number_of_layers_->value();
232  goal.height_between_layers = height_between_layers_->value() / 1000.0;
233  goal.deposited_material_width = deposited_material_width_->value() / 1000.0;
234  goal.contours_filtering_tolerance = contours_filtering_tolerance_->value() / 1000.0;
235 
236  // Slicing direction
237  goal.slicing_direction.x = slicing_direction_x_->value();
238  goal.slicing_direction.y = slicing_direction_y_->value();
239  goal.slicing_direction.z = slicing_direction_z_->value();
240  return "";
241 }
242 
243 std::string DonghongDingWidget::fileExtension(const std::string full_path)
244 {
245  size_t last_index = full_path.find_last_of("/");
246  std::string file_name = full_path.substr(last_index + 1, full_path.size());
247 
248  last_index = file_name.find_last_of("\\");
249  file_name = file_name.substr(last_index + 1, file_name.size());
250 
251  last_index = file_name.find_last_of(".");
252  if (last_index == std::string::npos)
253  return "";
254 
255  return file_name.substr(last_index + 1, file_name.size());
256 }
257 
258 }
QDoubleSpinBox * height_between_layers_
void load(const rviz::Config &config)
bool mapGetFloat(const QString &key, float *value_out) const
const double default_contours_filtering_tolerance_
bool mapGetString(const QString &key, QString *value_out) const
void mapSetValue(const QString &key, QVariant value)
QDoubleSpinBox * slicing_direction_z_
QDoubleSpinBox * deposited_material_width_
QDoubleSpinBox * contours_filtering_tolerance_
bool mapGetInt(const QString &key, int *value_out) const
QDoubleSpinBox * slicing_direction_y_
ROSLIB_DECL std::string getPath(const std::string &package_name)
std::string fileExtension(const std::string full_path)
void save(rviz::Config config) const
const double default_deposited_material_width_
QDoubleSpinBox * slicing_direction_x_
std::string fillGoal(ram_path_planning::DonghongDingGoal &goal)


ram_qt_guis
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Jun 10 2019 14:50:11