00001
00024 #include "ccny_rgbd/apps/rgbd_image_proc.h"
00025
00026 namespace ccny_rgbd {
00027
00028 RGBDImageProc::RGBDImageProc(
00029 const ros::NodeHandle& nh,
00030 const ros::NodeHandle& nh_private):
00031 nh_(nh), nh_private_(nh_private),
00032 rgb_image_transport_(nh_),
00033 depth_image_transport_(nh_),
00034 config_server_(nh_private_),
00035 size_in_(0,0)
00036 {
00037
00038 if (!nh_private_.getParam ("queue_size", queue_size_))
00039 queue_size_ = 5;
00040 if (!nh_private_.getParam("scale", scale_))
00041 scale_ = 1.0;
00042 if (!nh_private_.getParam("unwarp", unwarp_))
00043 unwarp_ = true;
00044 if (!nh_private_.getParam("publish_cloud", publish_cloud_))
00045 publish_cloud_ = true;
00046 if (!nh_private_.getParam("calib_path", calib_path_))
00047 {
00048 std::string home_path = getenv("HOME");
00049 calib_path_ = home_path + "./ros/rgbd_calibration";
00050 }
00051
00052 calib_extr_filename_ = calib_path_ + "/extr.yml";
00053 calib_warp_filename_ = calib_path_ + "/warp.yml";
00054
00055
00056 loadCalibration();
00057 if (unwarp_)
00058 {
00059 bool load_result = loadUnwarpCalibration();
00060 if (!load_result)
00061 {
00062 ROS_WARN("Disbaling unwarping due to missing calibration file");
00063 unwarp_ = true;
00064 }
00065 }
00066
00067
00068 rgb_publisher_ = rgb_image_transport_.advertise(
00069 "rgbd/rgb", queue_size_);
00070 depth_publisher_ = depth_image_transport_.advertise(
00071 "rgbd/depth", queue_size_);
00072 info_publisher_ = nh_.advertise<CameraInfoMsg>(
00073 "rgbd/info", queue_size_);
00074 cloud_publisher_ = nh_.advertise<PointCloudT>(
00075 "rgbd/cloud", queue_size_);
00076
00077
00078 ProcConfigServer::CallbackType f = boost::bind(&RGBDImageProc::reconfigCallback, this, _1, _2);
00079 config_server_.setCallback(f);
00080
00081
00082 sub_rgb_.subscribe (rgb_image_transport_,
00083 "/camera/rgb/image_color", queue_size_);
00084 sub_depth_.subscribe(depth_image_transport_,
00085 "/camera/depth/image_raw", queue_size_);
00086
00087 sub_rgb_info_.subscribe (nh_,
00088 "/camera/rgb/camera_info", queue_size_);
00089 sub_depth_info_.subscribe(nh_,
00090 "/camera/depth/camera_info", queue_size_);
00091
00092 sync_.reset(new RGBDSynchronizer4(
00093 RGBDSyncPolicy4(queue_size_), sub_rgb_, sub_depth_,
00094 sub_rgb_info_, sub_depth_info_));
00095
00096 sync_->registerCallback(boost::bind(&RGBDImageProc::RGBDCallback, this, _1, _2, _3, _4));
00097 }
00098
00099 RGBDImageProc::~RGBDImageProc()
00100 {
00101 ROS_INFO("Destroying RGBDImageProc");
00102 }
00103
00104 bool RGBDImageProc::loadCalibration()
00105 {
00106
00107 if (!boost::filesystem::exists(calib_extr_filename_))
00108 {
00109 ROS_ERROR("Could not open %s", calib_extr_filename_.c_str());
00111 return false;
00112 }
00113
00114
00115 ROS_INFO("Reading camera calibration files...");
00116 cv::FileStorage fs_extr(calib_extr_filename_, cv::FileStorage::READ);
00117
00118 fs_extr["ir2rgb"] >> ir2rgb_;
00119
00120 return true;
00121 }
00122
00123 bool RGBDImageProc::loadUnwarpCalibration()
00124 {
00125 if (!boost::filesystem::exists(calib_warp_filename_))
00126 {
00127 ROS_ERROR("Could not open %s", calib_warp_filename_.c_str());
00128 return false;
00129 }
00130
00131
00132 cv::FileStorage fs_warp(calib_warp_filename_, cv::FileStorage::READ);
00133
00134 fs_warp["c0"] >> coeff_0_;
00135 fs_warp["c1"] >> coeff_1_;
00136 fs_warp["c2"] >> coeff_2_;
00137 fs_warp["fit_mode"] >> fit_mode_;
00138
00139 return true;
00140 }
00141
00142 void RGBDImageProc::initMaps(
00143 const CameraInfoMsg::ConstPtr& rgb_info_msg,
00144 const CameraInfoMsg::ConstPtr& depth_info_msg)
00145 {
00146 boost::mutex::scoped_lock(mutex_);
00147
00148 ROS_INFO("Initializing rectification maps");
00149
00150
00151 cv::Mat intr_rgb, intr_depth;
00152 cv::Mat dist_rgb, dist_depth;
00153
00154 convertCameraInfoToMats(rgb_info_msg, intr_rgb, dist_rgb);
00155 convertCameraInfoToMats(depth_info_msg, intr_depth, dist_depth);
00156
00157
00158 double alpha = 0.0;
00159
00160 if (size_in_.width != (int)rgb_info_msg->width ||
00161 size_in_.height != (int)rgb_info_msg->height)
00162 {
00163 ROS_WARN("Image size does not match CameraInfo size. Rescaling.");
00164 double w_factor = (double)size_in_.width / (double)rgb_info_msg->width;
00165 double h_factor = (double)size_in_.height / (double)rgb_info_msg->height;
00166
00167 intr_rgb.at<double>(0,0) *= w_factor;
00168 intr_rgb.at<double>(1,1) *= h_factor;
00169 intr_rgb.at<double>(0,2) *= w_factor;
00170 intr_rgb.at<double>(1,2) *= h_factor;
00171
00172 intr_depth.at<double>(0,0) *= w_factor;
00173 intr_depth.at<double>(1,1) *= h_factor;
00174 intr_depth.at<double>(0,2) *= w_factor;
00175 intr_depth.at<double>(1,2) *= h_factor;
00176 }
00177
00178 cv::Size size_out;
00179 size_out.height = size_in_.height * scale_;
00180 size_out.width = size_in_.width * scale_;
00181
00182
00183 intr_rect_rgb_ = cv::getOptimalNewCameraMatrix(
00184 intr_rgb, dist_rgb, size_in_, alpha, size_out);
00185
00186 intr_rect_depth_ = cv::getOptimalNewCameraMatrix(
00187 intr_depth, dist_depth, size_in_, alpha, size_out);
00188
00189
00190 cv::initUndistortRectifyMap(
00191 intr_rgb, dist_rgb, cv::Mat(), intr_rect_rgb_,
00192 size_out, CV_16SC2, map_rgb_1_, map_rgb_2_);
00193
00194 cv::initUndistortRectifyMap(
00195 intr_depth, dist_depth, cv::Mat(), intr_rect_depth_,
00196 size_out, CV_16SC2, map_depth_1_, map_depth_2_);
00197
00198
00199 if(unwarp_)
00200 {
00201 cv::remap(coeff_0_, coeff_0_rect_, map_depth_1_, map_depth_2_, cv::INTER_NEAREST);
00202 cv::remap(coeff_1_, coeff_1_rect_, map_depth_1_, map_depth_2_, cv::INTER_NEAREST);
00203 cv::remap(coeff_2_, coeff_2_rect_, map_depth_1_, map_depth_2_, cv::INTER_NEAREST);
00204 }
00205
00206
00207 rgb_rect_info_msg_.header = rgb_info_msg->header;
00208 rgb_rect_info_msg_.width = size_out.width;
00209 rgb_rect_info_msg_.height = size_out.height;
00210
00211 depth_rect_info_msg_.header = depth_info_msg->header;
00212 depth_rect_info_msg_.width = size_out.width;
00213 depth_rect_info_msg_.height = size_out.height;
00214
00215 convertMatToCameraInfo(intr_rect_rgb_, rgb_rect_info_msg_);
00216 convertMatToCameraInfo(intr_rect_depth_, depth_rect_info_msg_);
00217 }
00218
00219 void RGBDImageProc::RGBDCallback(
00220 const ImageMsg::ConstPtr& rgb_msg,
00221 const ImageMsg::ConstPtr& depth_msg,
00222 const CameraInfoMsg::ConstPtr& rgb_info_msg,
00223 const CameraInfoMsg::ConstPtr& depth_info_msg)
00224 {
00225 boost::mutex::scoped_lock(mutex_);
00226
00227
00228 double dur_unwarp, dur_rectify, dur_reproject, dur_cloud, dur_allocate;
00229
00230
00231 if (rgb_msg->height != depth_msg->height ||
00232 rgb_msg->width != depth_msg->width)
00233 {
00234 ROS_WARN("RGB and depth images have different sizes, skipping");
00235 return;
00236 }
00237
00238
00239 if (size_in_.height != (int)rgb_msg->height ||
00240 size_in_.width != (int)rgb_msg->width)
00241 {
00242 ROS_INFO("Initializing");
00243
00244 size_in_.height = (int)rgb_msg->height;
00245 size_in_.width = (int)rgb_msg->width;
00246
00247 initMaps(rgb_info_msg, depth_info_msg);
00248 }
00249
00250
00251 cv_bridge::CvImageConstPtr rgb_ptr = cv_bridge::toCvShare(rgb_msg);
00252 cv_bridge::CvImageConstPtr depth_ptr = cv_bridge::toCvShare(depth_msg);
00253
00254 const cv::Mat& rgb_img = rgb_ptr->image;
00255 const cv::Mat& depth_img = depth_ptr->image;
00256
00257
00258
00259
00260
00261
00262 ros::WallTime start_rectify = ros::WallTime::now();
00263 cv::Mat rgb_img_rect, depth_img_rect;
00264 cv::remap(rgb_img, rgb_img_rect, map_rgb_1_, map_rgb_2_, cv::INTER_LINEAR);
00265 cv::remap(depth_img, depth_img_rect, map_depth_1_, map_depth_2_, cv::INTER_NEAREST);
00266 dur_rectify = getMsDuration(start_rectify);
00267
00268
00269
00270
00271
00272
00273 if (unwarp_)
00274 {
00275 ros::WallTime start_unwarp = ros::WallTime::now();
00276 unwarpDepthImage(depth_img_rect, coeff_0_rect_, coeff_1_rect_, coeff_2_rect_, fit_mode_);
00277 dur_unwarp = getMsDuration(start_unwarp);
00278 }
00279 else dur_unwarp = 0.0;
00280
00281
00282 ros::WallTime start_reproject = ros::WallTime::now();
00283 cv::Mat depth_img_rect_reg;
00284 buildRegisteredDepthImage(intr_rect_depth_, intr_rect_rgb_, ir2rgb_,
00285 depth_img_rect, depth_img_rect_reg);
00286 dur_reproject = getMsDuration(start_reproject);
00287
00288
00289 if (publish_cloud_)
00290 {
00291 ros::WallTime start_cloud = ros::WallTime::now();
00292 PointCloudT::Ptr cloud_ptr;
00293 cloud_ptr.reset(new PointCloudT());
00294 buildPointCloud(depth_img_rect_reg, rgb_img_rect, intr_rect_rgb_, *cloud_ptr);
00295 cloud_ptr->header = rgb_info_msg->header;
00296 cloud_publisher_.publish(cloud_ptr);
00297 dur_cloud = getMsDuration(start_cloud);
00298 }
00299 else dur_cloud = 0.0;
00300
00301
00302 ros::WallTime start_allocate = ros::WallTime::now();
00303
00304 cv_bridge::CvImage cv_img_rgb(rgb_msg->header, rgb_msg->encoding, rgb_img_rect);
00305 ImageMsg::Ptr rgb_out_msg = cv_img_rgb.toImageMsg();
00306
00307
00308 cv_bridge::CvImage cv_img_depth(depth_msg->header, depth_msg->encoding, depth_img_rect_reg);
00309 ImageMsg::Ptr depth_out_msg = cv_img_depth.toImageMsg();
00310
00311
00312 rgb_rect_info_msg_.header = rgb_info_msg->header;
00313
00314 dur_allocate = getMsDuration(start_allocate);
00315
00316
00317
00318 double dur_total = dur_rectify + dur_reproject + dur_unwarp + dur_cloud + dur_allocate;
00319
00320 ROS_INFO("Rect %.1f Reproj %.1f Unwarp %.1f Cloud %.1f Alloc %.1f Total %.1f ms",
00321 dur_rectify, dur_reproject, dur_unwarp, dur_cloud, dur_allocate,
00322 dur_total);
00323
00324
00325 rgb_publisher_.publish(rgb_out_msg);
00326 depth_publisher_.publish(depth_out_msg);
00327 info_publisher_.publish(rgb_rect_info_msg_);
00328 }
00329
00330 void RGBDImageProc::reconfigCallback(ProcConfig& config, uint32_t level)
00331 {
00332 boost::mutex::scoped_lock(mutex_);
00333 publish_cloud_ = config.publish_cloud;
00334 scale_ = config.scale;
00335 size_in_ = cv::Size(0,0);
00336 ROS_INFO("Resampling scale set to %.2f", scale_);
00337 }
00338
00339 }