pointcloud_cropper.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 Willow Garage 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 
39 #include <algorithm>
41 
42 #include <pcl_ros/pcl_nodelet.h>
43 
44 //using namespace jsk_interactive_marker;
45 namespace jsk_interactive_marker {
46  Cropper::Cropper(const unsigned int nr_parameter):
47  nr_parameter_(nr_parameter),
48  pose_(Eigen::Affine3f::Identity())
49  {
50  parameters_.resize(nr_parameter_);
51  }
52 
54  {
55 
56  }
57 
58  void Cropper::setPose(Eigen::Affine3f pose)
59  {
60  pose_ = pose;
61  }
62 
63  Eigen::Affine3f Cropper::getPose()
64  {
65  return pose_;
66  }
67 
68  void Cropper::crop(const pcl::PointCloud<pcl::PointXYZ>::Ptr& input,
69  pcl::PointCloud<pcl::PointXYZ>::Ptr output)
70  {
71  Eigen::Vector3f transf(pose_.translation());
72  ROS_DEBUG("%s transf: %f %f %f", __FUNCTION__, transf[0], transf[1], transf[2]);
73  output->points.clear();
74  for (size_t i = 0; i < input->points.size(); i++) {
75  pcl::PointXYZ p = input->points[i];
76  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
77  if (isInside(p)) {
78  output->points.push_back(p);
79  }
80  }
81  }
82  }
83 
84 
85  void Cropper::updateParameter(const double param, const unsigned int index)
86  {
87  if (parameters_.size() >= index + 1) {
88  parameters_[index] = param;
89  }
90  }
91 
93  {
94  fillInitialParameters(); // not so good?
95  }
96 
98  {
99 
100  }
101 
102  bool SphereCropper::isInside(const pcl::PointXYZ& p)
103  {
104  Eigen::Vector3f pos = p.getVector3fMap();
105  Eigen::Vector3f origin(pose_.translation());
106  double distance = (pos - origin).norm();
107  // ROS_DEBUG("pos: [%f, %f, %f], origin: [%f, %f, %f], distance: %f, R: %f",
108  // pos[0], pos[1], pos[2],
109  // origin[0], origin[1], origin[2],
110  // distance, getRadius());
111  if (distance < getRadius()) {
112  return true;
113  }
114  else {
115  return false;
116  }
117  }
118 
120  {
121  return parameters_[0];
122  }
123 
125  {
126  parameters_[0] = 0.5; // 50cm
127  }
128 
130  {
131  return "SphereCropper";
132  }
133 
134  visualization_msgs::Marker SphereCropper::getMarker()
135  {
136  visualization_msgs::Marker marker;
137  marker.type = visualization_msgs::Marker::SPHERE;
138  marker.scale.x = getRadius() * 2;
139  marker.scale.y = getRadius() * 2;
140  marker.scale.z = getRadius() * 2;
141  marker.color.r = 0.5;
142  marker.color.g = 0.5;
143  marker.color.b = 0.5;
144  marker.color.a = 0.5;
145  return marker;
146  }
147 
149  {
150  fillInitialParameters(); // not so good?
151  }
152 
154  {
155 
156  }
157 
158  std::string CubeCropper::getName()
159  {
160  return "CubeCropper";
161  }
162 
163  visualization_msgs::Marker CubeCropper::getMarker()
164  {
165  visualization_msgs::Marker marker;
166  marker.type = visualization_msgs::Marker::CUBE;
167  marker.scale.x = getWidthX() * 2;
168  marker.scale.y = getWidthY() * 2;
169  marker.scale.z = getWidthZ() * 2;
170  marker.color.r = 0.5;
171  marker.color.g = 0.5;
172  marker.color.b = 0.5;
173  marker.color.a = 0.5;
174  return marker;
175  }
176 
178  {
179  parameters_[0] = 0.5; // 50cm
180  parameters_[1] = 0.5; // 50cm
181  parameters_[2] = 0.5; // 50cm
182  }
183 
185  {
186  return parameters_[0];
187  }
188 
190  {
191  return parameters_[1];
192  }
193 
195  {
196  return parameters_[2];
197  }
198 
199  bool CubeCropper::isInside(const pcl::PointXYZ& p)
200  {
201  Eigen::Vector3f pos = p.getVector3fMap();
202  Eigen::Vector3f diff = pos - pose_.translation();
203  if ((fabs(diff[0]) < getWidthX()) &&
204  (fabs(diff[1]) < getWidthY()) &&
205  (fabs(diff[2]) < getWidthZ())) {
206  return true;
207  }
208  else {
209  return false;
210  }
211  }
212 
214  {
215  tf_listener_.reset(new tf::TransformListener);
216  // initialize cropper_candidates_
217  cropper_candidates_.push_back(std::make_shared<SphereCropper>());
218  cropper_candidates_.push_back(std::make_shared<CubeCropper>());
219  cropper_ = cropper_candidates_[0];
220  point_pub_ = pnh.advertise<sensor_msgs::PointCloud2>("output", 1);
221  point_visualization_pub_ = pnh.advertise<sensor_msgs::PointCloud2>(
222  "visualization_pointcloud", 1);
225  initializeInteractiveMarker();
226  srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (pnh);
227  dynamic_reconfigure::Server<Config>::CallbackType f =
228  boost::bind (&PointCloudCropper::configCallback, this, _1, _2);
229  srv_->setCallback (f);
230  point_sub_ = pnh.subscribe("input", 1, &PointCloudCropper::inputCallback, this);
231  }
232 
234  {
235 
236  }
237 
238  void PointCloudCropper::configCallback(Config &config, uint32_t level)
239  {
240  boost::mutex::scoped_lock lock(mutex_);
241  for (size_t i = 0; i < cropper_candidates_.size(); i++) {
242  cropper_candidates_[i]->updateParameter(config.param0, 0);
243  cropper_candidates_[i]->updateParameter(config.param1, 1);
244  cropper_candidates_[i]->updateParameter(config.param2, 2);
245  }
246  reInitializeInteractiveMarker();
247  }
248 
250  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
251  {
252  boost::mutex::scoped_lock lock(mutex_);
253  geometry_msgs::PoseStamped input_pose_stamped, transformed_pose_stamped;
254  input_pose_stamped.pose = feedback->pose;
255  input_pose_stamped.header.stamp = feedback->header.stamp;
256  input_pose_stamped.header.frame_id = feedback->header.frame_id;
257  if (!latest_pointcloud_) {
258  ROS_WARN("no pointcloud is available yet");
259  return;
260  }
261  // 1. update cropper's pose according to the posigoin of the process feedback
262  try {
263  tf_listener_->transformPose(
264  latest_pointcloud_->header.frame_id,
265  input_pose_stamped,
266  transformed_pose_stamped);
267  }
268  catch (...) {
269  ROS_FATAL("tf exception");
270  return;
271  }
272  Eigen::Affine3d pose_d;
273  tf::poseMsgToEigen(transformed_pose_stamped.pose, pose_d);
274  // convert Eigen::Affine3d to Eigen::Affine3f
275  Eigen::Vector3d transd(pose_d.translation());
276  Eigen::Quaterniond rotated(pose_d.rotation());
277  Eigen::Vector3f transf(transd[0], transd[1], transd[2]);
278  Eigen::Quaternionf rotatef(rotated.w(),
279  rotated.x(), rotated.y(), rotated.z());
280  Eigen::Affine3f pose_f = Eigen::Translation3f(transf) * rotatef;
281  ROS_DEBUG("transf: %f %f %f", transf[0], transf[1], transf[2]);
282  cropper_->setPose(pose_f);
283  // 2. crop pointcloud
284  cropAndPublish(point_visualization_pub_);
285  }
286 
288  {
289  pcl::PointCloud<pcl::PointXYZ>::Ptr input
290  (new pcl::PointCloud<pcl::PointXYZ>);
291  pcl::PointCloud<pcl::PointXYZ>::Ptr output
292  (new pcl::PointCloud<pcl::PointXYZ>);
293  pcl::fromROSMsg(*latest_pointcloud_, *input);
294  cropper_->crop(input, output);
295  ROS_DEBUG_STREAM(output->points.size() << " points to be cropped");
296  sensor_msgs::PointCloud2 ros_output;
297  pcl::toROSMsg(*output, ros_output);
298  ros_output.header = latest_pointcloud_->header;
299  pub.publish(ros_output);
300  }
301 
303  Eigen::Affine3f pose_offset)
304  {
305  updateInteractiveMarker();
306  // menu
307  menu_handler_.insert(
308  "Crop",
309  boost::bind(&PointCloudCropper::menuFeedback, this, _1));
310  // submenu to change the cropper
311  interactive_markers::MenuHandler::EntryHandle sub_cropper_menu_handle
312  = menu_handler_.insert("Switch");
313  cropper_entries_.clear();
314  for (size_t i = 0; i < cropper_candidates_.size(); i++) {
315  Cropper::Ptr the_cropper = cropper_candidates_[i];
317  = menu_handler_.insert(
318  sub_cropper_menu_handle, the_cropper->getName(),
319  boost::bind(&PointCloudCropper::changeCropperCallback, this, _1));
320  if (the_cropper != cropper_) {
321  menu_handler_.setCheckState(
322  cropper_entry,
324  }
325  else {
326  menu_handler_.setCheckState(
327  cropper_entry,
329  }
330  cropper_entries_.push_back(cropper_entry);
331  }
332  menu_handler_.apply(*server_, "pointcloud cropper");
333  server_->applyChanges();
334  }
335 
337  {
338  if (server_) {
339  updateInteractiveMarker(cropper_->getPose());
340  // update checkbox status of the menu
341  updateMenuCheckboxStatus();
342  menu_handler_.reApply(*server_);
343  server_->applyChanges();
344  }
345  }
346 
348  Eigen::Affine3f pose_offset)
349  {
350  visualization_msgs::InteractiveMarker int_marker;
351  if (latest_pointcloud_) {
352  int_marker.header.frame_id = latest_pointcloud_->header.frame_id;
353  }
354  else {
355  int_marker.header.frame_id = "/camera_link";
356  }
357  int_marker.name = "pointcloud cropper";
358  int_marker.description = cropper_->getName();
359  visualization_msgs::InteractiveMarkerControl control;
360  control.always_visible = true;
361  visualization_msgs::Marker cropper_marker = cropper_->getMarker();
362  control.interaction_mode
363  = visualization_msgs::InteractiveMarkerControl::BUTTON;
364  control.markers.push_back(cropper_marker);
365  int_marker.controls.push_back(control);
366  // set the position of the cropper_marker
367  Eigen::Vector3f offset_pos(pose_offset.translation());
368  Eigen::Quaternionf offset_rot(pose_offset.rotation());
369  int_marker.pose.position.x = offset_pos[0];
370  int_marker.pose.position.y = offset_pos[1];
371  int_marker.pose.position.z = offset_pos[2];
372  int_marker.pose.orientation.x = offset_rot.x();
373  int_marker.pose.orientation.y = offset_rot.y();
374  int_marker.pose.orientation.z = offset_rot.z();
375  int_marker.pose.orientation.w = offset_rot.w();
376  control.markers.push_back(cropper_marker);
377  ROS_DEBUG("pos: %f, %f, %f", int_marker.pose.position.x,
378  int_marker.pose.position.y,
379  int_marker.pose.position.z);
380  ROS_DEBUG("rot: %f.; %f, %f, %f", int_marker.pose.orientation.w,
381  int_marker.pose.orientation.x,
382  int_marker.pose.orientation.y,
383  int_marker.pose.orientation.z);
384 
385  // add 6dof marker
386  im_helpers::add6DofControl(int_marker, false);
387 
388  server_->insert(int_marker,
389  boost::bind(&PointCloudCropper::processFeedback, this, _1));
390  }
391 
393  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
394  {
395  unsigned int menu_entry_id = feedback->menu_entry_id;
396  EntryHandleVector::iterator it = std::find(cropper_entries_.begin(),
397  cropper_entries_.end(),
398  menu_entry_id);
399  size_t index = std::distance(cropper_entries_.begin(), it);
400  if (index >= cropper_candidates_.size()) {
401  ROS_ERROR("the index of the chosen cropper is out of the"
402  "range of candidate");
403  return;
404  }
405  Cropper::Ptr next_cropper = cropper_candidates_[index];
406  if (next_cropper == cropper_) {
407  ROS_DEBUG("same cropper");
408  return;
409  }
410  else {
411  changeCropper(next_cropper);
412  }
413  }
414 
416  {
417  for (size_t i = 0; i < cropper_candidates_.size(); i++) {
418  Cropper::Ptr the_cropper = cropper_candidates_[i];
419  if (the_cropper == cropper_) {
420  menu_handler_.setCheckState(
421  cropper_entries_[i],
423  }
424  else {
425  menu_handler_.setCheckState(
426  cropper_entries_[i],
428  }
429  }
430  }
431 
433  {
434  next_cropper->setPose(cropper_->getPose());
435  cropper_ = next_cropper;
436 
437  reInitializeInteractiveMarker();
438  }
439 
441  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
442  {
443  unsigned int menu_entry_id = feedback->menu_entry_id;
444  if (menu_entry_id == 1) { // "Crop"
445  cropAndPublish(point_pub_);
446  }
447  }
448 
449  void PointCloudCropper::inputCallback(const sensor_msgs::PointCloud2::ConstPtr& msg)
450  {
451  boost::mutex::scoped_lock lock(mutex_);
452  latest_pointcloud_ = msg;
453  cropAndPublish(point_visualization_pub_);
454  }
455 
456 }
457 int main(int argc, char** argv)
458 {
459  ros::init(argc, argv, "pointcloud_cropper");
460  ros::NodeHandle nh, pnh("~");
462  ros::spin();
463 }
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
f
virtual visualization_msgs::Marker getMarker()
#define ROS_FATAL(...)
virtual void menuFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
std::shared_ptr< Cropper > Ptr
pos
void publish(const boost::shared_ptr< M > &message) const
virtual void changeCropper(Cropper::Ptr next_cropper)
Cropper(const unsigned int nr_parameter)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual void initializeInteractiveMarker(Eigen::Affine3f pose_offset=Eigen::Affine3f::Identity())
virtual void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
ROSCPP_DECL const std::string & getName()
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
virtual visualization_msgs::Marker getMarker()
#define ROS_WARN(...)
virtual void setPose(Eigen::Affine3f pose)
std::vector< double > parameters_
ROSCPP_DECL void spin(Spinner &spinner)
virtual bool isInside(const pcl::PointXYZ &p)
virtual void changeCropperCallback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Identity
virtual Eigen::Affine3f getPose()
virtual void crop(const pcl::PointCloud< pcl::PointXYZ >::Ptr &input, pcl::PointCloud< pcl::PointXYZ >::Ptr output)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual bool isInside(const pcl::PointXYZ &p)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define ROS_DEBUG_STREAM(args)
mutex_t * lock
virtual void updateInteractiveMarker(Eigen::Affine3f pose_offset=Eigen::Affine3f::Identity())
char * index(char *sp, char c)
p
virtual void updateParameter(const double val, const unsigned int index)
void add6DofControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false)
int main(int argc, char **argv)
virtual void configCallback(Config &config, uint32_t level)
PointCloudCropper(ros::NodeHandle &nh, ros::NodeHandle &pnh)
virtual void cropAndPublish(ros::Publisher &pub)
virtual bool isInside(const pcl::PointXYZ &p)=0
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


jsk_interactive_marker
Author(s): furuta
autogenerated on Sat Mar 20 2021 03:03:33