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
00031
00032
00033
00034
00035
00036
00037 #include "depthcloud_encoder/depthcloud_encoder.h"
00038
00039 #include <boost/bind.hpp>
00040 #include <boost/cstdint.hpp>
00041
00042 #include <cv_bridge/cv_bridge.h>
00043
00044 #include <pcl/common/transforms.h>
00045 #include <pcl/io/pcd_io.h>
00046 #include <pcl_conversions/pcl_conversions.h>
00047 #include <tf_conversions/tf_eigen.h>
00048
00049 #include <iostream>
00050
00051 #include <ros/console.h>
00052
00053 namespace depthcloud
00054 {
00055
00056 using namespace message_filters::sync_policies;
00057 namespace enc = sensor_msgs::image_encodings;
00058
00059 DepthCloudEncoder::DepthCloudEncoder(ros::NodeHandle& nh, ros::NodeHandle& pnh) :
00060 nh_(nh),
00061 pnh_(pnh),
00062 depth_sub_(),
00063 color_sub_(),
00064 pub_it_(nh_),
00065 connectivityExceptionFlag(false),
00066 lookupExceptionFlag(false)
00067 {
00068
00069 ros::NodeHandle priv_nh_("~");
00070
00071
00072 priv_nh_.param<std::string>("depth_source", depth_source_, "depthmap");
00073
00074
00075 priv_nh_.param<std::string>("cloud", cloud_topic_, "");
00076
00077
00078 priv_nh_.param<std::string>("camera_info_topic", camera_info_topic_, "");
00079
00080
00081 priv_nh_.param<std::string>("camera_frame_id", camera_frame_id_, "/camera_rgb_optical_frame");
00082
00083
00084 priv_nh_.param<double>("f", f_, 525.0);
00085
00086
00087 priv_nh_.param<double>("f_mult_factor", f_mult_factor_, 1.0);
00088
00089
00090 priv_nh_.param<float>("max_depth_per_tile", max_depth_per_tile_, 1.0);
00091
00092
00093 priv_nh_.param<int>("target_resolution", crop_size_, 512);
00094
00095
00096 priv_nh_.param<std::string>("depth", depthmap_topic_, "/camera/depth/image");
00097
00098
00099 priv_nh_.param<std::string>("rgb", rgb_image_topic_, "/camera/rgb/image_color");
00100
00101
00102 priv_nh_.param<bool>("latch", latch_, false);
00103
00104
00105 image_transport::SubscriberStatusCallback connect_cb = boost::bind(&DepthCloudEncoder::connectCb, this);
00106
00107 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00108
00109 pub_ = pub_it_.advertise("depthcloud_encoded", 1, connect_cb, connect_cb, ros::VoidPtr(), latch_);
00110 }
00111 DepthCloudEncoder::~DepthCloudEncoder()
00112 {
00113 }
00114
00115 void DepthCloudEncoder::connectCb()
00116 {
00117 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00118
00119 if (pub_.getNumSubscribers())
00120 {
00121 if ( depth_source_ == "depthmap" && !depthmap_topic_.empty() )
00122 subscribe(depthmap_topic_, rgb_image_topic_);
00123 else if ( depth_source_ == "cloud" && !cloud_topic_.empty() )
00124 subscribeCloud(cloud_topic_);
00125 else {
00126 if ( depth_source_ != "depthmap" && depth_source_ != "cloud" ) {
00127 ROS_ERROR("Invalid depth_source given to DepthCloudEncoder: use 'depthmap' or 'cloud'.");
00128 return;
00129 }
00130 ROS_ERROR_STREAM("Empty topic provided for DepthCloudEncoder depth_source " << depth_source_ << ". Check your arguments.");
00131 }
00132 }
00133 else
00134 {
00135 unsubscribe();
00136 }
00137 }
00138
00139 void DepthCloudEncoder::cameraInfoCb(const sensor_msgs::CameraInfoConstPtr& cam_info_msg)
00140 {
00141 if (cam_info_msg) {
00142
00143 const double fx = f_mult_factor_ * cam_info_msg->K[0];
00144 const double fy = f_mult_factor_ * cam_info_msg->K[4];
00145 f_ = (fx + fy) / 2;
00146 }
00147 }
00148
00149 void DepthCloudEncoder::dynReconfCb(depthcloud_encoder::paramsConfig& config, uint32_t level)
00150 {
00151 max_depth_per_tile_ = config.max_depth_per_tile;
00152 f_mult_factor_ = config.f_mult_factor;
00153 }
00154
00155 void DepthCloudEncoder::subscribeCloud(std::string& cloud_topic)
00156 {
00157 unsubscribe();
00158
00159 ROS_DEBUG_STREAM("Subscribing to "<< cloud_topic);
00160
00161
00162 cloud_sub_ = nh_.subscribe(cloud_topic, 1, &DepthCloudEncoder::cloudCB, this );
00163 if (!camera_info_topic_.empty()) {
00164 camera_info_sub_ = nh_.subscribe(camera_info_topic_, 2, &DepthCloudEncoder::cameraInfoCb, this);
00165 }
00166 }
00167
00168 void DepthCloudEncoder::subscribe(std::string& depth_topic, std::string& color_topic)
00169 {
00170 unsubscribe();
00171
00172 ROS_DEBUG_STREAM("Subscribing to "<< color_topic);
00173 ROS_DEBUG_STREAM("Subscribing to "<< depth_topic);
00174
00175 if (!depth_topic.empty())
00176 {
00177 try
00178 {
00179 image_transport::ImageTransport depth_it(pnh_);
00180 image_transport::ImageTransport color_it(pnh_);
00181
00182
00183 depth_sub_->subscribe(depth_it, depth_topic, 1, image_transport::TransportHints("raw"));
00184
00185 if (!color_topic.empty())
00186 {
00187
00188 color_sub_->subscribe(color_it, color_topic, 1, image_transport::TransportHints("raw"));
00189
00190
00191 sync_depth_color_->connectInput(*depth_sub_, *color_sub_);
00192 sync_depth_color_->setInterMessageLowerBound(0, ros::Duration(1.5));
00193 sync_depth_color_->setInterMessageLowerBound(1, ros::Duration(1.5));
00194 sync_depth_color_->registerCallback(boost::bind(&DepthCloudEncoder::depthColorCB, this, _1, _2));
00195 }
00196 else
00197 {
00198 depth_sub_->registerCallback(boost::bind(&DepthCloudEncoder::depthCB, this, _1));
00199 }
00200 }
00201 catch (ros::Exception& e)
00202 {
00203 ROS_ERROR("Error subscribing: %s", e.what());
00204 }
00205 }
00206 }
00207
00208
00209 void DepthCloudEncoder::unsubscribe()
00210 {
00211 try
00212 {
00213
00214 cloud_sub_.shutdown();
00215 camera_info_sub_.shutdown();
00216 sync_depth_color_.reset(new SynchronizerDepthColor(SyncPolicyDepthColor(10)));
00217 depth_sub_.reset(new image_transport::SubscriberFilter());
00218 color_sub_.reset(new image_transport::SubscriberFilter());
00219 }
00220 catch (ros::Exception& e)
00221 {
00222 ROS_ERROR("Error unsubscribing: %s", e.what());
00223 }
00224 }
00225
00226 void DepthCloudEncoder::cloudCB(const sensor_msgs::PointCloud2& cloud_msg)
00227 {
00228 sensor_msgs::ImagePtr depth_msg( new sensor_msgs::Image() );
00229 sensor_msgs::ImagePtr color_msg( new sensor_msgs::Image() );
00230
00231
00232
00233
00234
00235
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245 color_msg->height = depth_msg->height = cloud_msg.height;
00246 color_msg->width = depth_msg->width = cloud_msg.width;
00247 depth_msg->encoding = "32FC1";
00248 color_msg->encoding = "rgb8";
00249 color_msg->is_bigendian = depth_msg->is_bigendian = 0;
00250 depth_msg->step = depth_msg->width * 4;
00251 color_msg->step = color_msg->width * 3;
00252
00253 depth_msg->data.resize(depth_msg->height * depth_msg->step);
00254
00255 color_msg->data.resize(color_msg->height * color_msg->step, 0);
00256 for (int j=0; j < depth_msg->height; ++j) {
00257 for (int i =0; i < depth_msg->width; ++i) {
00258 *(float*)&depth_msg->data[ j * cloud_msg.width * 4 + i * 4 ] =
00259 std::numeric_limits<float>::quiet_NaN();
00260 }
00261 }
00262
00263 cloudToDepth(cloud_msg, depth_msg, color_msg);
00264
00265 process(depth_msg, color_msg, crop_size_);
00266 }
00267
00268 void DepthCloudEncoder::depthCB(const sensor_msgs::ImageConstPtr& depth_msg)
00269 {
00270 process(depth_msg, sensor_msgs::ImageConstPtr(), crop_size_);
00271 }
00272
00273 void DepthCloudEncoder::depthColorCB(const sensor_msgs::ImageConstPtr& depth_msg,
00274 const sensor_msgs::ImageConstPtr& color_msg)
00275 {
00276 process(depth_msg, color_msg, crop_size_);
00277 }
00278
00279 void DepthCloudEncoder::cloudToDepth(const sensor_msgs::PointCloud2& cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg)
00280 {
00281
00282 double u, v, zd, cx, cy;
00283
00284 cx = depth_msg->width / 2;
00285 cy = depth_msg->height / 2;
00286
00287
00288 pcl::PointCloud<pcl::PointXYZRGB>::Ptr scene_cloud( new pcl::PointCloud<pcl::PointXYZRGB> );
00289 pcl::fromROSMsg(cloud_msg,*scene_cloud);
00290
00291
00292 if ( cloud_msg.header.frame_id != this->camera_frame_id_ ) {
00293
00294 tf::StampedTransform transform;
00295 try {
00296 ros::Duration timeout(0.05);
00297
00298 tf_listener_.waitForTransform( this->camera_frame_id_, cloud_msg.header.frame_id,
00299 ros::Time(0), timeout);
00300 tf_listener_.lookupTransform(this->camera_frame_id_, cloud_msg.header.frame_id,
00301 ros::Time(0), transform);
00302 }
00303 catch (tf::ExtrapolationException& ex) {
00304 ROS_WARN("[run_viewer] TF ExtrapolationException:\n%s", ex.what());
00305 }
00306 catch (tf::ConnectivityException& ex) {
00307 if (!connectivityExceptionFlag) {
00308 ROS_WARN("[run_viewer] TF ConnectivityException:\n%s", ex.what());
00309 ROS_INFO("[run_viewer] Pick-it-App might not run correctly");
00310 connectivityExceptionFlag = true;
00311 }
00312 }
00313 catch (tf::LookupException& ex) {
00314 if (!lookupExceptionFlag){
00315 ROS_WARN("[run_viewer] TF LookupException:\n%s", ex.what());
00316 ROS_INFO("[run_viewer] Pick-it-App might not be running yet");
00317 lookupExceptionFlag = true;
00318 return;
00319 }
00320 }
00321 catch (tf::TransformException& ex) {
00322 ROS_WARN("[run_viewer] TF exception:\n%s", ex.what());
00323 return;
00324 }
00325
00326 pcl::PointCloud<pcl::PointXYZRGB>::Ptr camera_cloud( new pcl::PointCloud<pcl::PointXYZRGB> );
00327
00328 Eigen::Affine3d eigen_transform3d;
00329 tf::transformTFToEigen(transform, eigen_transform3d );
00330 Eigen::Affine3f eigen_transform3f( eigen_transform3d );
00331 pcl::transformPointCloud(*scene_cloud,*camera_cloud,eigen_transform3f);
00332
00333
00334 scene_cloud = camera_cloud;
00335 }
00336
00337 int number_of_points = scene_cloud->size();
00338
00339 using namespace std;
00340
00341 for(int i = 0 ; i < number_of_points ; i++)
00342 {
00343 if(isFinite(scene_cloud->points[i]))
00344 {
00345
00346 u = (f_ / scene_cloud->points[i].z ) * scene_cloud->points[i].x + cx;
00347 v = (f_ / scene_cloud->points[i].z ) * scene_cloud->points[i].y + cy;
00348
00349 int dlocation = int(u)*4 + int(v)*depth_msg->step;
00350 if ( dlocation >=0 && dlocation < depth_msg->data.size() ) {
00351 *(float*)&depth_msg->data[ dlocation ] = scene_cloud->points[i].z;
00352 }
00353 int clocation = int(u)*3 + int(v)*color_msg->step;
00354 if ( clocation >=0 && clocation < color_msg->data.size() ) {
00355 color_msg->data[ clocation ] = scene_cloud->points[i].r;
00356 color_msg->data[ clocation+1 ] = scene_cloud->points[i].g;
00357 color_msg->data[ clocation+2 ] = scene_cloud->points[i].b;
00358 }
00359 }
00360 }
00361 }
00362
00363 void DepthCloudEncoder::process(const sensor_msgs::ImageConstPtr& depth_msg,
00364 const sensor_msgs::ImageConstPtr& color_msg,
00365 const std::size_t crop_size)
00366 {
00367
00368 int depth_bits = enc::bitDepth(depth_msg->encoding);
00369 int depth_channels = enc::numChannels(depth_msg->encoding);
00370
00371 int color_bits = 0;
00372 int color_channels = 0;
00373
00374 if ((depth_bits != 32) || (depth_channels != 1))
00375 {
00376 ROS_DEBUG_STREAM( "Invalid color depth image format ("<<depth_msg->encoding <<")");
00377 return;
00378 }
00379
00380
00381 cv_bridge::CvImagePtr color_cv_ptr;
00382
00383
00384 if (color_msg)
00385 {
00386 try
00387 {
00388 color_cv_ptr = cv_bridge::toCvCopy(color_msg, "bgr8");
00389
00390 }
00391 catch (cv_bridge::Exception& e)
00392 {
00393 ROS_ERROR_STREAM("OpenCV-ROS bridge error: " << e.what());
00394 return;
00395 }
00396
00397 if (depth_msg->width != color_msg->width || depth_msg->height != color_msg->height)
00398 {
00399 ROS_DEBUG_STREAM( "Depth image resolution (" << (int)depth_msg->width << "x" << (int)depth_msg->height << ") "
00400 "does not match color image resolution (" << (int)color_msg->width << "x" << (int)color_msg->height << ")");
00401 return;
00402 }
00403 }
00404
00405
00406 sensor_msgs::ImagePtr depth_int_msg(new sensor_msgs::Image());
00407 sensor_msgs::ImagePtr valid_mask_msg(new sensor_msgs::Image());
00408
00409 depthInterpolation(depth_msg, depth_int_msg, valid_mask_msg);
00410
00411 unsigned int pix_size = enc::bitDepth(enc::BGR8) / 8 * 3;
00412
00413
00414 sensor_msgs::ImagePtr output_msg(new sensor_msgs::Image);
00415 output_msg->header = depth_int_msg->header;
00416 output_msg->encoding = enc::BGR8;
00417 output_msg->width = crop_size * 2;
00418 output_msg->height = crop_size * 2;
00419 output_msg->step = output_msg->width * pix_size;
00420 output_msg->is_bigendian = depth_int_msg->is_bigendian;
00421
00422
00423 output_msg->data.resize(output_msg->width * output_msg->height * pix_size, 0xFF);
00424
00425 std::size_t input_width = depth_int_msg->width;
00426 std::size_t input_height = depth_int_msg->height;
00427
00428
00429 {
00430 std::size_t y, x, left_x, top_y, width_x, width_y;
00431
00432
00433 int top_bottom_corner = (static_cast<int>(input_height) - static_cast<int>(crop_size)) / 2;
00434 int left_right_corner = (static_cast<int>(input_width) - static_cast<int>(crop_size)) / 2;
00435
00436 if (top_bottom_corner < 0)
00437 {
00438 top_y = 0;
00439 width_y = input_height;
00440 }
00441 else
00442 {
00443 top_y = top_bottom_corner;
00444 width_y = input_height - top_bottom_corner;
00445 }
00446
00447 if (left_right_corner < 0)
00448 {
00449 left_x = 0;
00450 width_x = input_width;
00451 }
00452 else
00453 {
00454 left_x = left_right_corner;
00455 width_x = input_width - left_right_corner;
00456 }
00457
00458
00459 uint8_t* dest_ptr = &output_msg->data[((top_y - top_bottom_corner) * output_msg->width + left_x - left_right_corner)
00460 * pix_size];
00461 const std::size_t dest_y_step = output_msg->step;
00462
00463
00464 const float* source_depth_ptr = (const float*)&depth_int_msg->data[(top_y * input_width + left_x) * sizeof(float)];
00465
00466
00467 const uint8_t* source_mask_ptr = &valid_mask_msg->data[(top_y * input_width + left_x) * sizeof(uint8_t)];
00468
00469
00470 const uint8_t* source_color_ptr = 0;
00471 std::size_t source_color_y_step = 0;
00472 if (color_msg)
00473 {
00474 source_color_y_step = input_width * pix_size;
00475 source_color_ptr = static_cast<const uint8_t*>(&color_cv_ptr->image.data[(top_y * input_width + left_x) * pix_size]);
00476 }
00477
00478
00479 const std::size_t right_frame_shift = crop_size * pix_size;
00480 ;
00481 const std::size_t down_frame_shift = dest_y_step * crop_size;
00482
00483
00484 for (y = top_y; y < width_y;
00485 ++y, source_color_ptr += source_color_y_step, source_depth_ptr += input_width, source_mask_ptr += input_width, dest_ptr +=
00486 dest_y_step)
00487 {
00488 const float *depth_ptr = source_depth_ptr;
00489
00490
00491 const uint8_t *color_ptr = source_color_ptr;
00492 const uint8_t *mask_ptr = source_mask_ptr;
00493
00494 uint8_t *out_depth_low_ptr = dest_ptr;
00495 uint8_t *out_depth_high_ptr = dest_ptr + right_frame_shift;
00496 uint8_t *out_color_ptr = dest_ptr + right_frame_shift + down_frame_shift;
00497
00498 for (x = left_x; x < width_x; ++x)
00499 {
00500 int depth_pix_low;
00501 int depth_pix_high;
00502
00503 if (*depth_ptr == *depth_ptr)
00504 {
00505 depth_pix_low = std::min(std::max(0.0f, (*depth_ptr / max_depth_per_tile_) * (float)(0xFF * 3)), (float)(0xFF * 3));
00506 depth_pix_high = std::min(std::max(0.0f, ((*depth_ptr - max_depth_per_tile_) / max_depth_per_tile_) * (float)(0xFF) * 3), (float)(0xFF * 3));
00507 }
00508 else
00509 {
00510 depth_pix_low = 0;
00511 depth_pix_high = 0;
00512
00513 }
00514
00515 uint8_t *mask_pix_ptr = out_depth_low_ptr + down_frame_shift;
00516 if (*mask_ptr == 0)
00517 {
00518
00519 memset(mask_pix_ptr, 0x00, pix_size);
00520 }
00521 else
00522 {
00523
00524 memset(mask_pix_ptr, 0xFF, pix_size);
00525 }
00526
00527
00528 uint8_t depth_pix_low_r = std::min(std::max(0, depth_pix_low), (0xFF));
00529 uint8_t depth_pix_low_g = std::min(std::max(0, depth_pix_low-(0xFF)), (0xFF));
00530 uint8_t depth_pix_low_b = std::min(std::max(0, depth_pix_low-(0xFF*2)), (0xFF));
00531
00532 *out_depth_low_ptr = depth_pix_low_r; ++out_depth_low_ptr;
00533 *out_depth_low_ptr = depth_pix_low_g; ++out_depth_low_ptr;
00534 *out_depth_low_ptr = depth_pix_low_b; ++out_depth_low_ptr;
00535
00536 uint8_t depth_pix_high_r = std::min(std::max(0, depth_pix_high), (0xFF));
00537 uint8_t depth_pix_high_g = std::min(std::max(0, depth_pix_high-(0xFF)), (0xFF));
00538 uint8_t depth_pix_high_b = std::min(std::max(0, depth_pix_high-(0xFF*2)), (0xFF));
00539
00540 *out_depth_high_ptr = depth_pix_high_r; ++out_depth_high_ptr;
00541 *out_depth_high_ptr = depth_pix_high_g; ++out_depth_high_ptr;
00542 *out_depth_high_ptr = depth_pix_high_b; ++out_depth_high_ptr;
00543
00544 if (color_ptr)
00545 {
00546
00547 *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
00548
00549 *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
00550
00551 *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
00552 }
00553
00554
00555 ++mask_ptr;
00556 ++depth_ptr;
00557
00558 }
00559 }
00560 }
00561
00562 pub_.publish(output_msg);
00563 }
00564
00565 void DepthCloudEncoder::depthInterpolation(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImagePtr depth_int_msg,
00566 sensor_msgs::ImagePtr mask_msg)
00567 {
00568 const std::size_t input_width = depth_msg->width;
00569 const std::size_t input_height = depth_msg->height;
00570
00571
00572 depth_int_msg->header = depth_msg->header;
00573 depth_int_msg->encoding = depth_msg->encoding;
00574 depth_int_msg->width = input_width;
00575 depth_int_msg->height = input_height;
00576 depth_int_msg->step = depth_msg->step;
00577 depth_int_msg->is_bigendian = depth_msg->is_bigendian;
00578 depth_int_msg->data.resize(depth_int_msg->step * depth_int_msg->height, 0);
00579
00580
00581 mask_msg->header = depth_msg->header;
00582 mask_msg->encoding = enc::TYPE_8UC1;
00583 mask_msg->width = input_width;
00584 mask_msg->height = input_height;
00585 mask_msg->step = depth_msg->step;
00586 mask_msg->is_bigendian = depth_msg->is_bigendian;
00587 mask_msg->data.resize(mask_msg->step * mask_msg->height, 0xFF);
00588
00589 const float* depth_ptr = (const float*)&depth_msg->data[0];
00590 float* depth_int_ptr = (float*)&depth_int_msg->data[0];
00591 uint8_t* mask_ptr = (uint8_t*)&mask_msg->data[0];
00592
00593 float leftVal = -1.0f;
00594
00595 unsigned int y, len;
00596 for (y = 0; y < input_height; ++y, depth_ptr += input_width, depth_int_ptr += input_width, mask_ptr += input_width)
00597 {
00598 const float* in_depth_ptr = depth_ptr;
00599 float* out_depth_int_ptr = depth_int_ptr;
00600 uint8_t* out_mask_ptr = mask_ptr;
00601
00602 const float* in_depth_end_ptr = depth_ptr + input_width;
00603
00604 while (in_depth_ptr < in_depth_end_ptr)
00605 {
00606 len = 0;
00607 const float* last_valid_pix_ptr = in_depth_ptr;
00608 while ((isnan(*in_depth_ptr) || (*in_depth_ptr == 0)) && (in_depth_ptr < in_depth_end_ptr))
00609 {
00610 ++in_depth_ptr;
00611 ++len;
00612 }
00613 if (len > 0)
00614 {
00615
00616
00617
00618 float rightVal;
00619 if (in_depth_ptr < in_depth_end_ptr)
00620 {
00621 rightVal = *in_depth_ptr;
00622 }
00623 else
00624 {
00625 rightVal = leftVal;
00626 }
00627
00628
00629 if (isnan(leftVal) || (leftVal < 0.0f))
00630 leftVal = rightVal;
00631
00632 float incVal = (rightVal - leftVal) / (float)len;
00633 float fillVal = leftVal;
00634 const float* fill_ptr;
00635
00636 for (fill_ptr = last_valid_pix_ptr; fill_ptr < in_depth_ptr; ++fill_ptr)
00637 {
00638
00639 *out_depth_int_ptr = fillVal;
00640 ++out_depth_int_ptr;
00641
00642
00643 *out_mask_ptr = 0xFF; ++out_mask_ptr;
00644
00645 fillVal += incVal;
00646 }
00647
00648 leftVal = rightVal;
00649 }
00650 else
00651 {
00652
00653
00654 leftVal = *in_depth_ptr;
00655
00656 *out_depth_int_ptr = *in_depth_ptr;
00657
00658
00659 *out_mask_ptr = 0; ++out_mask_ptr;
00660
00661 ++in_depth_ptr;
00662 ++out_depth_int_ptr;
00663 }
00664
00665 }
00666
00667 }
00668
00669 }
00670
00671
00672 }