main_window.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Darby Lim, Hye-Jong KIM, Ryan Shim, Yong-Ho Na */
18 
19 /*****************************************************************************
20 ** Includes
21 *****************************************************************************/
22 
23 #include <QtGui>
24 #include <QMessageBox>
25 #include <iostream>
26 #include "../include/open_manipulator_control_gui/main_window.hpp"
27 
28 /*****************************************************************************
29 ** Namespaces
30 *****************************************************************************/
31 
33 
34 using namespace Qt;
35 
36 /*****************************************************************************
37 ** Implementation [MainWindow]
38 *****************************************************************************/
39 
40 MainWindow::MainWindow(int argc, char** argv, QWidget *parent)
41  : QMainWindow(parent)
42  , qnode(argc,argv)
43 {
44  ui.setupUi(this); // Calling this incidentally connects all ui's triggers to on_...() callbacks in this class.
45  QObject::connect(ui.actionAbout_Qt, SIGNAL(triggered(bool)), qApp, SLOT(aboutQt())); // qApp is a global variable for the application
46  connect(ui.tabWidget, SIGNAL(currentChanged(int)), this, SLOT(tabSelected()));
47  QObject::connect(&qnode, SIGNAL(rosShutdown()), this, SLOT(close()));
48 
49  qnode.init();
50 
51 }
52 
54 
56 {
57  std::vector<double> joint_angle = qnode.getPresentJointAngle();
58  if(joint_angle.size() != 5)
59  return;
60 
61  ui.txt_j1->setText(QString::number(joint_angle.at(0),'f', 3));
62  ui.txt_j2->setText(QString::number(joint_angle.at(1),'f', 3));
63  ui.txt_j3->setText(QString::number(joint_angle.at(2),'f', 3));
64  ui.txt_j4->setText(QString::number(joint_angle.at(3),'f', 3));
65  ui.txt_grip->setText(QString::number(joint_angle.at(4),'f', 3));
66 
67  std::vector<double> position = qnode.getPresentKinematicsPose();
68  if(position.size() != 3)
69  return;
70 
71  ui.txt_x->setText(QString::number(position.at(0),'f', 3));
72  ui.txt_y->setText(QString::number(position.at(1),'f', 3));
73  ui.txt_z->setText(QString::number(position.at(2),'f', 3));
74 
76  ui.txt_actuactor_state->setText("Actuator enabled");
77  else
78  ui.txt_actuactor_state->setText("Actuator disabled");
80  ui.txt_moving_state->setText("Robot is moving");
81  else
82  ui.txt_moving_state->setText("Robot is stopped");
83 
84 }
86 {
87  if(ui.tabWidget->currentIndex()==0)
89  if(ui.tabWidget->currentIndex()==1)
91 }
92 
93 void MainWindow::writeLog(QString str)
94 {
95  ui.plainTextEdit_log->moveCursor (QTextCursor::End);
96  ui.plainTextEdit_log->appendPlainText(str);
97 }
98 
100 {
101  timer = new QTimer(this);
102  connect(timer, SIGNAL(timeout()), this, SLOT(timerCallback()));
103  timer->start(100);
104 
105  writeLog("QTimer start : 100ms");
106  ui.btn_timer_start->setEnabled(false);
107  ui.btn_actuator_disable->setEnabled(true);
108  ui.btn_actuator_enable->setEnabled(true);
109  ui.btn_gripper_close->setEnabled(true);
110  ui.btn_gripper_open->setEnabled(true);
111  ui.btn_home_pose->setEnabled(true);
112  ui.btn_init_pose->setEnabled(true);
113  ui.btn_read_joint_angle->setEnabled(true);
114  ui.btn_read_kinematic_pose->setEnabled(true);
115  ui.btn_send_joint_angle->setEnabled(true);
116  ui.btn_send_kinematic_pose->setEnabled(true);
117  ui.btn_send_drawing_trajectory->setEnabled(true);
118  ui.btn_set_gripper->setEnabled(true);
119 }
120 
122 {
123  if(!qnode.setActuatorState(true))
124  {
125  writeLog("[ERR!!] Failed to send service");
126  return;
127  }
128 
129  writeLog("Send actuator state to enable");
130 }
131 
133 {
134  if(!qnode.setActuatorState(false))
135  {
136  writeLog("[ERR!!] Failed to send service");
137  return;
138  }
139 
140  writeLog("Send actuator state to disable");
141 }
142 
144 {
145  std::vector<std::string> joint_name;
146  std::vector<double> joint_angle;
147  double path_time = 2.0;
148  joint_name.push_back("joint1"); joint_angle.push_back(0.0);
149  joint_name.push_back("joint2"); joint_angle.push_back(0.0);
150  joint_name.push_back("joint3"); joint_angle.push_back(0.0);
151  joint_name.push_back("joint4"); joint_angle.push_back(0.0);
152 
153  if(!qnode.setJointSpacePath(joint_name, joint_angle, path_time))
154  {
155  writeLog("[ERR!!] Failed to send service");
156  return;
157  }
158 
159  writeLog("Send joint angle to initial pose");
160 }
161 
163 {
164  std::vector<std::string> joint_name;
165  std::vector<double> joint_angle;
166  double path_time = 2.0;
167 
168  joint_name.push_back("joint1"); joint_angle.push_back(0.0);
169  joint_name.push_back("joint2"); joint_angle.push_back(-1.05);
170  joint_name.push_back("joint3"); joint_angle.push_back(0.35);
171  joint_name.push_back("joint4"); joint_angle.push_back(0.70);
172  if(!qnode.setJointSpacePath(joint_name, joint_angle, path_time))
173  {
174  writeLog("[ERR!!] Failed to send service");
175  return;
176  }
177  writeLog("Send joint angle to home pose");
178 }
179 
181 {
182  std::vector<double> joint_angle;
183  joint_angle.push_back(0.01);
184 
185  if(!qnode.setToolControl(joint_angle))
186  {
187  writeLog("[ERR!!] Failed to send service");
188  return;
189  }
190 
191  writeLog("Send gripper open");
192 }
193 
195 {
196  std::vector<double> joint_angle;
197  joint_angle.push_back(-0.01);
198  if(!qnode.setToolControl(joint_angle))
199  {
200  writeLog("[ERR!!] Failed to send service");
201  return;
202  }
203 
204  writeLog("Send gripper close");
205 }
206 
207 
209 {
210  std::vector<double> joint_angle = qnode.getPresentJointAngle();
211  ui.doubleSpinBox_j1->setValue(joint_angle.at(0));
212  ui.doubleSpinBox_j2->setValue(joint_angle.at(1));
213  ui.doubleSpinBox_j3->setValue(joint_angle.at(2));
214  ui.doubleSpinBox_j4->setValue(joint_angle.at(3));
215  ui.doubleSpinBox_gripper->setValue(joint_angle.at(4));
216 
217  writeLog("Read joint angle");
218 }
220 {
221  std::vector<std::string> joint_name;
222  std::vector<double> joint_angle;
223  double path_time = ui.doubleSpinBox_time_js->value();
224 
225  joint_name.push_back("joint1"); joint_angle.push_back(ui.doubleSpinBox_j1->value());
226  joint_name.push_back("joint2"); joint_angle.push_back(ui.doubleSpinBox_j2->value());
227  joint_name.push_back("joint3"); joint_angle.push_back(ui.doubleSpinBox_j3->value());
228  joint_name.push_back("joint4"); joint_angle.push_back(ui.doubleSpinBox_j4->value());
229 
230  if(!qnode.setJointSpacePath(joint_name, joint_angle, path_time))
231  {
232  writeLog("[ERR!!] Failed to send service");
233  return;
234  }
235 
236  writeLog("Send joint angle");
237 }
239 {
240  std::vector<double> position = qnode.getPresentKinematicsPose();
241  ui.doubleSpinBox_x->setValue(position.at(0));
242  ui.doubleSpinBox_y->setValue(position.at(1));
243  ui.doubleSpinBox_z->setValue(position.at(2));
244 
245  writeLog("Read task pose");
246 }
248 {
249  std::vector<double> kinematics_pose;
250  double path_time = ui.doubleSpinBox_time_cs->value();
251 
252  kinematics_pose.push_back(ui.doubleSpinBox_x->value());
253  kinematics_pose.push_back(ui.doubleSpinBox_y->value());
254  kinematics_pose.push_back(ui.doubleSpinBox_z->value());
255 
256  if(!qnode.setTaskSpacePath(kinematics_pose, path_time))
257  {
258  writeLog("[ERR!!] Failed to send service");
259  return;
260  }
261 
262  writeLog("Send task pose");
263 }
265 {
266  std::vector<double> joint_angle;
267  joint_angle.push_back(ui.doubleSpinBox_gripper->value());
268  if(!qnode.setToolControl(joint_angle))
269  {
270  writeLog("[ERR!!] Failed to send service");
271  return;
272  }
273  writeLog("Send gripper value");
274 }
275 
277 {
278  qnode.setOption("print_open_manipulator_setting");
279  writeLog("Check the terminal of open_manipulator_controller package");
280 }
281 
282 
284 {
285  ui.txt_drawing_arg_1->setText("Transpose X");
286  ui.txt_drawing_arg_2->setText("Transpose Y");
287  ui.txt_drawing_arg_3->setText("Transpose Z");
288  ui.txt_drawing_arg_unit_1->setText("m");
289  ui.txt_drawing_arg_unit_2->setText("m");
290  ui.txt_drawing_arg_unit_3->setText("m");
291  ui.doubleSpinBox_drawing_arg_1->setValue(0.0);
292  ui.doubleSpinBox_drawing_arg_2->setValue(0.0);
293  ui.doubleSpinBox_drawing_arg_3->setValue(0.0);
294 }
296 {
297  ui.txt_drawing_arg_1->setText("Radius");
298  ui.txt_drawing_arg_2->setText("Revolution");
299  ui.txt_drawing_arg_3->setText("Start angle");
300  ui.txt_drawing_arg_unit_1->setText("m");
301  ui.txt_drawing_arg_unit_2->setText("rev");
302  ui.txt_drawing_arg_unit_3->setText("rad");
303  ui.doubleSpinBox_drawing_arg_1->setValue(0.0);
304  ui.doubleSpinBox_drawing_arg_2->setValue(0.0);
305  ui.doubleSpinBox_drawing_arg_3->setValue(0.0);
306 }
308 {
309  ui.txt_drawing_arg_1->setText("Radius");
310  ui.txt_drawing_arg_2->setText("Revolution");
311  ui.txt_drawing_arg_3->setText("Start angle");
312  ui.txt_drawing_arg_unit_1->setText("m");
313  ui.txt_drawing_arg_unit_2->setText("rev");
314  ui.txt_drawing_arg_unit_3->setText("rad");
315  ui.doubleSpinBox_drawing_arg_1->setValue(0.0);
316  ui.doubleSpinBox_drawing_arg_2->setValue(0.0);
317  ui.doubleSpinBox_drawing_arg_3->setValue(0.0);
318 }
320 {
321  ui.txt_drawing_arg_1->setText("Radius");
322  ui.txt_drawing_arg_2->setText("Revolution");
323  ui.txt_drawing_arg_3->setText("Start angle");
324  ui.txt_drawing_arg_unit_1->setText("m");
325  ui.txt_drawing_arg_unit_2->setText("rev");
326  ui.txt_drawing_arg_unit_3->setText("rad");
327  ui.doubleSpinBox_drawing_arg_1->setValue(0.0);
328  ui.doubleSpinBox_drawing_arg_2->setValue(0.0);
329  ui.doubleSpinBox_drawing_arg_3->setValue(0.0);
330 }
332 {
333  std::string name;
334  if(ui.radio_drawing_line->isChecked()) name = "line";
335  else if(ui.radio_drawing_circle->isChecked()) name = "circle";
336  else if(ui.radio_drawing_rhombus->isChecked()) name = "rhombus";
337  else if(ui.radio_drawing_heart->isChecked()) name = "heart";
338 
339  std::vector<double> arg;
340  arg.push_back(ui.doubleSpinBox_drawing_arg_1->value());
341  arg.push_back(ui.doubleSpinBox_drawing_arg_2->value());
342  arg.push_back(ui.doubleSpinBox_drawing_arg_3->value());
343 
344  double path_time = ui.doubleSpinBox_time_drawing->value();
345 
346  if(!qnode.setDrawingTrajectory(name, arg, path_time))
347  {
348  writeLog("[ERR!!] Failed to send service");
349  return;
350  }
351  writeLog("Send drawing trajectory");
352 }
353 
354 } // namespace open_manipulator_control_gui
355 
std::vector< double > getPresentKinematicsPose()
Definition: qnode.cpp:133
bool setTaskSpacePath(std::vector< double > kinematics_pose, double path_time)
Definition: qnode.cpp:167
bool setJointSpacePath(std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
Definition: qnode.cpp:153
bool setActuatorState(bool actuator_state)
Definition: qnode.cpp:220
bool setToolControl(std::vector< double > joint_angle)
Definition: qnode.cpp:207
bool setDrawingTrajectory(std::string name, std::vector< double > arg, double path_time)
Definition: qnode.cpp:191
MainWindow(int argc, char **argv, QWidget *parent=0)
Definition: main_window.cpp:40
void setOption(std::string opt)
Definition: qnode.cpp:146
std::vector< double > getPresentJointAngle()
Definition: qnode.cpp:129


open_manipulator_control_gui
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Mon Jun 10 2019 14:11:52