24 #include <QMessageBox> 26 #include "../include/open_manipulator_control_gui/main_window.hpp" 45 QObject::connect(
ui.actionAbout_Qt, SIGNAL(triggered(
bool)), qApp, SLOT(aboutQt()));
46 connect(
ui.tabWidget, SIGNAL(currentChanged(
int)),
this, SLOT(
tabSelected()));
47 QObject::connect(&
qnode, SIGNAL(rosShutdown()),
this, SLOT(close()));
58 if(joint_angle.size() != 5)
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));
68 if(position.size() != 3)
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));
76 ui.txt_actuactor_state->setText(
"Actuator enabled");
78 ui.txt_actuactor_state->setText(
"Actuator disabled");
80 ui.txt_moving_state->setText(
"Robot is moving");
82 ui.txt_moving_state->setText(
"Robot is stopped");
87 if(
ui.tabWidget->currentIndex()==0)
89 if(
ui.tabWidget->currentIndex()==1)
95 ui.plainTextEdit_log->moveCursor (QTextCursor::End);
96 ui.plainTextEdit_log->appendPlainText(str);
101 timer =
new QTimer(
this);
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);
125 writeLog(
"[ERR!!] Failed to send service");
129 writeLog(
"Send actuator state to enable");
136 writeLog(
"[ERR!!] Failed to send service");
140 writeLog(
"Send actuator state to disable");
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);
155 writeLog(
"[ERR!!] Failed to send service");
159 writeLog(
"Send joint angle to initial pose");
164 std::vector<std::string> joint_name;
165 std::vector<double> joint_angle;
166 double path_time = 2.0;
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);
174 writeLog(
"[ERR!!] Failed to send service");
177 writeLog(
"Send joint angle to home pose");
182 std::vector<double> joint_angle;
183 joint_angle.push_back(0.01);
187 writeLog(
"[ERR!!] Failed to send service");
196 std::vector<double> joint_angle;
197 joint_angle.push_back(-0.01);
200 writeLog(
"[ERR!!] Failed to send service");
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));
221 std::vector<std::string> joint_name;
222 std::vector<double> joint_angle;
223 double path_time =
ui.doubleSpinBox_time_js->value();
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());
232 writeLog(
"[ERR!!] Failed to send service");
241 ui.doubleSpinBox_x->setValue(position.at(0));
242 ui.doubleSpinBox_y->setValue(position.at(1));
243 ui.doubleSpinBox_z->setValue(position.at(2));
249 std::vector<double> kinematics_pose;
250 double path_time =
ui.doubleSpinBox_time_cs->value();
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());
258 writeLog(
"[ERR!!] Failed to send service");
266 std::vector<double> joint_angle;
267 joint_angle.push_back(
ui.doubleSpinBox_gripper->value());
270 writeLog(
"[ERR!!] Failed to send service");
279 writeLog(
"Check the terminal of open_manipulator_controller package");
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);
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);
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);
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);
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";
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());
344 double path_time =
ui.doubleSpinBox_time_drawing->value();
348 writeLog(
"[ERR!!] Failed to send service");
351 writeLog(
"Send drawing trajectory");
std::vector< double > getPresentKinematicsPose()
void on_radio_drawing_line_clicked(void)
void on_btn_gripper_close_clicked(void)
void on_btn_read_joint_angle_clicked(void)
void on_btn_send_drawing_trajectory_clicked(void)
bool getOpenManipulatorActuatorState()
void on_btn_send_joint_angle_clicked(void)
void on_btn_init_pose_clicked(void)
void on_btn_timer_start_clicked(void)
bool setTaskSpacePath(std::vector< double > kinematics_pose, double path_time)
void on_radio_drawing_circle_clicked(void)
bool setJointSpacePath(std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
void on_radio_drawing_heart_clicked(void)
void writeLog(QString str)
void on_btn_actuator_enable_clicked(void)
bool getOpenManipulatorMovingState()
bool setActuatorState(bool actuator_state)
void on_btn_gripper_open_clicked(void)
bool setToolControl(std::vector< double > joint_angle)
void on_btn_home_pose_clicked(void)
bool setDrawingTrajectory(std::string name, std::vector< double > arg, double path_time)
void on_btn_actuator_disable_clicked(void)
MainWindow(int argc, char **argv, QWidget *parent=0)
void on_radio_drawing_rhombus_clicked(void)
void setOption(std::string opt)
void on_btn_send_kinematic_pose_clicked(void)
void on_btn_get_manipulator_setting_clicked(void)
std::vector< double > getPresentJointAngle()
void on_btn_set_gripper_clicked(void)
void on_btn_read_kinematic_pose_clicked(void)