$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Vit Stancl (stancl@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: dd/mm/2011 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #include "but_depthtexture.h" 00029 00030 #include <opencv/cv.h> 00031 #include <opencv/highgui.h> 00032 #include <limits> 00033 00034 #define PUBLISHING_TOPIC "/srs_ui_but/depth/normalized_image" 00035 #define FLOAT_IMAGE_TOPIC "/srs_ui_but/depth/float_image" 00036 00037 00038 00039 //======================================================================================================================= 00040 // CDepthImageConvertor 00041 // 00042 00046 srs_ui_but::CDepthImageConvertor::CDepthImageConvertor(const ros::NodeHandle& nh, const std::string & topic) 00047 : m_depth_msg( new sensor_msgs::Image) 00048 , m_visible_msg( new sensor_msgs::Image ) 00049 , m_float_msg( new sensor_msgs::Image ) 00050 , m_msg_encoding(enc::TYPE_32FC4) 00051 , m_visible_encoding( enc::MONO8 ) 00052 , m_topic( topic ) 00053 , m_hints("raw", ros::TransportHints(), nh) 00054 , m_bCamModelInitialized( false ) 00055 , m_counter(0) 00056 { 00057 m_it.reset(new image_transport::ImageTransport(nh)); 00058 00059 00060 m_sub_raw = m_it->subscribe(topic, 1, &CDepthImageConvertor::depthCb, this, m_hints); 00061 00062 m_pub_depth = m_it->advertise(PUBLISHING_TOPIC, 1 ); 00063 m_pub_float = m_it->advertise(FLOAT_IMAGE_TOPIC, 1 ); 00064 00065 // Allocate new Image message 00066 00067 // std::cerr << "... CDepthImageConvertor: depth texture initialized..." << std::endl; 00068 } 00069 00073 srs_ui_but::CDepthImageConvertor::~CDepthImageConvertor() 00074 { 00075 m_sub_raw.shutdown(); 00076 } 00077 00081 void srs_ui_but::CDepthImageConvertor::depthCb(const sensor_msgs::ImageConstPtr& raw_msg) 00082 { 00083 boost::mutex::scoped_lock lock(m_mutex); 00084 00085 // std::cerr << "New depth image... " << std::endl; 00086 00087 // Convert image 00088 convertDepth(raw_msg); 00089 toVisible(2); 00090 toFloat(2); 00091 } 00095 bool srs_ui_but::CDepthImageConvertor::convertDepth(const sensor_msgs::ImageConstPtr& raw_msg) 00096 { 00097 if( ! m_bCamModelInitialized ) 00098 return false; 00099 00100 if( raw_msg->encoding == enc::MONO16) 00101 { 00102 return convertDepth16(raw_msg); 00103 } 00104 00105 if( raw_msg->encoding == enc::MONO8 ) 00106 { 00107 return convertDepth8(raw_msg); 00108 } 00109 00110 if( raw_msg->encoding == enc::TYPE_16UC1) 00111 { 00112 return convertDepth16UC1(raw_msg); 00113 } 00114 00115 std::cerr << "... CDepthImageConvertor: Expected data these types: " << enc::MONO8.c_str() << ", " << enc::MONO16.c_str() << ", " << enc::TYPE_16UC1.c_str() << std::endl; 00116 std::cerr << "Input type: " << raw_msg->encoding.c_str() << std::endl; 00117 ROS_ERROR("Unexpected input data of type [%s]", raw_msg->encoding.c_str()); 00118 return false; 00119 } 00120 00124 bool srs_ui_but::CDepthImageConvertor::convertDepth16UC1(const sensor_msgs::ImageConstPtr& raw_msg) 00125 { 00126 00127 typedef uint16_t tIPixel; 00128 typedef float tOPixel; 00129 00130 m_depth_msg->header = raw_msg->header; 00131 m_depth_msg->encoding = m_msg_encoding; 00132 m_depth_msg->height = raw_msg->height; 00133 m_depth_msg->width = raw_msg->width; 00134 m_depth_msg->step = raw_msg->width * 4 * sizeof (tOPixel); 00135 m_depth_msg->data.resize( m_depth_msg->height * m_depth_msg->step); 00136 00137 float bad_point = std::numeric_limits<float>::quiet_NaN (); 00138 00139 // Compute image centers 00140 float center_x( m_camera_model.cx() ), center_y( m_camera_model.cy() ); 00141 00142 // std::cerr << m_camera_model.fx() << ", " << m_camera_model.fy() << std::endl; 00143 00144 // Scaling 00145 float constant_x( 0.001 / m_camera_model.fx() ), constant_y( 0.001 / m_camera_model.fy() ); 00146 00147 // Fill in the depth image data, converting mm to m 00148 const tIPixel* raw_data = reinterpret_cast<const tIPixel*>(&raw_msg->data[0]); 00149 tOPixel* depth_data = reinterpret_cast<tOPixel*>(&m_depth_msg->data[0]); 00150 00151 // Clear ranges 00152 for( int i = 0; i < 4; ++i ) 00153 { 00154 m_max_range[i] = -1000000000.0; 00155 m_min_range[i] = 1000000000.0; 00156 } 00157 00158 Ogre::Vector4 v; 00159 v[3] = 0.0; 00160 00161 float x( 0.0 ), y( 0.0 ), depth; 00162 // long counter(0); 00163 00164 for (unsigned index = 0; index < m_depth_msg->height * m_depth_msg->width; ++index ) 00165 { 00166 tIPixel raw = raw_data[index ]; 00167 00168 // Distance cut-off 00169 // if( raw > 70000 ) 00170 // raw = 70000; 00171 00172 if( raw == 0 ) 00173 { 00174 v[0] = v[1] = v[2] = v[3] = bad_point; 00175 } 00176 else 00177 { 00178 depth = float(raw); 00179 00180 v[0] = (x - center_x) * depth * constant_x; 00181 v[1] = (y - center_y) * depth * constant_y; 00182 v[2] = depth * 0.001; 00183 v[3] = sqrt( v[0] * v[0] + v[1] * v[1] + v[2] * v[2] ); 00184 } 00185 00186 00187 // v = v * m_projectionMatrix; 00188 /* 00189 if( v[3] == 0.0 ) 00190 ++counter; 00191 else 00192 v /= v[3]; 00193 //*/ 00194 00195 depth_data[4*index] = v[0]; //(tOPixel)value; 00196 depth_data[4*index + 1] = v[1]; //(tOPixel)value; 00197 depth_data[4*index + 2] = v[2]; //(tOPixel)value; 00198 depth_data[4*index + 3] = v[3]; 00199 00200 for( int i = 0; i < 4; ++i ) 00201 { 00202 if( v[i] > m_max_range[i] ) 00203 m_max_range[i] = v[i]; 00204 00205 if( v[i] < m_min_range[i] ) 00206 m_min_range[i] = v[i]; 00207 } 00208 00209 ++x; 00210 if( x > raw_msg->width ) 00211 { 00212 x -= raw_msg->width; 00213 ++y; 00214 } 00215 } 00216 00217 ++m_counter; 00218 00219 return true; 00220 } 00221 00222 00226 bool srs_ui_but::CDepthImageConvertor::convertDepth16(const sensor_msgs::ImageConstPtr& raw_msg) 00227 { 00228 00229 typedef uint16_t tIPixel; 00230 typedef float tOPixel; 00231 00232 m_depth_msg->header = raw_msg->header; 00233 m_depth_msg->encoding = m_msg_encoding; 00234 m_depth_msg->height = raw_msg->height; 00235 m_depth_msg->width = raw_msg->width; 00236 m_depth_msg->step = raw_msg->width * 4 * sizeof (tOPixel); 00237 m_depth_msg->data.resize( m_depth_msg->height * m_depth_msg->step); 00238 00239 float bad_point = std::numeric_limits<float>::quiet_NaN (); 00240 00241 // Compute image centers 00242 float center_x( m_camera_model.cx() ), center_y( m_camera_model.cy() ); 00243 00244 // std::cerr << m_camera_model.fx() << ", " << m_camera_model.fy() << std::endl; 00245 00246 // Scaling 00247 float constant_x( 0.001 / m_camera_model.fx() ), constant_y( 0.001 / m_camera_model.fy() ); 00248 00249 // Fill in the depth image data, converting mm to m 00250 const tIPixel* raw_data = reinterpret_cast<const tIPixel*>(&raw_msg->data[0]); 00251 tOPixel* depth_data = reinterpret_cast<tOPixel*>(&m_depth_msg->data[0]); 00252 00253 // Clear ranges 00254 for( int i = 0; i < 4; ++i ) 00255 { 00256 m_max_range[i] = -1000000000.0; 00257 m_min_range[i] = 1000000000.0; 00258 } 00259 00260 Ogre::Vector4 v; 00261 v[3] = 0.0; 00262 00263 float x( 0.0 ), y( 0.0 ), depth; 00264 // long counter(0); 00265 00266 for (unsigned index = 0; index < m_depth_msg->height * m_depth_msg->width; ++index ) 00267 { 00268 tIPixel raw = raw_data[index ]; 00269 00270 // Distance cut-off 00271 // if( raw > 70000 ) 00272 // raw = 70000; 00273 00274 if( raw == 0 ) 00275 { 00276 v[0] = v[1] = v[2] = v[3] = bad_point; 00277 } 00278 else 00279 { 00280 depth = float(raw); 00281 00282 v[0] = (x - center_x) * depth * constant_x; 00283 v[1] = (y - center_y) * depth * constant_y; 00284 v[2] = depth * 0.001; 00285 v[3] = sqrt( v[0] * v[0] + v[1] * v[1] + v[2] * v[2] ); 00286 } 00287 00288 00289 // v = v * m_projectionMatrix; 00290 /* 00291 if( v[3] == 0.0 ) 00292 ++counter; 00293 else 00294 v /= v[3]; 00295 //*/ 00296 00297 depth_data[4*index] = v[0]; //(tOPixel)value; 00298 depth_data[4*index + 1] = v[1]; //(tOPixel)value; 00299 depth_data[4*index + 2] = v[2]; //(tOPixel)value; 00300 depth_data[4*index + 3] = v[3]; 00301 00302 for( int i = 0; i < 4; ++i ) 00303 { 00304 if( v[i] > m_max_range[i] ) 00305 m_max_range[i] = v[i]; 00306 00307 if( v[i] < m_min_range[i] ) 00308 m_min_range[i] = v[i]; 00309 } 00310 00311 ++x; 00312 if( x > raw_msg->width ) 00313 { 00314 x -= raw_msg->width; 00315 ++y; 00316 } 00317 } 00318 00319 // std::cerr << "All: " << m_depth_msg->height * m_depth_msg->width << ", zero: " << zr << std::endl; 00320 /* 00321 std::cerr << "Ranges: " << std::endl; 00322 for( int i = 0; i < 4; ++i ) 00323 { 00324 std::cerr << "< " << m_min_range[i] << " - " << m_max_range[i] << " >"<< std::endl; 00325 } 00326 */ 00327 // std::cerr << "Bad points: " << counter << std::endl; 00328 00329 ++m_counter; 00330 00331 return true; 00332 } 00333 00337 bool srs_ui_but::CDepthImageConvertor::convertDepth8(const sensor_msgs::ImageConstPtr& raw_msg) 00338 { 00339 00340 typedef uint8_t tIPixel; 00341 typedef float tOPixel; 00342 00343 m_depth_msg->header = raw_msg->header; 00344 m_depth_msg->encoding = m_msg_encoding; 00345 m_depth_msg->height = raw_msg->height; 00346 m_depth_msg->width = raw_msg->width; 00347 m_depth_msg->step = raw_msg->width * 4 * sizeof (tOPixel); 00348 m_depth_msg->data.resize( m_depth_msg->height * m_depth_msg->step); 00349 00350 float bad_point = std::numeric_limits<float>::quiet_NaN (); 00351 00352 // Compute image centers 00353 float center_x( m_camera_model.cx() ), center_y( m_camera_model.cy() ); 00354 00355 // std::cerr << m_camera_model.fx() << ", " << m_camera_model.fy() << std::endl; 00356 00357 // Scaling 00358 float constant_x( 0.001 / m_camera_model.fx() ), constant_y( 0.001 / m_camera_model.fy() ); 00359 00360 // Fill in the depth image data, converting mm to m 00361 const tIPixel* raw_data = reinterpret_cast<const tIPixel*>(&raw_msg->data[0]); 00362 tOPixel* depth_data = reinterpret_cast<tOPixel*>(&m_depth_msg->data[0]); 00363 00364 // Clear ranges 00365 for( int i = 0; i < 4; ++i ) 00366 { 00367 m_max_range[i] = -1000000000.0; 00368 m_min_range[i] = 1000000000.0; 00369 } 00370 00371 Ogre::Vector4 v; 00372 v[3] = 0.0; 00373 00374 float x( 0.0 ), y( 0.0 ), depth; 00375 // long counter(0); 00376 00377 for (unsigned index = 0; index < m_depth_msg->height * m_depth_msg->width; ++index ) 00378 { 00379 tIPixel raw = raw_data[index ]; 00380 00381 // Distance cut-off 00382 // if( raw > 70000 ) 00383 // raw = 70000; 00384 00385 if( raw == 0 ) 00386 { 00387 v[0] = v[1] = v[2] = v[3] = bad_point; 00388 } 00389 else 00390 { 00391 depth = float(raw); 00392 00393 v[0] = (x - center_x) * depth * constant_x; 00394 v[1] = (y - center_y) * depth * constant_y; 00395 v[2] = depth * 0.001; 00396 v[3] = sqrt( v[0] * v[0] + v[1] * v[1] + v[2] * v[2] ); 00397 } 00398 00399 00400 // v = v * m_projectionMatrix; 00401 /* 00402 if( v[3] == 0.0 ) 00403 ++counter; 00404 else 00405 v /= v[3]; 00406 //*/ 00407 00408 depth_data[4*index] = v[0]; //(tOPixel)value; 00409 depth_data[4*index + 1] = v[1]; //(tOPixel)value; 00410 depth_data[4*index + 2] = v[2]; //(tOPixel)value; 00411 depth_data[4*index + 3] = v[3]; 00412 00413 for( int i = 0; i < 4; ++i ) 00414 { 00415 if( v[i] > m_max_range[i] ) 00416 m_max_range[i] = v[i]; 00417 00418 if( v[i] < m_min_range[i] ) 00419 m_min_range[i] = v[i]; 00420 } 00421 00422 ++x; 00423 if( x > raw_msg->width ) 00424 { 00425 x -= raw_msg->width; 00426 ++y; 00427 } 00428 } 00429 00430 // std::cerr << "All: " << m_depth_msg->height * m_depth_msg->width << ", zero: " << zr << std::endl; 00431 /* 00432 std::cerr << "Ranges: " << std::endl; 00433 for( int i = 0; i < 4; ++i ) 00434 { 00435 std::cerr << "< " << m_min_range[i] << " - " << m_max_range[i] << " >"<< std::endl; 00436 } 00437 */ 00438 // std::cerr << "Bad points: " << counter << std::endl; 00439 00440 ++m_counter; 00441 00442 return true; 00443 } 00444 00448 bool srs_ui_but::CDepthImageConvertor::toVisible( int coord ) 00449 { 00450 typedef uint8_t tVPixel; 00451 00452 m_visible_msg->header = m_depth_msg->header; 00453 m_visible_msg->encoding = m_visible_encoding; 00454 m_visible_msg->height = m_depth_msg->height; 00455 m_visible_msg->width = m_depth_msg->width; 00456 m_visible_msg->step = m_depth_msg->width * sizeof(tVPixel); 00457 m_visible_msg->data.resize(m_visible_msg->height * m_visible_msg->step); 00458 00459 tVPixel c; 00460 00461 float divider(1.0); 00462 00463 if (m_max_range[coord] != m_min_range[coord]) 00464 divider = 1.0 / (m_max_range[coord] - m_min_range[coord]); 00465 00466 for (unsigned int y = 0; y < m_depth_msg->height; ++y) { 00467 float *f = reinterpret_cast<float *> (&m_depth_msg->data[y 00468 * m_depth_msg->step]); 00469 tVPixel *v = reinterpret_cast<tVPixel*> (&m_visible_msg->data[y 00470 * m_visible_msg->step]); 00471 00472 for (unsigned int x = 0; x < m_depth_msg->width; ++x) { 00473 c = (tVPixel) (255 * ((f[4 * x + coord] - m_min_range[coord]) * divider)); 00474 v[x] = c; 00475 // v[3*x+1] = c; 00476 // v[3*x+2] = c; 00477 00478 00479 } 00480 } 00481 /* 00482 for (unsigned index = 0; index < m_visible_msg->height * m_visible_msg->width; ++index) 00483 { 00484 c = (uint8_t) (255*((depth_data[index]-m_min_range)*divider)); 00485 00486 visible_data[oindex] = c; ++oindex; 00487 visible_data[oindex] = c; ++oindex; 00488 visible_data[oindex] = c; ++oindex; 00489 } 00490 */ 00491 // Publish 00492 m_pub_depth.publish(m_visible_msg); 00493 00494 return true; 00495 } 00496 00500 bool srs_ui_but::CDepthImageConvertor::toFloat( int coord ) 00501 { 00502 typedef uint8_t tVPixel; 00503 00504 m_float_msg->header = m_depth_msg->header; 00505 m_float_msg->encoding = m_visible_encoding; 00506 m_float_msg->height = m_depth_msg->height; 00507 m_float_msg->width = m_depth_msg->width; 00508 m_float_msg->step = m_depth_msg->width * sizeof(tVPixel); 00509 m_float_msg->data.resize(m_float_msg->height * m_float_msg->step); 00510 00511 tVPixel c; 00512 00513 float depth; 00514 00515 for (unsigned int y = 0; y < m_depth_msg->height; ++y) { 00516 float *f = reinterpret_cast<float *> (&m_depth_msg->data[y * m_depth_msg->step]); 00517 tVPixel *v = reinterpret_cast<tVPixel*> (&m_float_msg->data[y * m_float_msg->step]); 00518 00519 for (unsigned int x = 0; x < m_depth_msg->width; ++x) 00520 { 00521 depth = f[4 * x + coord] * 0.5 + 0.5; 00522 00523 c = (depth < 0.0 ) ? 0 : (depth > 1.0 ) ? 255 : depth * 255; 00524 v[x] = c; 00525 // v[3*x+1] = c; 00526 // v[3*x+2] = c; 00527 00528 00529 } 00530 } 00531 00532 // Publish 00533 m_pub_float.publish(m_float_msg); 00534 00535 return true; 00536 } 00537 00541 void srs_ui_but::CDepthImageConvertor::setTopic(const std::string& topic) 00542 { 00543 boost::mutex::scoped_lock lock(m_mutex); 00544 00545 if( topic.empty() ) 00546 m_sub_raw.shutdown(); 00547 else 00548 { 00549 m_sub_raw = m_it->subscribe(topic, 1, &CDepthImageConvertor::depthCb, this, m_hints); 00550 } 00551 00552 m_topic = topic; 00553 } 00554 00558 void srs_ui_but::CDepthImageConvertor::setCameraModel(const sensor_msgs::CameraInfo& msg) 00559 { 00560 m_bCamModelInitialized = m_camera_model.fromCameraInfo( msg ); 00561 00562 // if( m_bCamModelInitialized ) 00563 // std::cerr << "CDepthImageConvertor::setCameraModel - initialized." << std::endl; 00564 } 00565 00566 //================================================================================================= 00567 // CRosDepthTexture 00568 00569 srs_ui_but::CRosDepthTexture::CRosDepthTexture( const ros::NodeHandle& nh, const std::string & texture_name, const std::string& topic_name, const std::string & encoding, bool bStaticTexture /*= false*/ ) 00570 : CDepthImageConvertor( nh, topic_name ) 00571 , m_texture_converter( texture_name, encoding, true ) 00572 00573 { 00574 00575 } 00576 00580 bool srs_ui_but::CRosDepthTexture::convertDepth(const sensor_msgs::ImageConstPtr& raw_msg) 00581 { 00582 CDepthImageConvertor::convertDepth( raw_msg ); 00583 00584 // std::cerr << "...Depth: Converting image. M_COUNTER: " << m_counter << std::endl; 00585 00586 if( hasData() ) 00587 { 00588 // std::cerr << "...Depth: Converting image..." << std::endl; 00589 return m_texture_converter.convert( m_depth_msg, false ); 00590 } 00591 00592 return false; 00593 } 00594 00598 void srs_ui_but::CRosDepthTexture::clear() 00599 { 00600 00601 } 00602