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_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 */
37 
41 
42 #include <QMessageBox>
43 #include <QInputDialog>
44 
45 #include "ui_motion_planning_rviz_plugin_frame.h"
46 
47 namespace moveit_rviz_plugin
48 {
49 
50 void MotionPlanningFrame::populateRobotStatesList()
51 {
52  ui_->list_states->clear();
53  for (std::pair<const std::string, moveit_msgs::msg::RobotState>& robot_state : robot_states_)
54  {
55  QListWidgetItem* item = new QListWidgetItem(QString(robot_state.first.c_str()));
56  ui_->list_states->addItem(item);
57  }
58 }
59 
60 void MotionPlanningFrame::loadStateButtonClicked()
61 {
63  {
64  bool ok;
65 
66  QString text =
67  QInputDialog::getText(this, tr("Robot states to load"), tr("Pattern:"), QLineEdit::Normal, ".*", &ok);
68  if (ok && !text.isEmpty())
69  {
70  loadStoredStates(text.toStdString());
71  }
72  }
73  else
74  {
75  QMessageBox::warning(this, "Warning", "Not connected to a database.");
76  }
77 }
78 
79 void MotionPlanningFrame::loadStoredStates(const std::string& pattern)
80 {
81  std::vector<std::string> names;
82  try
83  {
84  robot_state_storage_->getKnownRobotStates(pattern, names);
85  }
86  catch (std::exception& ex)
87  {
88  QMessageBox::warning(this, "Cannot query the database",
89  QString("Wrongly formatted regular expression for robot states: ").append(ex.what()));
90  return;
91  }
92  // Clear the current list
93  clearStatesButtonClicked();
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  RCLCPP_ERROR(logger_, "%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  }
119  populateRobotStatesList();
120 }
121 
122 void MotionPlanningFrame::saveRobotStateButtonClicked(const moveit::core::RobotState& state)
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  {
141  QMessageBox::warning(this, "Name already exists",
142  QString("The name '").append(name.c_str()).append("' already exists. Not creating state."));
143  }
144  else
145  {
146  // Store the current start state
147  moveit_msgs::msg::RobotState msg;
149  robot_states_.insert(RobotStatePair(name, msg));
150 
151  // Save to the database if connected
153  {
154  try
155  {
156  robot_state_storage_->addRobotState(msg, name, planning_display_->getRobotModel()->getName());
157  }
158  catch (std::exception& ex)
159  {
160  RCLCPP_ERROR(logger_, "Cannot save robot state on the database: %s", ex.what());
161  }
162  }
163  else
164  {
165  QMessageBox::warning(this, "Warning", "Not connected to a database. The state will be created but not stored");
166  }
167  }
168  }
169  else
170  QMessageBox::warning(this, "Start state not saved", "Cannot use an empty name for a new start state.");
171  }
172  populateRobotStatesList();
173 }
174 
175 void MotionPlanningFrame::saveStartStateButtonClicked()
176 {
177  saveRobotStateButtonClicked(*planning_display_->getQueryStartState());
178 }
179 
180 void MotionPlanningFrame::saveGoalStateButtonClicked()
181 {
182  saveRobotStateButtonClicked(*planning_display_->getQueryGoalState());
183 }
184 
185 void MotionPlanningFrame::setAsStartStateButtonClicked()
186 {
187  QListWidgetItem* item = ui_->list_states->currentItem();
188 
189  if (item)
190  {
192  moveit::core::robotStateMsgToRobotState(robot_states_[item->text().toStdString()], robot_state);
194  }
195 }
196 
197 void MotionPlanningFrame::setAsGoalStateButtonClicked()
198 {
199  QListWidgetItem* item = ui_->list_states->currentItem();
200 
201  if (item)
202  {
204  moveit::core::robotStateMsgToRobotState(robot_states_[item->text().toStdString()], robot_state);
205  planning_display_->setQueryGoalState(robot_state);
206  }
207 }
208 
209 void MotionPlanningFrame::removeStateButtonClicked()
210 {
212  {
213  // Warn the user
214  QMessageBox msg_box;
215  msg_box.setText("All the selected states will be removed from the database");
216  msg_box.setInformativeText("Do you want to continue?");
217  msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
218  msg_box.setDefaultButton(QMessageBox::No);
219  int ret = msg_box.exec();
220 
221  switch (ret)
222  {
223  case QMessageBox::Yes:
224  {
225  QList<QListWidgetItem*> found_items = ui_->list_states->selectedItems();
226  for (QListWidgetItem* found_item : found_items)
227  {
228  const std::string& name = found_item->text().toStdString();
229  try
230  {
231  robot_state_storage_->removeRobotState(name);
232  robot_states_.erase(name);
233  }
234  catch (std::exception& ex)
235  {
236  RCLCPP_ERROR(logger_, "%s", ex.what());
237  }
238  }
239  break;
240  }
241  }
242  }
243  populateRobotStatesList();
244 }
245 
246 void MotionPlanningFrame::clearStatesButtonClicked()
247 {
248  QMessageBox msg_box;
249  msg_box.setText("Clear all stored robot states (from memory, not from the database)?");
250  msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
251  msg_box.setDefaultButton(QMessageBox::Yes);
252  int ret = msg_box.exec();
253  switch (ret)
254  {
255  case QMessageBox::Yes:
256  {
257  robot_states_.clear();
258  populateRobotStatesList();
259  }
260  break;
261  }
262  return;
263 }
264 
265 } // namespace moveit_rviz_plugin
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.hpp:90
void setQueryGoalState(const moveit::core::RobotState &goal)
void setQueryStartState(const moveit::core::RobotState &start)
moveit::core::RobotStateConstPtr getQueryStartState() const
moveit::core::RobotStateConstPtr getQueryGoalState() const
std::pair< std::string, moveit_msgs::msg::RobotState > RobotStatePair
moveit_warehouse::RobotStateStoragePtr robot_state_storage_
const moveit::core::RobotModelConstPtr & getRobotModel() const
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
std::string append(const std::string &left, const std::string &right)
name
Definition: setup.py:7