43 #include <boost/thread.hpp> 74 std::vector<double>
D_;
75 boost::array<double, 9>
K_;
82 virtual void onInit();
86 void imageCb(
const sensor_msgs::ImageConstPtr& depth_msg,
87 const sensor_msgs::ImageConstPtr& intensity_msg_in,
88 const sensor_msgs::CameraInfoConstPtr& info_msg);
92 void convert_depth(
const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg);
95 void convert_intensity(
const sensor_msgs::ImageConstPtr &inten_msg, PointCloud::Ptr& cloud_msg);
97 cv::Mat
initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs,
int width,
int height,
bool radial);
104 int totalsize = width*height;
105 cv::Mat pixelVectors(1,totalsize,CV_32FC3);
106 cv::Mat dst(1,totalsize,CV_32FC3);
108 cv::Mat sensorPoints(cv::Size(height,width), CV_32FC2);
109 cv::Mat undistortedSensorPoints(1,totalsize, CV_32FC2);
111 std::vector<cv::Mat> ch;
112 for(j = 0; j < height; j++)
114 for(i = 0; i < width; i++)
116 cv::Vec2f &p = sensorPoints.at<cv::Vec2f>(i,j);
122 sensorPoints = sensorPoints.reshape(2,1);
124 cv::undistortPoints(sensorPoints, undistortedSensorPoints, cameraMatrix, distCoeffs);
126 ch.push_back(undistortedSensorPoints);
127 ch.push_back(cv::Mat::ones(1,totalsize,CV_32FC1));
128 cv::merge(ch,pixelVectors);
132 for(i = 0; i < totalsize; i++)
134 normalize(pixelVectors.at<cv::Vec3f>(i),
135 dst.at<cv::Vec3f>(i));
139 return pixelVectors.reshape(3,width);
154 private_nh.
param(
"queue_size", queue_size_, 5);
164 boost::lock_guard<boost::mutex> lock(connect_mutex_);
171 boost::lock_guard<boost::mutex> lock(connect_mutex_);
173 if (pub_point_cloud_.getNumSubscribers() == 0)
175 sub_depth_.unsubscribe();
176 sub_intensity_.unsubscribe();
177 sub_info_.unsubscribe();
179 else if (!sub_depth_.getSubscriber())
183 std::string depth_image_transport_param =
"depth_image_transport";
187 sub_depth_.subscribe(*depth_it_,
"image_raw", 5, depth_hints);
191 sub_intensity_.subscribe(*intensity_it_,
"image_raw", 5, hints);
192 sub_info_.subscribe(*intensity_nh_,
"camera_info", 5);
197 const sensor_msgs::ImageConstPtr& intensity_msg,
198 const sensor_msgs::CameraInfoConstPtr& info_msg)
201 cloud_msg->header = depth_msg->header;
202 cloud_msg->height = depth_msg->height;
203 cloud_msg->width = depth_msg->width;
204 cloud_msg->is_dense =
false;
205 cloud_msg->is_bigendian =
false;
209 "x", 1, sensor_msgs::PointField::FLOAT32,
210 "y", 1, sensor_msgs::PointField::FLOAT32,
211 "z", 1, sensor_msgs::PointField::FLOAT32,
212 "intensity", 1, sensor_msgs::PointField::FLOAT32);
215 if(info_msg->D != D_ || info_msg->K != K_ || width_ != info_msg->width ||
216 height_ != info_msg->height)
220 width_ = info_msg->width;
221 height_ = info_msg->height;
222 transform_ =
initMatrix(cv::Mat_<double>(3, 3, &K_[0]),cv::Mat(D_),width_,height_,
true);
225 if (depth_msg->encoding == enc::TYPE_16UC1)
227 convert_depth<uint16_t>(depth_msg, cloud_msg);
229 else if (depth_msg->encoding == enc::TYPE_32FC1)
231 convert_depth<float>(depth_msg, cloud_msg);
239 if(intensity_msg->encoding == enc::TYPE_16UC1)
241 convert_intensity<uint16_t>(intensity_msg, cloud_msg);
244 else if(intensity_msg->encoding == enc::MONO8)
246 convert_intensity<uint8_t>(intensity_msg, cloud_msg);
250 NODELET_ERROR_THROTTLE(5,
"Intensity image has unsupported encoding [%s]", intensity_msg->encoding.c_str());
254 pub_point_cloud_.publish (cloud_msg);
259 PointCloud::Ptr& cloud_msg)
263 float bad_point = std::numeric_limits<float>::quiet_NaN();
268 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
270 int row_step = depth_msg->step /
sizeof(T);
271 for (
int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
273 for (
int u = 0; u < (int)cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z)
275 T depth = depth_row[u];
280 *iter_x = *iter_y = *iter_z = bad_point;
285 *iter_x = cvPoint(0);
286 *iter_y = cvPoint(1);
287 *iter_z = cvPoint(2);
294 PointCloud::Ptr& cloud_msg)
297 const T* inten_row =
reinterpret_cast<const T*
>(&intensity_msg->data[0]);
299 const int i_row_step = intensity_msg->step/
sizeof(T);
300 for (
int v = 0; v < (int)cloud_msg->height; ++v, inten_row += i_row_step)
302 for (
int u = 0; u < (int)cloud_msg->width; ++u, ++iter_i)
304 *iter_i = inten_row[u];
ros::Publisher pub_point_cloud_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
PLUGINLIB_EXPORT_CLASS(xiaoqiang_depth_image_proc::PointCloudXyziRadialNodelet, nodelet::Nodelet)
cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
boost::mutex connect_mutex_
#define NODELET_ERROR_THROTTLE(rate,...)
void convert_intensity(const sensor_msgs::ImageConstPtr &inten_msg, PointCloud::Ptr &cloud_msg)
void setPointCloud2Fields(int n_fields,...)
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
ros::NodeHandlePtr intensity_nh_
ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
boost::array< double, 9 > K_
sensor_msgs::PointCloud2 PointCloud
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
boost::shared_ptr< image_transport::ImageTransport > intensity_it_
cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
image_transport::SubscriberFilter sub_intensity_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void convert_depth(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg)
boost::shared_ptr< Synchronizer > sync_
message_filters::Synchronizer< SyncPolicy > Synchronizer
void imageCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &intensity_msg_in, const sensor_msgs::CameraInfoConstPtr &info_msg)