39 #include <opencv2/calib3d/calib3d.hpp>
40 #include <boost/thread.hpp>
62 std::vector<double>
D_;
63 boost::array<double, 9>
K_;
74 void depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
75 const sensor_msgs::CameraInfoConstPtr& info_msg);
79 void convert(
const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg);
82 cv::Mat
initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs,
int width,
int height,
bool radial)
85 int totalsize = width*height;
86 cv::Mat pixelVectors(1,totalsize,CV_32FC3);
87 cv::Mat dst(1,totalsize,CV_32FC3);
89 cv::Mat sensorPoints(cv::Size(height,width), CV_32FC2);
90 cv::Mat undistortedSensorPoints(1,totalsize, CV_32FC2);
92 std::vector<cv::Mat> ch;
93 for(j = 0; j < height; j++)
95 for(i = 0; i < width; i++)
97 cv::Vec2f &p = sensorPoints.at<cv::Vec2f>(i,j);
103 sensorPoints = sensorPoints.reshape(2,1);
105 cv::undistortPoints(sensorPoints, undistortedSensorPoints, cameraMatrix, distCoeffs);
107 ch.push_back(undistortedSensorPoints);
108 ch.push_back(cv::Mat::ones(1,totalsize,CV_32FC1));
109 cv::merge(ch,pixelVectors);
113 for(i = 0; i < totalsize; i++)
115 normalize(pixelVectors.at<cv::Vec3f>(i),
116 dst.at<cv::Vec3f>(i));
120 return pixelVectors.reshape(3,width);
160 const sensor_msgs::CameraInfoConstPtr& info_msg)
163 cloud_msg->header = depth_msg->header;
164 cloud_msg->height = depth_msg->height;
165 cloud_msg->width = depth_msg->width;
166 cloud_msg->is_dense =
false;
167 cloud_msg->is_bigendian =
false;
172 if(info_msg->D !=
D_ || info_msg->K !=
K_ ||
width_ != info_msg->width ||
182 if (depth_msg->encoding == enc::TYPE_16UC1)
184 convert<uint16_t>(depth_msg, cloud_msg);
186 else if (depth_msg->encoding == enc::TYPE_32FC1)
188 convert<float>(depth_msg, cloud_msg);
203 double unit_scaling = DepthTraits<T>::toMeters( T(1) );
204 float bad_point = std::numeric_limits<float>::quiet_NaN();
209 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
210 int row_step = depth_msg->step /
sizeof(T);
211 for (
int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
213 for (
int u = 0; u < (int)cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z)
215 T depth = depth_row[u];
218 if (!DepthTraits<T>::valid(depth))
220 *iter_x = *iter_y = *iter_z = bad_point;
223 const cv::Vec3f &cvPoint =
binned.at<cv::Vec3f>(u,v) * DepthTraits<T>::toMeters(depth);
225 *iter_x = cvPoint(0);
226 *iter_y = cvPoint(1);
227 *iter_z = cvPoint(2);