moveit2
The MoveIt Motion Planning Framework for ROS 2.
semantic_world.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: Sachin Chitta */
36 
37 #include <visualization_msgs/msg/marker_array.hpp>
38 #include <geometry_msgs/msg/quaternion.hpp>
39 // MoveIt
41 #include <geometric_shapes/shape_operations.h>
42 #include <moveit_msgs/msg/planning_scene.hpp>
43 // OpenCV
44 #include <opencv2/imgproc/imgproc.hpp>
45 #include <rclcpp/experimental/buffers/intra_process_buffer.hpp>
46 #include <rclcpp/logger.hpp>
47 #include <rclcpp/logging.hpp>
48 #include <rclcpp/node.hpp>
49 #include <rclcpp/publisher.hpp>
50 #include <rclcpp/qos_event.hpp>
51 #include <rclcpp/subscription.hpp>
52 
53 // Eigen
54 #include <tf2_eigen/tf2_eigen.hpp>
55 #include <Eigen/Geometry>
56 
57 namespace moveit
58 {
59 namespace semantic_world
60 {
61 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.perception.semantic_world");
62 
63 SemanticWorld::SemanticWorld(const rclcpp::Node::SharedPtr& node,
64  const planning_scene::PlanningSceneConstPtr& planning_scene)
65  : planning_scene_(planning_scene), node_handle_(node)
66 
67 {
68  table_subscriber_ = node_handle_->create_subscription<object_recognition_msgs::msg::TableArray>(
69  "table_array", rclcpp::SystemDefaultsQoS(),
70  [this](const object_recognition_msgs::msg::TableArray::ConstSharedPtr& msg) { return tableCallback(msg); });
71  visualization_publisher_ =
72  node_handle_->create_publisher<visualization_msgs::msg::MarkerArray>("visualize_place", 20);
73  collision_object_publisher_ =
74  node_handle_->create_publisher<moveit_msgs::msg::CollisionObject>("/collision_object", 20);
75  planning_scene_diff_publisher_ = node_handle_->create_publisher<moveit_msgs::msg::PlanningScene>("planning_scene", 1);
76 }
77 
78 visualization_msgs::msg::MarkerArray
79 SemanticWorld::getPlaceLocationsMarker(const std::vector<geometry_msgs::msg::PoseStamped>& poses) const
80 {
81  RCLCPP_DEBUG(LOGGER, "Visualizing: %d place poses", static_cast<int>(poses.size()));
82  visualization_msgs::msg::MarkerArray marker;
83  for (std::size_t i = 0; i < poses.size(); ++i)
84  {
85  visualization_msgs::msg::Marker m;
86  m.action = m.ADD;
87  m.type = m.SPHERE;
88  m.ns = "place_locations";
89  m.id = i;
90  m.pose = poses[i].pose;
91  m.header = poses[i].header;
92 
93  m.scale.x = 0.02;
94  m.scale.y = 0.02;
95  m.scale.z = 0.02;
96 
97  m.color.r = 1.0;
98  m.color.g = 0.0;
99  m.color.b = 0.0;
100  m.color.a = 1.0;
101  marker.markers.push_back(m);
102  }
103  return marker;
104 }
105 
107 {
108  moveit_msgs::msg::PlanningScene planning_scene;
109  planning_scene.is_diff = true;
110 
111  // Remove the existing tables
112  std::map<std::string, object_recognition_msgs::msg::Table>::iterator it;
113  for (it = current_tables_in_collision_world_.begin(); it != current_tables_in_collision_world_.end(); ++it)
114  {
115  moveit_msgs::msg::CollisionObject co;
116  co.id = it->first;
117  co.operation = moveit_msgs::msg::CollisionObject::REMOVE;
118  planning_scene.world.collision_objects.push_back(co);
119  // collision_object_publisher_.publish(co);
120  }
121 
122  planning_scene_diff_publisher_->publish(planning_scene);
123  planning_scene.world.collision_objects.clear();
124  current_tables_in_collision_world_.clear();
125  // Add the new tables
126  for (std::size_t i = 0; i < table_array_.tables.size(); ++i)
127  {
128  moveit_msgs::msg::CollisionObject co;
129  std::stringstream ss;
130  ss << "table_" << i;
131  co.id = ss.str();
132  current_tables_in_collision_world_[co.id] = table_array_.tables[i];
133  co.operation = moveit_msgs::msg::CollisionObject::ADD;
134 
135  const std::vector<geometry_msgs::msg::Point>& convex_hull = table_array_.tables[i].convex_hull;
136 
137  EigenSTL::vector_Vector3d vertices(convex_hull.size());
138  std::vector<unsigned int> triangles((vertices.size() - 2) * 3);
139  for (unsigned int j = 0; j < convex_hull.size(); ++j)
140  vertices[j] = Eigen::Vector3d(convex_hull[j].x, convex_hull[j].y, convex_hull[j].z);
141  for (unsigned int j = 1; j < triangles.size() - 1; ++j)
142  {
143  unsigned int i3 = j * 3;
144  triangles[i3++] = 0;
145  triangles[i3++] = j;
146  triangles[i3] = j + 1;
147  }
148 
149  shapes::Shape* table_shape = shapes::createMeshFromVertices(vertices, triangles);
150  if (!table_shape)
151  continue;
152 
153  shapes::Mesh* table_mesh = static_cast<shapes::Mesh*>(table_shape);
154  shapes::Mesh* table_mesh_solid = orientPlanarPolygon(*table_mesh);
155  if (!table_mesh_solid)
156  {
157  delete table_shape;
158  continue;
159  }
160 
161  shapes::ShapeMsg table_shape_msg;
162  if (!shapes::constructMsgFromShape(table_mesh_solid, table_shape_msg))
163  {
164  delete table_shape;
165  delete table_mesh_solid;
166  continue;
167  }
168 
169  const shape_msgs::msg::Mesh& table_shape_msg_mesh = boost::get<shape_msgs::msg::Mesh>(table_shape_msg);
170 
171  co.meshes.push_back(table_shape_msg_mesh);
172  co.mesh_poses.push_back(table_array_.tables[i].pose);
173  co.header = table_array_.tables[i].header;
174  planning_scene.world.collision_objects.push_back(co);
175  // collision_object_publisher_.publish(co);
176  delete table_shape;
177  delete table_mesh_solid;
178  }
179  planning_scene_diff_publisher_->publish(planning_scene);
180  return true;
181 }
182 
183 object_recognition_msgs::msg::TableArray SemanticWorld::getTablesInROI(double minx, double miny, double minz,
184  double maxx, double maxy, double maxz) const
185 {
186  object_recognition_msgs::msg::TableArray tables_in_roi;
187  std::map<std::string, object_recognition_msgs::msg::Table>::const_iterator it;
188  for (it = current_tables_in_collision_world_.begin(); it != current_tables_in_collision_world_.end(); ++it)
189  {
190  if (it->second.pose.position.x >= minx && it->second.pose.position.x <= maxx &&
191  it->second.pose.position.y >= miny && it->second.pose.position.y <= maxy &&
192  it->second.pose.position.z >= minz && it->second.pose.position.z <= maxz)
193  {
194  tables_in_roi.tables.push_back(it->second);
195  }
196  }
197  return tables_in_roi;
198 }
199 
200 std::vector<std::string> SemanticWorld::getTableNamesInROI(double minx, double miny, double minz, double maxx,
201  double maxy, double maxz) const
202 {
203  std::vector<std::string> result;
204  std::map<std::string, object_recognition_msgs::msg::Table>::const_iterator it;
205  for (it = current_tables_in_collision_world_.begin(); it != current_tables_in_collision_world_.end(); ++it)
206  {
207  if (it->second.pose.position.x >= minx && it->second.pose.position.x <= maxx &&
208  it->second.pose.position.y >= miny && it->second.pose.position.y <= maxy &&
209  it->second.pose.position.z >= minz && it->second.pose.position.z <= maxz)
210  {
211  result.push_back(it->first);
212  }
213  }
214  return result;
215 }
216 
218 {
219  table_array_.tables.clear();
220  current_tables_in_collision_world_.clear();
221 }
222 
223 std::vector<geometry_msgs::msg::PoseStamped>
224 SemanticWorld::generatePlacePoses(const std::string& table_name, const shapes::ShapeConstPtr& object_shape,
225  const geometry_msgs::msg::Quaternion& object_orientation, double resolution,
226  double delta_height, unsigned int num_heights) const
227 {
228  object_recognition_msgs::msg::Table chosen_table;
229  std::map<std::string, object_recognition_msgs::msg::Table>::const_iterator it =
230  current_tables_in_collision_world_.find(table_name);
231 
232  if (it != current_tables_in_collision_world_.end())
233  {
234  chosen_table = it->second;
235  return generatePlacePoses(chosen_table, object_shape, object_orientation, resolution, delta_height, num_heights);
236  }
237 
238  std::vector<geometry_msgs::msg::PoseStamped> place_poses;
239  RCLCPP_ERROR(LOGGER, "Did not find table %s to place on", table_name.c_str());
240  return place_poses;
241 }
242 
243 std::vector<geometry_msgs::msg::PoseStamped>
244 SemanticWorld::generatePlacePoses(const object_recognition_msgs::msg::Table& chosen_table,
245  const shapes::ShapeConstPtr& object_shape,
246  const geometry_msgs::msg::Quaternion& object_orientation, double resolution,
247  double delta_height, unsigned int num_heights) const
248 {
249  std::vector<geometry_msgs::msg::PoseStamped> place_poses;
250  if (object_shape->type != shapes::MESH && object_shape->type != shapes::SPHERE && object_shape->type != shapes::BOX &&
251  object_shape->type != shapes::CONE)
252  {
253  return place_poses;
254  }
255 
256  double x_min(std::numeric_limits<double>::max()), x_max(-std::numeric_limits<double>::max());
257  double y_min(std::numeric_limits<double>::max()), y_max(-std::numeric_limits<double>::max());
258  double z_min(std::numeric_limits<double>::max()), z_max(-std::numeric_limits<double>::max());
259 
260  Eigen::Quaterniond rotation(object_orientation.x, object_orientation.y, object_orientation.z, object_orientation.w);
261  Eigen::Isometry3d object_pose(rotation);
262  double min_distance_from_edge = 0;
263  double height_above_table = 0;
264 
265  if (object_shape->type == shapes::MESH)
266  {
267  const shapes::Mesh* mesh = static_cast<const shapes::Mesh*>(object_shape.get());
268 
269  for (std::size_t i = 0; i < mesh->vertex_count; ++i)
270  {
271  Eigen::Vector3d position(mesh->vertices[3 * i], mesh->vertices[3 * i + 1], mesh->vertices[3 * i + 2]);
272  position = object_pose * position;
273 
274  if (x_min > position.x())
275  x_min = position.x();
276  if (x_max < position.x())
277  x_max = position.x();
278  if (y_min > position.y())
279  y_min = position.y();
280  if (y_max < position.y())
281  y_max = position.y();
282  if (z_min > position.z())
283  z_min = position.z();
284  if (z_max < position.z())
285  z_max = position.z();
286  }
287  min_distance_from_edge = 0.5 * std::max<double>(fabs(x_max - x_min), fabs(y_max - y_min));
288  height_above_table = -z_min;
289  }
290  else if (object_shape->type == shapes::BOX) // assuming box is being kept down upright
291  {
292  const shapes::Box* box = static_cast<const shapes::Box*>(object_shape.get());
293  min_distance_from_edge = std::max<double>(fabs(box->size[0]), fabs(box->size[1])) / 2.0;
294  height_above_table = fabs(box->size[2]) / 2.0;
295  }
296  else if (object_shape->type == shapes::SPHERE)
297  {
298  const shapes::Sphere* sphere = static_cast<const shapes::Sphere*>(object_shape.get());
299  min_distance_from_edge = sphere->radius;
300  height_above_table = -sphere->radius;
301  }
302  else if (object_shape->type == shapes::CYLINDER) // assuming cylinder is being kept down upright
303  {
304  const shapes::Cylinder* cylinder = static_cast<const shapes::Cylinder*>(object_shape.get());
305  min_distance_from_edge = cylinder->radius;
306  height_above_table = cylinder->length / 2.0;
307  }
308  else if (object_shape->type == shapes::CONE) // assuming cone is being kept down upright
309  {
310  const shapes::Cone* cone = static_cast<const shapes::Cone*>(object_shape.get());
311  min_distance_from_edge = cone->radius;
312  height_above_table = cone->length / 2.0;
313  }
314 
315  return generatePlacePoses(chosen_table, resolution, height_above_table, delta_height, num_heights,
316  min_distance_from_edge);
317 }
318 
319 std::vector<geometry_msgs::msg::PoseStamped>
320 SemanticWorld::generatePlacePoses(const object_recognition_msgs::msg::Table& table, double resolution,
321  double height_above_table, double delta_height, unsigned int num_heights,
322  double min_distance_from_edge) const
323 {
324  std::vector<geometry_msgs::msg::PoseStamped> place_poses;
325  // Assumption that the table's normal is along the Z axis
326  if (table.convex_hull.empty())
327  return place_poses;
328  const int scale_factor = 100;
329  std::vector<cv::Point2f> table_contour;
330  float x_min = table.convex_hull[0].x, x_max = x_min, y_min = table.convex_hull[0].y, y_max = y_min;
331  for (std::size_t j = 1; j < table.convex_hull.size(); ++j)
332  {
333  if (table.convex_hull[j].x < x_min)
334  x_min = table.convex_hull[j].x;
335  else if (table.convex_hull[j].x > x_max)
336  x_max = table.convex_hull[j].x;
337  if (table.convex_hull[j].y < y_min)
338  y_min = table.convex_hull[j].y;
339  else if (table.convex_hull[j].y > y_max)
340  y_max = table.convex_hull[j].y;
341  }
342  for (const geometry_msgs::msg::Point& vertex : table.convex_hull)
343  table_contour.push_back(cv::Point((vertex.x - x_min) * scale_factor, (vertex.y - y_min) * scale_factor));
344 
345  double x_range = fabs(x_max - x_min);
346  double y_range = fabs(y_max - y_min);
347  int max_range = static_cast<int>(x_range) + 1;
348  if (max_range < static_cast<int>(y_range) + 1)
349  max_range = static_cast<int>(y_range) + 1;
350 
351  int image_scale = std::max<int>(max_range, 4);
352  cv::Mat src = cv::Mat::zeros(image_scale * scale_factor, image_scale * scale_factor, CV_8UC1);
353 
354  for (std::size_t j = 0; j < table.convex_hull.size(); ++j)
355  {
356  cv::line(src, table_contour[j], table_contour[(j + 1) % table.convex_hull.size()], cv::Scalar(255), 3, 8);
357  }
358 
359  unsigned int num_x = fabs(x_max - x_min) / resolution + 1;
360  unsigned int num_y = fabs(y_max - y_min) / resolution + 1;
361 
362  RCLCPP_DEBUG(LOGGER, "Num points for possible place operations: %d %d", num_x, num_y);
363 
364  std::vector<std::vector<cv::Point> > contours;
365  std::vector<cv::Vec4i> hierarchy;
366  cv::findContours(src, contours, hierarchy, cv::RETR_TREE, cv::CHAIN_APPROX_SIMPLE);
367 
368  for (std::size_t j = 0; j < num_x; ++j)
369  {
370  int point_x = j * resolution * scale_factor;
371  for (std::size_t k = 0; k < num_y; ++k)
372  {
373  for (std::size_t mm = 0; mm < num_heights; ++mm)
374  {
375  int point_y = k * resolution * scale_factor;
376  cv::Point2f point2f(point_x, point_y);
377  double result = cv::pointPolygonTest(contours[0], point2f, true);
378  if (static_cast<int>(result) >= static_cast<int>(min_distance_from_edge * scale_factor))
379  {
380  Eigen::Vector3d point((double)(point_x) / scale_factor + x_min, (double)(point_y) / scale_factor + y_min,
381  height_above_table + mm * delta_height);
382  Eigen::Isometry3d pose;
383  tf2::fromMsg(table.pose, pose);
384  point = pose * point;
385  geometry_msgs::msg::PoseStamped place_pose;
386  place_pose.pose.orientation.w = 1.0;
387  place_pose.pose.position.x = point.x();
388  place_pose.pose.position.y = point.y();
389  place_pose.pose.position.z = point.z();
390  place_pose.header = table.header;
391  place_poses.push_back(place_pose);
392  }
393  }
394  }
395  }
396  return place_poses;
397 }
398 
399 bool SemanticWorld::isInsideTableContour(const geometry_msgs::msg::Pose& pose,
400  const object_recognition_msgs::msg::Table& table,
401  double min_distance_from_edge, double min_vertical_offset) const
402 {
403  // Assumption that the table's normal is along the Z axis
404  if (table.convex_hull.empty())
405  return false;
406  float x_min = table.convex_hull[0].x, x_max = x_min, y_min = table.convex_hull[0].y, y_max = y_min;
407  for (std::size_t j = 1; j < table.convex_hull.size(); ++j)
408  {
409  if (table.convex_hull[j].x < x_min)
410  x_min = table.convex_hull[j].x;
411  else if (table.convex_hull[j].x > x_max)
412  x_max = table.convex_hull[j].x;
413  if (table.convex_hull[j].y < y_min)
414  y_min = table.convex_hull[j].y;
415  else if (table.convex_hull[j].y > y_max)
416  y_max = table.convex_hull[j].y;
417  }
418  const int scale_factor = 100;
419  std::vector<cv::Point2f> table_contour;
420  for (const geometry_msgs::msg::Point& vertex : table.convex_hull)
421  table_contour.push_back(cv::Point((vertex.x - x_min) * scale_factor, (vertex.y - y_min) * scale_factor));
422 
423  double x_range = fabs(x_max - x_min);
424  double y_range = fabs(y_max - y_min);
425  int max_range = static_cast<int>(x_range) + 1;
426  if (max_range < static_cast<int>(y_range) + 1)
427  max_range = static_cast<int>(y_range) + 1;
428 
429  int image_scale = std::max<int>(max_range, 4);
430  cv::Mat src = cv::Mat::zeros(image_scale * scale_factor, image_scale * scale_factor, CV_8UC1);
431 
432  for (std::size_t j = 0; j < table.convex_hull.size(); ++j)
433  {
434  cv::line(src, table_contour[j], table_contour[(j + 1) % table.convex_hull.size()], cv::Scalar(255), 3, 8);
435  }
436 
437  std::vector<std::vector<cv::Point> > contours;
438  std::vector<cv::Vec4i> hierarchy;
439  cv::findContours(src, contours, hierarchy, cv::RETR_TREE, cv::CHAIN_APPROX_SIMPLE);
440 
441  Eigen::Vector3d point(pose.position.x, pose.position.y, pose.position.z);
442  Eigen::Isometry3d pose_table;
443  tf2::fromMsg(table.pose, pose_table);
444 
445  // Point in table frame
446  point = pose_table.inverse() * point;
447  // Assuming Z axis points upwards for the table
448  if (point.z() < -fabs(min_vertical_offset))
449  {
450  RCLCPP_ERROR(LOGGER, "Object is not above table");
451  return false;
452  }
453 
454  int point_x = (point.x() - x_min) * scale_factor;
455  int point_y = (point.y() - y_min) * scale_factor;
456  cv::Point2f point2f(point_x, point_y);
457  double result = cv::pointPolygonTest(contours[0], point2f, true);
458  RCLCPP_DEBUG(LOGGER, "table distance: %f", result);
459 
460  return static_cast<int>(result) >= static_cast<int>(min_distance_from_edge * scale_factor);
461 }
462 
463 std::string SemanticWorld::findObjectTable(const geometry_msgs::msg::Pose& pose, double min_distance_from_edge,
464  double min_vertical_offset) const
465 {
466  std::map<std::string, object_recognition_msgs::msg::Table>::const_iterator it;
467  for (it = current_tables_in_collision_world_.begin(); it != current_tables_in_collision_world_.end(); ++it)
468  {
469  RCLCPP_DEBUG_STREAM(LOGGER, "Testing table: " << it->first);
470  if (isInsideTableContour(pose, it->second, min_distance_from_edge, min_vertical_offset))
471  return it->first;
472  }
473  return std::string();
474 }
475 
476 void SemanticWorld::tableCallback(const object_recognition_msgs::msg::TableArray::ConstSharedPtr& msg)
477 {
478  table_array_ = *msg;
479  RCLCPP_INFO(LOGGER, "Table callback with %d tables", static_cast<int>(table_array_.tables.size()));
480  transformTableArray(table_array_);
481  // Callback on an update
482  if (table_callback_)
483  {
484  RCLCPP_INFO(LOGGER, "Calling table callback");
485  table_callback_();
486  }
487 }
488 
489 void SemanticWorld::transformTableArray(object_recognition_msgs::msg::TableArray& table_array) const
490 {
491  for (object_recognition_msgs::msg::Table& table : table_array.tables)
492  {
493  std::string original_frame = table.header.frame_id;
494  if (table.convex_hull.empty())
495  continue;
496  RCLCPP_INFO_STREAM(LOGGER, "Original pose: " << table.pose.position.x << "," << table.pose.position.y << ","
497  << table.pose.position.z);
498  std::string error_text;
499  const Eigen::Isometry3d& original_transform = planning_scene_->getFrameTransform(original_frame);
500  Eigen::Isometry3d original_pose;
501  tf2::fromMsg(table.pose, original_pose);
502  original_pose = original_transform * original_pose;
503  table.pose = tf2::toMsg(original_pose);
504  table.header.frame_id = planning_scene_->getTransforms().getTargetFrame();
505  RCLCPP_INFO_STREAM(LOGGER, "Successfully transformed table array from " << original_frame << "to "
506  << table.header.frame_id);
507  RCLCPP_INFO_STREAM(LOGGER, "Transformed pose: " << table.pose.position.x << "," << table.pose.position.y << ","
508  << table.pose.position.z);
509  }
510 }
511 
512 shapes::Mesh* SemanticWorld::orientPlanarPolygon(const shapes::Mesh& polygon) const
513 {
514  if (polygon.vertex_count < 3 || polygon.triangle_count < 1)
515  return nullptr;
516  // first get the normal of the first triangle of the input polygon
517  Eigen::Vector3d vec1, vec2, vec3, normal;
518 
519  int v_idx1 = polygon.triangles[0];
520  int v_idx2 = polygon.triangles[1];
521  int v_idx3 = polygon.triangles[2];
522  vec1 =
523  Eigen::Vector3d(polygon.vertices[v_idx1 * 3], polygon.vertices[v_idx1 * 3 + 1], polygon.vertices[v_idx1 * 3 + 2]);
524  vec2 =
525  Eigen::Vector3d(polygon.vertices[v_idx2 * 3], polygon.vertices[v_idx2 * 3 + 1], polygon.vertices[v_idx2 * 3 + 2]);
526  vec3 =
527  Eigen::Vector3d(polygon.vertices[v_idx3 * 3], polygon.vertices[v_idx3 * 3 + 1], polygon.vertices[v_idx3 * 3 + 2]);
528  vec2 -= vec1;
529  vec3 -= vec1;
530  normal = vec3.cross(vec2);
531 
532  if (normal[2] < 0.0)
533  normal *= -1.0;
534 
535  normal.normalize();
536 
537  shapes::Mesh* solid = new shapes::Mesh(polygon.vertex_count, polygon.triangle_count); // + polygon.vertex_count * 2);
538  solid->type = shapes::MESH;
539 
540  // copy the first set of vertices
541  memcpy(solid->vertices, polygon.vertices, polygon.vertex_count * 3 * sizeof(double));
542  // copy the first set of triangles
543  memcpy(solid->triangles, polygon.triangles, polygon.triangle_count * 3 * sizeof(unsigned int));
544 
545  for (unsigned t_idx = 0; t_idx < polygon.triangle_count; ++t_idx)
546  {
547  int v_idx1 = polygon.triangles[t_idx * 3];
548  int v_idx2 = polygon.triangles[t_idx * 3 + 1];
549  int v_idx3 = polygon.triangles[t_idx * 3 + 2];
550 
551  vec1 = Eigen::Vector3d(polygon.vertices[v_idx1 * 3], polygon.vertices[v_idx1 * 3 + 1],
552  polygon.vertices[v_idx1 * 3 + 2]);
553  vec2 = Eigen::Vector3d(polygon.vertices[v_idx2 * 3], polygon.vertices[v_idx2 * 3 + 1],
554  polygon.vertices[v_idx2 * 3 + 2]);
555  vec3 = Eigen::Vector3d(polygon.vertices[v_idx3 * 3], polygon.vertices[v_idx3 * 3 + 1],
556  polygon.vertices[v_idx3 * 3 + 2]);
557 
558  vec2 -= vec1;
559  vec3 -= vec1;
560 
561  Eigen::Vector3d triangle_normal = vec2.cross(vec1);
562 
563  if (triangle_normal.dot(normal) < 0.0)
564  std::swap(solid->triangles[t_idx * 3 + 1], solid->triangles[t_idx * 3 + 2]);
565  }
566  return solid;
567 }
568 
569 shapes::Mesh* SemanticWorld::createSolidMeshFromPlanarPolygon(const shapes::Mesh& polygon, double thickness) const
570 {
571  if (polygon.vertex_count < 3 || polygon.triangle_count < 1 || thickness <= 0)
572  return nullptr;
573  // first get the normal of the first triangle of the input polygon
574  Eigen::Vector3d vec1, vec2, vec3, normal;
575 
576  int v_idx1 = polygon.triangles[0];
577  int v_idx2 = polygon.triangles[1];
578  int v_idx3 = polygon.triangles[2];
579  vec1 =
580  Eigen::Vector3d(polygon.vertices[v_idx1 * 3], polygon.vertices[v_idx1 * 3 + 1], polygon.vertices[v_idx1 * 3 + 2]);
581  vec2 =
582  Eigen::Vector3d(polygon.vertices[v_idx2 * 3], polygon.vertices[v_idx2 * 3 + 1], polygon.vertices[v_idx2 * 3 + 2]);
583  vec3 =
584  Eigen::Vector3d(polygon.vertices[v_idx3 * 3], polygon.vertices[v_idx3 * 3 + 1], polygon.vertices[v_idx3 * 3 + 2]);
585  vec2 -= vec1;
586  vec3 -= vec1;
587  normal = vec3.cross(vec2);
588 
589  if (normal[2] < 0.0)
590  normal *= -1.0;
591 
592  normal.normalize();
593 
594  // shapes::Mesh* solid = new shapes::Mesh(polygon.vertex_count, polygon.triangle_count);// + polygon.vertex_count *
595  // 2);
596 
597  shapes::Mesh* solid =
598  new shapes::Mesh(polygon.vertex_count * 2, polygon.triangle_count * 2); // + polygon.vertex_count * 2);
599  solid->type = shapes::MESH;
600 
601  // copy the first set of vertices
602  memcpy(solid->vertices, polygon.vertices, polygon.vertex_count * 3 * sizeof(double));
603  // copy the first set of triangles
604  memcpy(solid->triangles, polygon.triangles, polygon.triangle_count * 3 * sizeof(unsigned int));
605 
606  for (unsigned t_idx = 0; t_idx < polygon.triangle_count; ++t_idx)
607  {
608  solid->triangles[(t_idx + polygon.triangle_count) * 3 + 0] = solid->triangles[t_idx * 3 + 0] + polygon.vertex_count;
609  solid->triangles[(t_idx + polygon.triangle_count) * 3 + 1] = solid->triangles[t_idx * 3 + 1] + polygon.vertex_count;
610  solid->triangles[(t_idx + polygon.triangle_count) * 3 + 2] = solid->triangles[t_idx * 3 + 2] + polygon.vertex_count;
611 
612  int v_idx1 = polygon.triangles[t_idx * 3];
613  int v_idx2 = polygon.triangles[t_idx * 3 + 1];
614  int v_idx3 = polygon.triangles[t_idx * 3 + 2];
615 
616  vec1 = Eigen::Vector3d(polygon.vertices[v_idx1 * 3], polygon.vertices[v_idx1 * 3 + 1],
617  polygon.vertices[v_idx1 * 3 + 2]);
618  vec2 = Eigen::Vector3d(polygon.vertices[v_idx2 * 3], polygon.vertices[v_idx2 * 3 + 1],
619  polygon.vertices[v_idx2 * 3 + 2]);
620  vec3 = Eigen::Vector3d(polygon.vertices[v_idx3 * 3], polygon.vertices[v_idx3 * 3 + 1],
621  polygon.vertices[v_idx3 * 3 + 2]);
622 
623  vec2 -= vec1;
624  vec3 -= vec1;
625 
626  Eigen::Vector3d triangle_normal = vec2.cross(vec1);
627 
628  if (triangle_normal.dot(normal) < 0.0)
629  std::swap(solid->triangles[t_idx * 3 + 1], solid->triangles[t_idx * 3 + 2]);
630  else
631  std::swap(solid->triangles[(t_idx + polygon.triangle_count) * 3 + 1],
632  solid->triangles[(t_idx + polygon.triangle_count) * 3 + 2]);
633  }
634 
635  for (unsigned v_idx = 0; v_idx < polygon.vertex_count; ++v_idx)
636  {
637  solid->vertices[(v_idx + polygon.vertex_count) * 3 + 0] = solid->vertices[v_idx * 3 + 0] - thickness * normal[0];
638  solid->vertices[(v_idx + polygon.vertex_count) * 3 + 1] = solid->vertices[v_idx * 3 + 1] - thickness * normal[1];
639  solid->vertices[(v_idx + polygon.vertex_count) * 3 + 2] = solid->vertices[v_idx * 3 + 2] - thickness * normal[2];
640  }
641 
642  return solid;
643 }
644 } // namespace semantic_world
645 } // namespace moveit
std::vector< std::string > getTableNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz) const
Get all the tables within a region of interest.
object_recognition_msgs::msg::TableArray getTablesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz) const
Get all the tables within a region of interest.
visualization_msgs::msg::MarkerArray getPlaceLocationsMarker(const std::vector< geometry_msgs::msg::PoseStamped > &poses) const
std::string findObjectTable(const geometry_msgs::msg::Pose &pose, double min_distance_from_edge=0.0, double min_vertical_offset=0.0) const
std::vector< geometry_msgs::msg::PoseStamped > generatePlacePoses(const std::string &table_name, const shapes::ShapeConstPtr &object_shape, const geometry_msgs::msg::Quaternion &object_orientation, double resolution, double delta_height=0.01, unsigned int num_heights=2) const
Generate possible place poses on the table for a given object. This chooses appropriate values for mi...
bool isInsideTableContour(const geometry_msgs::msg::Pose &pose, const object_recognition_msgs::msg::Table &table, double min_distance_from_edge=0.0, double min_vertical_offset=0.0) const
SemanticWorld(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningSceneConstPtr &planning_scene)
A (simple) semantic world representation for pick and place and other tasks. Currently this is used o...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
Main namespace for MoveIt.
Definition: exceptions.h:43
x
Definition: pick.py:64
y
Definition: pick.py:65
z
Definition: pick.py:66
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
Definition: async_test.h:31