motion_planning_frame_context.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
40 
43 
44 #include <rviz/display_context.h>
46 
47 #include <QMessageBox>
48 #include <QInputDialog>
49 
50 #include "ui_motion_planning_rviz_plugin_frame.h"
51 
52 namespace moveit_rviz_plugin
53 {
55 {
57  "connect to database");
58 }
59 
61 {
63  if (ps)
64  {
65  moveit_msgs::PlanningScene msg;
66  ps->getPlanningSceneMsg(msg);
68  }
69 }
70 
72 {
73  std::string planner_id = ui_->planning_algorithm_combo_box->itemText(index).toStdString();
74  if (index <= 0)
75  planner_id = "";
76 
77  ui_->planner_param_treeview->setPlannerId(planner_id);
78  if (move_group_)
79  move_group_->setPlannerId(planner_id);
80 }
81 
83 {
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)
87  return;
88 
89  QStringList dbs;
90  dbs.append("Planning Scenes");
91  dbs.append("Constraints");
92  dbs.append("Robot States");
93 
94  bool ok = false;
95  QString response =
96  QInputDialog::getItem(this, tr("Select Database"), tr("Choose the database to reset:"), dbs, 2, false, &ok);
97  if (!ok)
98  return;
99 
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)
104  return;
105 
107  boost::bind(&MotionPlanningFrame::computeResetDbButtonClicked, this, response.toStdString()), "reset database");
108 }
109 
111 {
113  {
114  planning_scene_storage_.reset();
115  robot_state_storage_.reset();
116  constraints_storage_.reset();
119  }
120  else
121  {
124  try
125  {
127  conn->setParams(ui_->database_host->text().toStdString(), ui_->database_port->value(), 5.0);
128  if (conn->connect())
129  {
133  }
134  else
135  {
138  return;
139  }
140  }
141  catch (std::exception& ex)
142  {
145  ROS_ERROR("%s", ex.what());
146  return;
147  }
150  }
151 }
152 
154 {
155  if (mode == 1)
156  {
157  ui_->planning_scene_tree->setUpdatesEnabled(false);
158  ui_->planning_scene_tree->clear();
159  ui_->planning_scene_tree->setUpdatesEnabled(true);
160 
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();
166 
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);
173  populateConstraintsList(std::vector<std::string>());
174  }
175  else if (mode == 2)
176  {
177  ui_->database_connect_button->setUpdatesEnabled(false);
178  ui_->database_connect_button->setText(QString::fromStdString("Connecting ..."));
179  ui_->database_connect_button->setUpdatesEnabled(true);
180  populateConstraintsList(std::vector<std::string>());
181  }
182  else if (mode == 3)
183  {
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();
189  }
190  else if (mode == 4)
191  {
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();
199  loadStoredStates(".*"); // automatically populate the 'Stored States' tab with all states
200  if (move_group_)
201  {
202  move_group_->setConstraintsDatabase(ui_->database_host->text().toStdString(), ui_->database_port->value());
204  "populateConstraintsList");
205  }
206  }
207 }
208 
210 {
211  if (db == "Constraints" && constraints_storage_)
212  constraints_storage_->reset();
213  else if (db == "Robot States" && robot_state_storage_)
214  robot_state_storage_->reset();
215  else if (db == "Planning Scenes")
216  planning_scene_storage_->reset();
217 }
218 }
void publish(const boost::shared_ptr< M > &message) const
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 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)
#define ROS_ERROR(...)
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
const std::string response
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:04:23