37#include <visualization_msgs/msg/marker_array.hpp>
38#include <geometry_msgs/msg/quaternion.hpp>
41#include <geometric_shapes/shape_operations.h>
42#include <moveit_msgs/msg/planning_scene.hpp>
45#include <opencv2/imgproc/imgproc.hpp>
46#include <rclcpp/experimental/buffers/intra_process_buffer.hpp>
47#include <rclcpp/logger.hpp>
48#include <rclcpp/logging.hpp>
49#include <rclcpp/node.hpp>
50#include <rclcpp/publisher.hpp>
51#include <rclcpp/version.h>
52#if RCLCPP_VERSION_GTE(20, 0, 0)
53#include <rclcpp/event_handler.hpp>
55#include <rclcpp/qos_event.hpp>
57#include <rclcpp/subscription.hpp>
60#include <tf2_eigen/tf2_eigen.hpp>
61#include <Eigen/Geometry>
65namespace semantic_world
70 : planning_scene_(
planning_scene), node_handle_(node), logger_(
moveit::getLogger(
"moveit.ros.semantic_world"))
73 table_subscriber_ = node_handle_->create_subscription<object_recognition_msgs::msg::TableArray>(
74 "table_array", rclcpp::SystemDefaultsQoS(),
75 [
this](
const object_recognition_msgs::msg::TableArray::ConstSharedPtr& msg) {
return tableCallback(msg); });
76 visualization_publisher_ =
77 node_handle_->create_publisher<visualization_msgs::msg::MarkerArray>(
"visualize_place", 20);
78 collision_object_publisher_ =
79 node_handle_->create_publisher<moveit_msgs::msg::CollisionObject>(
"/collision_object", 20);
80 planning_scene_diff_publisher_ = node_handle_->create_publisher<moveit_msgs::msg::PlanningScene>(
"planning_scene", 1);
83visualization_msgs::msg::MarkerArray
86 RCLCPP_DEBUG(logger_,
"Visualizing: %d place poses",
static_cast<int>(poses.size()));
87 visualization_msgs::msg::MarkerArray marker;
88 for (std::size_t i = 0; i < poses.size(); ++i)
90 visualization_msgs::msg::Marker m;
93 m.ns =
"place_locations";
95 m.pose = poses[i].pose;
96 m.header = poses[i].header;
106 marker.markers.push_back(m);
117 std::map<std::string, object_recognition_msgs::msg::Table>::iterator it;
118 for (it = current_tables_in_collision_world_.begin(); it != current_tables_in_collision_world_.end(); ++it)
120 moveit_msgs::msg::CollisionObject co;
122 co.operation = moveit_msgs::msg::CollisionObject::REMOVE;
129 current_tables_in_collision_world_.clear();
131 for (std::size_t i = 0; i < table_array_.tables.size(); ++i)
133 moveit_msgs::msg::CollisionObject co;
134 std::stringstream ss;
137 current_tables_in_collision_world_[co.id] = table_array_.tables[i];
138 co.operation = moveit_msgs::msg::CollisionObject::ADD;
140 const std::vector<geometry_msgs::msg::Point>& convex_hull = table_array_.tables[i].convex_hull;
142 EigenSTL::vector_Vector3d vertices(convex_hull.size());
143 std::vector<unsigned int> triangles((vertices.size() - 2) * 3);
144 for (
unsigned int j = 0; j < convex_hull.size(); ++j)
145 vertices[j] = Eigen::Vector3d(convex_hull[j].x, convex_hull[j].y, convex_hull[j].z);
146 for (
unsigned int j = 1; j < triangles.size() - 1; ++j)
148 unsigned int i3 = j * 3;
151 triangles[i3] = j + 1;
154 shapes::Shape* table_shape = shapes::createMeshFromVertices(vertices, triangles);
158 shapes::Mesh* table_mesh =
static_cast<shapes::Mesh*
>(table_shape);
159 shapes::Mesh* table_mesh_solid = orientPlanarPolygon(*table_mesh);
160 if (!table_mesh_solid)
166 shapes::ShapeMsg table_shape_msg;
167 if (!shapes::constructMsgFromShape(table_mesh_solid, table_shape_msg))
170 delete table_mesh_solid;
174 const shape_msgs::msg::Mesh& table_shape_msg_mesh = boost::get<shape_msgs::msg::Mesh>(table_shape_msg);
176 co.meshes.push_back(table_shape_msg_mesh);
177 co.mesh_poses.push_back(table_array_.tables[i].pose);
178 co.header = table_array_.tables[i].header;
182 delete table_mesh_solid;
189 double maxx,
double maxy,
double maxz)
const
191 object_recognition_msgs::msg::TableArray tables_in_roi;
192 std::map<std::string, object_recognition_msgs::msg::Table>::const_iterator it;
193 for (it = current_tables_in_collision_world_.begin(); it != current_tables_in_collision_world_.end(); ++it)
195 if (it->second.pose.position.x >= minx && it->second.pose.position.x <= maxx &&
196 it->second.pose.position.y >= miny && it->second.pose.position.y <= maxy &&
197 it->second.pose.position.z >= minz && it->second.pose.position.z <= maxz)
199 tables_in_roi.tables.push_back(it->second);
202 return tables_in_roi;
206 double maxy,
double maxz)
const
208 std::vector<std::string> result;
209 std::map<std::string, object_recognition_msgs::msg::Table>::const_iterator it;
210 for (it = current_tables_in_collision_world_.begin(); it != current_tables_in_collision_world_.end(); ++it)
212 if (it->second.pose.position.x >= minx && it->second.pose.position.x <= maxx &&
213 it->second.pose.position.y >= miny && it->second.pose.position.y <= maxy &&
214 it->second.pose.position.z >= minz && it->second.pose.position.z <= maxz)
216 result.push_back(it->first);
224 table_array_.tables.clear();
225 current_tables_in_collision_world_.clear();
228std::vector<geometry_msgs::msg::PoseStamped>
230 const geometry_msgs::msg::Quaternion& object_orientation,
double resolution,
231 double delta_height,
unsigned int num_heights)
const
233 object_recognition_msgs::msg::Table chosen_table;
234 std::map<std::string, object_recognition_msgs::msg::Table>::const_iterator it =
235 current_tables_in_collision_world_.find(table_name);
237 if (it != current_tables_in_collision_world_.end())
239 chosen_table = it->second;
240 return generatePlacePoses(chosen_table, object_shape, object_orientation, resolution, delta_height, num_heights);
243 std::vector<geometry_msgs::msg::PoseStamped> place_poses;
244 RCLCPP_ERROR(logger_,
"Did not find table %s to place on", table_name.c_str());
248std::vector<geometry_msgs::msg::PoseStamped>
250 const shapes::ShapeConstPtr& object_shape,
251 const geometry_msgs::msg::Quaternion& object_orientation,
double resolution,
252 double delta_height,
unsigned int num_heights)
const
254 std::vector<geometry_msgs::msg::PoseStamped> place_poses;
255 if (object_shape->type != shapes::MESH && object_shape->type != shapes::SPHERE && object_shape->type != shapes::BOX &&
256 object_shape->type != shapes::CYLINDER && object_shape->type != shapes::CONE)
261 double x_min(std::numeric_limits<double>::max()), x_max(-std::numeric_limits<double>::max());
262 double y_min(std::numeric_limits<double>::max()), y_max(-std::numeric_limits<double>::max());
263 double z_min(std::numeric_limits<double>::max()), z_max(-std::numeric_limits<double>::max());
265 Eigen::Quaterniond rotation(object_orientation.x, object_orientation.y, object_orientation.z, object_orientation.w);
266 Eigen::Isometry3d object_pose(rotation);
267 double min_distance_from_edge = 0;
268 double height_above_table = 0;
270 if (object_shape->type == shapes::MESH)
272 const shapes::Mesh* mesh =
static_cast<const shapes::Mesh*
>(object_shape.get());
274 for (std::size_t i = 0; i < mesh->vertex_count; ++i)
276 Eigen::Vector3d position(mesh->vertices[3 * i], mesh->vertices[3 * i + 1], mesh->vertices[3 * i + 2]);
277 position = object_pose * position;
279 if (x_min > position.x())
280 x_min = position.x();
281 if (x_max < position.x())
282 x_max = position.x();
283 if (y_min > position.y())
284 y_min = position.y();
285 if (y_max < position.y())
286 y_max = position.y();
287 if (z_min > position.z())
288 z_min = position.z();
289 if (z_max < position.z())
290 z_max = position.z();
292 min_distance_from_edge = 0.5 * std::max<double>(fabs(x_max - x_min), fabs(y_max - y_min));
293 height_above_table = -z_min;
295 else if (object_shape->type == shapes::BOX)
297 const shapes::Box* box =
static_cast<const shapes::Box*
>(object_shape.get());
298 min_distance_from_edge = std::max<double>(fabs(box->size[0]), fabs(box->size[1])) / 2.0;
299 height_above_table = fabs(box->size[2]) / 2.0;
301 else if (object_shape->type == shapes::SPHERE)
303 const shapes::Sphere* sphere =
static_cast<const shapes::Sphere*
>(object_shape.get());
304 min_distance_from_edge = sphere->radius;
305 height_above_table = -sphere->radius;
307 else if (object_shape->type == shapes::CYLINDER)
309 const shapes::Cylinder* cylinder =
static_cast<const shapes::Cylinder*
>(object_shape.get());
310 min_distance_from_edge = cylinder->radius;
311 height_above_table = cylinder->length / 2.0;
313 else if (object_shape->type == shapes::CONE)
315 const shapes::Cone* cone =
static_cast<const shapes::Cone*
>(object_shape.get());
316 min_distance_from_edge = cone->radius;
317 height_above_table = cone->length / 2.0;
320 return generatePlacePoses(chosen_table, resolution, height_above_table, delta_height, num_heights,
321 min_distance_from_edge);
324std::vector<geometry_msgs::msg::PoseStamped>
326 double height_above_table,
double delta_height,
unsigned int num_heights,
327 double min_distance_from_edge)
const
329 std::vector<geometry_msgs::msg::PoseStamped> place_poses;
331 if (table.convex_hull.empty())
333 const int scale_factor = 100;
334 std::vector<cv::Point2f> table_contour;
335 float x_min = table.convex_hull[0].x, x_max = x_min, y_min = table.convex_hull[0].y, y_max = y_min;
336 for (std::size_t j = 1; j < table.convex_hull.size(); ++j)
338 if (table.convex_hull[j].x < x_min)
340 x_min = table.convex_hull[j].x;
342 else if (table.convex_hull[j].x > x_max)
344 x_max = table.convex_hull[j].x;
346 if (table.convex_hull[j].y < y_min)
348 y_min = table.convex_hull[j].y;
350 else if (table.convex_hull[j].y > y_max)
352 y_max = table.convex_hull[j].y;
355 for (
const geometry_msgs::msg::Point& vertex : table.convex_hull)
356 table_contour.push_back(cv::Point((vertex.x - x_min) * scale_factor, (vertex.y - y_min) * scale_factor));
358 double x_range = fabs(x_max - x_min);
359 double y_range = fabs(y_max - y_min);
360 int max_range =
static_cast<int>(x_range) + 1;
361 if (max_range <
static_cast<int>(y_range) + 1)
362 max_range =
static_cast<int>(y_range) + 1;
364 int image_scale = std::max<int>(max_range, 4);
365 cv::Mat src = cv::Mat::zeros(image_scale * scale_factor, image_scale * scale_factor, CV_8UC1);
367 for (std::size_t j = 0; j < table.convex_hull.size(); ++j)
369 cv::line(src, table_contour[j], table_contour[(j + 1) % table.convex_hull.size()], cv::Scalar(255), 3, 8);
372 unsigned int num_x = fabs(x_max - x_min) / resolution + 1;
373 unsigned int num_y = fabs(y_max - y_min) / resolution + 1;
375 RCLCPP_DEBUG(logger_,
"Num points for possible place operations: %d %d", num_x, num_y);
377 std::vector<std::vector<cv::Point> > contours;
378 std::vector<cv::Vec4i> hierarchy;
379 cv::findContours(src, contours, hierarchy, cv::RETR_TREE, cv::CHAIN_APPROX_SIMPLE);
381 for (std::size_t j = 0; j < num_x; ++j)
383 int point_x = j * resolution * scale_factor;
384 for (std::size_t k = 0; k < num_y; ++k)
386 for (std::size_t mm = 0; mm < num_heights; ++mm)
388 int point_y = k * resolution * scale_factor;
389 cv::Point2f point2f(point_x, point_y);
390 double result = cv::pointPolygonTest(contours[0], point2f,
true);
391 if (
static_cast<int>(result) >=
static_cast<int>(min_distance_from_edge * scale_factor))
393 Eigen::Vector3d point(
static_cast<double>(point_x) / scale_factor + x_min,
394 static_cast<double>(point_y) / scale_factor + y_min,
395 height_above_table + mm * delta_height);
396 Eigen::Isometry3d pose;
397 tf2::fromMsg(table.pose, pose);
398 point = pose * point;
399 geometry_msgs::msg::PoseStamped place_pose;
400 place_pose.pose.orientation.w = 1.0;
401 place_pose.pose.position.x = point.x();
402 place_pose.pose.position.y = point.y();
403 place_pose.pose.position.z = point.z();
404 place_pose.header = table.header;
405 place_poses.push_back(place_pose);
414 const object_recognition_msgs::msg::Table& table,
415 double min_distance_from_edge,
double min_vertical_offset)
const
418 if (table.convex_hull.empty())
420 float x_min = table.convex_hull[0].x, x_max = x_min, y_min = table.convex_hull[0].y, y_max = y_min;
421 for (std::size_t j = 1; j < table.convex_hull.size(); ++j)
423 if (table.convex_hull[j].x < x_min)
425 x_min = table.convex_hull[j].x;
427 else if (table.convex_hull[j].x > x_max)
429 x_max = table.convex_hull[j].x;
431 if (table.convex_hull[j].y < y_min)
433 y_min = table.convex_hull[j].y;
435 else if (table.convex_hull[j].y > y_max)
437 y_max = table.convex_hull[j].y;
440 const int scale_factor = 100;
441 std::vector<cv::Point2f> table_contour;
442 for (
const geometry_msgs::msg::Point& vertex : table.convex_hull)
443 table_contour.push_back(cv::Point((vertex.x - x_min) * scale_factor, (vertex.y - y_min) * scale_factor));
445 double x_range = fabs(x_max - x_min);
446 double y_range = fabs(y_max - y_min);
447 int max_range =
static_cast<int>(x_range) + 1;
448 if (max_range <
static_cast<int>(y_range) + 1)
449 max_range =
static_cast<int>(y_range) + 1;
451 int image_scale = std::max<int>(max_range, 4);
452 cv::Mat src = cv::Mat::zeros(image_scale * scale_factor, image_scale * scale_factor, CV_8UC1);
454 for (std::size_t j = 0; j < table.convex_hull.size(); ++j)
456 cv::line(src, table_contour[j], table_contour[(j + 1) % table.convex_hull.size()], cv::Scalar(255), 3, 8);
459 std::vector<std::vector<cv::Point> > contours;
460 std::vector<cv::Vec4i> hierarchy;
461 cv::findContours(src, contours, hierarchy, cv::RETR_TREE, cv::CHAIN_APPROX_SIMPLE);
463 Eigen::Vector3d point(pose.position.x, pose.position.y, pose.position.z);
464 Eigen::Isometry3d pose_table;
465 tf2::fromMsg(table.pose, pose_table);
468 point = pose_table.inverse() * point;
470 if (point.z() < -fabs(min_vertical_offset))
472 RCLCPP_ERROR(logger_,
"Object is not above table");
476 int point_x = (point.x() - x_min) * scale_factor;
477 int point_y = (point.y() - y_min) * scale_factor;
478 cv::Point2f point2f(point_x, point_y);
479 double result = cv::pointPolygonTest(contours[0], point2f,
true);
480 RCLCPP_DEBUG(logger_,
"table distance: %f", result);
482 return static_cast<int>(result) >=
static_cast<int>(min_distance_from_edge * scale_factor);
486 double min_vertical_offset)
const
488 std::map<std::string, object_recognition_msgs::msg::Table>::const_iterator it;
489 for (it = current_tables_in_collision_world_.begin(); it != current_tables_in_collision_world_.end(); ++it)
491 RCLCPP_DEBUG_STREAM(logger_,
"Testing table: " << it->first);
495 return std::string();
498void SemanticWorld::tableCallback(
const object_recognition_msgs::msg::TableArray::ConstSharedPtr& msg)
501 RCLCPP_INFO(logger_,
"Table callback with %d tables",
static_cast<int>(table_array_.tables.size()));
502 transformTableArray(table_array_);
506 RCLCPP_INFO(logger_,
"Calling table callback");
511void SemanticWorld::transformTableArray(object_recognition_msgs::msg::TableArray& table_array)
const
513 for (object_recognition_msgs::msg::Table& table : table_array.tables)
515 std::string original_frame = table.header.frame_id;
516 if (table.convex_hull.empty())
518 RCLCPP_INFO_STREAM(logger_,
"Original pose: " << table.pose.position.x <<
',' << table.pose.position.y <<
','
519 << table.pose.position.z);
520 std::string error_text;
521 const Eigen::Isometry3d& original_transform = planning_scene_->getFrameTransform(original_frame);
522 Eigen::Isometry3d original_pose;
523 tf2::fromMsg(table.pose, original_pose);
524 original_pose = original_transform * original_pose;
525 table.pose = tf2::toMsg(original_pose);
526 table.header.frame_id = planning_scene_->getTransforms().getTargetFrame();
527 RCLCPP_INFO_STREAM(logger_,
"Successfully transformed table array from " << original_frame <<
"to "
528 << table.header.frame_id);
529 RCLCPP_INFO_STREAM(logger_,
"Transformed pose: " << table.pose.position.x <<
',' << table.pose.position.y <<
','
530 << table.pose.position.z);
534shapes::Mesh* SemanticWorld::orientPlanarPolygon(
const shapes::Mesh& polygon)
const
536 if (polygon.vertex_count < 3 || polygon.triangle_count < 1)
539 Eigen::Vector3d vec1, vec2, vec3, normal;
541 int v_idx1 = polygon.triangles[0];
542 int v_idx2 = polygon.triangles[1];
543 int v_idx3 = polygon.triangles[2];
545 Eigen::Vector3d(polygon.vertices[v_idx1 * 3], polygon.vertices[v_idx1 * 3 + 1], polygon.vertices[v_idx1 * 3 + 2]);
547 Eigen::Vector3d(polygon.vertices[v_idx2 * 3], polygon.vertices[v_idx2 * 3 + 1], polygon.vertices[v_idx2 * 3 + 2]);
549 Eigen::Vector3d(polygon.vertices[v_idx3 * 3], polygon.vertices[v_idx3 * 3 + 1], polygon.vertices[v_idx3 * 3 + 2]);
552 normal = vec3.cross(vec2);
559 shapes::Mesh* solid =
new shapes::Mesh(polygon.vertex_count, polygon.triangle_count);
560 solid->type = shapes::MESH;
563 memcpy(solid->vertices, polygon.vertices, polygon.vertex_count * 3 *
sizeof(
double));
565 memcpy(solid->triangles, polygon.triangles, polygon.triangle_count * 3 *
sizeof(
unsigned int));
567 for (
unsigned t_idx = 0; t_idx < polygon.triangle_count; ++t_idx)
569 int v_idx1 = polygon.triangles[t_idx * 3];
570 int v_idx2 = polygon.triangles[t_idx * 3 + 1];
571 int v_idx3 = polygon.triangles[t_idx * 3 + 2];
573 vec1 = Eigen::Vector3d(polygon.vertices[v_idx1 * 3], polygon.vertices[v_idx1 * 3 + 1],
574 polygon.vertices[v_idx1 * 3 + 2]);
575 vec2 = Eigen::Vector3d(polygon.vertices[v_idx2 * 3], polygon.vertices[v_idx2 * 3 + 1],
576 polygon.vertices[v_idx2 * 3 + 2]);
577 vec3 = Eigen::Vector3d(polygon.vertices[v_idx3 * 3], polygon.vertices[v_idx3 * 3 + 1],
578 polygon.vertices[v_idx3 * 3 + 2]);
583 Eigen::Vector3d triangle_normal = vec2.cross(vec1);
585 if (triangle_normal.dot(normal) < 0.0)
586 std::swap(solid->triangles[t_idx * 3 + 1], solid->triangles[t_idx * 3 + 2]);
591shapes::Mesh* SemanticWorld::createSolidMeshFromPlanarPolygon(
const shapes::Mesh& polygon,
double thickness)
const
593 if (polygon.vertex_count < 3 || polygon.triangle_count < 1 || thickness <= 0)
596 Eigen::Vector3d vec1, vec2, vec3, normal;
598 int v_idx1 = polygon.triangles[0];
599 int v_idx2 = polygon.triangles[1];
600 int v_idx3 = polygon.triangles[2];
602 Eigen::Vector3d(polygon.vertices[v_idx1 * 3], polygon.vertices[v_idx1 * 3 + 1], polygon.vertices[v_idx1 * 3 + 2]);
604 Eigen::Vector3d(polygon.vertices[v_idx2 * 3], polygon.vertices[v_idx2 * 3 + 1], polygon.vertices[v_idx2 * 3 + 2]);
606 Eigen::Vector3d(polygon.vertices[v_idx3 * 3], polygon.vertices[v_idx3 * 3 + 1], polygon.vertices[v_idx3 * 3 + 2]);
609 normal = vec3.cross(vec2);
619 shapes::Mesh* solid =
620 new shapes::Mesh(polygon.vertex_count * 2, polygon.triangle_count * 2);
621 solid->type = shapes::MESH;
624 memcpy(solid->vertices, polygon.vertices, polygon.vertex_count * 3 *
sizeof(
double));
626 memcpy(solid->triangles, polygon.triangles, polygon.triangle_count * 3 *
sizeof(
unsigned int));
628 for (
unsigned t_idx = 0; t_idx < polygon.triangle_count; ++t_idx)
630 solid->triangles[(t_idx + polygon.triangle_count) * 3 + 0] = solid->triangles[t_idx * 3 + 0] + polygon.vertex_count;
631 solid->triangles[(t_idx + polygon.triangle_count) * 3 + 1] = solid->triangles[t_idx * 3 + 1] + polygon.vertex_count;
632 solid->triangles[(t_idx + polygon.triangle_count) * 3 + 2] = solid->triangles[t_idx * 3 + 2] + polygon.vertex_count;
634 int v_idx1 = polygon.triangles[t_idx * 3];
635 int v_idx2 = polygon.triangles[t_idx * 3 + 1];
636 int v_idx3 = polygon.triangles[t_idx * 3 + 2];
638 vec1 = Eigen::Vector3d(polygon.vertices[v_idx1 * 3], polygon.vertices[v_idx1 * 3 + 1],
639 polygon.vertices[v_idx1 * 3 + 2]);
640 vec2 = Eigen::Vector3d(polygon.vertices[v_idx2 * 3], polygon.vertices[v_idx2 * 3 + 1],
641 polygon.vertices[v_idx2 * 3 + 2]);
642 vec3 = Eigen::Vector3d(polygon.vertices[v_idx3 * 3], polygon.vertices[v_idx3 * 3 + 1],
643 polygon.vertices[v_idx3 * 3 + 2]);
648 Eigen::Vector3d triangle_normal = vec2.cross(vec1);
650 if (triangle_normal.dot(normal) < 0.0)
652 std::swap(solid->triangles[t_idx * 3 + 1], solid->triangles[t_idx * 3 + 2]);
656 std::swap(solid->triangles[(t_idx + polygon.triangle_count) * 3 + 1],
657 solid->triangles[(t_idx + polygon.triangle_count) * 3 + 2]);
661 for (
unsigned v_idx = 0; v_idx < polygon.vertex_count; ++v_idx)
663 solid->vertices[(v_idx + polygon.vertex_count) * 3 + 0] = solid->vertices[v_idx * 3 + 0] - thickness * normal[0];
664 solid->vertices[(v_idx + polygon.vertex_count) * 3 + 1] = solid->vertices[v_idx * 3 + 1] - thickness * normal[1];
665 solid->vertices[(v_idx + polygon.vertex_count) * 3 + 2] = solid->vertices[v_idx * 3 + 2] - thickness * normal[2];
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.
bool addTablesToCollisionWorld()
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...
Main namespace for MoveIt.
This namespace includes the central class for representing planning contexts.