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
00039 #include "pcl/win32_macros.h"
00040
00041 namespace pcl
00042 {
00043
00045 template <typename PointCloudType> void
00046 RangeImage::createFromPointCloud(const PointCloudType& point_cloud, float angular_resolution, float max_angle_width, float max_angle_height,
00047 const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame,
00048 float noise_level, float min_range, int border_size)
00049 {
00050
00051
00052
00053
00054
00055 angular_resolution_ = angular_resolution;
00056 angular_resolution_reciprocal_ = 1.0f / angular_resolution_;
00057
00058 width = lrint(floor(max_angle_width*angular_resolution_reciprocal_));
00059 height = lrint(floor(max_angle_height*angular_resolution_reciprocal_));
00060 image_offset_x_ = image_offset_y_ = 0;
00061 is_dense = false;
00062
00063 getCoordinateFrameTransformation(coordinate_frame, to_world_system_);
00064 to_world_system_ = sensor_pose * to_world_system_;
00065
00066 getInverse(to_world_system_, to_range_image_system_);
00067
00068
00069 unsigned int size = width*height;
00070 points.clear();
00071 points.resize(size, unobserved_point);
00072
00073 int top=height, right=-1, bottom=-1, left=width;
00074 doZBuffer(point_cloud, noise_level, min_range, top, right, bottom, left);
00075
00076 cropImage(border_size, top, right, bottom, left);
00077
00078 recalculate3DPointPositions();
00079 }
00080
00082 template <typename PointCloudTypeWithViewpoints> void
00083 RangeImage::createFromPointCloudWithViewpoints(const PointCloudTypeWithViewpoints& point_cloud, float angular_resolution,
00084 float max_angle_width, float max_angle_height, RangeImage::CoordinateFrame coordinate_frame,
00085 float noise_level, float min_range, int border_size)
00086 {
00087 Eigen::Vector3f average_viewpoint = getAverageViewPoint(point_cloud);
00088
00089 Eigen::Affine3f sensor_pose = (Eigen::Affine3f)Eigen::Translation3f(average_viewpoint);
00090
00091 createFromPointCloud(point_cloud, angular_resolution, max_angle_width, max_angle_height, sensor_pose, coordinate_frame, noise_level, min_range, border_size);
00092
00093
00094 }
00095
00097 template <typename PointCloudType> void
00098 RangeImage::createFromPointCloudWithKnownSize(const PointCloudType& point_cloud, float angular_resolution,
00099 const Eigen::Vector3f& point_cloud_center, float point_cloud_radius,
00100 const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame,
00101 float noise_level, float min_range, int border_size)
00102 {
00103
00104
00105
00106
00107 angular_resolution_ = angular_resolution;
00108 angular_resolution_reciprocal_ = 1.0f / angular_resolution_;
00109
00110 getCoordinateFrameTransformation(coordinate_frame, to_world_system_);
00111 to_world_system_ = sensor_pose * to_world_system_;
00112 getInverse(to_world_system_, to_range_image_system_);
00113
00114 float max_angle_size = getMaxAngleSize(sensor_pose, point_cloud_center, point_cloud_radius);
00115 int pixel_radius = lrint(ceil(0.5f*max_angle_size*angular_resolution_reciprocal_));
00116 width = height = 2*pixel_radius;
00117 is_dense = false;
00118
00119 image_offset_x_ = image_offset_y_ = 0;
00120 int center_pixel_x, center_pixel_y;
00121 getImagePoint(point_cloud_center, center_pixel_x, center_pixel_y);
00122 image_offset_x_ = (std::max)(0, center_pixel_x-pixel_radius);
00123 image_offset_y_ = (std::max)(0, center_pixel_y-pixel_radius);
00124
00125
00126
00127
00128 points.clear();
00129 points.resize(width*height, unobserved_point);
00130
00131 int top=height, right=-1, bottom=-1, left=width;
00132 doZBuffer(point_cloud, noise_level, min_range, top, right, bottom, left);
00133
00134 cropImage(border_size, top, right, bottom, left);
00135
00136 recalculate3DPointPositions();
00137 }
00138
00140 template <typename PointCloudType> void
00141 RangeImage::doZBuffer(const PointCloudType& point_cloud, float noise_level, float min_range, int& top, int& right, int& bottom, int& left)
00142 {
00143 typedef typename PointCloudType::PointType PointType2;
00144 const std::vector<PointType2, Eigen::aligned_allocator<PointType2> >& points2 = point_cloud.points;
00145
00146 unsigned int size = width*height;
00147 int* counters = new int[size];
00148 ERASE_ARRAY(counters, size);
00149
00150 top=height; right=-1; bottom=-1; left=width;
00151
00152 float x_real, y_real, range_of_current_point;
00153 int x, y;
00154 for (typename std::vector<PointType2, Eigen::aligned_allocator<PointType2> >::const_iterator it=points2.begin(); it!=points2.end(); ++it)
00155 {
00156 if (!hasValidXYZ(*it))
00157 continue;
00158 Vector3fMapConst current_point = it->getVector3fMap();
00159
00160 this->getImagePoint(current_point, x_real, y_real, range_of_current_point);
00161 this->real2DToInt2D(x_real, y_real, x, y);
00162
00163 if (range_of_current_point < min_range|| !isInImage(x, y))
00164 continue;
00165
00166
00167
00168 int floor_x = lrint (floor (x_real)), floor_y = lrint (floor (y_real)),
00169 ceil_x = lrint (ceil (x_real)), ceil_y = lrint (ceil (y_real));
00170
00171 int neighbor_x[4], neighbor_y[4];
00172 neighbor_x[0]=floor_x; neighbor_y[0]=floor_y;
00173 neighbor_x[1]=floor_x; neighbor_y[1]=ceil_y;
00174 neighbor_x[2]=ceil_x; neighbor_y[2]=floor_y;
00175 neighbor_x[3]=ceil_x; neighbor_y[3]=ceil_y;
00176
00177
00178 for (int i=0; i<4; ++i)
00179 {
00180 int n_x=neighbor_x[i], n_y=neighbor_y[i];
00181
00182 if (n_x==x && n_y==y)
00183 continue;
00184 if (isInImage(n_x, n_y))
00185 {
00186 int neighbor_array_pos = n_y*width + n_x;
00187 if (counters[neighbor_array_pos]==0)
00188 {
00189 float& neighbor_range = points[neighbor_array_pos].range;
00190 neighbor_range = (pcl_isinf(neighbor_range) ? range_of_current_point : (std::min)(neighbor_range, range_of_current_point));
00191 top=(std::min)(top, n_y); right=(std::max)(right, n_x); bottom=(std::max)(bottom, n_y); left=(std::min)(left, n_x);
00192 }
00193 }
00194 }
00195
00196
00197
00198 int arrayPos = y*width + x;
00199 float& range_at_image_point = points[arrayPos].range;
00200 int& counter = counters[arrayPos];
00201 bool addCurrentPoint=false, replace_with_current_point=false;
00202
00203 if (counter==0)
00204 {
00205 replace_with_current_point = true;
00206 }
00207 else
00208 {
00209 if (range_of_current_point < range_at_image_point-noise_level)
00210 {
00211 replace_with_current_point = true;
00212 }
00213 else if (fabs(range_of_current_point-range_at_image_point)<=noise_level)
00214 {
00215 addCurrentPoint = true;
00216 }
00217 }
00218
00219 if (replace_with_current_point)
00220 {
00221 counter = 1;
00222 range_at_image_point = range_of_current_point;
00223 top=(std::min)(top, y); right=(std::max)(right, x); bottom=(std::max)(bottom, y); left=(std::min)(left, x);
00224
00225 }
00226 else if (addCurrentPoint)
00227 {
00228 ++counter;
00229 range_at_image_point += (range_of_current_point-range_at_image_point)/counter;
00230 }
00231 }
00232
00233 delete[] counters;
00234 }
00235
00237 void
00238 RangeImage::getImagePoint(float x, float y, float z, float& image_x, float& image_y, float& range) const
00239 {
00240 Eigen::Vector3f point(x, y, z);
00241 getImagePoint(point, image_x, image_y, range);
00242 }
00243
00245 void
00246 RangeImage::getImagePoint(float x, float y, float z, float& image_x, float& image_y) const
00247 {
00248 float range;
00249 getImagePoint(x, y, z, image_x, image_y, range);
00250 }
00251
00253 void
00254 RangeImage::getImagePoint(float x, float y, float z, int& image_x, int& image_y) const
00255 {
00256 float image_x_float, image_y_float;
00257 getImagePoint(x, y, z, image_x_float, image_y_float);
00258 real2DToInt2D(image_x_float, image_y_float, image_x, image_y);
00259 }
00260
00262 void
00263 RangeImage::getImagePoint(const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const
00264 {
00265 Eigen::Vector3f transformedPoint = to_range_image_system_ * point;
00266 range = transformedPoint.norm();
00267 float angle_x = atan2f(transformedPoint[0], transformedPoint[2]),
00268 angle_y = asinf(transformedPoint[1]/range);
00269 getImagePointFromAngles(angle_x, angle_y, image_x, image_y);
00270
00271
00272
00273 }
00274
00276 void
00277 RangeImage::getImagePoint(const Eigen::Vector3f& point, int& image_x, int& image_y, float& range) const {
00278 float image_x_float, image_y_float;
00279 getImagePoint(point, image_x_float, image_y_float, range);
00280 real2DToInt2D(image_x_float, image_y_float, image_x, image_y);
00281 }
00282
00284 void
00285 RangeImage::getImagePoint(const Eigen::Vector3f& point, float& image_x, float& image_y) const
00286 {
00287 float range;
00288 getImagePoint(point, image_x, image_y, range);
00289 }
00290
00292 void
00293 RangeImage::getImagePoint(const Eigen::Vector3f& point, int& image_x, int& image_y) const
00294 {
00295 float image_x_float, image_y_float;
00296 getImagePoint(point, image_x_float, image_y_float);
00297 real2DToInt2D(image_x_float, image_y_float, image_x, image_y);
00298 }
00299
00301 float
00302 RangeImage::checkPoint(const Eigen::Vector3f& point, PointWithRange& point_in_image) const
00303 {
00304 int image_x, image_y;
00305 float range;
00306 getImagePoint(point, image_x, image_y, range);
00307 if (!isInImage(image_x, image_y))
00308 point_in_image = unobserved_point;
00309 else
00310 point_in_image = getPoint(image_x, image_y);
00311 return range;
00312 }
00313
00315 float
00316 RangeImage::getRangeDifference(const Eigen::Vector3f& point) const
00317 {
00318 int image_x, image_y;
00319 float range;
00320 getImagePoint(point, image_x, image_y, range);
00321 if (!isInImage(image_x, image_y))
00322 return -std::numeric_limits<float>::infinity ();
00323 float image_point_range = getPoint(image_x, image_y).range;
00324 if (pcl_isinf(image_point_range))
00325 {
00326 if (image_point_range > 0.0f)
00327 return std::numeric_limits<float>::infinity ();
00328 else
00329 return -std::numeric_limits<float>::infinity ();
00330 }
00331 return image_point_range - range;
00332 }
00333
00335 void
00336 RangeImage::getImagePointFromAngles(float angle_x, float angle_y, float& image_x, float& image_y) const
00337 {
00338 image_x = (angle_x*cosf(angle_y) + float(M_PI))*angular_resolution_reciprocal_ - image_offset_x_;
00339 image_y = (angle_y + 0.5f*float(M_PI))*angular_resolution_reciprocal_ - image_offset_y_;
00340 }
00341
00343 void
00344 RangeImage::real2DToInt2D(float x, float y, int& xInt, int& yInt) const
00345 {
00346 xInt = lrint(x); yInt = lrint(y);
00347 }
00348
00350 bool
00351 RangeImage::isInImage(int x, int y) const
00352 {
00353 return x>=0 && x<(int)width && y>=0 && y<(int)height;
00354 }
00355
00357 bool
00358 RangeImage::isValid(int x, int y) const
00359 {
00360 return isInImage(x,y) && pcl_isfinite(getPoint(x,y).range);
00361 }
00362
00364 bool
00365 RangeImage::isValid(int index) const
00366 {
00367 return pcl_isfinite(getPoint(index).range);
00368 }
00369
00371 bool
00372 RangeImage::isObserved(int x, int y) const
00373 {
00374 if (!isInImage(x,y) || (pcl_isinf(getPoint(x,y).range)&&getPoint(x,y).range<0.0f))
00375 return false;
00376 return true;
00377 }
00378
00380 bool
00381 RangeImage::isMaxRange(int x, int y) const
00382 {
00383 float range = getPoint(x,y).range;
00384 return pcl_isinf(range) && range>0.0f;
00385 }
00386
00388 const PointWithRange&
00389 RangeImage::getPointConsideringWrapAround(int image_x, int image_y) const
00390 {
00391 if (!isObserved(image_x, image_y))
00392 {
00393 float angle_x, angle_y, image_x_f, image_y_f;
00394 getAnglesFromImagePoint(image_x, image_y, angle_x, angle_y);
00395 angle_x = normAngle(angle_x); angle_y = normAngle(angle_y);
00396 getImagePointFromAngles(angle_x, angle_y, image_x_f, image_y_f);
00397 int new_image_x, new_image_y;
00398 real2DToInt2D(image_x_f, image_y_f, new_image_x, new_image_y);
00399 if (image_x!=new_image_x || image_y!=new_image_y)
00400 std::cout << image_x<<","<<image_y << " was change to "<<new_image_x<<","<<new_image_y<<"\n";
00401 if (!isInImage(new_image_x, new_image_y))
00402 return unobserved_point;
00403 image_x=new_image_x; image_y=new_image_y;
00404 }
00405 return points[image_y*width + image_x];
00406 }
00407
00409 const PointWithRange&
00410 RangeImage::getPoint(int image_x, int image_y) const
00411 {
00412 if (!isInImage(image_x, image_y))
00413 return unobserved_point;
00414 return points[image_y*width + image_x];
00415 }
00416
00418 const PointWithRange&
00419 RangeImage::getPointNoCheck(int image_x, int image_y) const
00420 {
00421 return points[image_y*width + image_x];
00422 }
00423
00425 PointWithRange&
00426 RangeImage::getPointNoCheck(int image_x, int image_y)
00427 {
00428 return points[image_y*width + image_x];
00429 }
00430
00432 PointWithRange&
00433 RangeImage::getPoint(int image_x, int image_y)
00434 {
00435 return points[image_y*width + image_x];
00436 }
00437
00438
00440 const PointWithRange&
00441 RangeImage::getPoint(int index) const
00442 {
00443 return points[index];
00444 }
00445
00447 const PointWithRange&
00448 RangeImage::getPoint(float image_x, float image_y) const
00449 {
00450 int x, y;
00451 real2DToInt2D(image_x, image_y, x, y);
00452 return getPoint(x, y);
00453 }
00454
00456 PointWithRange&
00457 RangeImage::getPoint(float image_x, float image_y)
00458 {
00459 return getPoint(image_x, image_y);
00460 }
00461
00463 void
00464 RangeImage::getPoint(int image_x, int image_y, Eigen::Vector3f& point) const
00465 {
00466
00467 point = getPoint(image_x, image_y).getVector3fMap();
00468 }
00469
00471 void
00472 RangeImage::getPoint(int index, Eigen::Vector3f& point) const
00473 {
00474 point = getPoint(index).getVector3fMap();
00475 }
00476
00478 const Eigen::Map<const Eigen::Vector3f>
00479 RangeImage::getEigenVector3f(int x, int y) const
00480 {
00481 return getPoint(x, y).getVector3fMap();
00482 }
00483
00485 const Eigen::Map<const Eigen::Vector3f>
00486 RangeImage::getEigenVector3f(int index) const
00487 {
00488 return getPoint(index).getVector3fMap();
00489 }
00490
00492 void
00493 RangeImage::calculate3DPoint(float image_x, float image_y, float range, Eigen::Vector3f& point) const
00494 {
00495 float angle_x, angle_y;
00496
00497 getAnglesFromImagePoint(image_x, image_y, angle_x, angle_y);
00498
00499 float cosY = cosf(angle_y);
00500 point = Eigen::Vector3f(range * sinf(angle_x) * cosY, range * sinf(angle_y), range * cosf(angle_x)*cosY);
00501 point = to_world_system_ * point;
00502 }
00503
00505 void
00506 RangeImage::calculate3DPoint(float image_x, float image_y, Eigen::Vector3f& point) const
00507 {
00508 const PointWithRange& point_in_image = getPoint(image_x, image_y);
00509 calculate3DPoint(image_x, image_y, point_in_image.range, point);
00510 }
00511
00513 void
00514 RangeImage::calculate3DPoint(float image_x, float image_y, float range, PointWithRange& point) const {
00515 point.range = range;
00516 Eigen::Vector3f tmp_point;
00517 calculate3DPoint(image_x, image_y, range, tmp_point);
00518 point.x=tmp_point[0]; point.y=tmp_point[1]; point.z=tmp_point[2];
00519 }
00520
00522 void
00523 RangeImage::calculate3DPoint(float image_x, float image_y, PointWithRange& point) const
00524 {
00525 const PointWithRange& point_in_image = getPoint(image_x, image_y);
00526 calculate3DPoint(image_x, image_y, point_in_image.range, point);
00527 }
00528
00530 void
00531 RangeImage::getAnglesFromImagePoint(float image_x, float image_y, float& angle_x, float& angle_y) const
00532 {
00533 angle_y = (image_y+image_offset_y_)*angular_resolution_ - 0.5f*float(M_PI);
00534 float cos_angle_y = cosf(angle_y);
00535 angle_x = (cos_angle_y==0.0f ? 0.0f : ((image_x+image_offset_x_)*angular_resolution_ - float(M_PI))/cos_angle_y);
00536 }
00537
00539 float
00540 RangeImage::getImpactAngle(int x1, int y1, int x2, int y2) const
00541 {
00542 if (!isInImage(x1, y1) || !isInImage(x2,y2))
00543 return -std::numeric_limits<float>::infinity ();
00544 return getImpactAngle(getPoint(x1,y1),getPoint(x2,y2));
00545 }
00546
00548 float
00549 RangeImage::getImpactAngle(const PointWithRange& point1, const PointWithRange& point2) const {
00550 if ((pcl_isinf(point1.range)&&point1.range<0) || (pcl_isinf(point2.range)&&point2.range<0))
00551 return -std::numeric_limits<float>::infinity ();
00552
00553 float r1 = (std::min)(point1.range, point2.range),
00554 r2 = (std::max)(point1.range, point2.range);
00555 float impact_angle = 0.5f*M_PI;
00556
00557 if (pcl_isinf(r2)) {
00558 if (r2 > 0.0f && !pcl_isinf(r1))
00559 impact_angle = 0.0f;
00560 }
00561 else if (!pcl_isinf(r1)) {
00562 float r1Sqr = r1*r1,
00563 r2Sqr = r2*r2,
00564 dSqr = squaredEuclideanDistance(point1, point2),
00565 d = sqrtf(dSqr);
00566 float cos_impact_angle = (r2Sqr + dSqr - r1Sqr)/(2.0f*r2*d);
00567 cos_impact_angle = (std::max)(0.0f, (std::min)(1.0f, cos_impact_angle));
00568 impact_angle = acosf(cos_impact_angle);
00569 }
00570
00571 if (point1.range > point2.range)
00572 impact_angle = -impact_angle;
00573
00574 return impact_angle;
00575 }
00576
00578 float
00579 RangeImage::getAcutenessValue(const PointWithRange& point1, const PointWithRange& point2) const
00580 {
00581 float impact_angle = getImpactAngle(point1, point2);
00582 if (pcl_isinf(impact_angle))
00583 return -std::numeric_limits<float>::infinity ();
00584 float ret = 1.0f - fabs(impact_angle)/(0.5f*M_PI);
00585 if (impact_angle < 0.0f)
00586 ret = -ret;
00587
00588
00589 return ret;
00590 }
00591
00593 float
00594 RangeImage::getAcutenessValue(int x1, int y1, int x2, int y2) const
00595 {
00596 if (!isInImage(x1, y1) || !isInImage(x2,y2))
00597 return -std::numeric_limits<float>::infinity ();
00598 return getAcutenessValue(getPoint(x1,y1), getPoint(x2,y2));
00599 }
00600
00602 const Eigen::Vector3f
00603 RangeImage::getSensorPos() const
00604 {
00605 return Eigen::Vector3f(to_world_system_(0,3), to_world_system_(1,3), to_world_system_(2,3));
00606 }
00607
00609 void
00610 RangeImage::getSurfaceAngleChange(int x, int y, int radius, float& angle_change_x, float& angle_change_y) const
00611 {
00612 angle_change_x = angle_change_y = -std::numeric_limits<float>::infinity ();
00613 if (!isValid(x,y))
00614 return;
00615 Eigen::Vector3f point;
00616 getPoint(x, y, point);
00617 Eigen::Affine3f transformation = getTransformationToViewerCoordinateFrame(point);
00618
00619 if (isObserved(x-radius, y) && isObserved(x+radius, y))
00620 {
00621 Eigen::Vector3f transformed_left;
00622 if (isMaxRange(x-radius, y))
00623 transformed_left = Eigen::Vector3f(0.0f, 0.0f, -1.0f);
00624 else
00625 {
00626 Eigen::Vector3f left;
00627 getPoint(x-radius, y, left);
00628 transformed_left = -(transformation * left);
00629
00630 transformed_left[1] = 0.0f;
00631 transformed_left.normalize();
00632 }
00633
00634 Eigen::Vector3f transformed_right;
00635 if (isMaxRange(x+radius, y))
00636 transformed_right = Eigen::Vector3f(0.0f, 0.0f, 1.0f);
00637 else
00638 {
00639 Eigen::Vector3f right;
00640 getPoint(x+radius, y, right);
00641 transformed_right = transformation * right;
00642
00643 transformed_right[1] = 0.0f;
00644 transformed_right.normalize();
00645 }
00646 angle_change_x = transformed_left.dot(transformed_right);
00647 angle_change_x = (std::max)(0.0f, (std::min)(1.0f, angle_change_x));
00648 angle_change_x = acosf(angle_change_x);
00649 }
00650
00651 if (isObserved(x, y-radius) && isObserved(x, y+radius))
00652 {
00653 Eigen::Vector3f transformed_top;
00654 if (isMaxRange(x, y-radius))
00655 transformed_top = Eigen::Vector3f(0.0f, 0.0f, -1.0f);
00656 else
00657 {
00658 Eigen::Vector3f top;
00659 getPoint(x, y-radius, top);
00660 transformed_top = -(transformation * top);
00661
00662 transformed_top[0] = 0.0f;
00663 transformed_top.normalize();
00664 }
00665
00666 Eigen::Vector3f transformed_bottom;
00667 if (isMaxRange(x, y+radius))
00668 transformed_bottom = Eigen::Vector3f(0.0f, 0.0f, 1.0f);
00669 else
00670 {
00671 Eigen::Vector3f bottom;
00672 getPoint(x, y+radius, bottom);
00673 transformed_bottom = transformation * bottom;
00674
00675 transformed_bottom[0] = 0.0f;
00676 transformed_bottom.normalize();
00677 }
00678 angle_change_y = transformed_top.dot(transformed_bottom);
00679 angle_change_y = (std::max)(0.0f, (std::min)(1.0f, angle_change_y));
00680 angle_change_y = acosf(angle_change_y);
00681 }
00682 }
00683
00684
00685
00686
00687
00688
00689
00690
00691
00692
00693
00694
00695
00696
00697
00698
00699
00700
00701
00702
00703
00704
00705
00706
00707
00709
00710
00711
00712
00714 float
00715 RangeImage::getMaxAngleSize(const Eigen::Affine3f& viewer_pose, const Eigen::Vector3f& center, float radius)
00716 {
00717 return 2.0f * asinf(radius/(getTranslation(viewer_pose)-center).norm());
00718 }
00719
00721 Eigen::Vector3f
00722 RangeImage::getEigenVector3f(const PointWithRange& point)
00723 {
00724 return Eigen::Vector3f(point.x, point.y, point.z);
00725 }
00726
00728 void
00729 RangeImage::get1dPointAverage(int x, int y, int delta_x, int delta_y, int no_of_points, PointWithRange& average_point) const
00730 {
00731
00732
00733 float weight_sum = 1.0f;
00734 average_point = getPoint(x,y);
00735 if (pcl_isinf(average_point.range))
00736 {
00737 if (average_point.range>0.0f)
00738 return;
00739 weight_sum = 0.0f;
00740 average_point.x = average_point.y = average_point.z = average_point.range = 0.0f;
00741 }
00742
00743 int x2=x, y2=y;
00744 Vector4fMap average_point_eigen = average_point.getVector4fMap();
00745
00746 for (int step=1; step<no_of_points; ++step)
00747 {
00748
00749 x2+=delta_x; y2+=delta_y;
00750 if (!isValid(x2, y2))
00751 continue;
00752 const PointWithRange& p = getPointNoCheck(x2, y2);
00753 average_point_eigen+=p.getVector4fMap(); average_point.range+=p.range;
00754 weight_sum += 1.0f;
00755 }
00756 if (weight_sum<= 0.0f)
00757 {
00758 average_point = unobserved_point;
00759 return;
00760 }
00761 float normalization_factor = 1.0f/weight_sum;
00762 average_point_eigen *= normalization_factor;
00763 average_point.range *= normalization_factor;
00764
00765 }
00766
00768 float
00769 RangeImage::getEuclideanDistanceSquared(int x1, int y1, int x2, int y2) const
00770 {
00771 if (!isObserved(x1,y1)||!isObserved(x2,y2))
00772 return -std::numeric_limits<float>::infinity ();
00773 const PointWithRange& point1 = getPoint(x1,y1),
00774 & point2 = getPoint(x2,y2);
00775 if (pcl_isinf(point1.range) && pcl_isinf(point2.range))
00776 return 0.0f;
00777 if (pcl_isinf(point1.range) || pcl_isinf(point2.range))
00778 return std::numeric_limits<float>::infinity ();
00779 return squaredEuclideanDistance(point1, point2);
00780 }
00781
00783 float
00784 RangeImage::getAverageEuclideanDistance(int x, int y, int offset_x, int offset_y, int max_steps) const
00785 {
00786 float average_pixel_distance = 0.0f;
00787 float weight=0.0f;
00788 for (int i=0; i<max_steps; ++i)
00789 {
00790 int x1=x+i*offset_x, y1=y+i*offset_y;
00791 int x2=x+(i+1)*offset_x, y2=y+(i+1)*offset_y;
00792 float pixel_distance = getEuclideanDistanceSquared(x1,y1,x2,y2);
00793 if (!pcl_isfinite(pixel_distance))
00794 {
00795
00796 if (i==0)
00797 return pixel_distance;
00798 else
00799 break;
00800 }
00801
00802 weight += 1.0f;
00803 average_pixel_distance += sqrtf(pixel_distance);
00804 }
00805 average_pixel_distance /= weight;
00806
00807 return average_pixel_distance;
00808 }
00809
00811 float
00812 RangeImage::getImpactAngleBasedOnLocalNormal(int x, int y, int radius) const
00813 {
00814 if (!isValid(x,y))
00815 return -std::numeric_limits<float>::infinity ();
00816 const PointWithRange& point = getPoint(x, y);
00817 int no_of_nearest_neighbors = pow((double)(radius+1), 2.0);
00818 Eigen::Vector3f normal;
00819 if (!getNormalForClosestNeighbors(x, y, radius, point, no_of_nearest_neighbors, normal, 1))
00820 return -std::numeric_limits<float>::infinity ();
00821 return deg2rad(90.0f) - acosf(normal.dot((getSensorPos()-getEigenVector3f(point)).normalized()));
00822 }
00823
00824
00826 bool
00827 RangeImage::getNormal(int x, int y, int radius, Eigen::Vector3f& normal, int step_size) const
00828 {
00829 VectorAverage3f vector_average;
00830 for (int y2=y-radius; y2<=y+radius; y2+=step_size)
00831 {
00832 for (int x2=x-radius; x2<=x+radius; x2+=step_size)
00833 {
00834 if (!isInImage(x2, y2))
00835 continue;
00836 const PointWithRange& point = getPoint(x2, y2);
00837 if (!pcl_isfinite(point.range))
00838 continue;
00839 vector_average.add(Eigen::Vector3f(point.x, point.y, point.z));
00840 }
00841 }
00842 if (vector_average.getNoOfSamples() < 3)
00843 return false;
00844 Eigen::Vector3f eigen_values, eigen_vector2, eigen_vector3;
00845 vector_average.doPCA(eigen_values, normal, eigen_vector2, eigen_vector3);
00846 if (normal.dot((getSensorPos()-vector_average.getMean()).normalized()) < 0.0f)
00847 normal *= -1.0f;
00848 return true;
00849 }
00850
00852 float
00853 RangeImage::getNormalBasedAcutenessValue(int x, int y, int radius) const
00854 {
00855 float impact_angle = getImpactAngleBasedOnLocalNormal(x, y, radius);
00856 if (pcl_isinf(impact_angle))
00857 return -std::numeric_limits<float>::infinity ();
00858 float ret = 1.0f - impact_angle/(0.5f*M_PI);
00859
00860 return ret;
00861 }
00862
00864 bool
00865 RangeImage::getNormalForClosestNeighbors(int x, int y, int radius, const PointWithRange& point,
00866 int no_of_nearest_neighbors, Eigen::Vector3f& normal, int step_size) const
00867 {
00868 return getNormalForClosestNeighbors(x, y, radius, Eigen::Vector3f(point.x, point.y, point.z), no_of_nearest_neighbors, normal, NULL, step_size);
00869 }
00870
00872 bool
00873 RangeImage::getNormalForClosestNeighbors(int x, int y, Eigen::Vector3f& normal, int radius) const
00874 {
00875 if (!isValid(x,y))
00876 return false;
00877 int no_of_nearest_neighbors = pow ((double)(radius+1), 2.0);
00878 return getNormalForClosestNeighbors(x, y, radius, getPoint(x,y).getVector3fMap(), no_of_nearest_neighbors, normal);
00879 }
00880
00881 namespace
00882 {
00883 struct NeighborWithDistance
00884 {
00885 float distance;
00886 const PointWithRange* neighbor;
00887 bool operator <(const NeighborWithDistance& other) const { return distance<other.distance;}
00888 };
00889 }
00890
00892 bool
00893 RangeImage::getSurfaceInformation (int x, int y, int radius, const Eigen::Vector3f& point, int no_of_closest_neighbors, int step_size,
00894 float& max_closest_neighbor_distance_squared,
00895 Eigen::Vector3f& normal, Eigen::Vector3f& mean, Eigen::Vector3f& eigen_values,
00896 Eigen::Vector3f* normal_all_neighbors, Eigen::Vector3f* mean_all_neighbors,
00897 Eigen::Vector3f* eigen_values_all_neighbors) const
00898 {
00899 max_closest_neighbor_distance_squared=0.0f;
00900 normal.setZero(); mean.setZero(); eigen_values.setZero();
00901 if (normal_all_neighbors!=NULL)
00902 normal_all_neighbors->setZero();
00903 if (mean_all_neighbors!=NULL)
00904 mean_all_neighbors->setZero();
00905 if (eigen_values_all_neighbors!=NULL)
00906 eigen_values_all_neighbors->setZero();
00907
00908 int blocksize = pow ((double)(2*radius+1), 2.0);
00909
00910 PointWithRange given_point;
00911 given_point.x=point[0]; given_point.y=point[1]; given_point.z=point[2];
00912
00913 std::vector<NeighborWithDistance> ordered_neighbors (blocksize);
00914 int neighbor_counter = 0;
00915 for (int y2=y-radius; y2<=y+radius; y2+=step_size)
00916 {
00917 for (int x2=x-radius; x2<=x+radius; x2+=step_size)
00918 {
00919 if (!isValid(x2, y2))
00920 continue;
00921 NeighborWithDistance& neighbor_with_distance = ordered_neighbors[neighbor_counter];
00922 neighbor_with_distance.neighbor = &getPoint(x2, y2);
00923 neighbor_with_distance.distance = squaredEuclideanDistance(given_point, *neighbor_with_distance.neighbor);
00924 ++neighbor_counter;
00925 }
00926 }
00927 no_of_closest_neighbors = (std::min)(neighbor_counter, no_of_closest_neighbors);
00928
00929 std::sort (ordered_neighbors.begin (), ordered_neighbors.begin () + neighbor_counter);
00930
00931
00932
00933 max_closest_neighbor_distance_squared = ordered_neighbors[no_of_closest_neighbors-1].distance;
00934
00935 float max_distance_squared = max_closest_neighbor_distance_squared*4.0f;
00936
00937
00938 VectorAverage3f vector_average;
00939
00940 int neighbor_idx;
00941 for (neighbor_idx=0; neighbor_idx<neighbor_counter; ++neighbor_idx)
00942 {
00943 if (ordered_neighbors[neighbor_idx].distance > max_distance_squared)
00944 break;
00945
00946 vector_average.add(ordered_neighbors[neighbor_idx].neighbor->getVector3fMap());
00947 }
00948
00949 if (vector_average.getNoOfSamples() < 3)
00950 return false;
00951
00952 Eigen::Vector3f eigen_vector2, eigen_vector3;
00953 vector_average.doPCA(eigen_values, normal, eigen_vector2, eigen_vector3);
00954 Eigen::Vector3f viewing_direction = (getSensorPos()-point).normalized();
00955 if (normal.dot(viewing_direction) < 0.0f)
00956 normal *= -1.0f;
00957 mean = vector_average.getMean();
00958
00959 if (normal_all_neighbors==NULL)
00960 return true;
00961
00962
00963 for (int neighbor_idx2=neighbor_idx; neighbor_idx2<neighbor_counter; ++neighbor_idx2)
00964 vector_average.add(ordered_neighbors[neighbor_idx2].neighbor->getVector3fMap());
00965
00966 vector_average.doPCA(*eigen_values_all_neighbors, *normal_all_neighbors, eigen_vector2, eigen_vector3);
00967
00968 if (normal_all_neighbors->dot(viewing_direction) < 0.0f)
00969 *normal_all_neighbors *= -1.0f;
00970 *mean_all_neighbors = vector_average.getMean();
00971
00972
00973
00974 return true;
00975 }
00976
00978 float
00979 RangeImage::getSquaredDistanceOfNthNeighbor(int x, int y, int radius, int n, int step_size) const
00980 {
00981 const PointWithRange& point = getPoint(x, y);
00982 if (!pcl_isfinite(point.range))
00983 return -std::numeric_limits<float>::infinity ();
00984
00985 int blocksize = pow ((double)(2*radius+1), 2.0);
00986 std::vector<float> neighbor_distances (blocksize);
00987 int neighbor_counter = 0;
00988 for (int y2=y-radius; y2<=y+radius; y2+=step_size)
00989 {
00990 for (int x2=x-radius; x2<=x+radius; x2+=step_size)
00991 {
00992 if (!isValid(x2, y2) || (x2==x&&y2==y))
00993 continue;
00994 const PointWithRange& neighbor = getPointNoCheck(x2,y2);
00995 float& neighbor_distance = neighbor_distances[neighbor_counter++];
00996 neighbor_distance = squaredEuclideanDistance(point, neighbor);
00997 }
00998 }
00999 std::sort (neighbor_distances.begin (), neighbor_distances.begin () + neighbor_counter);
01000
01001 n = (std::min)(neighbor_counter, n);
01002 return neighbor_distances[n-1];
01003 }
01004
01005
01007 bool
01008 RangeImage::getNormalForClosestNeighbors(int x, int y, int radius, const Eigen::Vector3f& point, int no_of_nearest_neighbors,
01009 Eigen::Vector3f& normal, Eigen::Vector3f* point_on_plane, int step_size) const
01010 {
01011 Eigen::Vector3f mean, eigen_values;
01012 float used_squared_max_distance;
01013 bool ret = getSurfaceInformation(x, y, radius, point, no_of_nearest_neighbors, step_size, used_squared_max_distance,
01014 normal, mean, eigen_values);
01015
01016 if (ret)
01017 {
01018 if (point_on_plane != NULL)
01019 *point_on_plane = (normal.dot(mean) - normal.dot(point))*normal + point;
01020 }
01021 return ret;
01022 }
01023
01024
01026 float
01027 RangeImage::getCurvature(int x, int y, int radius, int step_size) const
01028 {
01029 VectorAverage3f vector_average;
01030 for (int y2=y-radius; y2<=y+radius; y2+=step_size)
01031 {
01032 for (int x2=x-radius; x2<=x+radius; x2+=step_size)
01033 {
01034 if (!isInImage(x2, y2))
01035 continue;
01036 const PointWithRange& point = getPoint(x2, y2);
01037 if (!pcl_isfinite(point.range))
01038 continue;
01039 vector_average.add(Eigen::Vector3f(point.x, point.y, point.z));
01040 }
01041 }
01042 if (vector_average.getNoOfSamples() < 3)
01043 return false;
01044 Eigen::Vector3f eigen_values;
01045 vector_average.doPCA(eigen_values);
01046 return eigen_values[0]/eigen_values.sum();
01047 }
01048
01049
01051 template <typename PointCloudTypeWithViewpoints> Eigen::Vector3f
01052 RangeImage::getAverageViewPoint(const PointCloudTypeWithViewpoints& point_cloud)
01053 {
01054 Eigen::Vector3f average_viewpoint(0,0,0);
01055 int point_counter = 0;
01056 for (unsigned int point_idx=0; point_idx<point_cloud.points.size(); ++point_idx)
01057 {
01058 const typename PointCloudTypeWithViewpoints::PointType& point = point_cloud.points[point_idx];
01059 if (!pcl_isfinite(point.vp_x) || !pcl_isfinite(point.vp_y) || !pcl_isfinite(point.vp_z))
01060 continue;
01061 average_viewpoint[0] += point.vp_x;
01062 average_viewpoint[1] += point.vp_y;
01063 average_viewpoint[2] += point.vp_z;
01064 ++point_counter;
01065 }
01066 average_viewpoint /= point_counter;
01067
01068 return average_viewpoint;
01069 }
01070
01072 bool
01073 RangeImage::getViewingDirection(int x, int y, Eigen::Vector3f& viewing_direction) const
01074 {
01075 if (!isValid(x, y))
01076 return false;
01077 viewing_direction = (getPoint(x,y).getVector3fMap()-getSensorPos()).normalized();
01078 return true;
01079 }
01080
01082 void
01083 RangeImage::getViewingDirection(const Eigen::Vector3f& point, Eigen::Vector3f& viewing_direction) const
01084 {
01085 viewing_direction = (point-getSensorPos()).normalized();
01086 }
01087
01089 Eigen::Affine3f
01090 RangeImage::getTransformationToViewerCoordinateFrame(const Eigen::Vector3f& point) const
01091 {
01092 Eigen::Affine3f transformation;
01093 getTransformationToViewerCoordinateFrame(point, transformation);
01094 return transformation;
01095 }
01096
01098 void
01099 RangeImage::getTransformationToViewerCoordinateFrame(const Eigen::Vector3f& point, Eigen::Affine3f& transformation) const
01100 {
01101 Eigen::Vector3f viewing_direction = (point-getSensorPos()).normalized();
01102 getTransformationFromTwoUnitVectorsAndOrigin(Eigen::Vector3f(0.0f, -1.0f, 0.0f), viewing_direction, point, transformation);
01103 }
01104
01106 void
01107 RangeImage::getRotationToViewerCoordinateFrame(const Eigen::Vector3f& point, Eigen::Affine3f& transformation) const
01108 {
01109 Eigen::Vector3f viewing_direction = (point-getSensorPos()).normalized();
01110 getTransformationFromTwoUnitVectors(Eigen::Vector3f(0.0f, -1.0f, 0.0f), viewing_direction, transformation);
01111 }
01112
01114 inline void
01115 RangeImage::setAngularResolution (float angular_resolution)
01116 {
01117 angular_resolution_ = angular_resolution;
01118 angular_resolution_reciprocal_ = 1.0f / angular_resolution_;
01119 }
01120
01121 }