32 #include <sensor_msgs/PointCloud2.h> 33 #include <sensor_msgs/CameraInfo.h> 36 #include <opencv/cv.h> 37 #include <opencv/highgui.h> 57 : node_handle_(node_handle),
62 sub_pc2_.
subscribe(node_handle_,
"tof/point_cloud2", 1);
63 sub_camera_info_.
subscribe(node_handle_,
"tof/camera_info", 1);
64 pub_pc2_ = node_handle_.
advertise<sensor_msgs::PointCloud2>(
"point_cloud_undistorted", 1);
111 cv::Mat
D = cv::Mat(1,4,CV_64FC1);
112 D.at<
double>(0,0) = camera_info->D[0];
113 D.at<
double>(0,1) = camera_info->D[1];
114 D.at<
double>(0,2) = camera_info->D[2];
115 D.at<
double>(0,3) = camera_info->D[3];
116 cv::Mat cam_matrix = cv::Mat::zeros(3,3,CV_64FC1);
117 cam_matrix.at<
double>(0,0) = camera_info->K[0];
118 cam_matrix.at<
double>(0,2) = camera_info->K[2];
119 cam_matrix.at<
double>(1,1) = camera_info->K[4];
120 cam_matrix.at<
double>(1,2) = camera_info->K[5];
121 cam_matrix.at<
double>(2,2) = 1;
123 int z_offset = 0, i_offset = 0, c_offset = 0, x_offset = 0, y_offset = 0;;
124 for (
size_t d = 0;
d < tof_camera_data->fields.size(); ++
d)
126 if(tof_camera_data->fields[
d].name ==
"x")
127 x_offset = tof_camera_data->fields[
d].offset;
128 if(tof_camera_data->fields[
d].name ==
"y")
129 y_offset = tof_camera_data->fields[
d].offset;
130 if(tof_camera_data->fields[
d].name ==
"z")
131 z_offset = tof_camera_data->fields[
d].offset;
132 if(tof_camera_data->fields[
d].name ==
"intensity")
133 i_offset = tof_camera_data->fields[
d].offset;
134 if(tof_camera_data->fields[
d].name ==
"confidence")
135 c_offset = tof_camera_data->fields[
d].offset;
137 cv::Mat z_image = cv::Mat(tof_camera_data->height, tof_camera_data->width,CV_32FC1);
138 cv::Mat intensity_image = cv::Mat(tof_camera_data->height, tof_camera_data->width,CV_32FC1);
142 for (
int row = 0; row < z_image.rows; row++)
144 f_ptr = z_image.ptr<
float>(row);
145 i_ptr = intensity_image.ptr<
float>(row);
146 for (
int col = 0; col < z_image.cols; col++, pc_msg_idx++)
148 memcpy(&f_ptr[col], &tof_camera_data->data[pc_msg_idx * tof_camera_data->point_step + z_offset],
sizeof(
float));
149 memcpy(&i_ptr[col], &tof_camera_data->data[pc_msg_idx * tof_camera_data->point_step + i_offset],
sizeof(
float));
153 cv::imshow(
"distorted", z_image);
155 cv::Mat z_image_undistorted;
156 cv::undistort(z_image, z_image_undistorted, cam_matrix, D);
157 cv::Mat intensity_image_undistorted;
158 cv::undistort(intensity_image, intensity_image_undistorted, cam_matrix, D);
160 cv::imshow(
"undistorted", z_image_undistorted);
163 sensor_msgs::PointCloud2 pc_pub = *(tof_camera_data.get());
165 double fx, fy, cx, cy;
167 fx = cam_matrix.at<
double>(0,0);
168 fy = cam_matrix.at<
double>(1, 1);
170 cx = cam_matrix.at<
double>(0, 2);
171 cy = cam_matrix.at<
double>(1, 2);
174 for (
size_t d = 0;
d < pc_pub.fields.size(); ++
d)
177 for(
unsigned int row=0; row<pc_pub.height; row++)
179 float* z = z_image_undistorted.ptr<
float>(row);
182 for (
unsigned int col=0; col<pc_pub.width; col++)
184 memcpy(&pc_pub.data[row * col * pc_pub.point_step + z_offset], &z[col],
sizeof(
float));
185 float x = (float) (z[col]*(col-cx)/fx);
186 float y = (float) (z[col]*(row-cy)/fy);
187 memcpy(&pc_pub.data[row * col * pc_pub.point_step + x_offset], &x,
sizeof(
float));
188 memcpy(&pc_pub.data[row * col * pc_pub.point_step + y_offset], &y,
sizeof(
float));
199 int main(
int argc,
char** argv)
void Undistort(const boost::shared_ptr< sensor_msgs::PointCloud2 const > &tof_camera_data, const sensor_msgs::CameraInfoConstPtr &camera_info)
int main(int argc, char **argv)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_pc2_
void publish(const boost::shared_ptr< M > &message) const
sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > SyncPolicy
UndistortTOF(const ros::NodeHandle &node_handle)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
Connection registerCallback(C &callback)
ros::NodeHandle node_handle_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void connectInput(F0 &f0, F1 &f1)
unsigned long GetCalibratedXYMatlab(int u, int v, float z, float &x, float &y)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
sensor_msgs::PointCloud2 pc2_msg_
unsigned long GetCalibratedZSwissranger(int u, int v, int width, float &zCalibrated)
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
message_filters::Synchronizer< SyncPolicy > sub_sync_