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 {
56  planning_display_->addBackgroundJob([this] { computeDatabaseConnectButtonClicked(); }, "connect to database");
57 }
58 
60 {
61  // Refresh planner interface description for selected pipeline
62  if (index >= 0 && static_cast<size_t>(index) < planner_descriptions_.size())
63  {
64  // Set the selected pipeline id
65  if (move_group_)
66  move_group_->setPlanningPipelineId(planner_descriptions_[index].pipeline_id);
67 
69  }
70 }
71 
73 {
74  std::string planner_id = ui_->planning_algorithm_combo_box->itemText(index).toStdString();
75  if (index <= 0)
76  planner_id = "";
77 
78  ui_->planner_param_treeview->setPlannerId(planner_id);
79 
80  if (move_group_)
81  move_group_->setPlannerId(planner_id);
82 }
83 
85 {
86  if (QMessageBox::warning(this, "Data about to be deleted",
87  "The following dialog will allow you to drop a MoveIt "
88  "Warehouse database. Are you sure you want to continue?",
89  QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
90  return;
91 
92  QStringList dbs;
93  dbs.append("Planning Scenes");
94  dbs.append("Constraints");
95  dbs.append("Robot States");
96 
97  bool ok = false;
98  QString response =
99  QInputDialog::getItem(this, tr("Select Database"), tr("Choose the database to reset:"), dbs, 2, false, &ok);
100  if (!ok)
101  return;
102 
103  if (QMessageBox::critical(
104  this, "Data about to be deleted",
105  QString("All data in database '").append(response).append("'. Are you sure you want to continue?"),
106  QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
107  return;
108 
109  planning_display_->addBackgroundJob([this, db = response.toStdString()] { computeResetDbButtonClicked(db); },
110  "reset database");
111 }
112 
114 {
116  {
117  planning_scene_storage_.reset();
118  robot_state_storage_.reset();
119  constraints_storage_.reset();
121  }
122  else
123  {
125  try
126  {
128  conn->setParams(ui_->database_host->text().toStdString(), ui_->database_port->value(), 5.0);
129  if (conn->connect())
130  {
131  planning_scene_storage_ = std::make_shared<moveit_warehouse::PlanningSceneStorage>(conn);
132  robot_state_storage_ = std::make_shared<moveit_warehouse::RobotStateStorage>(conn);
133  constraints_storage_ = std::make_shared<moveit_warehouse::ConstraintsStorage>(conn);
134  }
135  else
136  {
138  return;
139  }
140  }
141  catch (std::exception& ex)
142  {
144  ROS_ERROR("%s", ex.what());
145  return;
146  }
148  }
149 }
150 
152 {
153  if (mode == 1)
154  {
155  ui_->planning_scene_tree->setUpdatesEnabled(false);
156  ui_->planning_scene_tree->clear();
157  ui_->planning_scene_tree->setUpdatesEnabled(true);
158 
159  ui_->database_connect_button->setUpdatesEnabled(false);
160  ui_->database_connect_button->setText(QString::fromStdString("Connect"));
161  ui_->database_connect_button->setStyleSheet("QPushButton { color : green }");
162  ui_->database_connect_button->setUpdatesEnabled(true);
163  ui_->reset_db_button->hide();
164 
165  ui_->load_scene_button->setEnabled(false);
166  ui_->load_query_button->setEnabled(false);
167  ui_->save_query_button->setEnabled(false);
168  ui_->save_scene_button->setEnabled(false);
169  ui_->delete_query_button->setEnabled(false);
170  ui_->delete_scene_button->setEnabled(false);
171  populateConstraintsList(std::vector<std::string>());
172  }
173  else if (mode == 2)
174  {
175  ui_->database_connect_button->setUpdatesEnabled(false);
176  ui_->database_connect_button->setText(QString::fromStdString("Connecting ..."));
177  ui_->database_connect_button->setUpdatesEnabled(true);
178  populateConstraintsList(std::vector<std::string>());
179  }
180  else if (mode == 3)
181  {
182  ui_->database_connect_button->setUpdatesEnabled(false);
183  ui_->database_connect_button->setText(QString::fromStdString("Connect"));
184  ui_->database_connect_button->setStyleSheet("QPushButton { color : green }");
185  ui_->database_connect_button->setUpdatesEnabled(true);
186  ui_->reset_db_button->hide();
187  }
188  else if (mode == 4)
189  {
190  ui_->database_connect_button->setUpdatesEnabled(false);
191  ui_->database_connect_button->setText(QString::fromStdString("Disconnect"));
192  ui_->database_connect_button->setStyleSheet("QPushButton { color : darkBlue }");
193  ui_->database_connect_button->setUpdatesEnabled(true);
194  ui_->save_scene_button->setEnabled(true);
195  ui_->reset_db_button->show();
197  loadStoredStates(".*"); // automatically populate the 'Stored States' tab with all states
198  if (move_group_)
199  {
200  move_group_->setConstraintsDatabase(ui_->database_host->text().toStdString(), ui_->database_port->value());
201  planning_display_->addBackgroundJob([this]() { populateConstraintsList(); }, "populateConstraintsList");
202  }
203  }
204 }
205 
206 void MotionPlanningFrame::computeResetDbButtonClicked(const std::string& db)
207 {
208  if (db == "Constraints" && constraints_storage_)
209  constraints_storage_->reset();
210  else if (db == "Robot States" && robot_state_storage_)
211  robot_state_storage_->reset();
212  else if (db == "Planning Scenes")
213  planning_scene_storage_->reset();
214 }
215 } // namespace moveit_rviz_plugin
response
const std::string response
moveit_rviz_plugin::MotionPlanningFrame::loadStoredStates
void loadStoredStates(const std::string &pattern)
Definition: motion_planning_frame_states.cpp:110
moveit_rviz_plugin::MotionPlanningFrame::databaseConnectButtonClicked
void databaseConnectButtonClicked()
Definition: motion_planning_frame_context.cpp:86
boost::shared_ptr< DatabaseConnection >
moveit_rviz_plugin::MotionPlanningFrame::robot_state_storage_
moveit_warehouse::RobotStateStoragePtr robot_state_storage_
Definition: motion_planning_frame.h:136
motion_planning_display.h
planning_scene_storage.h
constraints_storage.h
moveit_rviz_plugin::MotionPlanningFrame::planningAlgorithmIndexChanged
void planningAlgorithmIndexChanged(int index)
Definition: motion_planning_frame_context.cpp:104
moveit_rviz_plugin::MotionPlanningFrame::constraints_storage_
moveit_warehouse::ConstraintsStoragePtr constraints_storage_
Definition: motion_planning_frame.h:135
state_storage.h
moveit_rviz_plugin::PlanningSceneDisplay::addMainLoopJob
void addMainLoopJob(const boost::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
Definition: planning_scene_display.cpp:265
moveit_rviz_plugin::MotionPlanningFrame::computeDatabaseConnectButtonClicked
void computeDatabaseConnectButtonClicked()
Definition: motion_planning_frame_context.cpp:145
ok
ROSCPP_DECL bool ok()
moveit_warehouse::loadDatabase
warehouse_ros::DatabaseConnection::Ptr loadDatabase()
moveit_rviz_plugin::MotionPlanningFrame::ui_
Ui::MotionPlanningUI * ui_
Definition: motion_planning_frame.h:127
window_manager_interface.h
moveit_rviz_plugin::MotionPlanningFrame::planning_scene_storage_
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
Definition: motion_planning_frame.h:134
ROS_ERROR
#define ROS_ERROR(...)
moveit_rviz_plugin::MotionPlanningFrame::planningPipelineIndexChanged
void planningPipelineIndexChanged(int index)
Definition: motion_planning_frame_context.cpp:91
moveit_rviz_plugin::PlanningSceneDisplay::addBackgroundJob
void addBackgroundJob(const boost::function< void()> &job, const std::string &name)
Definition: planning_scene_display.cpp:255
moveit_rviz_plugin::MotionPlanningFrame::populatePlannerDescription
void populatePlannerDescription(const moveit_msgs::PlannerInterfaceDescription &desc)
Definition: motion_planning_frame_planning.cpp:440
moveit_rviz_plugin::MotionPlanningFrame::planner_descriptions_
std::vector< moveit_msgs::PlannerInterfaceDescription > planner_descriptions_
Definition: motion_planning_frame.h:144
moveit_rviz_plugin
Definition: motion_planning_display.h:80
append
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
moveit_rviz_plugin::MotionPlanningFrame::computeResetDbButtonClicked
void computeResetDbButtonClicked(const std::string &db)
Definition: motion_planning_frame_context.cpp:238
moveit_rviz_plugin::MotionPlanningFrame::populateConstraintsList
void populateConstraintsList()
Definition: motion_planning_frame_planning.cpp:487
moveit_rviz_plugin::MotionPlanningFrame::populatePlanningSceneTreeView
void populatePlanningSceneTreeView()
Definition: motion_planning_frame_scenes.cpp:285
moveit_rviz_plugin::MotionPlanningFrame::planning_display_
MotionPlanningDisplay * planning_display_
Definition: motion_planning_frame.h:125
moveit_rviz_plugin::MotionPlanningFrame::resetDbButtonClicked
void resetDbButtonClicked()
Definition: motion_planning_frame_context.cpp:116
moveit_rviz_plugin::MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper
void computeDatabaseConnectButtonClickedHelper(int mode)
Definition: motion_planning_frame_context.cpp:183
motion_planning_frame.h
moveit_rviz_plugin::MotionPlanningFrame::move_group_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
Definition: motion_planning_frame.h:130
display_context.h


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:25