moveit2
The MoveIt Motion Planning Framework for ROS 2.
motion_planning_frame_manipulation.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: Sachin Chitta */
36 
39 
42 #include <object_recognition_msgs/action/object_recognition.hpp>
43 
44 #include <tf2_eigen/tf2_eigen.hpp>
45 
46 #include "ui_motion_planning_rviz_plugin_frame.h"
47 
48 namespace moveit_rviz_plugin
49 {
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros_visualization.motion_planning_frame_manipulation");
51 
53 void MotionPlanningFrame::detectObjectsButtonClicked()
54 {
55  // TODO (ddengster): Enable when moveit_ros_perception is ported
56  // if (!semantic_world_)
57  // {
58  // const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
59  // if (ps)
60  // {
61  // semantic_world_ = std::make_shared<moveit::semantic_world::SemanticWorld>(ps);
62  // }
63  // if (semantic_world_)
64  // {
65  // semantic_world_->addTableCallback([this] { updateTables(); });
66  // }
67  // }
68  planning_display_->addBackgroundJob([this] { triggerObjectDetection(); }, "detect objects");
69 }
70 
71 void MotionPlanningFrame::processDetectedObjects()
72 {
73  pick_object_name_.clear();
74 
75  std::vector<std::string> object_ids;
76  double min_x = ui_->roi_center_x->value() - ui_->roi_size_x->value() / 2.0;
77  double min_y = ui_->roi_center_y->value() - ui_->roi_size_y->value() / 2.0;
78  double min_z = ui_->roi_center_z->value() - ui_->roi_size_z->value() / 2.0;
79 
80  double max_x = ui_->roi_center_x->value() + ui_->roi_size_x->value() / 2.0;
81  double max_y = ui_->roi_center_y->value() + ui_->roi_size_y->value() / 2.0;
82  double max_z = ui_->roi_center_z->value() + ui_->roi_size_z->value() / 2.0;
83 
84  rclcpp::Time start_time = rclcpp::Clock().now();
85  while (object_ids.empty() && (rclcpp::Clock().now() - start_time) <= rclcpp::Duration::from_seconds(3))
86  {
87  // collect all objects in region of interest
88  {
90  const collision_detection::WorldConstPtr& world = ps->getWorld();
91  object_ids.clear();
92  for (const auto& object : *world)
93  {
94  const auto& position = object.second->pose_.translation();
95  if (position.x() >= min_x && position.x() <= max_x && position.y() >= min_y && position.y() <= max_y &&
96  position.z() >= min_z && position.z() <= max_z)
97  {
98  object_ids.push_back(object.first);
99  }
100  }
101  if (!object_ids.empty())
102  break;
103  }
104  rclcpp::sleep_for(std::chrono::milliseconds(500));
105  }
106 
107  RCLCPP_DEBUG(LOGGER, "Found %d objects", static_cast<int>(object_ids.size()));
108  updateDetectedObjectsList(object_ids);
109 }
110 
111 void MotionPlanningFrame::selectedDetectedObjectChanged()
112 {
113  QList<QListWidgetItem*> sel = ui_->detected_objects_list->selectedItems();
114  if (sel.empty())
115  {
116  RCLCPP_INFO(LOGGER, "No objects to select");
117  return;
118  }
120  std_msgs::msg::ColorRGBA pick_object_color;
121  pick_object_color.r = 1.0;
122  pick_object_color.g = 0.0;
123  pick_object_color.b = 0.0;
124  pick_object_color.a = 1.0;
125 
126  if (ps)
127  {
128  if (!selected_object_name_.empty())
129  ps->removeObjectColor(selected_object_name_);
130  selected_object_name_ = sel[0]->text().toStdString();
131  ps->setObjectColor(selected_object_name_, pick_object_color);
132  }
133 }
134 
135 void MotionPlanningFrame::detectedObjectChanged(QListWidgetItem* /*item*/)
136 {
137 }
138 
139 void MotionPlanningFrame::triggerObjectDetection()
140 {
141  if (!object_recognition_client_)
142  {
143  object_recognition_client_ = rclcpp_action::create_client<object_recognition_msgs::action::ObjectRecognition>(
145  if (!object_recognition_client_->wait_for_action_server(std::chrono::seconds(3)))
146  {
147  RCLCPP_ERROR(LOGGER, "Object recognition action server not responsive");
148  return;
149  }
150  }
151 
152  object_recognition_msgs::action::ObjectRecognition::Goal goal;
153  auto goal_handle_future = object_recognition_client_->async_send_goal(goal);
154  goal_handle_future.wait();
155  if (goal_handle_future.get()->get_status() != rclcpp_action::GoalStatus::STATUS_SUCCEEDED)
156  {
157  RCLCPP_ERROR(LOGGER, "ObjectRecognition client: send goal call failed");
158  return;
159  }
160 }
161 
162 void MotionPlanningFrame::listenDetectedObjects(
163  const object_recognition_msgs::msg::RecognizedObjectArray::ConstSharedPtr& /*msg*/)
164 {
165  rclcpp::sleep_for(std::chrono::seconds(1));
166  planning_display_->addMainLoopJob([this] { processDetectedObjects(); });
167 }
168 
169 void MotionPlanningFrame::updateDetectedObjectsList(const std::vector<std::string>& object_ids)
170 {
171  ui_->detected_objects_list->setUpdatesEnabled(false);
172  bool old_state = ui_->detected_objects_list->blockSignals(true);
173  ui_->detected_objects_list->clear();
174  {
175  for (std::size_t i = 0; i < object_ids.size(); ++i)
176  {
177  QListWidgetItem* item =
178  new QListWidgetItem(QString::fromStdString(object_ids[i]), ui_->detected_objects_list, static_cast<int>(i));
179  item->setToolTip(item->text());
180  Qt::ItemFlags flags = item->flags();
181  flags &= ~(Qt::ItemIsUserCheckable);
182  item->setFlags(flags);
183  ui_->detected_objects_list->addItem(item);
184  }
185  }
186  ui_->detected_objects_list->blockSignals(old_state);
187  ui_->detected_objects_list->setUpdatesEnabled(true);
188  if (!object_ids.empty())
189  ui_->pick_button->setEnabled(true);
190 }
191 
193 void MotionPlanningFrame::updateTables()
194 {
195  RCLCPP_DEBUG(LOGGER, "Update table callback");
196  planning_display_->addBackgroundJob([this] { publishTables(); }, "publish tables");
197 }
198 
199 void MotionPlanningFrame::publishTables()
200 {
201  // TODO (ddengster): Enable when moveit_ros_perception is ported
202  // semantic_world_->addTablesToCollisionWorld();
203 
204  planning_display_->addMainLoopJob([this] { updateSupportSurfacesList(); });
205 }
206 
207 void MotionPlanningFrame::selectedSupportSurfaceChanged()
208 {
209  QList<QListWidgetItem*> sel = ui_->support_surfaces_list->selectedItems();
210  if (sel.empty())
211  {
212  RCLCPP_INFO(LOGGER, "No tables to select");
213  return;
214  }
216  std_msgs::msg::ColorRGBA selected_support_surface_color;
217  selected_support_surface_color.r = 0.0;
218  selected_support_surface_color.g = 0.0;
219  selected_support_surface_color.b = 1.0;
220  selected_support_surface_color.a = 1.0;
221 
222  if (ps)
223  {
224  if (!selected_support_surface_name_.empty())
225  ps->removeObjectColor(selected_support_surface_name_);
226  selected_support_surface_name_ = sel[0]->text().toStdString();
227  ps->setObjectColor(selected_support_surface_name_, selected_support_surface_color);
228  }
229 }
230 
231 void MotionPlanningFrame::updateSupportSurfacesList()
232 {
233  // TODO (ddengster): Enable when moveit_ros_perception is ported
234  // double min_x = ui_->roi_center_x->value() - ui_->roi_size_x->value() / 2.0;
235  // double min_y = ui_->roi_center_y->value() - ui_->roi_size_y->value() / 2.0;
236  // double min_z = ui_->roi_center_z->value() - ui_->roi_size_z->value() / 2.0;
237 
238  // double max_x = ui_->roi_center_x->value() + ui_->roi_size_x->value() / 2.0;
239  // double max_y = ui_->roi_center_y->value() + ui_->roi_size_y->value() / 2.0;
240  // double max_z = ui_->roi_center_z->value() + ui_->roi_size_z->value() / 2.0;
241  // std::vector<std::string> support_ids = semantic_world_->getTableNamesInROI(min_x, min_y, min_z, max_x, max_y,
242  // max_z);
243  std::vector<std::string> support_ids;
244  RCLCPP_INFO(LOGGER, "%d Tables in collision world", static_cast<int>(support_ids.size()));
245 
246  ui_->support_surfaces_list->setUpdatesEnabled(false);
247  bool old_state = ui_->support_surfaces_list->blockSignals(true);
248  ui_->support_surfaces_list->clear();
249  {
250  for (std::size_t i = 0; i < support_ids.size(); ++i)
251  {
252  QListWidgetItem* item =
253  new QListWidgetItem(QString::fromStdString(support_ids[i]), ui_->support_surfaces_list, static_cast<int>(i));
254  item->setToolTip(item->text());
255  Qt::ItemFlags flags = item->flags();
256  flags &= ~(Qt::ItemIsUserCheckable);
257  item->setFlags(flags);
258  ui_->support_surfaces_list->addItem(item);
259  }
260  }
261  ui_->support_surfaces_list->blockSignals(old_state);
262  ui_->support_surfaces_list->setUpdatesEnabled(true);
263 }
264 
266 void MotionPlanningFrame::pickObjectButtonClicked()
267 {
268  RCLCPP_WARN_STREAM(LOGGER, "Pick & Place capability isn't supported yet");
269  // QList<QListWidgetItem*> sel = ui_->detected_objects_list->selectedItems();
270  // QList<QListWidgetItem*> sel_table = ui_->support_surfaces_list->selectedItems();
271  //
272  // std::string group_name = planning_display_->getCurrentPlanningGroup();
273  // if (sel.empty())
274  // {
275  // RCLCPP_INFO(LOGGER, "No objects to pick");
276  // return;
277  // }
278  // pick_object_name_[group_name] = sel[0]->text().toStdString();
279  //
280  // if (!sel_table.empty())
281  // support_surface_name_ = sel_table[0]->text().toStdString();
282  // else
283  // {
284  // if (semantic_world_)
285  // {
286  // const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
287  // if (ps->getWorld()->hasObject(pick_object_name_[group_name]))
288  // {
289  // geometry_msgs::msg::Pose
290  // object_pose(tf2::toMsg(ps->getWorld()->getTransform(pick_object_name_[group_name])));
291  // RCLCPP_DEBUG(LOGGER, "Finding current table for object: " << pick_object_name_[group_name]);
292  // support_surface_name_ = semantic_world_->findObjectTable(object_pose);
293  // }
294  // else
295  // support_surface_name_.clear();
296  // }
297  // else
298  // support_surface_name_.clear();
299  // }
300  // RCLCPP_INFO(LOGGER, "Trying to pick up object %s from support surface %s", pick_object_name_[group_name].c_str(),
301  // support_surface_name_.c_str());
302  // planning_display_->addBackgroundJob([this] { pickObject(); }, "pick");
303 }
304 
305 void MotionPlanningFrame::placeObjectButtonClicked()
306 {
307  QList<QListWidgetItem*> sel_table = ui_->support_surfaces_list->selectedItems();
308  std::string group_name = planning_display_->getCurrentPlanningGroup();
309 
310  if (!sel_table.empty())
311  support_surface_name_ = sel_table[0]->text().toStdString();
312  else
313  {
314  support_surface_name_.clear();
315  RCLCPP_ERROR(LOGGER, "Need to specify table to place object on");
316  return;
317  }
318 
319  ui_->pick_button->setEnabled(false);
320  ui_->place_button->setEnabled(false);
321 
322  std::vector<const moveit::core::AttachedBody*> attached_bodies;
324  if (!ps)
325  {
326  RCLCPP_ERROR(LOGGER, "No planning scene");
327  return;
328  }
329  const moveit::core::JointModelGroup* jmg = ps->getCurrentState().getJointModelGroup(group_name);
330  if (jmg)
331  ps->getCurrentState().getAttachedBodies(attached_bodies, jmg);
332 
333  if (attached_bodies.empty())
334  {
335  RCLCPP_ERROR(LOGGER, "No bodies to place");
336  return;
337  }
338 
339  geometry_msgs::msg::Quaternion upright_orientation;
340  upright_orientation.w = 1.0;
341 
342  // Else place the first one
343  place_poses_.clear();
344  // TODO (ddengster): Enable when moveit_ros_perception is ported
345  // place_poses_ = semantic_world_->generatePlacePoses(support_surface_name_, attached_bodies[0]->getShapes()[0],
346  // upright_orientation, 0.1);
347  // planning_display_->visualizePlaceLocations(place_poses_);
348  // place_object_name_ = attached_bodies[0]->getName();
349  // planning_display_->addBackgroundJob([this] { placeObject(); }, "place");
350 }
351 
352 // void MotionPlanningFrame::pickObject()
353 //{
354 // std::string group_name = planning_display_->getCurrentPlanningGroup();
355 // ui_->pick_button->setEnabled(false);
356 // if (pick_object_name_.find(group_name) == pick_object_name_.end())
357 // {
358 // RCLCPP_ERROR(LOGGER, "No pick object set for this group");
359 // return;
360 // }
361 // if (!support_surface_name_.empty())
362 // {
363 // move_group_->setSupportSurfaceName(support_surface_name_);
364 // }
365 // if (move_group_->pick(pick_object_name_[group_name]))
366 // {
367 // ui_->place_button->setEnabled(true);
368 // }
369 //}
370 //
371 // void MotionPlanningFrame::placeObject()
372 // move_group_->place(place_object_name_, place_poses_);
373 // return;
374 //}
375 } // namespace moveit_rviz_plugin
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW()
get write access to planning scene
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)
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
const std::string OBJECT_RECOGNITION_ACTION
const rclcpp::Logger LOGGER
Definition: async_test.h:31