snapit_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, JSK Lab
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 the JSK Lab 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 #include "jsk_pcl_ros/snapit.h"
37 #include <geometry_msgs/PolygonStamped.h>
38 #include <Eigen/StdVector>
39 #include <pcl/ModelCoefficients.h>
40 #include <pcl/filters/project_inliers.h>
41 #include <pcl/filters/extract_indices.h>
42 #include <pcl/sample_consensus/method_types.h>
43 #include <pcl/sample_consensus/model_types.h>
44 #include <pcl/segmentation/sac_segmentation.h>
45 #include <pcl/common/distances.h>
46 #include <pcl/features/normal_3d.h>
47 #include <pcl/surface/concave_hull.h>
48 #include <pcl/common/centroid.h>
49 #include <visualization_msgs/Marker.h>
54 #include <visualization_msgs/MarkerArray.h>
55 #include <algorithm>
56 
57 namespace jsk_pcl_ros
58 {
59  void SnapIt::onInit()
60  {
61  DiagnosticNodelet::onInit();
63  pnh_->param("use_service", use_service_, false);
64  polygon_aligned_pub_ = advertise<geometry_msgs::PoseStamped>(
65  *pnh_, "output/plane_aligned", 1);
66  convex_aligned_pub_ = advertise<geometry_msgs::PoseStamped>(
67  *pnh_, "output/convex_aligned", 1);
68  convex_aligned_pose_array_pub_ = advertise<geometry_msgs::PoseArray>(
69  *pnh_, "output/convex_aligned_pose_array", 1);
70  if (use_service_) {
71  subscribe();
72  align_footstep_srv_ = pnh_->advertiseService(
73  "align_footstep", &SnapIt::footstepAlignServiceCallback, this);
74  }
75  onInitPostProcess();
76  }
77 
78  SnapIt::~SnapIt() {
79  // message_filters::Synchronizer needs to be called reset
80  // before message_filters::Subscriber is freed.
81  // Calling reset fixes the following error on shutdown of the nodelet:
82  // terminate called after throwing an instance of
83  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
84  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
85  // Also see https://github.com/ros/ros_comm/issues/720 .
86  sync_polygon_.reset();
87  }
88 
89  void SnapIt::subscribe()
90  {
91  sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
92  sub_coefficients_.subscribe(*pnh_, "input/polygon_coefficients", 1);
94  = boost::make_shared<message_filters::Synchronizer<SyncPolygonPolicy> >(100);
96  sync_polygon_->registerCallback(
97  boost::bind(&SnapIt::polygonCallback, this, _1, _2));
98  polygon_align_sub_ = pnh_->subscribe("input/plane_align", 1,
100  convex_align_sub_ = pnh_->subscribe("input/convex_align", 1,
102  convex_align_polygon_sub_ = pnh_->subscribe(
103  "input/convex_align_polygon", 1,
105  }
106 
107  void SnapIt::unsubscribe()
108  {
109  if (!use_service_) {
114  }
115  polygons_.reset();
116  }
117 
119  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
120  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
121  {
122  boost::mutex::scoped_lock lock(mutex_);
123  vital_checker_->poke();
125  }
126 
128  const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
129  {
130  boost::mutex::scoped_lock lock(mutex_);
131  if (!polygons_) {
132  NODELET_ERROR("no polygon is ready");
133  polygon_aligned_pub_.publish(pose_msg);
134  return;
135  }
136  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes
137  = createConvexes(pose_msg->header.frame_id,
138  pose_msg->header.stamp,
140  Eigen::Affine3d pose_eigend;
141  Eigen::Affine3f pose_eigen;
142  tf::poseMsgToEigen(pose_msg->pose, pose_eigend);
143  convertEigenAffine3(pose_eigend, pose_eigen);
144  Eigen::Vector3f pose_point(pose_eigen.translation());
145  double min_distance = DBL_MAX;
147  for (size_t i = 0; i < convexes.size(); i++) {
148  jsk_recognition_utils::ConvexPolygon::Ptr convex = convexes[i];
149  double d = convex->distanceToPoint(pose_point);
150  if (d < min_distance) {
151  min_convex = convex;
152  min_distance = d;
153  }
154  }
155 
156  if (min_convex) {
157  geometry_msgs::PoseStamped aligned_pose = alignPose(pose_eigen, min_convex);
158  aligned_pose.header = pose_msg->header;
160  }
161  else {
162  polygon_aligned_pub_.publish(pose_msg);
163  }
164  }
165 
167  jsk_recognition_msgs::SnapFootstep::Request& req,
168  jsk_recognition_msgs::SnapFootstep::Response& res)
169  {
170  boost::mutex::scoped_lock lock(mutex_);
171  jsk_footstep_msgs::FootstepArray input_footsteps = req.input;
172  res.output.header = input_footsteps.header;
173  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes
174  = createConvexes(input_footsteps.header.frame_id,
175  input_footsteps.header.stamp,
176  polygons_);
177  for (size_t i = 0; i < input_footsteps.footsteps.size(); i++) {
178  jsk_footstep_msgs::Footstep footstep = input_footsteps.footsteps[i];
179  Eigen::Affine3d pose_eigend;
180  Eigen::Affine3f pose_eigen;
181  tf::poseMsgToEigen(footstep.pose, pose_eigen);
182  Eigen::Vector3f pose_point(pose_eigen.translation());
183  int min_index = findNearestConvex(pose_point, convexes);
184  jsk_footstep_msgs::Footstep aligned_footstep;
185  if (min_index != -1) {
186  jsk_recognition_utils::ConvexPolygon::Ptr min_convex = convexes[min_index];
187  geometry_msgs::PoseStamped aligned_pose = alignPose(pose_eigen, min_convex);
188  aligned_footstep.pose = aligned_pose.pose;
189  }
190  else {
191  aligned_footstep.pose = footstep.pose;
192  //convex_aligned_pub_.publish(pose_msg); // shoud we publish this?
193  }
194  aligned_footstep.leg = footstep.leg;
195  aligned_footstep.dimensions = footstep.dimensions;
196  aligned_footstep.duration = footstep.duration;
197  aligned_footstep.footstep_group = footstep.footstep_group;
198  res.output.footsteps.push_back(aligned_footstep);
199  }
200  return true;
201  }
202 
204  const geometry_msgs::PolygonStamped::ConstPtr& poly_msg)
205  {
206  boost::mutex::scoped_lock lock(mutex_);
207  geometry_msgs::PoseArray pose_array;
208  pose_array.header = poly_msg->header;
209  if (!polygons_) {
210  NODELET_ERROR("no polygon is ready");
211  return;
212  }
213  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes
214  = createConvexes(poly_msg->header.frame_id,
215  poly_msg->header.stamp,
216  polygons_);
217  for (size_t i = 0; i < poly_msg->polygon.points.size(); i++) {
218  geometry_msgs::Point32 p = poly_msg->polygon.points[i];
219  Eigen::Vector3f pose_point(p.x, p.y, p.z);
220  int min_index = findNearestConvex(pose_point, convexes);
221  if (min_index == -1) {
222  NODELET_ERROR("cannot project onto convex");
223  return;
224  }
225  else {
226  jsk_recognition_utils::ConvexPolygon::Ptr min_convex = convexes[min_index];
227  Eigen::Affine3f pose_eigen = Eigen::Affine3f::Identity();
228  pose_eigen.translate(pose_point);
229  geometry_msgs::PoseStamped aligned_pose = alignPose(pose_eigen, min_convex);
230  aligned_pose.header = poly_msg->header;
231  pose_array.poses.push_back(aligned_pose.pose);
232  }
233  }
235  }
236 
238  const Eigen::Vector3f& pose_point,
239  const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
240  {
241  int min_index = -1;
242  double min_distance = DBL_MAX;
244  for (size_t i = 0; i < convexes.size(); i++) {
245  jsk_recognition_utils::ConvexPolygon::Ptr convex = convexes[i];
246  if (convex->isProjectableInside(pose_point)) {
247  double d = convex->distanceToPoint(pose_point);
248  if (d < min_distance) {
249  min_distance = d;
250  min_convex = convex;
251  min_index = i;
252  }
253  }
254  }
255  return min_index;
256  }
257 
259  const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
260  {
261  boost::mutex::scoped_lock lock(mutex_);
262  if (!polygons_) {
263  NODELET_ERROR("no polygon is ready");
264  convex_aligned_pub_.publish(pose_msg);
265  return;
266  }
267  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes
268  = createConvexes(pose_msg->header.frame_id,
269  pose_msg->header.stamp,
270  polygons_);
271  Eigen::Affine3d pose_eigend;
272  Eigen::Affine3f pose_eigen;
273  tf::poseMsgToEigen(pose_msg->pose, pose_eigend);
274  convertEigenAffine3(pose_eigend, pose_eigen);
275  Eigen::Vector3f pose_point(pose_eigen.translation());
276  int min_index = findNearestConvex(pose_point, convexes);
277  if (min_index != -1) {
278  jsk_recognition_utils::ConvexPolygon::Ptr min_convex = convexes[min_index];
279  geometry_msgs::PoseStamped aligned_pose = alignPose(pose_eigen, min_convex);
280  aligned_pose.header = pose_msg->header;
281  convex_aligned_pub_.publish(aligned_pose);
282  }
283  else {
284  convex_aligned_pub_.publish(pose_msg); // shoud we publish this?
285  }
286  }
287 
288  geometry_msgs::PoseStamped SnapIt::alignPose(
289  Eigen::Affine3f& pose, jsk_recognition_utils::ConvexPolygon::Ptr convex)
290  {
291  Eigen::Affine3f aligned_pose(pose);
292  Eigen::Vector3f original_point(pose.translation());
293  Eigen::Vector3f projected_point;
294  convex->project(original_point, projected_point);
295 
296  Eigen::Vector3f normal = convex->getNormal();
297  Eigen::Vector3f old_normal;
298  old_normal[0] = pose(0, 2);
299  old_normal[1] = pose(1, 2);
300  old_normal[2] = pose(2, 2);
301  Eigen::Quaternionf rot;
302  if (normal.dot(old_normal) < 0) {
303  normal = - normal;
304  }
305  rot.setFromTwoVectors(old_normal, normal);
306  aligned_pose = aligned_pose * rot;
307  aligned_pose.translation() = projected_point;
308  Eigen::Affine3d aligned_posed;
309  convertEigenAffine3(aligned_pose, aligned_posed);
310  geometry_msgs::PoseStamped ret;
311  tf::poseEigenToMsg(aligned_posed, ret.pose);
312  return ret;
313  }
314 
315  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> SnapIt::createConvexes(
316  const std::string& frame_id, const ros::Time& stamp,
317  jsk_recognition_msgs::PolygonArray::ConstPtr polygons)
318  {
319  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> result;
320  try
321  {
322  for (size_t i = 0; i < polygons->polygons.size(); i++) {
323  geometry_msgs::PolygonStamped polygon = polygons->polygons[i];
325 
327  tf_listener_,
328  polygon.header.frame_id, frame_id, stamp, ros::Duration(5.0));
329  for (size_t j = 0; j < polygon.polygon.points.size(); j++) {
330  Eigen::Vector4d p;
331  p[0] = polygon.polygon.points[j].x;
332  p[1] = polygon.polygon.points[j].y;
333  p[2] = polygon.polygon.points[j].z;
334  p[3] = 1;
335  Eigen::Affine3d eigen_transform;
336  tf::transformTFToEigen(transform, eigen_transform);
337  Eigen::Vector4d transformed_pointd = eigen_transform.inverse() * p;
338  Eigen::Vector3f transformed_point;
339  transformed_point[0] = transformed_pointd[0];
340  transformed_point[1] = transformed_pointd[1];
341  transformed_point[2] = transformed_pointd[2];
342  vertices.push_back(transformed_point);
343  }
344  std::reverse(vertices.begin(), vertices.end());
346  result.push_back(convex);
347  }
348  }
349  catch (tf2::ConnectivityException &e)
350  {
351  NODELET_ERROR("Transform error: %s", e.what());
352  }
354  {
355  NODELET_ERROR("Transform error: %s", e.what());
356  }
357  catch (tf2::ExtrapolationException &e)
358  {
359  NODELET_ERROR("Transform error: %s", e.what());
360  }
361  return result;
362  }
363 }
364 
tf::poseMsgToEigen
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
result
def result
rot
rot
polygons
polygons
NODELET_ERROR
#define NODELET_ERROR(...)
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
jsk_recognition_utils::ConvexPolygon
sample_simulate_tabletop_cloud.polygon
polygon
Definition: sample_simulate_tabletop_cloud.py:167
boost::shared_ptr< ConvexPolygon >
i
int i
p
p
attention_pose_set.stamp
stamp
Definition: attention_pose_set.py:15
jsk_pcl_ros::SnapIt::onInit
virtual void onInit()
Definition: snapit_nodelet.cpp:91
snapit.h
jsk_pcl_ros::SnapIt::polygonAlignCallback
virtual void polygonAlignCallback(const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: snapit_nodelet.cpp:159
jsk_pcl_ros::SnapIt::convexAlignCallback
virtual void convexAlignCallback(const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: snapit_nodelet.cpp:290
ros::Subscriber::shutdown
void shutdown()
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
tf::StampedTransform
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros::SnapIt::sync_polygon_
boost::shared_ptr< message_filters::Synchronizer< SyncPolygonPolicy > > sync_polygon_
Definition: snapit.h:163
message_filters::Subscriber::unsubscribe
void unsubscribe()
convertEigenAffine3
void convertEigenAffine3(const Eigen::Affine3d &from, Eigen::Affine3f &to)
jsk_pcl_ros::SnapIt::createConvexes
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > createConvexes(const std::string &frame_id, const ros::Time &stamp, jsk_recognition_msgs::PolygonArray::ConstPtr polygons)
Definition: snapit_nodelet.cpp:347
pose
pose
class_list_macros.h
jsk_pcl_ros::SnapIt
Definition: snapit.h:90
tf_eigen.h
jsk_pcl_ros::SnapIt::subscribe
virtual void subscribe()
Definition: snapit_nodelet.cpp:121
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::SnapIt::convex_aligned_pub_
ros::Publisher convex_aligned_pub_
Definition: snapit.h:165
tf2::ExtrapolationException
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
jsk_pcl_ros::SnapIt::polygon_aligned_pub_
ros::Publisher polygon_aligned_pub_
Definition: snapit.h:164
eigen_msg.h
d
d
jsk_pcl_ros::SnapIt::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: snapit.h:162
tf::poseEigenToMsg
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
pcl_conversion_util.h
tf2::ConnectivityException
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::SnapIt::footstepAlignServiceCallback
virtual bool footstepAlignServiceCallback(jsk_recognition_msgs::SnapFootstep::Request &req, jsk_recognition_msgs::SnapFootstep::Response &res)
Definition: snapit_nodelet.cpp:198
jsk_pcl_ros::SnapIt::convex_align_sub_
ros::Subscriber convex_align_sub_
Definition: snapit.h:169
jsk_pcl_ros::SnapIt::alignPose
virtual geometry_msgs::PoseStamped alignPose(Eigen::Affine3f &pose, jsk_recognition_utils::ConvexPolygon::Ptr convex)
Definition: snapit_nodelet.cpp:320
nodelet::Nodelet
ros::Time
jsk_pcl_ros::SnapIt::~SnapIt
virtual ~SnapIt()
Definition: snapit_nodelet.cpp:110
jsk_pcl_ros::SnapIt::polygons_
jsk_recognition_msgs::PolygonArray::ConstPtr polygons_
Definition: snapit.h:173
jsk_pcl_ros::SnapIt::polygonCallback
virtual void polygonCallback(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
Definition: snapit_nodelet.cpp:150
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::SnapIt, nodelet::Nodelet)
jsk_pcl_ros::SnapIt::convex_aligned_pose_array_pub_
ros::Publisher convex_aligned_pose_array_pub_
Definition: snapit.h:166
jsk_pcl_ros::SnapIt::use_service_
bool use_service_
Definition: snapit.h:171
jsk_pcl_ros::SnapIt::unsubscribe
virtual void unsubscribe()
Definition: snapit_nodelet.cpp:139
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
lookupTransformWithDuration
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
attention_pose_set.frame_id
frame_id
Definition: attention_pose_set.py:16
tf2::InvalidArgumentException
jsk_pcl_ros::SnapIt::align_footstep_srv_
ros::ServiceServer align_footstep_srv_
Definition: snapit.h:172
jsk_pcl_ros::SnapIt::polygon_align_sub_
ros::Subscriber polygon_align_sub_
Definition: snapit.h:168
jsk_pcl_ros::SnapIt::tf_listener_
tf::TransformListener * tf_listener_
Definition: snapit.h:160
polygon_msg
jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg
ros::Duration
jsk_pcl_ros::SnapIt::convexAlignPolygonCallback
virtual void convexAlignPolygonCallback(const geometry_msgs::PolygonStamped::ConstPtr &poly_msg)
Definition: snapit_nodelet.cpp:235
jsk_pcl_ros::SnapIt::findNearestConvex
virtual int findNearestConvex(const Eigen::Vector3f &pose_point, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Definition: snapit_nodelet.cpp:269
jsk_pcl_ros::SnapIt::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: snapit.h:161
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::SnapIt::convex_align_polygon_sub_
ros::Subscriber convex_align_polygon_sub_
Definition: snapit.h:170
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::SnapIt::mutex_
boost::mutex mutex_
Definition: snapit.h:174
jsk_recognition_utils::Vertices
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45