undistort_tof.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 //##################
19 //#### includes ####
20 
21 // standard includes
22 //--
23 
24 // ROS includes
25 #include <ros/ros.h>
26 
30 
31 // ROS message includes
32 #include <sensor_msgs/PointCloud2.h>
33 #include <sensor_msgs/CameraInfo.h>
34 
35 // external includes
36 #include <opencv/cv.h>
37 #include <opencv/highgui.h>
38 
39 using namespace message_filters;
40 
42 
43 
45 {
46 private:
48  sensor_msgs::PointCloud2 pc2_msg_;
49 
54 
55 public:
56  UndistortTOF(const ros::NodeHandle& node_handle)
57  : node_handle_(node_handle),
58  sub_sync_(SyncPolicy(3))
59  {
60  sub_sync_.connectInput(sub_pc2_, sub_camera_info_);
61  sub_sync_.registerCallback(boost::bind(&UndistortTOF::Undistort, this, _1, _2));
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);
65  }
66 
67  // Return value is in m
68  unsigned long GetCalibratedZSwissranger(int u, int v, int width, float& zCalibrated)
69  {
70  //zCalibrated = (float) m_Z[v*width + u];
71 
72  //return RET_OK;
73  }
74 
75  // u and v are assumed to be distorted coordinates
76  unsigned long GetCalibratedXYMatlab(int u, int v, float z, float& x, float& y)
77  {
78  // Use intrinsic camera parameters
79  /*double fx, fy, cx, cy;
80 
81  fx = m_intrinsicMatrix.at<double>(0, 0);
82  fy = m_intrinsicMatrix.at<double>(1, 1);
83 
84  cx = m_intrinsicMatrix.at<double>(0, 2);
85  cy = m_intrinsicMatrix.at<double>(1, 2);
86 
87  // Fundamental equation: u = (fx*x)/z + cx
88  if (fx == 0)
89  {
90  std::cerr << "ERROR - Swissranger::GetCalibratedXYZ:" << std::endl;
91  std::cerr << "\t ... fx is 0.\n";
92  return RET_FAILED;
93  }
94  x = (float) (z*(u-cx)/fx) ;
95 
96  // Fundamental equation: v = (fy*y)/z + cy
97  if (fy == 0)
98  {
99  std::cerr << "ERROR - Swissranger::GetCalibratedXYZ:" << std::endl;
100  std::cerr << "\t ... fy is 0.\n";
101  return RET_FAILED;
102  }
103  y = (float) (z*(v-cy)/fy);
104 
105  return RET_OK;*/
106  }
107 
108  //void Undistort(const sensor_msgs::PointCloud2ConstPtr& tof_camera_data, const sensor_msgs::CameraInfoConstPtr& camera_info)
109  void Undistort(const boost::shared_ptr<sensor_msgs::PointCloud2 const>& tof_camera_data, const sensor_msgs::CameraInfoConstPtr& camera_info)
110  {
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;
122 
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)
125  {
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;
136  }
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);
139  float* f_ptr = 0;
140  float* i_ptr = 0;
141  int pc_msg_idx=0;
142  for (int row = 0; row < z_image.rows; row++)
143  {
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++)
147  {
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));
150  }
151  }
152 
153  cv::imshow("distorted", z_image);
154  // Undistort
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);
159 
160  cv::imshow("undistorted", z_image_undistorted);
161  cv::waitKey(20);
162 
163  sensor_msgs::PointCloud2 pc_pub = *(tof_camera_data.get());
164  // Calculate X and Y based on instrinsic rotation and translation
165  double fx, fy, cx, cy;
166 
167  fx = cam_matrix.at<double>(0,0);
168  fy = cam_matrix.at<double>(1, 1);
169 
170  cx = cam_matrix.at<double>(0, 2);
171  cy = cam_matrix.at<double>(1, 2);
172 
173 
174  for (size_t d = 0; d < pc_pub.fields.size(); ++d)
175  {
176  }
177  for(unsigned int row=0; row<pc_pub.height; row++)
178  {
179  float* z = z_image_undistorted.ptr<float>(row);
180  //f_ptr = (float*)(cartesianImageData + row*widthStepCartesianImage);
181 
182  for (unsigned int col=0; col<pc_pub.width; col++)
183  {
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));
189  }
190  }
191  pub_pc2_.publish(pc_pub);
192  }
193 
194 };
195 
196 
197 //#######################
198 //#### main programm ####
199 int main(int argc, char** argv)
200 {
202  ros::init(argc, argv, "undistort_tof");
203 
205  ros::NodeHandle nh;
206 
208  UndistortTOF undistort_tof(nh);
209 
211  //if (!camera_node.init()) return 0;
212 
213  ros::spin();
214 
215  return 0;
216 }
void Undistort(const boost::shared_ptr< sensor_msgs::PointCloud2 const > &tof_camera_data, const sensor_msgs::CameraInfoConstPtr &camera_info)
d
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)
ros::Publisher pub_pc2_
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_


cob_camera_sensors
Author(s): Jan Fischer , Richard Bormann
autogenerated on Thu Mar 19 2020 03:23:05