moveit2
The MoveIt Motion Planning Framework for ROS 2.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Pages
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 */
41 
42 #include <rviz_common/display_context.hpp>
43 #include <rviz_common/window_manager_interface.hpp>
44 
45 #include <QMessageBox>
46 #include <QInputDialog>
47 
48 #include "ui_motion_planning_rviz_plugin_frame.h"
49 
50 namespace moveit_rviz_plugin
51 {
52 
53 void MotionPlanningFrame::databaseConnectButtonClicked()
54 {
55  planning_display_->addBackgroundJob([this] { computeDatabaseConnectButtonClicked(); }, "connect to database");
56 }
57 
58 void MotionPlanningFrame::planningPipelineIndexChanged(int index)
59 {
60  // Refresh planner interface description for selected pipeline
61  if (index >= 0 && static_cast<size_t>(index) < planner_descriptions_.size())
62  {
63  // Set the selected pipeline id
64  if (move_group_)
65  move_group_->setPlanningPipelineId(planner_descriptions_[index].pipeline_id);
66 
67  populatePlannerDescription(planner_descriptions_[index]);
68  }
69 }
70 
71 void MotionPlanningFrame::planningAlgorithmIndexChanged(int index)
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 
79  if (move_group_)
80  move_group_->setPlannerId(planner_id);
81 }
82 
83 void MotionPlanningFrame::resetDbButtonClicked()
84 {
85  if (QMessageBox::warning(this, "Data about to be deleted",
86  "The following dialog will allow you to drop a MoveIt "
87  "Warehouse database. Are you sure you want to continue?",
88  QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
89  return;
90 
91  QStringList dbs;
92  dbs.append("Planning Scenes");
93  dbs.append("Constraints");
94  dbs.append("Robot States");
95 
96  bool ok = false;
97  QString response =
98  QInputDialog::getItem(this, tr("Select Database"), tr("Choose the database to reset:"), dbs, 2, false, &ok);
99  if (!ok)
100  return;
101 
102  if (QMessageBox::critical(
103  this, "Data about to be deleted",
104  QString("All data in database '").append(response).append("'. Are you sure you want to continue?"),
105  QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
106  return;
107 
108  planning_display_->addBackgroundJob([this, db = response.toStdString()] { computeResetDbButtonClicked(db); },
109  "reset database");
110 }
111 
112 void MotionPlanningFrame::computeDatabaseConnectButtonClicked()
113 {
114  RCLCPP_INFO(logger_, "Connect to database: {host: %s, port: %d}", ui_->database_host->text().toStdString().c_str(),
115  ui_->database_port->value());
117  {
118  planning_scene_storage_.reset();
119  robot_state_storage_.reset();
120  constraints_storage_.reset();
121  planning_display_->addMainLoopJob([this] { computeDatabaseConnectButtonClickedHelper(1); });
122  }
123  else
124  {
125  planning_display_->addMainLoopJob([this] { computeDatabaseConnectButtonClickedHelper(2); });
126  try
127  {
128  warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node_);
129  conn->setParams(ui_->database_host->text().toStdString(), ui_->database_port->value(), 5.0);
130  if (conn->connect())
131  {
132  planning_scene_storage_ = std::make_shared<moveit_warehouse::PlanningSceneStorage>(conn);
133  robot_state_storage_ = std::make_shared<moveit_warehouse::RobotStateStorage>(conn);
134  constraints_storage_ = std::make_shared<moveit_warehouse::ConstraintsStorage>(conn);
135  }
136  else
137  {
138  planning_display_->addMainLoopJob([this] { computeDatabaseConnectButtonClickedHelper(3); });
139  return;
140  }
141  }
142  catch (std::exception& ex)
143  {
144  planning_display_->addMainLoopJob([this] { computeDatabaseConnectButtonClickedHelper(3); });
145  RCLCPP_ERROR(logger_, "%s", ex.what());
146  return;
147  }
148  planning_display_->addMainLoopJob([this] { computeDatabaseConnectButtonClickedHelper(4); });
149  }
150 }
151 
152 void MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper(int mode)
153 {
154  if (mode == 1)
155  {
156  ui_->planning_scene_tree->setUpdatesEnabled(false);
157  ui_->planning_scene_tree->clear();
158  ui_->planning_scene_tree->setUpdatesEnabled(true);
159 
160  ui_->database_connect_button->setUpdatesEnabled(false);
161  ui_->database_connect_button->setText(QString::fromStdString("Connect"));
162  ui_->database_connect_button->setStyleSheet("QPushButton { color : green }");
163  ui_->database_connect_button->setUpdatesEnabled(true);
164  ui_->reset_db_button->hide();
165 
166  ui_->load_scene_button->setEnabled(false);
167  ui_->load_query_button->setEnabled(false);
168  ui_->save_query_button->setEnabled(false);
169  ui_->save_scene_button->setEnabled(false);
170  ui_->delete_query_button->setEnabled(false);
171  ui_->delete_scene_button->setEnabled(false);
172  populateConstraintsList(std::vector<std::string>());
173  }
174  else if (mode == 2)
175  {
176  ui_->database_connect_button->setUpdatesEnabled(false);
177  ui_->database_connect_button->setText(QString::fromStdString("Connecting ..."));
178  ui_->database_connect_button->setUpdatesEnabled(true);
179  populateConstraintsList(std::vector<std::string>());
180  }
181  else if (mode == 3)
182  {
183  ui_->database_connect_button->setUpdatesEnabled(false);
184  ui_->database_connect_button->setText(QString::fromStdString("Connect"));
185  ui_->database_connect_button->setStyleSheet("QPushButton { color : green }");
186  ui_->database_connect_button->setUpdatesEnabled(true);
187  ui_->reset_db_button->hide();
188  }
189  else if (mode == 4)
190  {
191  ui_->database_connect_button->setUpdatesEnabled(false);
192  ui_->database_connect_button->setText(QString::fromStdString("Disconnect"));
193  ui_->database_connect_button->setStyleSheet("QPushButton { color : darkBlue }");
194  ui_->database_connect_button->setUpdatesEnabled(true);
195  ui_->save_scene_button->setEnabled(true);
196  ui_->reset_db_button->show();
197  populatePlanningSceneTreeView();
198  loadStoredStates(".*"); // automatically populate the 'Stored States' tab with all states
199  if (move_group_)
200  {
201  move_group_->setConstraintsDatabase(ui_->database_host->text().toStdString(), ui_->database_port->value());
202  planning_display_->addBackgroundJob([this]() { populateConstraintsList(); }, "populateConstraintsList");
203  }
204  }
205 }
206 
207 void MotionPlanningFrame::computeResetDbButtonClicked(const std::string& db)
208 {
209  if (db == "Constraints" && constraints_storage_)
210  {
211  constraints_storage_->reset();
212  }
213  else if (db == "Robot States" && robot_state_storage_)
214  {
215  robot_state_storage_->reset();
216  }
217  else if (db == "Planning Scenes")
218  {
219  planning_scene_storage_->reset();
220  }
221 }
222 } // namespace moveit_rviz_plugin
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
std::vector< moveit_msgs::msg::PlannerInterfaceDescription > planner_descriptions_
moveit_warehouse::ConstraintsStoragePtr constraints_storage_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
moveit_warehouse::RobotStateStoragePtr robot_state_storage_
void addMainLoopJob(const std::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
std::string append(const std::string &left, const std::string &right)