environment_plane_modeling_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
39 #include <pcl/filters/extract_indices.h>
40 #include <pcl/common/distances.h>
42 #include <pcl/filters/project_inliers.h>
43 #include <pcl/surface/convex_hull.h>
44 #include <pcl/filters/project_inliers.h>
45 #include <jsk_recognition_msgs/SparseOccupancyGridArray.h>
46 
48 #include <geometry_msgs/PoseArray.h>
50 #include "jsk_pcl_ros/grid_map.h"
52 namespace jsk_pcl_ros
53 {
55  {
56  DiagnosticNodelet::onInit();
57 
58  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
59  typename dynamic_reconfigure::Server<Config>::CallbackType f =
60  boost::bind (&EnvironmentPlaneModeling::configCallback, this, _1, _2);
61  srv_->setCallback (f);
62 
63  pnh_->param("complete_footprint_region", complete_footprint_region_, false);
65  = pnh_->advertise<jsk_recognition_msgs::PolygonArray>(
66  "debug/magnified_polygons", 1);
68  = pnh_->advertise<sensor_msgs::PointCloud2>(
69  "debug/convex_cloud", 1);
71  = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
72  "debug/raw_grid_map", 1);
74  = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
75  "debug/noeroded_grid_map", 1);
77  = pnh_->advertise<geometry_msgs::PoseArray>(
78  "debug/plane_poses", 1);
80  = pnh_->advertise<geometry_msgs::PoseArray>(
81  "debug/magnified_plane_poses", 1);
83  = pnh_->advertise<jsk_recognition_msgs::SimpleOccupancyGridArray>(
84  "output", 1, true);
85  pub_snapped_move_base_simple_goal_ = pnh_->advertise<geometry_msgs::PoseStamped>(
86  "/footstep_simple/goal", 1);
87  pub_non_plane_indices_ = pnh_->advertise<PCLIndicesMsg>(
88  "output/non_plane_indices", 1);
91 
92  sub_leg_bbox_ = pnh_->subscribe(
93  "input/leg_bounding_box", 1,
95 
97  *pnh_, "footprint_frames", footprint_frames_);
98 
99  }
100  sub_move_base_simple_goal_ = pnh_->subscribe(
101  "/move_base_simple/goal", 1,
103  sub_cloud_.subscribe(*pnh_, "input", 1);
104  sub_full_cloud_.subscribe(*pnh_, "input/full_cloud", 1);
105  sub_indices_.subscribe(*pnh_, "input/indices", 1);
106  sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
107  sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
108  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
111  sync_->registerCallback(
113  this, _1, _2, _3, _4, _5));
114 
116  }
117 
118  void EnvironmentPlaneModeling::configCallback(Config &config, uint32_t level)
119  {
120  boost::mutex::scoped_lock lock(mutex_);
121  magnify_distance_ = config.magnify_distance;
122  distance_threshold_ = config.distance_threshold;
123  normal_threshold_ = config.normal_threshold;
124  resolution_ = config.resolution;
125  morphological_filter_size_ = config.morphological_filter_size;
126  erode_filter_size_ = config.erode_filter_size;
127  footprint_plane_angular_threshold_ = config.footprint_plane_angular_threshold;
128  footprint_plane_distance_threshold_ = config.footprint_plane_distance_threshold;
129  }
130 
132  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
133  const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
134  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
135  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
136  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
137  {
138  NODELET_INFO("Input data --");
139  NODELET_INFO(" Number of points -- %d", cloud_msg->width * cloud_msg->height);
140  NODELET_INFO(" Number of full points -- %d", full_cloud_msg->width * full_cloud_msg->height);
141  NODELET_INFO(" Number of clusters: -- %lu", indices_msg->cluster_indices.size());
142  NODELET_INFO(" Frame Id: %s", cloud_msg->header.frame_id.c_str());
143  NODELET_INFO(" Complete Footprint: %s", complete_footprint_region_? "true": "false");
144  }
145 
147  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
148  const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
149  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
150  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
151  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
152  {
153  std::string frame_id = cloud_msg->header.frame_id;
154  if (full_cloud_msg->header.frame_id != frame_id) {
155  return false;
156  }
157  if (polygon_msg->header.frame_id != frame_id) {
158  return false;
159  }
160  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
161  if (polygon_msg->polygons[i].header.frame_id != frame_id) {
162  return false;
163  }
164  }
165  if (coefficients_msg->header.frame_id != frame_id) {
166  return false;
167  }
168  for (size_t i = 0; i < coefficients_msg->coefficients.size(); i++) {
169  if (coefficients_msg->coefficients[i].header.frame_id != frame_id) {
170  return false;
171  }
172  }
173  if (indices_msg->header.frame_id != frame_id) {
174  return false;
175  }
176  for (size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
177  if (indices_msg->cluster_indices[i].header.frame_id != frame_id) {
178  return false;
179  }
180  }
181  return true;
182  }
183 
185  const geometry_msgs::PoseStamped::ConstPtr& msg)
186  {
187  boost::mutex::scoped_lock lock(mutex_);
188  if (latest_grid_maps_.size() == 0) {
189  NODELET_WARN("not yet grid maps are available");
190  return;
191  }
192 
194  tf_listener_,
195  latest_global_header_.frame_id,
196  msg->header.frame_id,
197  latest_global_header_.stamp,
198  ros::Duration(1.0));
199 
200  Eigen::Affine3f local_coords, transform;
201  tf::poseMsgToEigen(msg->pose, local_coords);
202  tf::transformTFToEigen(tf_transform, transform);
203  Eigen::Affine3f global_coords = transform * local_coords;
204 
205  // lookup suitable grid
206  double max_height = - DBL_MAX;
207  GridPlane::Ptr max_grid;
208  Eigen::Affine3f max_projected_coords = Eigen::Affine3f::Identity();
209  for (size_t i = 0; i < latest_grid_maps_.size(); i++) {
210  GridPlane::Ptr target_grid = latest_grid_maps_[i];
211  Eigen::Affine3f projected_coords;
212  target_grid->getPolygon()->projectOnPlane(global_coords, projected_coords);
213  Eigen::Vector3f projected_point(projected_coords.translation());
214  if (target_grid->isOccupiedGlobal(projected_point)) {
215  double height = projected_point[2];
216  if (max_height < height) {
217  max_height = height;
218  max_grid = target_grid;
219  max_projected_coords = projected_coords;
220  }
221  }
222  }
223  if (max_grid) {
224  // publish it
225  geometry_msgs::PoseStamped ros_coords;
226  tf::poseEigenToMsg(max_projected_coords, ros_coords.pose);
227  ros_coords.header.stamp = msg->header.stamp;
228  ros_coords.header.frame_id = latest_global_header_.frame_id;
230  }
231  else {
232  NODELET_ERROR("Failed to find corresponding grid");
233  }
234  }
235 
237  const jsk_recognition_msgs::BoundingBox::ConstPtr& box)
238  {
239  boost::mutex::scoped_lock lock(mutex_);
241  }
242 
244  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
245  const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
246  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
247  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
248  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
249  {
250  boost::mutex::scoped_lock lock(mutex_);
251  try {
252  // check frame_id
253  if (!isValidFrameIds(cloud_msg, full_cloud_msg, polygon_msg, coefficients_msg, indices_msg)) {
254  NODELET_FATAL("frame_id is not correct");
255  return;
256  }
258  NODELET_ERROR("Bounding Box for Footprint is not yet ready");
259  return;
260  }
261  // first, print all the information about ~inputs
262  printInputData(cloud_msg, full_cloud_msg, polygon_msg, coefficients_msg, indices_msg);
263 
264 
265  pcl::PointCloud<pcl::PointNormal>::Ptr cloud (new pcl::PointCloud<pcl::PointNormal>);
266  pcl::fromROSMsg(*cloud_msg, *cloud);
267 
268  pcl::PointCloud<pcl::PointNormal>::Ptr full_cloud (new pcl::PointCloud<pcl::PointNormal>);
269  pcl::fromROSMsg(*full_cloud_msg, *full_cloud);
270 
271  // convert to jsk_recognition_utils::ConvexPolygon
272  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes = convertToConvexPolygons(cloud, indices_msg, coefficients_msg);
273  // magnify convexes
274  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> magnified_convexes = magnifyConvexes(convexes);
275  publishConvexPolygonsBoundaries(pub_debug_convex_point_cloud_, cloud_msg->header, magnified_convexes);
276  // Publish magnified convexes for debug
277  publishConvexPolygons(pub_debug_magnified_polygons_, cloud_msg->header, magnified_convexes);
278  // publish pose_array for debug
279  {
280  geometry_msgs::PoseArray pose_array;
281  pose_array.header = cloud_msg->header;
282  for (size_t i = 0; i < convexes.size(); i++) {
283  Eigen::Affine3f pose = convexes[i]->coordinates();
284  geometry_msgs::Pose ros_pose;
285  tf::poseEigenToMsg(pose, ros_pose);
286  pose_array.poses.push_back(ros_pose);
287  }
288  pub_debug_plane_coords_.publish(pose_array);
289  }
290  {
291  geometry_msgs::PoseArray pose_array;
292  pose_array.header = cloud_msg->header;
293  for (size_t i = 0; i < magnified_convexes.size(); i++) {
294  Eigen::Affine3f pose = magnified_convexes[i]->coordinates();
295  geometry_msgs::Pose ros_pose;
296  tf::poseEigenToMsg(pose, ros_pose);
297  pose_array.poses.push_back(ros_pose);
298  }
300  }
301 
302  // build GridMaps
303  std::set<int> non_plane_indices;
304  std::vector<GridPlane::Ptr> raw_grid_planes = buildGridPlanes(full_cloud, magnified_convexes, non_plane_indices);
305 
306  publishGridMaps(pub_debug_raw_grid_map_, cloud_msg->header, raw_grid_planes);
307  PCLIndicesMsg ros_non_plane_indices;
308  ros_non_plane_indices.indices = std::vector<int>(non_plane_indices.begin(),
309  non_plane_indices.end());
310  ros_non_plane_indices.header = cloud_msg->header;
311  pub_non_plane_indices_.publish(ros_non_plane_indices);
312  std::vector<GridPlane::Ptr> morphological_filtered_grid_planes
313  = morphologicalFiltering(raw_grid_planes);
314 
316  morphological_filtered_grid_planes);
317 
318  std::vector<GridPlane::Ptr> eroded_grid_planes
319  = erodeFiltering(morphological_filtered_grid_planes);
320  std::vector<GridPlane::Ptr> result_grid_planes;
321 
322  if (complete_footprint_region_) { // complete footprint region if needed
323  result_grid_planes
324  = completeFootprintRegion(cloud_msg->header,
325  eroded_grid_planes);
326  }
327  else {
328  result_grid_planes = eroded_grid_planes;
329  }
330 
331  publishGridMaps(pub_grid_map_, cloud_msg->header,
332  result_grid_planes);
333 
334  latest_global_header_ = cloud_msg->header;
335  latest_grid_maps_ = result_grid_planes;
336  }
337  catch (tf2::TransformException& e) {
338  NODELET_ERROR("Failed to lookup transformation: %s", e.what());
339  }
340  }
341 
342  std::vector<GridPlane::Ptr> EnvironmentPlaneModeling::erodeFiltering(
343  std::vector<GridPlane::Ptr>& grid_maps)
344  {
345  std::vector<GridPlane::Ptr> ret;
346  for (size_t i = 0; i < grid_maps.size(); i++) {
347  GridPlane::Ptr eroded_grid_map = grid_maps[i]->erode(erode_filter_size_);
348  ret.push_back(eroded_grid_map);
349  }
350  return ret;
351  }
352 
354  const Eigen::Affine3f& pose, const std::vector<GridPlane::Ptr>& grid_maps)
355  {
356  Eigen::Vector3f foot_z = (pose.rotation() * Eigen::Vector3f::UnitZ()).normalized();
357  Eigen::Vector3f foot_p(pose.translation());
358  double min_distance = DBL_MAX;
359  int min_index = -1;
360  for (size_t i = 0; i < grid_maps.size(); i++) {
361  GridPlane::Ptr grid = grid_maps[i];
362  Eigen::Vector3f normal = grid->getPolygon()->getNormal();
363  if (std::abs(normal.dot(foot_z)) > cos(footprint_plane_angular_threshold_)) {
364  // compare distance
365  if (grid->getPolygon()->distanceToPoint(foot_p) < footprint_plane_distance_threshold_) {
366  Eigen::Vector3f foot_center(pose.translation());
367  if (!grid->isOccupiedGlobal(foot_center)) {
368  // check distance to point
369  double d = grid->getPolygon()->distanceFromVertices(foot_center);
370  if (d < min_distance) {
371  min_distance = d;
372  min_index = i;
373  }
374  }
375  else {
376  NODELET_INFO("Foot print is already occupied");
377  return -1;
378  }
379  // NB: else break?
380  }
381  }
382  }
383  return min_index;
384  }
385 
387  const std::string& footprint_frame, const std_msgs::Header& header,
388  const std::vector<GridPlane::Ptr>& grid_maps)
389  {
390  // first, lookup location of frames
391  tf::StampedTransform transform
393  header.frame_id, footprint_frame,
394  header.stamp,
395  ros::Duration(1.0));
396  Eigen::Affine3f eigen_transform;
397  tf::transformTFToEigen(transform, eigen_transform);
398  // lookup ground plane for the foot
399  return lookupGroundPlaneForFootprint(eigen_transform, grid_maps);
400  }
401 
403  const jsk_recognition_msgs::BoundingBox::ConstPtr& box,
404  const std_msgs::Header& header,
405  GridPlane::Ptr grid_map)
406  {
407  // resolve tf
409  tf_listener_,
410  header.frame_id,
411  box->header.frame_id,
412  header.stamp,
413  ros::Duration(1.0));
414  Eigen::Affine3f transform;
415  tf::transformTFToEigen(tf_transform, transform);
416  Eigen::Affine3f local_pose;
417  tf::poseMsgToEigen(box->pose, local_pose);
418  Eigen::Affine3f global_pose = transform * local_pose;
419  std::vector<double> dimensions;
420  dimensions.push_back(box->dimensions.x);
421  dimensions.push_back(box->dimensions.y);
422  dimensions.push_back(box->dimensions.z);
423  jsk_recognition_utils::Cube::Ptr cube (new Cube(Eigen::Vector3f(global_pose.translation()),
424  Eigen::Quaternionf(global_pose.rotation()),
425  dimensions));
426  GridPlane::Ptr completed_grid_map = grid_map->clone();
427  completed_grid_map->fillCellsFromCube(*cube);
428  return completed_grid_map;
429  }
430 
432  const std_msgs::Header& header, std::vector<GridPlane::Ptr>& grid_maps)
433  {
434  try {
435  std::vector<GridPlane::Ptr> completed_grid_maps(grid_maps.size());
436  std::set<int> ground_plane_indices;
437  for (size_t i = 0; i < footprint_frames_.size(); i++) {
438  std::string footprint_frame = footprint_frames_[i];
439  int grid_index = lookupGroundPlaneForFootprint(
440  footprint_frame, header, grid_maps);
441  if (grid_index != -1) {
442  NODELET_INFO("Found ground plane for %s: %d", footprint_frame.c_str(), grid_index);
443  ground_plane_indices.insert(grid_index);
444  }
445  else {
446  NODELET_WARN("Cannnot find ground plane for %s: %d", footprint_frame.c_str(), grid_index);
447  }
448  }
449  for (size_t i = 0; i < grid_maps.size(); i++) {
450  if (ground_plane_indices.find(i) == ground_plane_indices.end()) {
451  // It's not a ground plane, just copy the original
452  completed_grid_maps[i] = grid_maps[i];
453  }
454  else {
455  completed_grid_maps[i] = completeGridMapByBoundingBox(
456  latest_leg_bounding_box_, header, grid_maps[i]);
457  }
458  }
459  return completed_grid_maps;
460  }
461  catch (tf2::TransformException& e) {
462  NODELET_FATAL("Failed to lookup transformation: %s", e.what());
463  return std::vector<GridPlane::Ptr>();
464  }
465  }
466 
468  std::vector<GridPlane::Ptr>& raw_grid_maps)
469  {
470  std::vector<GridPlane::Ptr> ret;
471  for (size_t i = 0; i < raw_grid_maps.size(); i++) {
472  GridPlane::Ptr dilated_grid_map = raw_grid_maps[i]->dilate(morphological_filter_size_);
473  GridPlane::Ptr eroded_grid_map = dilated_grid_map->erode(morphological_filter_size_);
474  ret.push_back(eroded_grid_map);
475  }
476  return ret;
477  }
478 
479 
482  const std_msgs::Header& header,
483  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
484  {
485  pcl::PointCloud<pcl::PointXYZ>::Ptr
486  boundary_cloud (new pcl::PointCloud<pcl::PointXYZ>);
487  for (size_t i = 0; i < convexes.size(); i++) {
488  pcl::PointCloud<pcl::PointXYZ>::Ptr
489  one_boundary_cloud (new pcl::PointCloud<pcl::PointXYZ>);
490  convexes[i]->boundariesToPointCloud<pcl::PointXYZ>(
491  *one_boundary_cloud);
492  *boundary_cloud = *boundary_cloud + *one_boundary_cloud;
493  }
494  sensor_msgs::PointCloud2 ros_cloud;
495  pcl::toROSMsg(*boundary_cloud, ros_cloud);
496  ros_cloud.header = header;
497  pub.publish(ros_cloud);
498  }
499 
502  const std_msgs::Header& header,
503  std::vector<GridPlane::Ptr>& grids)
504  {
505  jsk_recognition_msgs::SimpleOccupancyGridArray grid_array;
506  grid_array.header = header;
507  for (size_t i = 0; i < grids.size(); i++) {
508  jsk_recognition_msgs::SimpleOccupancyGrid grid = grids[i]->toROSMsg();
509  grid.header = header;
510  grid_array.grids.push_back(grid);
511  }
512  pub.publish(grid_array);
513  }
514 
515 
516  std::vector<GridPlane::Ptr> EnvironmentPlaneModeling::buildGridPlanes(
517  pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
518  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes,
519  std::set<int>& non_plane_indices)
520  {
521  std::vector<GridPlane::Ptr> ret(convexes.size());
522 //#pragma omp parallel for
523  for (size_t i = 0; i < convexes.size(); i++) {
524  GridPlane::Ptr grid(new GridPlane(convexes[i], resolution_));
525  size_t num = grid->fillCellsFromPointCloud(cloud, distance_threshold_,
527  non_plane_indices);
528  NODELET_INFO("%lu plane contains %lu points",
529  i, num);
530  ret[i] = grid;
531  }
532  return ret;
533  }
534 
535 
536 
539  const std_msgs::Header& header,
540  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
541  {
542  jsk_recognition_msgs::PolygonArray polygon_array;
543  polygon_array.header = header;
544  for (size_t i = 0; i < convexes.size(); i++) {
545  geometry_msgs::PolygonStamped polygon;
546  polygon.polygon = convexes[i]->toROSMsg();
547  polygon.header = header;
548  polygon_array.polygons.push_back(polygon);
549  }
550  pub.publish(polygon_array);
551  }
552 
553  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> EnvironmentPlaneModeling::magnifyConvexes(
554  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
555  {
556  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> ret(0);
557  for (size_t i = 0; i < convexes.size(); i++) {
558  jsk_recognition_utils::ConvexPolygon::Ptr vertices_convex(new jsk_recognition_utils::ConvexPolygon(convexes[i]->getVertices()));
559  jsk_recognition_utils::ConvexPolygon::Ptr new_convex = vertices_convex->magnifyByDistance(magnify_distance_);
560  // check orientation
561  if (new_convex->getNormalFromVertices().dot(Eigen::Vector3f::UnitZ()) < 0) {
562  new_convex = boost::make_shared<jsk_recognition_utils::ConvexPolygon>(new_convex->flipConvex());
563  }
564  ret.push_back(new_convex);
565  }
566  return ret;
567  }
568 
569  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> EnvironmentPlaneModeling::convertToConvexPolygons(
570  const pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
571  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
572  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
573  {
574  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes(0);
575  for (size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
576  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
577  inliers->indices = indices_msg->cluster_indices[i].indices;
578  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
579  coefficients->values = coefficients_msg->coefficients[i].values;
581  = jsk_recognition_utils::convexFromCoefficientsAndInliers<pcl::PointNormal>(
582  cloud, inliers, coefficients);
583  convexes.push_back(convex);
584  }
585 
586  return convexes;
587  }
588 
589 }
590 
d
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > magnifyConvexes(std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Magnify jsk_recognition_utils::ConvexPolygons according to maginify_distance_ parameter.
num
virtual void configCallback(Config &config, uint32_t level)
Callback method of dynamic reconfigure.
virtual GridPlane::Ptr completeGridMapByBoundingBox(const jsk_recognition_msgs::BoundingBox::ConstPtr &box, const std_msgs::Header &header, GridPlane::Ptr grid_map)
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::EnvironmentPlaneModeling, nodelet::Nodelet)
virtual std::vector< GridPlane::Ptr > completeFootprintRegion(const std_msgs::Header &header, std::vector< GridPlane::Ptr > &grid_maps)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > convertToConvexPolygons(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
double cos()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
virtual std::vector< GridPlane::Ptr > erodeFiltering(std::vector< GridPlane::Ptr > &grid_maps)
coefficients
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
pose
int min_index
virtual std::vector< GridPlane::Ptr > morphologicalFiltering(std::vector< GridPlane::Ptr > &raw_grid_maps)
virtual void boundingBoxCallback(const jsk_recognition_msgs::BoundingBox::ConstPtr &box_array)
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
virtual void publishConvexPolygonsBoundaries(ros::Publisher &pub, const std_msgs::Header &header, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
main callback function
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_full_cloud_
TFSIMD_FORCE_INLINE Vector3 normalized() const
Nodelet implementation of jsk_pcl/EnvironmentPlaneModeling.
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
virtual void moveBaseSimpleGoalCallback(const geometry_msgs::PoseStamped::ConstPtr &msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual std::vector< GridPlane::Ptr > buildGridPlanes(pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > convexes, std::set< int > &non_plane_indices)
make GridPlane from jsk_recognition_utils::ConvexPolygon and PointCloud
virtual void printInputData(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
virtual bool isValidFrameIds(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
virtual void publishConvexPolygons(ros::Publisher &pub, const std_msgs::Header &header, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Publish array of jsk_recognition_utils::ConvexPolygon::Ptr by using specified publisher.
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define NODELET_INFO(...)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
height
virtual int lookupGroundPlaneForFootprint(const std::string &footprint_frame_id, const std_msgs::Header &header, const std::vector< GridPlane::Ptr > &grid_maps)
static tf::TransformListener * getInstance()
std::vector< GridPlane::Ptr > latest_grid_maps_
#define NODELET_FATAL(...)
pcl::PointIndices PCLIndicesMsg
cloud
Cube cube(Eigen::Vector3f(1, 0, 0), Eigen::Quaternionf(0.108755, 0.088921, 0.108755, 0.984092), Eigen::Vector3f(0.3, 0.3, 0.3))
virtual void publishGridMaps(ros::Publisher &pub, const std_msgs::Header &header, std::vector< GridPlane::Ptr > &grids)
Publish array of GridPlane::Ptr by using specified publisher.
jsk_recognition_msgs::BoundingBox::ConstPtr latest_leg_bounding_box_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46