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


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sat Apr 27 2024 02:26:39