00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <ros/ros.h>
00031
00032 #include <sensor_msgs/Image.h>
00033 #include <sensor_msgs/CameraInfo.h>
00034 #include <stereo_msgs/DisparityImage.h>
00035 #include <sensor_msgs/PointCloud2.h>
00036 #include <sensor_msgs/PointCloud.h>
00037
00038 #include <sensor_msgs/point_cloud_conversion.h>
00039
00040 #include <tf/transform_listener.h>
00041
00042 #include "rviz_interaction_tools/image_tools.h"
00043
00044 #include "rgbd_assembler/msg_saver.h"
00045 #include "rgbd_assembler/utils.h"
00046 #include "rgbd_assembler/RgbdAssembly.h"
00047
00048 #include <limits>
00049 #include <math.h>
00050
00051
00052 namespace rgbd_assembler {
00053
00054 class RgbdAssembler {
00055
00056 typedef geometry_msgs::Point32 Point;
00057
00058 private:
00060 ros::NodeHandle root_nh_;
00062 ros::NodeHandle priv_nh_;
00063
00064 ros::ServiceServer rgbd_srv_;
00065
00066 tf::TransformListener listener_;
00067
00068
00069
00070
00072 bool rgbdServiceCallback(RgbdAssembly::Request &request,
00073 RgbdAssembly::Response &response);
00074
00075
00076 bool assembleSensorData(ros::Duration time_out);
00077
00078
00079
00080
00081 bool assembleRgbd();
00082
00083 void getPointCloudFromIm(sensor_msgs::PointCloud2 &point_cloud,
00084 const stereo_msgs::DisparityImage &disparity_image,
00085 const sensor_msgs::CameraInfo &narrow_cam_info);
00086
00087 void projectPointCloud( sensor_msgs::PointCloud2 &point_cloud,
00088 const sensor_msgs::CameraInfo &cam_info );
00089
00090 void getPixel( const sensor_msgs::PointCloud2 &point_cloud,
00091 int i, Point &p);
00092
00093 void extractRgbVals( sensor_msgs::PointCloud2 &point_cloud,
00094 const sensor_msgs::Image &wide_img,
00095 const sensor_msgs::Image &narrow_img );
00096
00097
00098
00099 sensor_msgs::Image narrow_image_;
00100 sensor_msgs::Image wide_image_;
00101 stereo_msgs::DisparityImage disparity_image_;
00102 sensor_msgs::CameraInfo narrow_cam_info_;
00103 sensor_msgs::CameraInfo wide_cam_info_;
00104 sensor_msgs::PointCloud2 point_cloud_;
00105
00106 public:
00107
00108 RgbdAssembler() :
00109 root_nh_(""), priv_nh_("~")
00110 {
00111 rgbd_srv_ = root_nh_.advertiseService(root_nh_.resolveName("/rgbd_assembly"),
00112 &RgbdAssembler::rgbdServiceCallback, this);
00113
00114
00115 ROS_INFO("RGB-D Assembler node started");
00116 }
00117
00118 ~RgbdAssembler()
00119 {}
00120
00121 };
00122
00123 bool RgbdAssembler::rgbdServiceCallback(RgbdAssembly::Request &request,
00124 RgbdAssembly::Response &response)
00125 {
00126 if (!assembleSensorData(ros::Duration(15.0))) return false;
00127 ROS_INFO("Assembled Sensor Data");
00128
00129 if (!priv_nh_.ok())
00130 return false;
00131
00132 if (!assembleRgbd()) {
00133 ROS_INFO("RGB-D assembly has not succeeded;");
00134 response.result = response.OTHER_ERROR;
00135 } else {
00136
00137 ROS_INFO("RGB-D assembly has succeeded;");
00138 response.point_cloud = point_cloud_;
00139 response.image = narrow_image_;
00140 response.disparity_image = disparity_image_;
00141 response.camera_info = narrow_cam_info_;
00142 response.result = response.SUCCESS;
00143
00144 }
00145
00146 return true;
00147 }
00148
00149 bool RgbdAssembler::assembleSensorData(ros::Duration time_out)
00150 {
00151 ROS_INFO("RGB-D Assembly: waiting for messages...");
00152
00153 MsgSaver< sensor_msgs::Image >
00154 recent_wide_image("/wide_stereo/left/image_rect_color");
00155 MsgSaver< sensor_msgs::Image >
00156 recent_image("/narrow_stereo/left/image_rect");
00157 MsgSaver< stereo_msgs::DisparityImage >
00158 recent_disparity_image("/narrow_stereo_textured/disparity");
00159 MsgSaver< sensor_msgs::CameraInfo >
00160 recent_camera_info("/narrow_stereo_textured/left/camera_info");
00161 MsgSaver< sensor_msgs::CameraInfo >
00162 recent_wide_camera_info("/wide_stereo/left/camera_info");
00163
00164 ros::Time start_time = ros::Time::now();
00165
00166
00167 while ( (!recent_disparity_image.hasMsg() ||
00168 !recent_image.hasMsg() ||
00169 !recent_camera_info.hasMsg() ||
00170 !recent_wide_camera_info.hasMsg() ||
00171 !recent_wide_image.hasMsg())
00172 && priv_nh_.ok()) {
00173
00174 ros::spinOnce();
00175
00176 ros::Time current_time = ros::Time::now();
00177 if (time_out >= ros::Duration(0) && current_time - start_time >= time_out) {
00178 ROS_ERROR("Timed out while waiting for sensor data.");
00179 return false;
00180 }
00181 ros::Duration(1.0).sleep();
00182 }
00183 if (!priv_nh_.ok()) return false;
00184
00185 narrow_image_ = *recent_image.getMsg();
00186 wide_image_ = *recent_wide_image.getMsg();
00187 disparity_image_ = *recent_disparity_image.getMsg();
00188 narrow_cam_info_ = *recent_camera_info.getMsg();
00189 wide_cam_info_ = *recent_wide_camera_info.getMsg();
00190
00191 return true;
00192 }
00193
00194 bool RgbdAssembler::assembleRgbd() {
00195
00196 ROS_INFO("Reconstructing point cloud");
00197
00198
00199 getPointCloudFromIm(point_cloud_, disparity_image_, narrow_cam_info_);
00200
00201 int w = point_cloud_.width;
00202 int h = point_cloud_.height;
00203
00204
00205 sensor_msgs::PointCloud2::ConstPtr point_cloud_ptr
00206 = boost::make_shared<const sensor_msgs::PointCloud2> (point_cloud_);
00207 sensor_msgs::PointCloud old_cloud;
00208 sensor_msgs::convertPointCloud2ToPointCloud (*point_cloud_ptr, old_cloud);
00209
00210
00211 try
00212 {
00213 ROS_DEBUG("Transforming point cloud from frame %s into frame %s",
00214 point_cloud_.header.frame_id.c_str(),
00215 "wide_stereo_optical_frame");
00216 listener_.transformPointCloud("wide_stereo_optical_frame", old_cloud, old_cloud);
00217 }
00218 catch (tf::TransformException ex)
00219 {
00220 ROS_ERROR("Failed to transform point cloud from frame %s into frame %s; error %s",
00221 old_cloud.header.frame_id.c_str(),
00222 "wide_stereo_optical_frame",
00223 ex.what());
00224 return false;
00225 }
00226
00227 sensor_msgs::PointCloud2 converted_cloud;
00228 sensor_msgs::convertPointCloudToPointCloud2 (old_cloud, point_cloud_);
00229
00230
00231 point_cloud_.height = h;
00232 point_cloud_.width = w;
00233
00234
00235 projectPointCloud(point_cloud_, wide_cam_info_);
00236
00237 extractRgbVals(point_cloud_, wide_image_, narrow_image_);
00238
00239 return true;
00240 }
00241
00242 void RgbdAssembler::getPointCloudFromIm(sensor_msgs::PointCloud2 &point_cloud,
00243 const stereo_msgs::DisparityImage &disparity_image,
00244 const sensor_msgs::CameraInfo &narrow_cam_info)
00245 {
00246 int w = narrow_cam_info.width;
00247 int h = narrow_cam_info.height;
00248
00249
00250 point_cloud.header = narrow_cam_info.header;
00251 point_cloud.height = h;
00252 point_cloud.width = w;
00253 point_cloud.is_dense = false;
00254 point_cloud.is_bigendian = false;
00255
00256 point_cloud.fields.resize( 3 + 3);
00257 point_cloud.fields[0].name = "x"; point_cloud.fields[1].name = "y"; point_cloud.fields[2].name = "z";
00258 point_cloud.fields[3].name = "rgb"; point_cloud.fields[4].name = "u"; point_cloud.fields[5].name = "v";
00259 int offset = 0;
00260 for (size_t d = 0; d < point_cloud.fields.size (); ++d, offset += 4) {
00261 point_cloud.fields[d].offset = offset;
00262 point_cloud.fields[d].datatype = sensor_msgs::PointField::FLOAT32;
00263 point_cloud.fields[d].count = 1;
00264 }
00265
00266 point_cloud.point_step = offset;
00267 point_cloud.row_step = point_cloud.point_step * w;
00268
00269 point_cloud.data.resize (w * h * point_cloud.point_step);
00270
00271 for (int i=0; i<h; i++) {
00272 for (int j=0; j<w; j++) {
00273 int adr = i * w + j;
00274 float x, y, z;
00275 if (rviz_interaction_tools::hasDisparityValue(disparity_image, i, j)) {
00276
00277 rviz_interaction_tools::getPoint( disparity_image, narrow_cam_info_, i, j, x, y, z);
00278
00279 memcpy (&point_cloud.data[adr * point_cloud.point_step + point_cloud.fields[0].offset], &x, sizeof (float));
00280 memcpy (&point_cloud.data[adr * point_cloud.point_step + point_cloud.fields[1].offset], &y, sizeof (float));
00281 memcpy (&point_cloud.data[adr * point_cloud.point_step + point_cloud.fields[2].offset], &z, sizeof (float));
00282
00283 } else {
00284
00285 float nan = std::numeric_limits<float>::quiet_NaN();
00286 memcpy (&point_cloud.data[adr * point_cloud.point_step + point_cloud.fields[0].offset], &nan, sizeof (float));
00287 memcpy (&point_cloud.data[adr * point_cloud.point_step + point_cloud.fields[1].offset], &nan, sizeof (float));
00288 memcpy (&point_cloud.data[adr * point_cloud.point_step + point_cloud.fields[2].offset], &nan, sizeof (float));
00289
00290 }
00291 }
00292 }
00293 }
00294
00295
00296 void RgbdAssembler::projectPointCloud(sensor_msgs::PointCloud2 &point_cloud,
00297 const sensor_msgs::CameraInfo &cam_info ){
00298
00299 float fx = cam_info.P[0*4+0];
00300 float fy = cam_info.P[1*4+1];
00301 float cx = cam_info.P[0*4+2];
00302 float cy = cam_info.P[1*4+2];
00303 float tx = cam_info.P[0*4+3];
00304 float ty = cam_info.P[1*4+3];
00305
00306 int w = cam_info.width;
00307 int h = cam_info.height;
00308
00309 for(int x=0; x<w; ++x){
00310 for(int y=0; y<h; ++y){
00311 int i = y*w+x;
00312 float nan;
00313 memcpy (&nan, &point_cloud.data[i * point_cloud.point_step + point_cloud.fields[0].offset], sizeof (float));
00314 if(!isnan(nan)){
00315
00316 float x, y, z;
00317
00318 memcpy (&x, &point_cloud.data[i * point_cloud.point_step + point_cloud.fields[0].offset], sizeof (float));
00319 memcpy (&y, &point_cloud.data[i * point_cloud.point_step + point_cloud.fields[1].offset], sizeof (float));
00320 memcpy (&z, &point_cloud.data[i * point_cloud.point_step + point_cloud.fields[2].offset], sizeof (float));
00321
00322 float u = (fx * x + tx)/z + cx;
00323 float v = (fy * y + ty)/z + cy;
00324
00325 memcpy (&point_cloud.data[i * point_cloud.point_step + point_cloud.fields[4].offset], &u, sizeof (float));
00326 memcpy (&point_cloud.data[i * point_cloud.point_step + point_cloud.fields[5].offset], &v, sizeof (float));
00327
00328 }
00329 }
00330 }
00331 }
00332
00333 void RgbdAssembler::getPixel( const sensor_msgs::PointCloud2 &point_cloud,
00334 int i, Point &p){
00335 float u, v;
00336 memcpy ( &u, &point_cloud.data[i * point_cloud.point_step + point_cloud.fields[4].offset], sizeof (float));
00337 memcpy ( &v, &point_cloud.data[i * point_cloud.point_step + point_cloud.fields[5].offset], sizeof (float));
00338
00339 p.x = u;
00340 p.y = v;
00341 p.z = 1.0;
00342
00343 }
00344
00345 void RgbdAssembler::extractRgbVals(sensor_msgs::PointCloud2 &point_cloud,
00346 const sensor_msgs::Image &wide_img,
00347 const sensor_msgs::Image &narrow_img)
00348 {
00349
00350 ROS_INFO("Size of point cloud in extractRgbVals %d", (int)point_cloud.data.size());
00351
00352 for(unsigned int x=0; x<narrow_img.width; ++x){
00353 for(unsigned int y=0; y<narrow_img.height; ++y){
00354 int i = y * narrow_img.width + x;
00355
00356 float val = (float)narrow_img.data.at(i)/255.0f;
00357 float r, g, b;
00358
00359 float nan;
00360 memcpy (&nan, &point_cloud.data[i * point_cloud.point_step + point_cloud.fields[0].offset], sizeof (float));
00361 if(!isnan(nan)){
00362 Point p;
00363 getPixel( point_cloud, i, p);
00364
00365 int wide_i = (int)p.y * (int)wide_img.step + (int)p.x*3;
00366 r = (float)wide_img.data.at(wide_i+2)/255.0f;
00367 g = (float)wide_img.data.at(wide_i+1)/255.0f;
00368 b = (float)wide_img.data.at(wide_i+0)/255.0f;
00369
00370 float h, s, v;
00371 RGBToHSV(r,g,b,h,s,v);
00372 HSVToRGB(h,s,val, r, g, b);
00373
00374 } else {
00375
00376 r = val;
00377 g = val;
00378 b = val;
00379
00380 }
00381
00382 float rgb = getRGB(r,g,b);
00383 memcpy ( &point_cloud.data[i * point_cloud.point_step + point_cloud.fields[3].offset], &rgb, sizeof (float));
00384 }
00385 }
00386 }
00387
00388 }
00389
00390 int main(int argc, char **argv)
00391 {
00392 ros::init(argc, argv, "rgbd_assembler_node");
00393 rgbd_assembler::RgbdAssembler node;
00394 ros::spin();
00395 return 0;
00396 }