39 #include <boost/thread.hpp> 61 std::vector<double>
D_;
62 boost::array<double, 9>
K_;
73 void depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
74 const sensor_msgs::CameraInfoConstPtr& info_msg);
78 void convert(
const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg);
81 cv::Mat
initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs,
int width,
int height,
bool radial)
84 int totalsize = width*height;
85 cv::Mat pixelVectors(1,totalsize,CV_32FC3);
86 cv::Mat dst(1,totalsize,CV_32FC3);
88 cv::Mat sensorPoints(cv::Size(height,width), CV_32FC2);
89 cv::Mat undistortedSensorPoints(1,totalsize, CV_32FC2);
91 std::vector<cv::Mat> ch;
92 for(j = 0; j < height; j++)
94 for(i = 0; i < width; i++)
96 cv::Vec2f &p = sensorPoints.at<cv::Vec2f>(i,j);
102 sensorPoints = sensorPoints.reshape(2,1);
104 cv::undistortPoints(sensorPoints, undistortedSensorPoints, cameraMatrix, distCoeffs);
106 ch.push_back(undistortedSensorPoints);
107 ch.push_back(cv::Mat::ones(1,totalsize,CV_32FC1));
108 cv::merge(ch,pixelVectors);
112 for(i = 0; i < totalsize; i++)
114 normalize(pixelVectors.at<cv::Vec3f>(i),
115 dst.at<cv::Vec3f>(i));
119 return pixelVectors.reshape(3,width);
159 const sensor_msgs::CameraInfoConstPtr& info_msg)
162 cloud_msg->header = depth_msg->header;
163 cloud_msg->height = depth_msg->height;
164 cloud_msg->width = depth_msg->width;
165 cloud_msg->is_dense =
false;
166 cloud_msg->is_bigendian =
false;
171 if(info_msg->D !=
D_ || info_msg->K !=
K_ ||
width_ != info_msg->width ||
181 if (depth_msg->encoding == enc::TYPE_16UC1)
183 convert<uint16_t>(depth_msg, cloud_msg);
185 else if (depth_msg->encoding == enc::TYPE_32FC1)
187 convert<float>(depth_msg, cloud_msg);
203 float bad_point = std::numeric_limits<float>::quiet_NaN();
208 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
209 int row_step = depth_msg->step /
sizeof(T);
210 for (
int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
212 for (
int u = 0; u < (int)cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z)
214 T depth = depth_row[u];
219 *iter_x = *iter_y = *iter_z = bad_point;
224 *iter_x = cvPoint(0);
225 *iter_y = cvPoint(1);
226 *iter_z = cvPoint(2);
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::Publisher pub_point_cloud_
ros::NodeHandle & getNodeHandle() const
#define NODELET_ERROR_THROTTLE(rate,...)
ros::NodeHandle & getPrivateNodeHandle() const
image_transport::CameraSubscriber sub_depth_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyzRadialNodelet, nodelet::Nodelet)
void convert(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg)
sensor_msgs::PointCloud2 PointCloud
cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
boost::array< double, 9 > K_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::mutex connect_mutex_
uint32_t getNumSubscribers() const
void setPointCloud2FieldsByString(int n_fields,...)
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
boost::shared_ptr< image_transport::ImageTransport > it_