motion_planning_frame_states.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, 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: Mario Prats, Ioan Sucan */
36 
41 
42 #include <QMessageBox>
43 #include <QInputDialog>
44 
45 #include "ui_motion_planning_rviz_plugin_frame.h"
46 
47 namespace moveit_rviz_plugin
48 {
50 {
51  ui_->list_states->clear();
52  for (std::pair<const std::string, moveit_msgs::RobotState>& robot_state : robot_states_)
53  {
54  QListWidgetItem* item = new QListWidgetItem(QString(robot_state.first.c_str()));
55  ui_->list_states->addItem(item);
56  }
57 }
58 
60 {
62  {
63  bool ok;
64 
65  QString text =
66  QInputDialog::getText(this, tr("Robot states to load"), tr("Pattern:"), QLineEdit::Normal, ".*", &ok);
67  if (ok && !text.isEmpty())
68  {
69  loadStoredStates(text.toStdString());
70  }
71  }
72  else
73  {
74  QMessageBox::warning(this, "Warning", "Not connected to a database.");
75  }
76 }
77 
78 void MotionPlanningFrame::loadStoredStates(const std::string& pattern)
79 {
80  std::vector<std::string> names;
81  try
82  {
83  robot_state_storage_->getKnownRobotStates(pattern, names);
84  }
85  catch (std::exception& ex)
86  {
87  QMessageBox::warning(this, "Cannot query the database",
88  QString("Wrongly formatted regular expression for robot states: ").append(ex.what()));
89  return;
90  }
91 
92  // Clear the current list
94 
95  for (const std::string& name : names)
96  {
98  bool got_state = false;
99  try
100  {
101  got_state = robot_state_storage_->getRobotState(rs, name);
102  }
103  catch (std::exception& ex)
104  {
105  ROS_ERROR("%s", ex.what());
106  }
107  if (!got_state)
108  continue;
109 
110  // Overwrite if exists.
111  if (robot_states_.find(name) != robot_states_.end())
112  {
113  robot_states_.erase(name);
114  }
115 
116  // Store the current start state
117  robot_states_.insert(RobotStatePair(name, *rs));
118  }
120 }
121 
123 {
124  bool ok = false;
125 
126  std::stringstream ss;
127  ss << planning_display_->getRobotModel()->getName().c_str() << "_state_" << std::setfill('0') << std::setw(4)
128  << robot_states_.size();
129 
130  QString text = QInputDialog::getText(this, tr("Choose a name"), tr("State name:"), QLineEdit::Normal,
131  QString(ss.str().c_str()), &ok);
132 
133  std::string name;
134  if (ok)
135  {
136  if (!text.isEmpty())
137  {
138  name = text.toStdString();
139  if (robot_states_.find(name) != robot_states_.end())
140  QMessageBox::warning(this, "Name already exists",
141  QString("The name '").append(name.c_str()).append("' already exists. Not creating state."));
142  else
143  {
144  // Store the current start state
145  moveit_msgs::RobotState msg;
147  robot_states_.insert(RobotStatePair(name, msg));
148 
149  // Save to the database if connected
151  {
152  try
153  {
154  robot_state_storage_->addRobotState(msg, name, planning_display_->getRobotModel()->getName());
155  }
156  catch (std::exception& ex)
157  {
158  ROS_ERROR("Cannot save robot state on the database: %s", ex.what());
159  }
160  }
161  else
162  {
163  QMessageBox::warning(this, "Warning", "Not connected to a database. The state will be created but not stored");
164  }
165  }
166  }
167  else
168  QMessageBox::warning(this, "Start state not saved", "Cannot use an empty name for a new start state.");
169  }
171 }
172 
174 {
176 }
177 
179 {
181 }
182 
184 {
185  QListWidgetItem* item = ui_->list_states->currentItem();
186 
187  if (item)
188  {
190  moveit::core::robotStateMsgToRobotState(robot_states_[item->text().toStdString()], robot_state);
192  }
193 }
194 
196 {
197  QListWidgetItem* item = ui_->list_states->currentItem();
198 
199  if (item)
200  {
202  moveit::core::robotStateMsgToRobotState(robot_states_[item->text().toStdString()], robot_state);
203  planning_display_->setQueryGoalState(robot_state);
204  }
205 }
206 
208 {
210  {
211  // Warn the user
212  QMessageBox msg_box;
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();
218 
219  switch (ret)
220  {
221  case QMessageBox::Yes:
222  {
223  QList<QListWidgetItem*> found_items = ui_->list_states->selectedItems();
224  for (QListWidgetItem* found_item : found_items)
225  {
226  const std::string& name = found_item->text().toStdString();
227  try
228  {
229  robot_state_storage_->removeRobotState(name);
230  robot_states_.erase(name);
231  }
232  catch (std::exception& ex)
233  {
234  ROS_ERROR("%s", ex.what());
235  }
236  }
237  break;
238  }
239  }
240  }
242 }
243 
245 {
246  QMessageBox msg_box;
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();
251  switch (ret)
252  {
253  case QMessageBox::Yes:
254  {
255  robot_states_.clear();
257  }
258  break;
259  }
260  return;
261 }
262 
263 } // namespace moveit_rviz_plugin
moveit_rviz_plugin::MotionPlanningFrame::loadStoredStates
void loadStoredStates(const std::string &pattern)
Definition: motion_planning_frame_states.cpp:110
moveit_rviz_plugin::MotionPlanningFrame::saveStartStateButtonClicked
void saveStartStateButtonClicked()
Definition: motion_planning_frame_states.cpp:205
moveit_rviz_plugin::MotionPlanningFrame::populateRobotStatesList
void populateRobotStatesList()
Definition: motion_planning_frame_states.cpp:81
boost::shared_ptr
moveit_rviz_plugin::MotionPlanningFrame::robot_state_storage_
moveit_warehouse::RobotStateStoragePtr robot_state_storage_
Definition: motion_planning_frame.h:136
motion_planning_display.h
moveit_rviz_plugin::MotionPlanningFrame::RobotStatePair
std::pair< std::string, moveit_msgs::RobotState > RobotStatePair
Definition: motion_planning_frame.h:141
moveit_rviz_plugin::MotionPlanningFrame::setAsStartStateButtonClicked
void setAsStartStateButtonClicked()
Definition: motion_planning_frame_states.cpp:215
moveit_rviz_plugin::MotionPlanningFrame::removeStateButtonClicked
void removeStateButtonClicked()
Definition: motion_planning_frame_states.cpp:239
moveit::core::RobotState
state_storage.h
ok
ROSCPP_DECL bool ok()
moveit_rviz_plugin::MotionPlanningFrame::saveRobotStateButtonClicked
void saveRobotStateButtonClicked(const moveit::core::RobotState &state)
Definition: motion_planning_frame_states.cpp:154
moveit_rviz_plugin::MotionPlanningFrame::ui_
Ui::MotionPlanningUI * ui_
Definition: motion_planning_frame.h:127
ROS_ERROR
#define ROS_ERROR(...)
moveit_rviz_plugin::MotionPlanningFrame::clearStatesButtonClicked
void clearStatesButtonClicked()
Definition: motion_planning_frame_states.cpp:276
moveit_rviz_plugin::MotionPlanningDisplay::getQueryStartState
moveit::core::RobotStateConstPtr getQueryStartState() const
Definition: motion_planning_display.h:99
name
name
text
text
moveit_rviz_plugin
Definition: motion_planning_display.h:80
moveit_rviz_plugin::MotionPlanningFrame::saveGoalStateButtonClicked
void saveGoalStateButtonClicked()
Definition: motion_planning_frame_states.cpp:210
moveit_rviz_plugin::MotionPlanningDisplay::setQueryStartState
void setQueryStartState(const moveit::core::RobotState &start)
Definition: motion_planning_display.cpp:974
append
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
moveit_rviz_plugin::MotionPlanningFrame::setAsGoalStateButtonClicked
void setAsGoalStateButtonClicked()
Definition: motion_planning_frame_states.cpp:227
moveit_rviz_plugin::PlanningSceneDisplay::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: planning_scene_display.cpp:310
conversions.h
moveit_rviz_plugin::MotionPlanningFrame::planning_display_
MotionPlanningDisplay * planning_display_
Definition: motion_planning_frame.h:125
moveit_rviz_plugin::MotionPlanningDisplay::setQueryGoalState
void setQueryGoalState(const moveit::core::RobotState &goal)
Definition: motion_planning_display.cpp:980
moveit_rviz_plugin::MotionPlanningFrame::loadStateButtonClicked
void loadStateButtonClicked()
Definition: motion_planning_frame_states.cpp:91
motion_planning_frame.h
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
moveit_rviz_plugin::MotionPlanningFrame::robot_states_
RobotStateMap robot_states_
Definition: motion_planning_frame.h:142
moveit::core::robotStateMsgToRobotState
bool robotStateMsgToRobotState(const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
moveit_rviz_plugin::MotionPlanningDisplay::getQueryGoalState
moveit::core::RobotStateConstPtr getQueryGoalState() const
Definition: motion_planning_display.h:104


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