moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros_visualization.motion_planning_frame_states");
50 
51 void MotionPlanningFrame::populateRobotStatesList()
52 {
53  ui_->list_states->clear();
54  for (std::pair<const std::string, moveit_msgs::msg::RobotState>& robot_state : robot_states_)
55  {
56  QListWidgetItem* item = new QListWidgetItem(QString(robot_state.first.c_str()));
57  ui_->list_states->addItem(item);
58  }
59 }
60 
61 void MotionPlanningFrame::loadStateButtonClicked()
62 {
64  {
65  bool ok;
66 
67  QString text =
68  QInputDialog::getText(this, tr("Robot states to load"), tr("Pattern:"), QLineEdit::Normal, ".*", &ok);
69  if (ok && !text.isEmpty())
70  {
71  loadStoredStates(text.toStdString());
72  }
73  }
74  else
75  {
76  QMessageBox::warning(this, "Warning", "Not connected to a database.");
77  }
78 }
79 
80 void MotionPlanningFrame::loadStoredStates(const std::string& pattern)
81 {
82  std::vector<std::string> names;
83  try
84  {
85  robot_state_storage_->getKnownRobotStates(pattern, names);
86  }
87  catch (std::exception& ex)
88  {
89  QMessageBox::warning(this, "Cannot query the database",
90  QString("Wrongly formatted regular expression for robot states: ").append(ex.what()));
91  return;
92  }
93  // Clear the current list
94  clearStatesButtonClicked();
95 
96  for (const std::string& name : names)
97  {
99  bool got_state = false;
100  try
101  {
102  got_state = robot_state_storage_->getRobotState(rs, name);
103  }
104  catch (std::exception& ex)
105  {
106  RCLCPP_ERROR(LOGGER, "%s", ex.what());
107  }
108  if (!got_state)
109  continue;
110 
111  // Overwrite if exists.
112  if (robot_states_.find(name) != robot_states_.end())
113  {
114  robot_states_.erase(name);
115  }
116 
117  // Store the current start state
118  robot_states_.insert(RobotStatePair(name, *rs));
119  }
120  populateRobotStatesList();
121 }
122 
123 void MotionPlanningFrame::saveRobotStateButtonClicked(const moveit::core::RobotState& state)
124 {
125  bool ok = false;
126 
127  std::stringstream ss;
128  ss << planning_display_->getRobotModel()->getName().c_str() << "_state_" << std::setfill('0') << std::setw(4)
129  << robot_states_.size();
130 
131  QString text = QInputDialog::getText(this, tr("Choose a name"), tr("State name:"), QLineEdit::Normal,
132  QString(ss.str().c_str()), &ok);
133 
134  std::string name;
135  if (ok)
136  {
137  if (!text.isEmpty())
138  {
139  name = text.toStdString();
140  if (robot_states_.find(name) != robot_states_.end())
141  QMessageBox::warning(this, "Name already exists",
142  QString("The name '").append(name.c_str()).append("' already exists. Not creating state."));
143  else
144  {
145  // Store the current start state
146  moveit_msgs::msg::RobotState msg;
148  robot_states_.insert(RobotStatePair(name, msg));
149 
150  // Save to the database if connected
152  {
153  try
154  {
155  robot_state_storage_->addRobotState(msg, name, planning_display_->getRobotModel()->getName());
156  }
157  catch (std::exception& ex)
158  {
159  RCLCPP_ERROR(LOGGER, "Cannot save robot state on the database: %s", ex.what());
160  }
161  }
162  else
163  {
164  QMessageBox::warning(this, "Warning", "Not connected to a database. The state will be created but not stored");
165  }
166  }
167  }
168  else
169  QMessageBox::warning(this, "Start state not saved", "Cannot use an empty name for a new start state.");
170  }
171  populateRobotStatesList();
172 }
173 
174 void MotionPlanningFrame::saveStartStateButtonClicked()
175 {
176  saveRobotStateButtonClicked(*planning_display_->getQueryStartState());
177 }
178 
179 void MotionPlanningFrame::saveGoalStateButtonClicked()
180 {
181  saveRobotStateButtonClicked(*planning_display_->getQueryGoalState());
182 }
183 
184 void MotionPlanningFrame::setAsStartStateButtonClicked()
185 {
186  QListWidgetItem* item = ui_->list_states->currentItem();
187 
188  if (item)
189  {
191  moveit::core::robotStateMsgToRobotState(robot_states_[item->text().toStdString()], robot_state);
193  }
194 }
195 
196 void MotionPlanningFrame::setAsGoalStateButtonClicked()
197 {
198  QListWidgetItem* item = ui_->list_states->currentItem();
199 
200  if (item)
201  {
203  moveit::core::robotStateMsgToRobotState(robot_states_[item->text().toStdString()], robot_state);
204  planning_display_->setQueryGoalState(robot_state);
205  }
206 }
207 
208 void MotionPlanningFrame::removeStateButtonClicked()
209 {
211  {
212  // Warn the user
213  QMessageBox msg_box;
214  msg_box.setText("All the selected states will be removed from the database");
215  msg_box.setInformativeText("Do you want to continue?");
216  msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
217  msg_box.setDefaultButton(QMessageBox::No);
218  int ret = msg_box.exec();
219 
220  switch (ret)
221  {
222  case QMessageBox::Yes:
223  {
224  QList<QListWidgetItem*> found_items = ui_->list_states->selectedItems();
225  for (QListWidgetItem* found_item : found_items)
226  {
227  const std::string& name = found_item->text().toStdString();
228  try
229  {
230  robot_state_storage_->removeRobotState(name);
231  robot_states_.erase(name);
232  }
233  catch (std::exception& ex)
234  {
235  RCLCPP_ERROR(LOGGER, "%s", ex.what());
236  }
237  }
238  break;
239  }
240  }
241  }
242  populateRobotStatesList();
243 }
244 
245 void MotionPlanningFrame::clearStatesButtonClicked()
246 {
247  QMessageBox msg_box;
248  msg_box.setText("Clear all stored robot states (from memory, not from the database)?");
249  msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
250  msg_box.setDefaultButton(QMessageBox::Yes);
251  int ret = msg_box.exec();
252  switch (ret)
253  {
254  case QMessageBox::Yes:
255  {
256  robot_states_.clear();
257  populateRobotStatesList();
258  }
259  break;
260  }
261  return;
262 }
263 
264 } // namespace moveit_rviz_plugin
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h: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
Definition: state_storage.h:47
std::string append(const std::string &left, const std::string &right)
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31