45 #include <Eigen/Geometry> 77 virtual void onInit();
81 void imageCb(
const sensor_msgs::ImageConstPtr& depth_image_msg,
82 const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
83 const sensor_msgs::CameraInfoConstPtr& rgb_info_msg);
86 void convert(
const sensor_msgs::ImageConstPtr& depth_msg,
87 const sensor_msgs::ImagePtr& registered_msg,
88 const Eigen::Affine3d& depth_to_rgb);
103 private_nh.
param(
"queue_size", queue_size, 5);
104 private_nh.
param(
"fill_upsampling_holes", fill_upsampling_holes_,
false);
107 sync_.reset(
new Synchronizer(
SyncPolicy(queue_size), sub_depth_image_, sub_depth_info_, sub_rgb_info_) );
115 boost::lock_guard<boost::mutex> lock(connect_mutex_);
117 image_connect_cb, image_connect_cb,
118 info_connect_cb, info_connect_cb);
124 boost::lock_guard<boost::mutex> lock(connect_mutex_);
125 if (pub_registered_.getNumSubscribers() == 0)
127 sub_depth_image_.unsubscribe();
128 sub_depth_info_ .unsubscribe();
129 sub_rgb_info_ .unsubscribe();
131 else if (!sub_depth_image_.getSubscriber())
134 sub_depth_image_.subscribe(*it_depth_,
"image_rect", 1, hints);
135 sub_depth_info_ .subscribe(*nh_depth_,
"camera_info", 1);
136 sub_rgb_info_ .subscribe(*nh_rgb_,
"camera_info", 1);
141 const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
142 const sensor_msgs::CameraInfoConstPtr& rgb_info_msg)
145 depth_model_.fromCameraInfo(depth_info_msg);
146 rgb_model_ .fromCameraInfo(rgb_info_msg);
149 Eigen::Affine3d depth_to_rgb;
152 geometry_msgs::TransformStamped transform = tf_buffer_->lookupTransform (
153 rgb_info_msg->header.frame_id, depth_info_msg->header.frame_id,
154 depth_info_msg->header.stamp);
167 sensor_msgs::ImagePtr registered_msg(
new sensor_msgs::Image );
168 registered_msg->header.stamp = depth_image_msg->header.stamp;
169 registered_msg->header.frame_id = rgb_info_msg->header.frame_id;
170 registered_msg->encoding = depth_image_msg->encoding;
172 cv::Size resolution = rgb_model_.reducedResolution();
173 registered_msg->height = resolution.height;
174 registered_msg->width = resolution.width;
177 if (depth_image_msg->encoding == enc::TYPE_16UC1)
179 convert<uint16_t>(depth_image_msg, registered_msg, depth_to_rgb);
181 else if (depth_image_msg->encoding == enc::TYPE_32FC1)
183 convert<float>(depth_image_msg, registered_msg, depth_to_rgb);
187 NODELET_ERROR_THROTTLE(5,
"Depth image has unsupported encoding [%s]", depth_image_msg->encoding.c_str());
192 sensor_msgs::CameraInfoPtr registered_info_msg(
new sensor_msgs::CameraInfo(*rgb_info_msg) );
193 registered_info_msg->header.stamp = registered_msg->header.stamp;
195 pub_registered_.publish(registered_msg, registered_info_msg);
200 const sensor_msgs::ImagePtr& registered_msg,
201 const Eigen::Affine3d& depth_to_rgb)
204 registered_msg->step = registered_msg->width *
sizeof(T);
205 registered_msg->data.resize( registered_msg->height * registered_msg->step );
210 double inv_depth_fx = 1.0 / depth_model_.fx();
211 double inv_depth_fy = 1.0 / depth_model_.fy();
212 double depth_cx = depth_model_.cx(), depth_cy = depth_model_.cy();
213 double depth_Tx = depth_model_.Tx(), depth_Ty = depth_model_.Ty();
214 double rgb_fx = rgb_model_.fx(), rgb_fy = rgb_model_.fy();
215 double rgb_cx = rgb_model_.cx(), rgb_cy = rgb_model_.cy();
216 double rgb_Tx = rgb_model_.Tx(), rgb_Ty = rgb_model_.Ty();
220 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
221 int row_step = depth_msg->step /
sizeof(T);
222 T* registered_data =
reinterpret_cast<T*
>(®istered_msg->data[0]);
224 for (
unsigned v = 0; v < depth_msg->height; ++v, depth_row += row_step)
226 for (
unsigned u = 0; u < depth_msg->width; ++u, ++raw_index)
228 T raw_depth = depth_row[u];
234 if (fill_upsampling_holes_ ==
false)
238 Eigen::Vector4d xyz_depth;
239 xyz_depth << ((u - depth_cx)*depth - depth_Tx) * inv_depth_fx,
240 ((v - depth_cy)*depth - depth_Ty) * inv_depth_fy,
245 Eigen::Vector4d xyz_rgb = depth_to_rgb * xyz_depth;
248 double inv_Z = 1.0 / xyz_rgb.z();
249 int u_rgb = (rgb_fx*xyz_rgb.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
250 int v_rgb = (rgb_fy*xyz_rgb.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
252 if (u_rgb < 0 || u_rgb >= (
int)registered_msg->width ||
253 v_rgb < 0 || v_rgb >= (int)registered_msg->height)
256 T& reg_depth = registered_data[v_rgb*registered_msg->width + u_rgb];
260 reg_depth = new_depth;
265 Eigen::Vector4d xyz_depth_1, xyz_depth_2;
266 xyz_depth_1 << ((u-0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
267 ((v-0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
270 xyz_depth_2 << ((u+0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
271 ((v+0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
276 Eigen::Vector4d xyz_rgb_1 = depth_to_rgb * xyz_depth_1;
277 Eigen::Vector4d xyz_rgb_2 = depth_to_rgb * xyz_depth_2;
280 double inv_Z = 1.0 / xyz_rgb_1.z();
281 int u_rgb_1 = (rgb_fx*xyz_rgb_1.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
282 int v_rgb_1 = (rgb_fy*xyz_rgb_1.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
283 inv_Z = 1.0 / xyz_rgb_2.z();
284 int u_rgb_2 = (rgb_fx*xyz_rgb_2.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
285 int v_rgb_2 = (rgb_fy*xyz_rgb_2.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
287 if (u_rgb_1 < 0 || u_rgb_2 >= (
int)registered_msg->width ||
288 v_rgb_1 < 0 || v_rgb_2 >= (int)registered_msg->height)
291 for (
int nv=v_rgb_1; nv<=v_rgb_2; ++nv)
293 for (
int nu=u_rgb_1; nu<=u_rgb_2; ++nu)
295 T& reg_depth = registered_data[nv*registered_msg->width + nu];
299 reg_depth = new_depth;
void convert(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg, const image_geometry::PinholeCameraModel &model, double range_max=0.0)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< Synchronizer > sync_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_rgb_info_
ros::NodeHandlePtr nh_rgb_
#define NODELET_ERROR_THROTTLE(rate,...)
ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
boost::shared_ptr< image_transport::ImageTransport > it_depth_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< tf2_ros::TransformListener > tf_
image_geometry::PinholeCameraModel rgb_model_
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define NODELET_WARN_THROTTLE(rate,...)
image_transport::SubscriberFilter sub_depth_image_
void imageCb(const sensor_msgs::ImageConstPtr &depth_image_msg, const sensor_msgs::CameraInfoConstPtr &depth_info_msg, const sensor_msgs::CameraInfoConstPtr &rgb_info_msg)
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
PLUGINLIB_EXPORT_CLASS(depth_image_proc::RegisterNodelet, nodelet::Nodelet)
void convert(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImagePtr ®istered_msg, const Eigen::Affine3d &depth_to_rgb)
bool fill_upsampling_holes_
boost::mutex connect_mutex_
image_transport::CameraPublisher pub_registered_
boost::shared_ptr< tf2_ros::Buffer > tf_buffer_
ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > SyncPolicy
message_filters::Synchronizer< SyncPolicy > Synchronizer