47 #include <QMessageBox> 48 #include <QInputDialog> 50 #include "ui_motion_planning_rviz_plugin_frame.h" 57 "connect to database");
65 moveit_msgs::PlanningScene msg;
66 ps->getPlanningSceneMsg(msg);
73 std::string planner_id =
ui_->planning_algorithm_combo_box->itemText(index).toStdString();
77 ui_->planner_param_treeview->setPlannerId(planner_id);
84 if (QMessageBox::warning(
this,
"Data about to be deleted",
"The following dialog will allow you to drop a MoveIt! " 85 "Warehouse database. Are you sure you want to continue?",
86 QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
90 dbs.append(
"Planning Scenes");
91 dbs.append(
"Constraints");
92 dbs.append(
"Robot States");
96 QInputDialog::getItem(
this, tr(
"Select Database"), tr(
"Choose the database to reset:"), dbs, 2,
false, &ok);
100 if (QMessageBox::critical(
101 this,
"Data about to be deleted",
102 QString(
"All data in database '").
append(response).
append(
"'. Are you sure you want to continue?"),
103 QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
127 conn->setParams(
ui_->database_host->text().toStdString(),
ui_->database_port->value(), 5.0);
141 catch (std::exception& ex)
157 ui_->planning_scene_tree->setUpdatesEnabled(
false);
158 ui_->planning_scene_tree->clear();
159 ui_->planning_scene_tree->setUpdatesEnabled(
true);
161 ui_->database_connect_button->setUpdatesEnabled(
false);
162 ui_->database_connect_button->setText(QString::fromStdString(
"Connect"));
163 ui_->database_connect_button->setStyleSheet(
"QPushButton { color : green }");
164 ui_->database_connect_button->setUpdatesEnabled(
true);
165 ui_->reset_db_button->hide();
167 ui_->load_scene_button->setEnabled(
false);
168 ui_->load_query_button->setEnabled(
false);
169 ui_->save_query_button->setEnabled(
false);
170 ui_->save_scene_button->setEnabled(
false);
171 ui_->delete_query_button->setEnabled(
false);
172 ui_->delete_scene_button->setEnabled(
false);
177 ui_->database_connect_button->setUpdatesEnabled(
false);
178 ui_->database_connect_button->setText(QString::fromStdString(
"Connecting ..."));
179 ui_->database_connect_button->setUpdatesEnabled(
true);
184 ui_->database_connect_button->setUpdatesEnabled(
false);
185 ui_->database_connect_button->setText(QString::fromStdString(
"Connect"));
186 ui_->database_connect_button->setStyleSheet(
"QPushButton { color : green }");
187 ui_->database_connect_button->setUpdatesEnabled(
true);
188 ui_->reset_db_button->hide();
192 ui_->database_connect_button->setUpdatesEnabled(
false);
193 ui_->database_connect_button->setText(QString::fromStdString(
"Disconnect"));
194 ui_->database_connect_button->setStyleSheet(
"QPushButton { color : darkBlue }");
195 ui_->database_connect_button->setUpdatesEnabled(
true);
196 ui_->save_scene_button->setEnabled(
true);
197 ui_->reset_db_button->show();
202 move_group_->setConstraintsDatabase(
ui_->database_host->text().toStdString(),
ui_->database_port->value());
204 "populateConstraintsList");
215 else if (db ==
"Planning Scenes")
void publishSceneButtonClicked()
void publish(const boost::shared_ptr< M > &message) const
void populateConstraintsList()
void computeResetDbButtonClicked(const std::string &db)
void populatePlanningSceneTreeView()
void computeDatabaseConnectButtonClicked()
void loadStoredStates(const std::string &pattern)
moveit::planning_interface::MoveGroupInterfacePtr move_group_
void addBackgroundJob(const boost::function< void()> &job, const std::string &name)
warehouse_ros::DatabaseConnection::Ptr loadDatabase()
moveit_warehouse::RobotStateStoragePtr robot_state_storage_
moveit_warehouse::ConstraintsStoragePtr constraints_storage_
void databaseConnectButtonClicked()
MotionPlanningDisplay * planning_display_
void resetDbButtonClicked()
Ui::MotionPlanningUI * ui_
void computeDatabaseConnectButtonClickedHelper(int mode)
void addMainLoopJob(const boost::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called ...
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
void planningAlgorithmIndexChanged(int index)
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
ros::Publisher planning_scene_publisher_
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene