42 #include <QMessageBox>
43 #include <QInputDialog>
45 #include "ui_motion_planning_rviz_plugin_frame.h"
51 ui_->list_states->clear();
52 for (std::pair<const std::string, moveit_msgs::RobotState>& robot_state :
robot_states_)
54 QListWidgetItem* item =
new QListWidgetItem(QString(robot_state.first.c_str()));
55 ui_->list_states->addItem(item);
66 QInputDialog::getText(
this, tr(
"Robot states to load"), tr(
"Pattern:"), QLineEdit::Normal,
".*", &ok);
67 if (ok && !
text.isEmpty())
74 QMessageBox::warning(
this,
"Warning",
"Not connected to a database.");
80 std::vector<std::string> names;
85 catch (std::exception& ex)
87 QMessageBox::warning(
this,
"Cannot query the database",
88 QString(
"Wrongly formatted regular expression for robot states: ").
append(ex.what()));
95 for (
const std::string& name : names)
98 bool got_state =
false;
103 catch (std::exception& ex)
126 std::stringstream ss;
130 QString
text = QInputDialog::getText(
this, tr(
"Choose a name"), tr(
"State name:"), QLineEdit::Normal,
131 QString(ss.str().c_str()), &ok);
140 QMessageBox::warning(
this,
"Name already exists",
141 QString(
"The name '").
append(
name.c_str()).append(
"' already exists. Not creating state."));
145 moveit_msgs::RobotState msg;
156 catch (std::exception& ex)
158 ROS_ERROR(
"Cannot save robot state on the database: %s", ex.what());
163 QMessageBox::warning(
this,
"Warning",
"Not connected to a database. The state will be created but not stored");
168 QMessageBox::warning(
this,
"Start state not saved",
"Cannot use an empty name for a new start state.");
185 QListWidgetItem* item =
ui_->list_states->currentItem();
197 QListWidgetItem* item =
ui_->list_states->currentItem();
213 msg_box.setText(
"All the selected states will be removed from the database");
214 msg_box.setInformativeText(
"Do you want to continue?");
215 msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
216 msg_box.setDefaultButton(QMessageBox::No);
217 int ret = msg_box.exec();
221 case QMessageBox::Yes:
223 QList<QListWidgetItem*> found_items =
ui_->list_states->selectedItems();
224 for (QListWidgetItem* found_item : found_items)
226 const std::string&
name = found_item->text().toStdString();
232 catch (std::exception& ex)
247 msg_box.setText(
"Clear all stored robot states (from memory, not from the database)?");
248 msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
249 msg_box.setDefaultButton(QMessageBox::Yes);
250 int ret = msg_box.exec();
253 case QMessageBox::Yes: