moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
41#include <image_transport/subscriber_filter.h>
42#include <sensor_msgs/image_encodings.h>
45#include <cv_bridge/cv_bridge.h>
46
47namespace enc = sensor_msgs::image_encodings;
48
49mesh_filter::DepthSelfFiltering::~DepthSelfFiltering()
50{
51}
52
54{
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);
62
63 // Read parameters
64 private_nh.param("queue_size", rmw_qos_profile_sensor_data.depth, 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);
67 ;
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);
74
75 image_transport::SubscriberStatusCallback itssc = [this](auto&&) { connectCb(); };
76 ros::SubscriberStatusCallback rssc = [this](auto&&) { connectCb(); };
77
78 std::lock_guard<std::mutex> lock(connect_mutex_);
79 pub_filtered_depth_image_ = filtered_depth_transport_->advertiseCamera(
80 "/filtered/depth", rmw_qos_profile_sensor_data.depth, itssc, itssc, rssc, rssc, rmw_qos_profile_sensor_data);
81 pub_filtered_label_image_ = filtered_label_transport_->advertiseCamera(
82 "/filtered/labels", rmw_qos_profile_sensor_data.depth, itssc, itssc, rssc, rssc, rmw_qos_profile_sensor_data);
83 pub_model_depth_image_ = model_depth_transport_->advertiseCamera(
84 "/model/depth", rmw_qos_profile_sensor_data.depth, itssc, itssc, rssc, rssc, rmw_qos_profile_sensor_data);
85 pub_model_label_image_ = model_depth_transport_->advertiseCamera(
86 "/model/label", rmw_qos_profile_sensor_data.depth, itssc, itssc, rssc, rssc, rmw_qos_profile_sensor_data);
87
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>();
92
93 mesh_filter_ = std::make_shared<MeshFilter<StereoCameraModel>>(
94 [&tfp = transform_provider_](mesh_filter::MeshHandle mesh, Eigen::Isometry3d& tf) {
95 return tfp.getTransform(mesh, tf);
96 },
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_);
102 // add meshesfla
103 addMeshes(*mesh_filter_);
104 transform_provider_.start();
105}
106
107void mesh_filter::DepthSelfFiltering::filter(const sensor_msgs::ImageConstPtr& depth_msg,
108 const sensor_msgs::CameraInfoConstPtr& info_msg)
109{
110 transform_provider_.setFrame(depth_msg->header.frame_id);
111 // do filtering here
112 mesh_filter::StereoCameraModel::Parameters& params = mesh_filter_->parameters();
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);
115
116 const double* src = (const double*)&depth_msg->data[0];
117 //*
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);
124
125 mesh_filter_->filter(data, GL_UNSIGNED_SHORT);
126 // delete[] data;
127 /*/
128 mesh_filter_->filter ((void*) &depth_msg->data[0], GL_FLOAT);
129 //*/
130 if (pub_filtered_depth_image_.getNumSubscribers() > 0)
131 {
132 filtered_depth_ptr_->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
133 filtered_depth_ptr_->header = depth_msg->header;
134
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((double*)filtered_depth_ptr_->image.data);
139 pub_filtered_depth_image_.publish(filtered_depth_ptr_->toImageMsg(), info_msg);
140 }
141
142 // this is from rendering of the model
143 if (pub_model_depth_image_.getNumSubscribers() > 0)
144 {
145 model_depth_ptr_->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
146 model_depth_ptr_->header = depth_msg->header;
147
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((double*)model_depth_ptr_->image.data);
152 pub_model_depth_image_.publish(model_depth_ptr_->toImageMsg(), info_msg);
153 }
154
155 if (pub_filtered_label_image_.getNumSubscribers() > 0)
156 {
157 filtered_label_ptr_->encoding = sensor_msgs::image_encodings::RGBA8;
158 filtered_label_ptr_->header = depth_msg->header;
159
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);
165 }
166
167 if (pub_model_label_image_.getNumSubscribers() > 0)
168 {
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);
176 }
177}
178
179void mesh_filter::DepthSelfFiltering::addMeshes(MeshFilter<StereoCameraModel>& mesh_filter)
180{
182 moveit::core::RobotModelConstPtr robot_model = robot_model_loader.getModel();
183 const auto& links = robot_model->getLinkModelsWithCollisionGeometry();
184 for (auto link : links)
185 {
186 const auto& shapes = link->getShapes();
187 for (const auto& shape : shapes)
188 {
189 if (shape->type == shapes::MESH)
190 {
191 const shapes::Mesh& m = static_cast<const shapes::Mesh&>(*shape);
192 MeshHandle mesh_handle = mesh_filter.addMesh(m);
193 transform_provider_.addHandle(mesh_handle, link->getName());
194 }
195 }
196 }
197}
198
199// Handles (un)subscribing when clients (un)subscribe
200void mesh_filter::DepthSelfFiltering::connectCb()
201{
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)
205 {
206 sub_depth_image_.shutdown();
207 }
208 else if (!sub_depth_image_)
209 {
210 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
211 sub_depth_image_ =
212 input_depth_transport_->subscribeCamera("depth", rmw_qos_profile_sensor_data.depth,
213 &DepthSelfFiltering::depthCb, this, hints, rmw_qos_profile_sensor_data);
214 }
215}
216
217void mesh_filter::DepthSelfFiltering::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
218 const sensor_msgs::CameraInfoConstPtr& info_msg)
219{
220 filter(depth_msg, info_msg);
221}
222
223#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)
unsigned int MeshHandle
Definition world.h:49