45 #include <Eigen/Geometry>
69 boost::mutex connect_mutex_;
75 bool fill_upsampling_holes_;
76 bool use_rgb_timestamp_;
78 virtual void onInit();
82 void imageCb(
const sensor_msgs::ImageConstPtr& depth_image_msg,
83 const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
84 const sensor_msgs::CameraInfoConstPtr& rgb_info_msg);
87 void convert(
const sensor_msgs::ImageConstPtr& depth_msg,
88 const sensor_msgs::ImagePtr& registered_msg,
89 const Eigen::Affine3d& depth_to_rgb);
104 private_nh.
param(
"queue_size", queue_size, 5);
105 private_nh.
param(
"fill_upsampling_holes", fill_upsampling_holes_,
false);
106 private_nh.
param(
"use_rgb_timestamp", use_rgb_timestamp_,
false);
109 sync_.reset(
new Synchronizer(
SyncPolicy(queue_size), sub_depth_image_, sub_depth_info_, sub_rgb_info_) );
110 sync_->registerCallback(boost::bind(&
RegisterNodelet::imageCb,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
117 boost::lock_guard<boost::mutex> lock(connect_mutex_);
118 pub_registered_ = it_depth_reg.advertiseCamera(
"image_rect", 1,
119 image_connect_cb, image_connect_cb,
120 info_connect_cb, info_connect_cb);
126 boost::lock_guard<boost::mutex> lock(connect_mutex_);
127 if (pub_registered_.getNumSubscribers() == 0)
129 sub_depth_image_.unsubscribe();
130 sub_depth_info_ .unsubscribe();
131 sub_rgb_info_ .unsubscribe();
133 else if (!sub_depth_image_.getSubscriber())
136 sub_depth_image_.subscribe(*it_depth_,
"image_rect", 1, hints);
137 sub_depth_info_ .subscribe(*nh_depth_,
"camera_info", 1);
138 sub_rgb_info_ .subscribe(*nh_rgb_,
"camera_info", 1);
143 const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
144 const sensor_msgs::CameraInfoConstPtr& rgb_info_msg)
147 depth_model_.fromCameraInfo(depth_info_msg);
148 rgb_model_ .fromCameraInfo(rgb_info_msg);
151 Eigen::Affine3d depth_to_rgb;
154 geometry_msgs::TransformStamped transform = tf_buffer_->lookupTransform (
155 rgb_info_msg->header.frame_id, depth_info_msg->header.frame_id,
156 depth_info_msg->header.stamp);
169 sensor_msgs::ImagePtr registered_msg(
new sensor_msgs::Image );
170 registered_msg->header.stamp = use_rgb_timestamp_ ? rgb_info_msg->header.stamp : depth_image_msg->header.stamp;
171 registered_msg->header.frame_id = rgb_info_msg->header.frame_id;
172 registered_msg->encoding = depth_image_msg->encoding;
174 cv::Size resolution = rgb_model_.reducedResolution();
175 registered_msg->height = resolution.height;
176 registered_msg->width = resolution.width;
179 if (depth_image_msg->encoding == enc::TYPE_16UC1)
181 convert<uint16_t>(depth_image_msg, registered_msg, depth_to_rgb);
183 else if (depth_image_msg->encoding == enc::TYPE_32FC1)
185 convert<float>(depth_image_msg, registered_msg, depth_to_rgb);
189 NODELET_ERROR_THROTTLE(5,
"Depth image has unsupported encoding [%s]", depth_image_msg->encoding.c_str());
194 sensor_msgs::CameraInfoPtr registered_info_msg(
new sensor_msgs::CameraInfo(*rgb_info_msg) );
195 registered_info_msg->header.stamp = registered_msg->header.stamp;
197 pub_registered_.publish(registered_msg, registered_info_msg);
202 const sensor_msgs::ImagePtr& registered_msg,
203 const Eigen::Affine3d& depth_to_rgb)
206 registered_msg->step = registered_msg->width *
sizeof(T);
207 registered_msg->data.resize( registered_msg->height * registered_msg->step );
209 DepthTraits<T>::initializeBuffer(registered_msg->data);
212 double inv_depth_fx = 1.0 / depth_model_.fx();
213 double inv_depth_fy = 1.0 / depth_model_.fy();
214 double depth_cx = depth_model_.cx(), depth_cy = depth_model_.cy();
215 double depth_Tx = depth_model_.Tx(), depth_Ty = depth_model_.Ty();
216 double rgb_fx = rgb_model_.fx(), rgb_fy = rgb_model_.fy();
217 double rgb_cx = rgb_model_.cx(), rgb_cy = rgb_model_.cy();
218 double rgb_Tx = rgb_model_.Tx(), rgb_Ty = rgb_model_.Ty();
222 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
223 int row_step = depth_msg->step /
sizeof(T);
224 T* registered_data =
reinterpret_cast<T*
>(®istered_msg->data[0]);
226 for (
unsigned v = 0; v < depth_msg->height; ++v, depth_row += row_step)
228 for (
unsigned u = 0; u < depth_msg->width; ++u, ++raw_index)
230 T raw_depth = depth_row[u];
231 if (!DepthTraits<T>::valid(raw_depth))
236 if (fill_upsampling_holes_ ==
false)
240 Eigen::Vector4d xyz_depth;
241 xyz_depth << ((u - depth_cx)*depth - depth_Tx) * inv_depth_fx,
242 ((v - depth_cy)*depth - depth_Ty) * inv_depth_fy,
247 Eigen::Vector4d xyz_rgb = depth_to_rgb * xyz_depth;
250 double inv_Z = 1.0 / xyz_rgb.z();
251 int u_rgb = (rgb_fx*xyz_rgb.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
252 int v_rgb = (rgb_fy*xyz_rgb.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
254 if (u_rgb < 0 || u_rgb >= (
int)registered_msg->width ||
255 v_rgb < 0 || v_rgb >= (int)registered_msg->height)
258 T& reg_depth = registered_data[v_rgb*registered_msg->width + u_rgb];
262 reg_depth = new_depth;
267 Eigen::Vector4d xyz_depth_1, xyz_depth_2;
268 xyz_depth_1 << ((u-0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
269 ((v-0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
272 xyz_depth_2 << ((u+0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
273 ((v+0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
278 Eigen::Vector4d xyz_rgb_1 = depth_to_rgb * xyz_depth_1;
279 Eigen::Vector4d xyz_rgb_2 = depth_to_rgb * xyz_depth_2;
282 double inv_Z = 1.0 / xyz_rgb_1.z();
283 int u_rgb_1 = (rgb_fx*xyz_rgb_1.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
284 int v_rgb_1 = (rgb_fy*xyz_rgb_1.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
285 inv_Z = 1.0 / xyz_rgb_2.z();
286 int u_rgb_2 = (rgb_fx*xyz_rgb_2.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
287 int v_rgb_2 = (rgb_fy*xyz_rgb_2.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
289 if (u_rgb_1 < 0 || u_rgb_2 >= (
int)registered_msg->width ||
290 v_rgb_1 < 0 || v_rgb_2 >= (int)registered_msg->height)
293 for (
int nv=v_rgb_1; nv<=v_rgb_2; ++nv)
295 for (
int nu=u_rgb_1; nu<=u_rgb_2; ++nu)
297 T& reg_depth = registered_data[nv*registered_msg->width + nu];
301 reg_depth = new_depth;