roi_clipper_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/or 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 <cv_bridge/cv_bridge.h>
41 #include <opencv2/opencv.hpp>
44 
45 namespace jsk_pcl_ros
46 {
48  {
49  DiagnosticNodelet::onInit();
50  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
51  pnh_->param("not_sync", not_sync_, false);
52  pnh_->param("keep_organized", keep_organized_, false);
53  pub_image_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
54  if (not_sync_) {
55  pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
56  pub_cloud_indices_ = advertise<PCLIndicesMsg>(*pnh_, "output/cloud_indices", 1);
57  }
58  onInitPostProcess();
59  }
60 
62  // message_filters::Synchronizer needs to be called reset
63  // before message_filters::Subscriber is freed.
64  // Calling reset fixes the following error on shutdown of the nodelet:
65  // terminate called after throwing an instance of
66  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
67  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
68  // Also see https://github.com/ros/ros_comm/issues/720 .
69  sync_.reset();
70  }
71 
73  {
74  if (!not_sync_) {
75  sub_image_.subscribe(*pnh_, "input/image", 1);
76  sub_info_.subscribe(*pnh_, "input/camera_info", 1);
77  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
78  sync_->connectInput(sub_image_, sub_info_);
79  sync_->registerCallback(boost::bind(&ROIClipper::clip, this, _1, _2));
80  }
81  else {
82  sub_image_no_sync_ = pnh_->subscribe(
83  "input/image", 1,
85  sub_info_no_sync_ = pnh_->subscribe(
86  "input/camera_info", 1,
88  sub_cloud_no_sync_ = pnh_->subscribe(
89  "input/cloud", 1,
91  }
92  }
93 
95  {
96  if (!not_sync_) {
99  }
100  else {
104  }
105  }
106  void ROIClipper::clip(const sensor_msgs::Image::ConstPtr& image_msg,
107  const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg)
108  {
109  vital_checker_->poke();
110  try {
112  cv::Mat image = cv_ptr->image;
113  cv::Rect roi(camera_info_msg->roi.x_offset, camera_info_msg->roi.y_offset,
114  camera_info_msg->roi.width, camera_info_msg->roi.height);
115  //NODELET_INFO("roi::(%d, %d, %d, %d)", roi.x, roi.y, roi.width, roi.height);
116  cv::Mat image_roi = image(roi);
117  // cv::imshow("roi", image_roi);
118  // cv::waitKey(3);
119  cv_bridge::CvImage roi_bridge(image_msg->header,
121  image_roi);
122  pub_image_.publish(roi_bridge.toImageMsg());
123  }
124  catch (cv_bridge::Exception& e)
125  {
126  NODELET_ERROR("cv_bridge exception: %s", e.what());
127  return;
128  }
129  }
130 
132  const sensor_msgs::CameraInfo::ConstPtr& info_msg)
133  {
134  boost::mutex::scoped_lock lock(mutex_);
136  }
137 
139  const sensor_msgs::Image::ConstPtr& image_msg)
140  {
141  boost::mutex::scoped_lock lock(mutex_);
142  if (latest_camera_info_) {
143  clip(image_msg, latest_camera_info_);
144  }
145  }
146 
148  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
149  {
150  boost::mutex::scoped_lock lock(mutex_);
151  vital_checker_->poke();
152  if (latest_camera_info_) {
154  PCLIndicesMsg indices;
155  model.fromCameraInfo(latest_camera_info_);
156  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud
157  (new pcl::PointCloud<pcl::PointXYZRGB>);
158  pcl::fromROSMsg(*cloud_msg, *cloud);
159  pcl::PointCloud<pcl::PointXYZRGB>::Ptr clipped_cloud
160  (new pcl::PointCloud<pcl::PointXYZRGB>);
161  cv::Rect region = model.rectifiedRoi();
162  pcl::PointXYZRGB nan_point;
163  nan_point.x = nan_point.y = nan_point.z
164  = std::numeric_limits<float>::quiet_NaN();;
165  for (size_t i = 0; i < cloud->points.size(); i++) {
166  pcl::PointXYZRGB p = cloud->points[i];
167  bool foundp = false;
168  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
169  cv::Point2d uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
170  if (uv.x >= 0 && uv.x <= region.width &&
171  uv.y >= 0 && uv.y <= region.height) {
172  indices.indices.push_back(i);
173  clipped_cloud->points.push_back(p);
174  foundp = true;
175  }
176  }
177  if (!foundp && keep_organized_) {
178  clipped_cloud->points.push_back(nan_point);
179  }
180  }
181  if (keep_organized_) {
182  clipped_cloud->width = cloud->width;
183  clipped_cloud->height = cloud->height;
184  }
185  sensor_msgs::PointCloud2 ros_cloud;
186  pcl::toROSMsg(*clipped_cloud, ros_cloud);
187  ros_cloud.header = cloud_msg->header;
188  pub_cloud_.publish(ros_cloud);
189  indices.header = cloud_msg->header;
190  pub_cloud_indices_.publish(indices);
191  }
192  }
193 }
194 
NODELET_ERROR
#define NODELET_ERROR(...)
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
image_encodings.h
jsk_pcl_ros::ROIClipper::keep_organized_
bool keep_organized_
Definition: roi_clipper.h:138
boost::shared_ptr< CvImage >
i
int i
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
jsk_pcl_ros::ROIClipper::mutex_
boost::mutex mutex_
Definition: roi_clipper.h:136
pinhole_camera_model.h
jsk_pcl_ros::ROIClipper::sub_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
Definition: roi_clipper.h:143
p
p
jsk_pcl_ros::ROIClipper::pub_cloud_indices_
ros::Publisher pub_cloud_indices_
Definition: roi_clipper.h:141
jsk_pcl_ros::ROIClipper::sub_cloud_no_sync_
ros::Subscriber sub_cloud_no_sync_
Definition: roi_clipper.h:147
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
jsk_pcl_ros::ROIClipper::sub_info_no_sync_
ros::Subscriber sub_info_no_sync_
Definition: roi_clipper.h:146
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ROIClipper, nodelet::Nodelet)
ros::Subscriber::shutdown
void shutdown()
cv_bridge::Exception
sensor_msgs::image_encodings::RGB8
const std::string RGB8
jsk_pcl_ros::ROIClipper::onInit
virtual void onInit()
Definition: roi_clipper_nodelet.cpp:47
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
cloud
cloud
jsk_pcl_ros::ROIClipper::cloudCallback
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Definition: roi_clipper_nodelet.cpp:147
class_list_macros.h
roi_clipper.h
jsk_pcl_ros
Definition: add_color_from_image.h:51
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
jsk_pcl_ros::ROIClipper::sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
Definition: roi_clipper.h:142
jsk_pcl_ros::ROIClipper::imageCallback
virtual void imageCallback(const sensor_msgs::Image::ConstPtr &image_msg)
Definition: roi_clipper_nodelet.cpp:138
_1
boost::arg< 1 > _1
jsk_pcl_ros::ROIClipper::~ROIClipper
virtual ~ROIClipper()
Definition: roi_clipper_nodelet.cpp:61
jsk_pcl_ros::ROIClipper::not_sync_
bool not_sync_
Definition: roi_clipper.h:137
jsk_pcl_ros::ROIClipper::unsubscribe
virtual void unsubscribe()
Definition: roi_clipper_nodelet.cpp:94
jsk_pcl_ros::ROIClipper::latest_camera_info_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
Definition: roi_clipper.h:148
pcl_conversion_util.h
depth_error_calibration.model
model
Definition: depth_error_calibration.py:37
message_filters::Subscriber::subscribe
void subscribe()
nodelet::Nodelet
image_geometry::PinholeCameraModel
jsk_pcl_ros::ROIClipper::subscribe
virtual void subscribe()
Definition: roi_clipper_nodelet.cpp:72
cv_bridge.h
jsk_pcl_ros::ROIClipper::pub_image_
ros::Publisher pub_image_
Definition: roi_clipper.h:139
jsk_pcl_ros::ROIClipper
Definition: roi_clipper.h:83
cv_bridge::CvImage
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::ROIClipper::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: roi_clipper.h:144
jsk_pcl_ros::ROIClipper::pub_cloud_
ros::Publisher pub_cloud_
Definition: roi_clipper.h:140
jsk_pcl_ros::ROIClipper::clip
virtual void clip(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info_msg)
Definition: roi_clipper_nodelet.cpp:106
info_msg
info_msg
jsk_pcl_ros::ROIClipper::sub_image_no_sync_
ros::Subscriber sub_image_no_sync_
Definition: roi_clipper.h:145
jsk_pcl_ros::ROIClipper::infoCallback
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Definition: roi_clipper_nodelet.cpp:131


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