43 #include <opencv2/calib3d/calib3d.hpp>
44 #include <boost/thread.hpp>
67 boost::mutex connect_mutex_;
75 std::vector<double> D_;
76 boost::array<double, 9> K_;
83 virtual void onInit();
87 void imageCb(
const sensor_msgs::ImageConstPtr& depth_msg,
88 const sensor_msgs::ImageConstPtr& intensity_msg_in,
89 const sensor_msgs::CameraInfoConstPtr& info_msg);
93 void convert_depth(
const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg);
96 void convert_intensity(
const sensor_msgs::ImageConstPtr &inten_msg, PointCloud::Ptr& cloud_msg);
98 cv::Mat
initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs,
int width,
int height,
bool radial);
105 int totalsize = width*height;
106 cv::Mat pixelVectors(1,totalsize,CV_32FC3);
107 cv::Mat dst(1,totalsize,CV_32FC3);
109 cv::Mat sensorPoints(cv::Size(height,width), CV_32FC2);
110 cv::Mat undistortedSensorPoints(1,totalsize, CV_32FC2);
112 std::vector<cv::Mat> ch;
113 for(j = 0; j < height; j++)
115 for(i = 0; i < width; i++)
117 cv::Vec2f &p = sensorPoints.at<cv::Vec2f>(i,j);
123 sensorPoints = sensorPoints.reshape(2,1);
125 cv::undistortPoints(sensorPoints, undistortedSensorPoints, cameraMatrix, distCoeffs);
127 ch.push_back(undistortedSensorPoints);
128 ch.push_back(cv::Mat::ones(1,totalsize,CV_32FC1));
129 cv::merge(ch,pixelVectors);
133 for(i = 0; i < totalsize; i++)
135 normalize(pixelVectors.at<cv::Vec3f>(i),
136 dst.at<cv::Vec3f>(i));
140 return pixelVectors.reshape(3,width);
155 private_nh.
param(
"queue_size", queue_size_, 5);
158 sync_.reset(
new Synchronizer(
SyncPolicy(queue_size_), sub_depth_, sub_intensity_, sub_info_) );
165 boost::lock_guard<boost::mutex> lock(connect_mutex_);
172 boost::lock_guard<boost::mutex> lock(connect_mutex_);
174 if (pub_point_cloud_.getNumSubscribers() == 0)
176 sub_depth_.unsubscribe();
177 sub_intensity_.unsubscribe();
178 sub_info_.unsubscribe();
180 else if (!sub_depth_.getSubscriber())
184 std::string depth_image_transport_param =
"depth_image_transport";
188 sub_depth_.subscribe(*depth_it_,
"image_raw", 5, depth_hints);
192 sub_intensity_.subscribe(*intensity_it_,
"image_raw", 5, hints);
193 sub_info_.subscribe(*intensity_nh_,
"camera_info", 5);
198 const sensor_msgs::ImageConstPtr& intensity_msg,
199 const sensor_msgs::CameraInfoConstPtr& info_msg)
202 cloud_msg->header = depth_msg->header;
203 cloud_msg->height = depth_msg->height;
204 cloud_msg->width = depth_msg->width;
205 cloud_msg->is_dense =
false;
206 cloud_msg->is_bigendian =
false;
209 pcd_modifier.setPointCloud2Fields(4,
210 "x", 1, sensor_msgs::PointField::FLOAT32,
211 "y", 1, sensor_msgs::PointField::FLOAT32,
212 "z", 1, sensor_msgs::PointField::FLOAT32,
213 "intensity", 1, sensor_msgs::PointField::FLOAT32);
216 if(info_msg->D != D_ || info_msg->K != K_ || width_ != info_msg->width ||
217 height_ != info_msg->height)
221 width_ = info_msg->width;
222 height_ = info_msg->height;
223 transform_ =
initMatrix(cv::Mat_<double>(3, 3, &K_[0]),cv::Mat(D_),width_,height_,
true);
226 if (depth_msg->encoding == enc::TYPE_16UC1)
228 convert_depth<uint16_t>(depth_msg, cloud_msg);
230 else if (depth_msg->encoding == enc::TYPE_32FC1)
232 convert_depth<float>(depth_msg, cloud_msg);
240 if(intensity_msg->encoding == enc::TYPE_16UC1)
242 convert_intensity<uint16_t>(intensity_msg, cloud_msg);
245 else if(intensity_msg->encoding == enc::MONO8)
247 convert_intensity<uint8_t>(intensity_msg, cloud_msg);
249 else if(intensity_msg->encoding == enc::TYPE_32FC1)
251 convert_intensity<float>(intensity_msg, cloud_msg);
255 NODELET_ERROR_THROTTLE(5,
"Intensity image has unsupported encoding [%s]", intensity_msg->encoding.c_str());
259 pub_point_cloud_.publish (cloud_msg);
264 PointCloud::Ptr& cloud_msg)
267 double unit_scaling = DepthTraits<T>::toMeters( T(1) );
268 float bad_point = std::numeric_limits<float>::quiet_NaN();
273 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
275 int row_step = depth_msg->step /
sizeof(T);
276 for (
int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
278 for (
int u = 0; u < (int)cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z)
280 T depth = depth_row[u];
283 if (!DepthTraits<T>::valid(depth))
285 *iter_x = *iter_y = *iter_z = bad_point;
288 const cv::Vec3f &cvPoint = transform_.at<cv::Vec3f>(u,v) * DepthTraits<T>::toMeters(depth);
290 *iter_x = cvPoint(0);
291 *iter_y = cvPoint(1);
292 *iter_z = cvPoint(2);
299 PointCloud::Ptr& cloud_msg)
302 const T* inten_row =
reinterpret_cast<const T*
>(&intensity_msg->data[0]);
304 const int i_row_step = intensity_msg->step/
sizeof(T);
305 for (
int v = 0; v < (int)cloud_msg->height; ++v, inten_row += i_row_step)
307 for (
int u = 0; u < (int)cloud_msg->width; ++u, ++iter_i)
309 *iter_i = inten_row[u];