41 #include <image_transport/subscriber_filter.h>
42 #include <sensor_msgs/image_encodings.h>
45 #include <cv_bridge/cv_bridge.h>
47 namespace enc = sensor_msgs::image_encodings;
49 mesh_filter::DepthSelfFiltering::~DepthSelfFiltering()
55 ros::NodeHandle& nh = getNodeHandle();
56 ros::NodeHandle& private_nh = getPrivateNodeHandle();
57 input_depth_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
58 filtered_depth_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
59 filtered_label_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
60 model_depth_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
61 model_label_transport_ = std::make_shared<image_transport::ImageTransport>(nh);
64 private_nh.param(
"queue_size", queue_size_, 1);
65 private_nh.param(
"near_clipping_plane_distance", near_clipping_plane_distance_, 0.4);
66 private_nh.param(
"far_clipping_plane_distance", far_clipping_plane_distance_, 5.0);
68 private_nh.param(
"shadow_threshold", shadow_threshold_, 0.3);
69 private_nh.param(
"padding_scale", padding_scale_, 1.0);
70 private_nh.param(
"padding_offset", padding_offset_, 0.005);
71 double tf_update_rate = 30.;
72 private_nh.param(
"tf_update_rate", tf_update_rate, 30.0);
73 transform_provider_.setUpdateRate(tf_update_rate);
75 image_transport::SubscriberStatusCallback itssc = [
this](
auto&&) { connectCb(); };
76 ros::SubscriberStatusCallback rssc = [
this](
auto&&) { connectCb(); };
78 std::lock_guard<std::mutex> lock(connect_mutex_);
79 pub_filtered_depth_image_ =
80 filtered_depth_transport_->advertiseCamera(
"/filtered/depth", queue_size_, itssc, itssc, rssc, rssc);
81 pub_filtered_label_image_ =
82 filtered_label_transport_->advertiseCamera(
"/filtered/labels", queue_size_, itssc, itssc, rssc, rssc);
83 pub_model_depth_image_ =
84 model_depth_transport_->advertiseCamera(
"/model/depth", queue_size_, itssc, itssc, rssc, rssc);
85 pub_model_label_image_ =
86 model_depth_transport_->advertiseCamera(
"/model/label", queue_size_, itssc, itssc, rssc, rssc);
88 filtered_depth_ptr_ = std::make_shared<cv_bridge::CvImage>();
89 filtered_label_ptr_ = std::make_shared<cv_bridge::CvImage>();
90 model_depth_ptr_ = std::make_shared<cv_bridge::CvImage>();
91 model_label_ptr_ = std::make_shared<cv_bridge::CvImage>();
93 mesh_filter_ = std::make_shared<MeshFilter<StereoCameraModel>>(
95 return tfp.getTransform(mesh, tf);
98 mesh_filter_->parameters().setDepthRange(near_clipping_plane_distance_, far_clipping_plane_distance_);
99 mesh_filter_->setShadowThreshold(shadow_threshold_);
100 mesh_filter_->setPaddingOffset(padding_offset_);
101 mesh_filter_->setPaddingScale(padding_scale_);
103 addMeshes(*mesh_filter_);
104 transform_provider_.start();
107 void mesh_filter::DepthSelfFiltering::filter(
const sensor_msgs::ImageConstPtr& depth_msg,
108 const sensor_msgs::CameraInfoConstPtr& info_msg)
110 transform_provider_.setFrame(depth_msg->header.frame_id);
113 params.
setCameraParameters(info_msg->K[0], info_msg->K[4], info_msg->K[2], info_msg->K[5]);
114 params.
setImageSize(depth_msg->width, depth_msg->height);
116 const float* src = (
const float*)&depth_msg->data[0];
118 static unsigned data_size = 0;
119 static unsigned short* data =
nullptr;
120 if (data_size < depth_msg->width * depth_msg->height)
121 data =
new unsigned short[depth_msg->width * depth_msg->height];
122 for (
unsigned idx = 0; idx < depth_msg->width * depth_msg->height; ++idx)
123 data[idx] = (
unsigned short)(src[idx] * 1000.0);
125 mesh_filter_->filter(data, GL_UNSIGNED_SHORT);
130 if (pub_filtered_depth_image_.getNumSubscribers() > 0)
132 filtered_depth_ptr_->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
133 filtered_depth_ptr_->header = depth_msg->header;
135 if (
static_cast<uint32_t
>(filtered_depth_ptr_->image.cols) != depth_msg->width ||
136 static_cast<uint32_t
>(filtered_depth_ptr_->image.rows) != depth_msg->height)
137 filtered_depth_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_32FC1);
138 mesh_filter_->getFilteredDepth((
float*)filtered_depth_ptr_->image.data);
139 pub_filtered_depth_image_.publish(filtered_depth_ptr_->toImageMsg(), info_msg);
143 if (pub_model_depth_image_.getNumSubscribers() > 0)
145 model_depth_ptr_->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
146 model_depth_ptr_->header = depth_msg->header;
148 if (
static_cast<uint32_t
>(model_depth_ptr_->image.cols) != depth_msg->width ||
149 static_cast<uint32_t
>(model_depth_ptr_->image.rows) != depth_msg->height)
150 model_depth_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_32FC1);
151 mesh_filter_->getModelDepth((
float*)model_depth_ptr_->image.data);
152 pub_model_depth_image_.publish(model_depth_ptr_->toImageMsg(), info_msg);
155 if (pub_filtered_label_image_.getNumSubscribers() > 0)
157 filtered_label_ptr_->encoding = sensor_msgs::image_encodings::RGBA8;
158 filtered_label_ptr_->header = depth_msg->header;
160 if (
static_cast<uint32_t
>(filtered_label_ptr_->image.cols) != depth_msg->width ||
161 static_cast<uint32_t
>(filtered_label_ptr_->image.rows) != depth_msg->height)
162 filtered_label_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_8UC4);
163 mesh_filter_->getFilteredLabels((
unsigned int*)filtered_label_ptr_->image.data);
164 pub_filtered_label_image_.publish(filtered_label_ptr_->toImageMsg(), info_msg);
167 if (pub_model_label_image_.getNumSubscribers() > 0)
169 model_label_ptr_->encoding = sensor_msgs::image_encodings::RGBA8;
170 model_label_ptr_->header = depth_msg->header;
171 if (
static_cast<uint32_t
>(model_label_ptr_->image.cols) != depth_msg->width ||
172 static_cast<uint32_t
>(model_label_ptr_->image.rows) != depth_msg->height)
173 model_label_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_8UC4);
174 mesh_filter_->getModelLabels((
unsigned int*)model_label_ptr_->image.data);
175 pub_model_label_image_.publish(model_label_ptr_->toImageMsg(), info_msg);
179 void mesh_filter::DepthSelfFiltering::addMeshes(MeshFilter<StereoCameraModel>&
mesh_filter)
183 const auto& links = robot_model->getLinkModelsWithCollisionGeometry();
184 for (
auto link : links)
186 const auto&
shapes = link->getShapes();
187 for (
const auto& shape :
shapes)
189 if (shape->type == shapes::MESH)
191 const shapes::Mesh& m =
static_cast<const shapes::Mesh&
>(*shape);
193 transform_provider_.addHandle(mesh_handle, link->getName());
200 void mesh_filter::DepthSelfFiltering::connectCb()
202 std::lock_guard<std::mutex> lock(connect_mutex_);
203 if (pub_filtered_depth_image_.getNumSubscribers() == 0 && pub_filtered_label_image_.getNumSubscribers() == 0 &&
204 pub_model_depth_image_.getNumSubscribers() == 0 && pub_model_label_image_.getNumSubscribers() == 0)
206 sub_depth_image_.shutdown();
208 else if (!sub_depth_image_)
210 image_transport::TransportHints hints(
"raw", ros::TransportHints(), getPrivateNodeHandle());
212 input_depth_transport_->subscribeCamera(
"depth", queue_size_, &DepthSelfFiltering::depthCb,
this, hints);
216 void mesh_filter::DepthSelfFiltering::depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
217 const sensor_msgs::CameraInfoConstPtr& info_msg)
219 filter(depth_msg, info_msg);
222 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where...
void onInit() override
Nodelet init callback.
void setImageSize(unsigned width, unsigned height)
sets the image size
Parameters for Stereo-like devices.
void setCameraParameters(float fx, float fy, float cx, float cy)
sets the camera parameters of the pinhole camera where the disparities were obtained....
static const StereoCameraModel::Parameters & REGISTERED_PSDK_PARAMS
predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion)