depth_self_filter_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Willow Garage, Inc.
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 Willow Garage 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 /* Author: Suat Gedikli */
36 
40 #include <ros/ros.h>
45 #include <cv_bridge/cv_bridge.h>
46 
48 static const std::string LOGNAME = "depth_self_filter_nodelet";
49 
51 {
52 }
53 
55 {
56  ros::NodeHandle& nh = getNodeHandle();
57  ros::NodeHandle& private_nh = getPrivateNodeHandle();
58  input_depth_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
59  filtered_depth_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
60  filtered_label_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
61  model_depth_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
62  model_label_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
63 
64  // Read parameters
65  private_nh.param("queue_size", queue_size_, 1);
66  private_nh.param("near_clipping_plane_distance", near_clipping_plane_distance_, 0.4);
67  private_nh.param("far_clipping_plane_distance", far_clipping_plane_distance_, 5.0);
68  ;
69  private_nh.param("shadow_threshold", shadow_threshold_, 0.3);
70  private_nh.param("padding_scale", padding_scale_, 1.0);
71  private_nh.param("padding_offset", padding_offset_, 0.005);
72  double tf_update_rate = 30.;
73  private_nh.param("tf_update_rate", tf_update_rate, 30.0);
74  transform_provider_.setUpdateRate(tf_update_rate);
75 
76  image_transport::SubscriberStatusCallback itssc = [this](auto&& /*unused*/) { connectCb(); };
77  ros::SubscriberStatusCallback rssc = [this](auto&& /*unused*/) { connectCb(); };
78 
79  std::lock_guard<std::mutex> lock(connect_mutex_);
80  pub_filtered_depth_image_ =
81  filtered_depth_transport_->advertiseCamera("/filtered/depth", queue_size_, itssc, itssc, rssc, rssc);
82  pub_filtered_label_image_ =
83  filtered_label_transport_->advertiseCamera("/filtered/labels", queue_size_, itssc, itssc, rssc, rssc);
84  pub_model_depth_image_ =
85  model_depth_transport_->advertiseCamera("/model/depth", queue_size_, itssc, itssc, rssc, rssc);
86  pub_model_label_image_ =
87  model_depth_transport_->advertiseCamera("/model/label", queue_size_, itssc, itssc, rssc, rssc);
88 
89  filtered_depth_ptr_ = std::make_shared<cv_bridge::CvImage>();
90  filtered_label_ptr_ = std::make_shared<cv_bridge::CvImage>();
91  model_depth_ptr_ = std::make_shared<cv_bridge::CvImage>();
92  model_label_ptr_ = std::make_shared<cv_bridge::CvImage>();
93 
94  mesh_filter_ = std::make_shared<MeshFilter<StereoCameraModel>>(
95  [&tfp = transform_provider_](mesh_filter::MeshHandle mesh, Eigen::Isometry3d& tf) {
96  return tfp.getTransform(mesh, tf);
97  },
99  mesh_filter_->parameters().setDepthRange(near_clipping_plane_distance_, far_clipping_plane_distance_);
100  mesh_filter_->setShadowThreshold(shadow_threshold_);
101  mesh_filter_->setPaddingOffset(padding_offset_);
102  mesh_filter_->setPaddingScale(padding_scale_);
103  // add meshesfla
104  addMeshes(*mesh_filter_);
105  transform_provider_.start();
106 }
107 
108 void mesh_filter::DepthSelfFiltering::filter(const sensor_msgs::ImageConstPtr& depth_msg,
109  const sensor_msgs::CameraInfoConstPtr& info_msg)
110 {
111  transform_provider_.setFrame(depth_msg->header.frame_id);
112  // do filtering here
113  mesh_filter::StereoCameraModel::Parameters& params = mesh_filter_->parameters();
114  params.setCameraParameters(info_msg->K[0], info_msg->K[4], info_msg->K[2], info_msg->K[5]);
115  params.setImageSize(depth_msg->width, depth_msg->height);
116 
117  // Handling of two possible encodings of a depth image: 16UC1 and 32FC1
118  if (depth_msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1)
119  {
121  "The input depth image uses a 16UC1 encoding. Consider converting the publisher to "
122  "generate the canonical 32FC1 encoding instead according to ROS REP-118.");
123  mesh_filter_->filter(depth_msg->data.data(), GL_UNSIGNED_SHORT);
124  }
125  else if (depth_msg->encoding == sensor_msgs::image_encodings::TYPE_32FC1)
126  mesh_filter_->filter(reinterpret_cast<const float*>(depth_msg->data.data()), GL_FLOAT);
127  else
128  {
129  ROS_WARN_STREAM_THROTTLE_NAMED(1.0, LOGNAME, "Unsupported encoding of depth image: " << depth_msg->encoding);
130  return;
131  }
132 
133  if (pub_filtered_depth_image_.getNumSubscribers() > 0)
134  {
135  filtered_depth_ptr_->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
136  filtered_depth_ptr_->header = depth_msg->header;
137 
138  if (static_cast<uint32_t>(filtered_depth_ptr_->image.cols) != depth_msg->width ||
139  static_cast<uint32_t>(filtered_depth_ptr_->image.rows) != depth_msg->height)
140  filtered_depth_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_32FC1);
141  mesh_filter_->getFilteredDepth((float*)filtered_depth_ptr_->image.data);
142  pub_filtered_depth_image_.publish(filtered_depth_ptr_->toImageMsg(), info_msg);
143  }
144 
145  // this is from rendering of the model
146  if (pub_model_depth_image_.getNumSubscribers() > 0)
147  {
148  model_depth_ptr_->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
149  model_depth_ptr_->header = depth_msg->header;
150 
151  if (static_cast<uint32_t>(model_depth_ptr_->image.cols) != depth_msg->width ||
152  static_cast<uint32_t>(model_depth_ptr_->image.rows) != depth_msg->height)
153  model_depth_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_32FC1);
154  mesh_filter_->getModelDepth((float*)model_depth_ptr_->image.data);
155  pub_model_depth_image_.publish(model_depth_ptr_->toImageMsg(), info_msg);
156  }
157 
158  if (pub_filtered_label_image_.getNumSubscribers() > 0)
159  {
160  filtered_label_ptr_->encoding = sensor_msgs::image_encodings::RGBA8;
161  filtered_label_ptr_->header = depth_msg->header;
162 
163  if (static_cast<uint32_t>(filtered_label_ptr_->image.cols) != depth_msg->width ||
164  static_cast<uint32_t>(filtered_label_ptr_->image.rows) != depth_msg->height)
165  filtered_label_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_8UC4);
166  mesh_filter_->getFilteredLabels((unsigned int*)filtered_label_ptr_->image.data);
167  pub_filtered_label_image_.publish(filtered_label_ptr_->toImageMsg(), info_msg);
168  }
169 
170  if (pub_model_label_image_.getNumSubscribers() > 0)
171  {
172  model_label_ptr_->encoding = sensor_msgs::image_encodings::RGBA8;
173  model_label_ptr_->header = depth_msg->header;
174  if (static_cast<uint32_t>(model_label_ptr_->image.cols) != depth_msg->width ||
175  static_cast<uint32_t>(model_label_ptr_->image.rows) != depth_msg->height)
176  model_label_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_8UC4);
177  mesh_filter_->getModelLabels((unsigned int*)model_label_ptr_->image.data);
178  pub_model_label_image_.publish(model_label_ptr_->toImageMsg(), info_msg);
179  }
180 }
181 
183 {
185  moveit::core::RobotModelConstPtr robot_model = robot_model_loader.getModel();
186  const auto& links = robot_model->getLinkModelsWithCollisionGeometry();
187  for (auto link : links)
188  {
189  const auto& shapes = link->getShapes();
190  for (const auto& shape : shapes)
191  {
192  if (shape->type == shapes::MESH)
193  {
194  const shapes::Mesh& m = static_cast<const shapes::Mesh&>(*shape);
195  MeshHandle mesh_handle = mesh_filter.addMesh(m);
196  transform_provider_.addHandle(mesh_handle, link->getName());
197  }
198  }
199  }
200 }
201 
202 // Handles (un)subscribing when clients (un)subscribe
204 {
205  std::lock_guard<std::mutex> lock(connect_mutex_);
206  if (pub_filtered_depth_image_.getNumSubscribers() == 0 && pub_filtered_label_image_.getNumSubscribers() == 0 &&
207  pub_model_depth_image_.getNumSubscribers() == 0 && pub_model_label_image_.getNumSubscribers() == 0)
208  {
209  sub_depth_image_.shutdown();
210  }
211  else if (!sub_depth_image_)
212  {
213  image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
214  sub_depth_image_ =
215  input_depth_transport_->subscribeCamera("depth", queue_size_, &DepthSelfFiltering::depthCb, this, hints);
216  }
217 }
218 
219 void mesh_filter::DepthSelfFiltering::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
220  const sensor_msgs::CameraInfoConstPtr& info_msg)
221 {
222  filter(depth_msg, info_msg);
223 }
224 
ROS_WARN_STREAM_THROTTLE_NAMED
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
robot_model.h
sensor_msgs::image_encodings
shapes
image_encodings.h
mesh_filter::DepthSelfFiltering::filter
void filter(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
main filtering routine
Definition: depth_self_filter_nodelet.cpp:108
ros.h
robot_model_loader
sensor_msgs::image_encodings::RGBA8
const std::string RGBA8
ros::TransportHints
mesh_filter::DepthSelfFiltering::addMeshes
void addMeshes(mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > &mesh_filter)
adding the meshes to a given mesh filter object.
Definition: depth_self_filter_nodelet.cpp:182
mesh_filter::DepthSelfFiltering::connectCb
void connectCb()
Callback for connection/deconnection of listener.
Definition: depth_self_filter_nodelet.cpp:203
robot_model_loader.h
mesh_filter::SensorModel::Parameters::setImageSize
void setImageSize(unsigned width, unsigned height)
sets the image size
Definition: sensor_model.cpp:53
shapes::Mesh
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
mesh_filter::DepthSelfFiltering
Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where...
Definition: depth_self_filter_nodelet.h:86
shapes::MESH
MESH
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
stereo_camera_model.h
LOGNAME
static const std::string LOGNAME
Definition: depth_self_filter_nodelet.cpp:48
mesh_filter.h
robot_model_loader::RobotModelLoader
subscriber_filter.h
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(test_moveit_controller_manager::TestMoveItControllerManager, moveit_controller_manager::MoveItControllerManager)
depth_self_filter_nodelet.h
mesh_filter::DepthSelfFiltering::onInit
void onInit() override
Nodelet init callback.
Definition: depth_self_filter_nodelet.cpp:54
ROS_WARN_STREAM_ONCE_NAMED
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
mesh_filter::StereoCameraModel::Parameters::setCameraParameters
void setCameraParameters(float fx, float fy, float cx, float cy)
sets the camera parameters of the pinhole camera where the disparities were obtained....
Definition: stereo_camera_model.cpp:63
mesh_filter::MeshHandle
unsigned int MeshHandle
Definition: mesh_filter_base.h:60
nodelet::Nodelet
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
mesh_filter::StereoCameraModel::REGISTERED_PSDK_PARAMS
static const StereoCameraModel::Parameters & REGISTERED_PSDK_PARAMS
predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion)
Definition: stereo_camera_model.h:215
cv_bridge.h
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
mesh_filter::MeshFilter< StereoCameraModel >
mesh_filter::DepthSelfFiltering::depthCb
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Callback for subscribed depth images.
Definition: depth_self_filter_nodelet.cpp:219
image_transport::TransportHints
mesh_filter::DepthSelfFiltering::~DepthSelfFiltering
~DepthSelfFiltering() override
Definition: depth_self_filter_nodelet.cpp:50
ros::NodeHandle
mesh_filter
Definition: depth_self_filter_nodelet.h:47
mesh_filter::StereoCameraModel::Parameters
Parameters for Stereo-like devices.
Definition: stereo_camera_model.h:119


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Thu Jun 27 2024 02:27:08