$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 /* author: Radu Bogdan Rusu <rusu@cs.tum.edu> */ 00031 00032 #include "stoc.h" 00033 #include <SVS/svsclass.h> 00034 00035 using namespace sensor_msgs; 00036 using namespace deprecated_msgs; 00037 00039 #define STOC_EXCEPT(except, msg) \ 00040 { \ 00041 char buf[100]; \ 00042 snprintf(buf, 100, "[STOC::%s]: " msg, __FUNCTION__); \ 00043 throw except(buf); \ 00044 } 00045 00047 #define STOC_EXCEPT_ARGS(except, msg, ...) \ 00048 { \ 00049 char buf[100]; \ 00050 snprintf(buf, 100, "[STOC::%s]: " msg, __FUNCTION__, __VA_ARGS__); \ 00051 throw except(buf); \ 00052 } 00053 00054 stoc::STOC::STOC () : capture_type_(-1), format_(-1), channel_(-1), swap_mode_(false), color_mode_(0), 00055 // color_alg_(2), proc_mode_(PROC_MODE_RECTIFIED), rate_(15), frame_div_(-1), size_w_(640), size_h_(480), 00056 color_alg_(2), proc_mode_(PROC_MODE_NONE), rate_(15), frame_div_(-1), size_w_(640), size_h_(480), 00057 rectification_(1), z_max_(5), multiproc_en_(true), cut_di_(64), speckle_diff_(-1), 00058 speckle_size_(400), horopter_(-1), corrsize_(15), unique_(10), tex_thresh_(5), ndisp_(64), 00059 debug_(true) 00060 { 00061 process_ = new svsStereoProcess (); // Compute the disparity image, and 3D points 00062 multiproc_ = new svsMultiProcess (); // Multiscale processing 00063 video_ = getVideoObject (); // Get access to the video stream 00064 // Set the intrinsic camera parameters (found after calibration) 00065 intrinsic_ = cvCreateMat (3, 3, CV_64FC1); 00066 distortion_ = cvCreateMat (1, 4, CV_64FC1); 00067 cvmSet (intrinsic_, 0, 0, 429.609702); cvmSet (intrinsic_, 0, 1, 0.0); cvmSet (intrinsic_, 0, 2, 309.444590); 00068 cvmSet (intrinsic_, 1, 0, 0.0); cvmSet (intrinsic_, 1, 1, 429.070702); cvmSet (intrinsic_, 1, 2, 222.472089); 00069 cvmSet (intrinsic_, 2, 0, 0.0); cvmSet (intrinsic_, 2, 1, 0.0); cvmSet (intrinsic_, 2, 2, 1.0); 00070 cvmSet (distortion_, 0, 0, -0.006479); cvmSet (distortion_, 0, 1, 0.039474); cvmSet (distortion_, 0, 2, 0.0); cvmSet (distortion_, 0, 3, 0.0); 00071 } 00072 00073 stoc::STOC::~STOC () 00074 { 00075 } 00076 00078 // Set up the device 00079 void 00080 stoc::STOC::readParametersFromFile (const char* parameter_file) 00081 { 00082 if (parameter_file != NULL) 00083 { 00084 video_->ReadParams ((char*)parameter_file); 00085 fprintf (stderr, ">> Using camera parameters from %s\n", parameter_file); 00086 } 00087 } 00088 00090 // Set up the device 00091 void 00092 stoc::STOC::sendInternalParameters () 00093 { 00094 if (capture_type_ != -1) 00095 { 00096 if (video_->SetCapture (capture_type_)) 00097 { if (debug_) fprintf (stderr, "[STOC] >> Set capture type to %d\n", capture_type_); } 00098 else 00099 STOC_EXCEPT_ARGS(stoc::Exception, "Error while setting capture type to %d!", capture_type_); 00100 } 00101 00102 if (format_ != -1) 00103 { 00104 if (video_->SetFormat (format_)) 00105 { if (debug_) fprintf (stderr, "[STOC] >> Set format type to %d\n", format_); } 00106 else 00107 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting format type to %d!", format_); 00108 } 00109 00110 if (channel_ != -1) 00111 { 00112 if (video_->SetChannel (channel_)) 00113 { if (debug_) fprintf (stderr, "[STOC] >> Set channel type to %d\n", channel_); } 00114 else 00115 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting channel type to %d!", channel_); 00116 } 00117 00118 if (swap_mode_) 00119 { 00120 if (video_->SetSwap (swap_mode_)) 00121 { if (debug_) fprintf (stderr, "[STOC] >> Swap mode enabled\n"); } 00122 else 00123 STOC_EXCEPT(stoc::Exception, "Error enabling swap mode!"); 00124 } 00125 00126 if (color_mode_ != -1) 00127 { 00128 bool r = false; 00129 if (color_mode_ == 0) r = video_->SetColor (true, true); 00130 if (color_mode_ == 1) r = video_->SetColor (true, false); 00131 if (color_mode_ == 2) r = video_->SetColor (false, true); 00132 if (r & debug_) 00133 fprintf (stderr, "[STOC] >> Color mode set to %d\n", color_mode_); 00134 else 00135 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting color mode to %d!", color_mode_); 00136 } 00137 00138 if (color_alg_ != -1) 00139 { 00140 if (video_->SetColorAlg (color_alg_)) 00141 { if (debug_) fprintf (stderr, "[STOC] >> Color algorithm set to %d\n", color_alg_); } 00142 else 00143 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting color algorithm to %d!", color_alg_); 00144 } 00145 00146 if (video_->SetSize (size_w_, size_h_)) 00147 { if (debug_) fprintf (stderr, "[STOC] >> Image size set to %dx%d\n", size_w_, size_h_); } 00148 else 00149 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting image size to %dx%d!", size_w_, size_h_); 00150 00151 if (frame_div_ != -1) 00152 { 00153 if (video_->SetFrameDiv (frame_div_)) 00154 { if (debug_) fprintf (stderr, "[STOC] >> Image sampling set to %d\n", frame_div_); } 00155 else 00156 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting image sampling to %d!", frame_div_); 00157 } 00158 00159 if (rate_ != -1) 00160 { 00161 if (video_->SetRate (rate_)) 00162 { if (debug_) fprintf (stderr, "[STOC] >> Image rate set to %d\n", rate_); } 00163 else 00164 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting image rate to %d!", rate_); 00165 } 00166 00167 if (proc_mode_ != -1) 00168 { 00169 if (video_->SetProcMode (proc_mode_type(proc_mode_))) 00170 { if (debug_) fprintf (stderr, "[STOC] >> Processing mode set to %d\n", proc_mode_); } 00171 else 00172 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting STOC processing mode to %d!", proc_mode_); 00173 } 00174 00175 if (rectification_ != -1) 00176 { 00177 if (video_->SetRect (rectification_)) 00178 { if (debug_) fprintf (stderr, "[STOC] >> Image rectification set to %d\n", rectification_); } 00179 else 00180 STOC_EXCEPT_ARGS(stoc::Exception, "Error setting image rectification to %d!", rectification_); 00181 } 00182 } 00183 00185 // Set up the device 00186 void 00187 stoc::STOC::sendStereoParameters () 00188 { 00189 if (cut_di_ != 0 && debug_) 00190 fprintf (stderr, "[STOC] >> Disconsidering the last %d lines from the bottom of the disparity image...\n", cut_di_); 00191 if (ndisp_ != -1) 00192 { 00193 video_->SetNDisp (ndisp_); 00194 if (debug_) fprintf (stderr, "[STOC] >> Number of disparities set to %d\n", ndisp_); 00195 } 00196 if (tex_thresh_ != -1) 00197 { 00198 video_->SetThresh (tex_thresh_); 00199 if (debug_) fprintf (stderr, "[STOC] >> Texture filter threshold set to %d\n", tex_thresh_); 00200 } 00201 if (unique_ != -1) 00202 { 00203 video_->SetUnique (unique_); 00204 if (debug_) fprintf (stderr, "[STOC] >> Uniqueness filter threshold set to %d\n", unique_); 00205 } 00206 if (corrsize_ != -1) 00207 { 00208 video_->SetCorrsize (corrsize_); 00209 if (debug_) fprintf (stderr, "[STOC] >> Correlation window size set to %d\n", corrsize_); 00210 } 00211 if (horopter_ != -1) 00212 { 00213 video_->SetHoropter (horopter_); 00214 if (debug_) fprintf (stderr, "[STOC] >> Horopter (X-Offset) value set to %d\n", horopter_); 00215 } 00216 if (speckle_size_ != -1) 00217 { 00218 video_->SetSpeckleSize (speckle_size_); 00219 if (debug_) fprintf (stderr, "[STOC] >> Minimum disparity region size set to %d\n", speckle_size_); 00220 } 00221 if (speckle_diff_ != -1) 00222 { 00223 video_->SetSpeckleDiff (speckle_diff_); 00224 if (debug_) fprintf (stderr, "[STOC] >> Disparity region neighbor diff to %d\n", speckle_diff_); 00225 } 00226 } 00227 00229 // Set up the device 00230 int 00231 stoc::STOC::open () 00232 { 00233 int res; 00234 int nr_cam = video_->Enumerate (); // Get the number of cameras available 00235 00236 // No cameras found on the bus ? Search for one in the taxi... 00237 if (nr_cam == 0) 00238 { 00239 STOC_EXCEPT(stoc::Exception, "No cameras found!"); 00240 return (-1); 00241 } 00242 00243 if (debug_) 00244 for (int i = 0; i < nr_cam; i++) 00245 fprintf (stderr, "[STOC] > Found camera %d: %s\n", i, video_->DeviceIDs ()[i]); 00246 00247 // ---[ Open the camera ]--- 00248 res = video_->Open (nr_cam - 1); // Open camera 00249 device_id_ = video_->DeviceIDs ()[nr_cam - 1]; 00250 00251 if (!res) 00252 { 00253 STOC_EXCEPT(stoc::Exception, "Failed to open camera port!"); 00254 return (-1); 00255 } 00256 00257 res = video_->ReadParams (); 00258 if (!res) 00259 { 00260 STOC_EXCEPT(stoc::Exception, "Could not query camera for intrinsic parameters!"); 00261 return (-1); 00262 } 00263 00264 sendInternalParameters (); 00265 video_->binning = 1; 00266 00267 sendStereoParameters (); 00268 00269 // Start video streaming 00270 res = video_->Start (); 00271 if (!res) 00272 STOC_EXCEPT(stoc::Exception, "Failed to start data acquisition!"); 00273 00274 return (0); 00275 } 00276 00278 // Shutdown the device 00279 int 00280 stoc::STOC::close () 00281 { 00282 int res = video_->Stop (); // Stop video streaming 00283 // ---[ Close the camera ]--- 00284 res = video_->Close (); 00285 if (!res) 00286 return (-1); 00287 return (0); 00288 } 00289 00291 // Undistort an image based on the intrinsic camera parameters 00292 void 00293 stoc::STOC::undistort (uint8_t *img, uint8_t *un_img, int width, int height) 00294 { 00295 CvMat *src = cvCreateMatHeader (height, width, CV_8UC3); 00296 cvSetData (src, img, width * 3); 00297 CvMat *dst = cvCreateMatHeader (height, width, CV_8UC3); 00298 cvSetData (dst, un_img, width * 3); 00299 00300 cvUndistort2 (src, dst, intrinsic_, distortion_); 00301 } 00302 00303 00305 // Read data from the device 00306 void 00307 stoc::STOC::readData (PointCloud &cloud, ImageArray &images) 00308 { 00309 svsStereoImage *si = video_->GetImage (10); // 10 ms timeout 00310 if (si == NULL && debug_) 00311 STOC_EXCEPT(stoc::Exception, "No image, timed out..."); 00312 00313 // Compute the disparity image 00314 if (multiproc_en_) 00315 multiproc_->CalcStereo (si); 00316 else 00317 process_->CalcStereo (si); 00318 00319 // Trim down those nasty points at the bottom of the disparity image (errors?) 00320 for (int i = si->ip.height - cut_di_; i < si->ip.height; i++) 00321 for (int j = 0; j < si->ip.width; j++) 00322 si->disparity[i * si->ip.width + j] = -2; 00323 00324 // Compute the 3D point cloud information 00325 if (multiproc_en_) 00326 multiproc_->Calc3D (si, 0, 0, 0, 0, NULL, NULL, z_max_); 00327 else 00328 process_->Calc3D (si, 0, 0, 0, 0, NULL, NULL, z_max_); 00329 00330 // Save the 3D point cloud data in the structure, if present 00331 int nr_points = 0; 00332 00333 // Fill in the ROS PointCloud message 00334 cloud.points.resize (si->ip.height * si->ip.width); // allocate more than needed, we will resize later 00335 cloud.channels.resize (1); 00336 cloud.channels[0].name = "i"; 00337 cloud.channels[0].values.resize (cloud.points.size ()); 00338 00339 // RGB or monochrome ? 00340 if (si->haveColor) 00341 { 00342 cloud.channels.resize (3); 00343 cloud.channels[0].name = "r"; 00344 cloud.channels[0].values.resize (cloud.points.size ()); // re-do channels[0], just in case 00345 cloud.channels[1].name = "g"; 00346 cloud.channels[1].values.resize (cloud.points.size ()); 00347 cloud.channels[2].name = "b"; 00348 cloud.channels[2].values.resize (cloud.points.size ()); 00349 } 00350 00351 if (si->have3D) 00352 { 00353 svs3Dpoint *pts = si->pts3D; 00354 for (int i = 0; i < si->ip.height; i++) 00355 { 00356 for (int j = 0; j < si->ip.width; j++, pts++) 00357 { 00358 // Check if the point is valid 00359 if (pts->A <= 0) 00360 continue; 00361 00362 cloud.points[nr_points].x = pts->X; 00363 cloud.points[nr_points].y = pts->Y; 00364 cloud.points[nr_points].z = pts->Z; 00365 00366 if (si->haveColor) 00367 { 00368 svsColorPixel *mpc = (svsColorPixel*)(si->color + (i*si->ip.width + j) * 4); 00369 cloud.channels[0].values[nr_points] = mpc->r; // red 00370 cloud.channels[1].values[nr_points] = mpc->g; // green 00371 cloud.channels[2].values[nr_points] = mpc->b; // blue 00372 } 00373 else 00374 cloud.channels[0].values[nr_points] = (unsigned char)si->Left ()[i*si->ip.width + j]; 00375 00376 nr_points++; 00377 } // width 00378 } // height 00379 00380 } // have3D 00381 cloud.points.resize (nr_points); 00382 cloud.channels[0].values.resize (nr_points); 00383 // RGB or monochrome ? 00384 if (si->haveColor) 00385 { 00386 cloud.channels[1].values.resize (nr_points); 00387 cloud.channels[2].values.resize (nr_points); 00388 } 00389 00390 // Do we send the disparity image as well ? 00391 if (si->haveDisparity) 00392 images.set_images_size (3); 00393 else 00394 images.set_images_size (2); 00395 00396 // Prepare the left channel 00397 images.images[0].width = si->ip.width; 00398 images.images[0].height = si->ip.height; 00399 images.images[0].compression = "raw"; 00400 images.images[0].label = "stoc-left"; 00401 images.images[0].set_data_size (si->ip.width * si->ip.height); 00402 // Check if <left> has color or monochrome 00403 if (si->haveColor) 00404 { 00405 images.images[0].set_data_size (images.images[0].get_data_size () * 3); // RGB 00406 images.images[0].colorspace = "rgb24"; 00407 unsigned char *in_left = (unsigned char*)si->Color (); 00408 00409 // Stores a copy of the left image 00410 uint8_t *img_tmp = (uint8_t*)malloc (si->ip.width * si->ip.height * 3); 00411 00412 for (int i = 0, j = 0; i < si->ip.width * si->ip.height; i++, j+=3, in_left +=4) 00413 { 00414 /* images.images[0].data[j + 0] = in_left[0]; 00415 images.images[0].data[j + 1] = in_left[1]; 00416 images.images[0].data[j + 2] = in_left[2];*/ 00417 img_tmp[j + 0] = in_left[0]; 00418 img_tmp[j + 1] = in_left[1]; 00419 img_tmp[j + 2] = in_left[2]; 00420 } 00421 memcpy (&(images.images[0].data[0]), img_tmp, si->ip.width * si->ip.height * 3); 00422 // undistort (img_tmp, &(images.images[0].data[0]), si->ip.width, si->ip.height); 00423 free (img_tmp); 00424 } 00425 else 00426 { 00427 images.images[0].colorspace = "mono8"; 00428 memcpy (&(images.images[0].data[0]), si->Left (), images.images[0].get_data_size ()); 00429 } 00430 00431 // Prepare the right channel 00432 images.images[1].width = si->ip.width; 00433 images.images[1].height = si->ip.height; 00434 images.images[1].compression = "raw"; 00435 images.images[1].label = "stoc-right"; 00436 images.images[1].set_data_size (si->ip.width * si->ip.height); 00437 // Check if <right> has color or monochrome 00438 if (si->haveColorRight) 00439 { 00440 images.images[1].set_data_size (images.images[1].get_data_size () * 3); // RGB 00441 images.images[1].colorspace = "rgb24"; 00442 unsigned char *in_right = (unsigned char*)si->ColorRight (); 00443 for (int i = 0, j = 0; i < si->ip.width * si->ip.height; i++, j+=3, in_right +=4) 00444 { 00445 images.images[1].data[j + 0] = in_right[0]; 00446 images.images[1].data[j + 1] = in_right[1]; 00447 images.images[1].data[j + 2] = in_right[2]; 00448 } 00449 } 00450 else 00451 { 00452 images.images[1].colorspace = "mono8"; 00453 memcpy (&(images.images[1].data[0]), si->Right (), images.images[1].get_data_size ()); 00454 } 00455 00456 // Prepare the disparity channel 00457 if (si->haveDisparity) 00458 { 00459 images.images[2].width = si->dp.dwidth; 00460 images.images[2].height = si->dp.dheight; 00461 images.images[2].colorspace = "mono16"; 00462 images.images[2].compression = "raw"; 00463 images.images[2].label = "stoc-disparity"; 00464 images.images[2].set_data_size (si->dp.dwidth * si->dp.dheight * 2); 00465 memcpy (&(images.images[2].data[0]), si->disparity, images.images[2].get_data_size ()); 00466 } 00467 00468 cloud.header.stamp = ros::Time::now (); 00469 images.header.stamp = ros::Time::now (); 00470 return; 00471 } 00472 00474 // Read data from the device 00475 void 00476 stoc::STOC::readDataLeft (PointCloud &cloud, Image &left_image) 00477 { 00478 svsStereoImage *si = video_->GetImage (10); // 10 ms timeout 00479 if (si == NULL && debug_) 00480 STOC_EXCEPT(stoc::Exception, "No image, timed out..."); 00481 00482 // Compute the disparity image 00483 if (multiproc_en_) 00484 multiproc_->CalcStereo (si); 00485 else 00486 process_->CalcStereo (si); 00487 00488 // Trim down those nasty points at the bottom of the disparity image (errors?) 00489 for (int i = si->ip.height - cut_di_; i < si->ip.height; i++) 00490 for (int j = 0; j < si->ip.width; j++) 00491 si->disparity[i * si->ip.width + j] = -2; 00492 00493 // Compute the 3D point cloud information 00494 if (multiproc_en_) 00495 multiproc_->Calc3D (si, 0, 0, 0, 0, NULL, NULL, z_max_); 00496 else 00497 process_->Calc3D (si, 0, 0, 0, 0, NULL, NULL, z_max_); 00498 00499 // Save the 3D point cloud data in the structure, if present 00500 int nr_points = 0; 00501 00502 // Fill in the ROS PointCloud message 00503 cloud.points.resize (si->ip.height * si->ip.width); // allocate more than needed, we will resize later 00504 cloud.channels.resize (1); 00505 cloud.channels[0].name = "i"; 00506 cloud.channels[0].values.resize (cloud.points.size ()); 00507 00508 // RGB or monochrome ? 00509 if (si->haveColor) 00510 { 00511 cloud.channels.resize (3); 00512 cloud.channels[0].name = "r"; 00513 cloud.channels[0].values.resize (cloud.points.size ()); // re-do channels[0], just in case 00514 cloud.channels[1].name = "g"; 00515 cloud.channels[1].values.resize (cloud.points.size ()); 00516 cloud.channels[2].name = "b"; 00517 cloud.channels[2].values.resize (cloud.points.size ()); 00518 } 00519 00520 if (si->have3D) 00521 { 00522 svs3Dpoint *pts = si->pts3D; 00523 for (int i = 0; i < si->ip.height; i++) 00524 { 00525 for (int j = 0; j < si->ip.width; j++, pts++) 00526 { 00527 // Check if the point is valid 00528 if (pts->A <= 0) 00529 continue; 00530 00531 cloud.points[nr_points].x = pts->X; 00532 cloud.points[nr_points].y = pts->Y; 00533 cloud.points[nr_points].z = pts->Z; 00534 00535 if (si->haveColor) 00536 { 00537 svsColorPixel *mpc = (svsColorPixel*)(si->color + (i*si->ip.width + j) * 4); 00538 cloud.channels[0].values[nr_points] = mpc->r; // red 00539 cloud.channels[1].values[nr_points] = mpc->g; // green 00540 cloud.channels[2].values[nr_points] = mpc->b; // blue 00541 } 00542 else 00543 cloud.channels[0].values[nr_points] = (unsigned char)si->Left ()[i*si->ip.width + j]; 00544 00545 nr_points++; 00546 } // width 00547 } // height 00548 00549 } // have3D 00550 cloud.points.resize (nr_points); 00551 cloud.channels[0].values.resize (nr_points); 00552 // RGB or monochrome ? 00553 if (si->haveColor) 00554 { 00555 cloud.channels[1].values.resize (nr_points); 00556 cloud.channels[2].values.resize (nr_points); 00557 } 00558 00559 // Prepare the left channel 00560 left_image.width = si->ip.width; 00561 left_image.height = si->ip.height; 00562 left_image.compression = "raw"; 00563 left_image.label = "stoc-left"; 00564 left_image.set_data_size (si->ip.width * si->ip.height); 00565 // Check if <left> has color or monochrome 00566 if (si->haveColor) 00567 { 00568 left_image.set_data_size (left_image.get_data_size () * 3); // RGB 00569 left_image.colorspace = "rgb24"; 00570 unsigned char *in_left = (unsigned char*)si->Color (); 00571 for (int i = 0, j = 0; i < si->ip.width * si->ip.height; i++, j+=3, in_left +=4) 00572 { 00573 left_image.data[j + 0] = in_left[0]; 00574 left_image.data[j + 1] = in_left[1]; 00575 left_image.data[j + 2] = in_left[2]; 00576 } 00577 } 00578 else 00579 { 00580 left_image.colorspace = "mono8"; 00581 memcpy (&(left_image.data[0]), si->Left (), left_image.get_data_size ()); 00582 } 00583 00584 cloud.header.stamp = ros::Time::now (); 00585 left_image.header.stamp = ros::Time::now (); 00586 return; 00587 }