undistort_tof.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 //##################
00019 //#### includes ####
00020 
00021 // standard includes
00022 //--
00023 
00024 // ROS includes
00025 #include <ros/ros.h>
00026 
00027 #include <message_filters/subscriber.h>
00028 #include <message_filters/sync_policies/approximate_time.h>
00029 #include <message_filters/synchronizer.h>
00030 
00031 // ROS message includes
00032 #include <sensor_msgs/PointCloud2.h>
00033 #include <sensor_msgs/CameraInfo.h>
00034 
00035 // external includes
00036 #include <opencv/cv.h>
00037 #include <opencv/highgui.h>
00038 
00039 using namespace message_filters;
00040 
00041 typedef sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::CameraInfo> SyncPolicy;
00042 
00043 
00044 class UndistortTOF
00045 {
00046 private:
00047         ros::NodeHandle node_handle_;
00048         sensor_msgs::PointCloud2 pc2_msg_;
00049 
00050         message_filters::Subscriber<sensor_msgs::PointCloud2> sub_pc2_;
00051         message_filters::Subscriber<sensor_msgs::CameraInfo> sub_camera_info_;
00052         message_filters::Synchronizer<SyncPolicy> sub_sync_;
00053         ros::Publisher pub_pc2_;
00054 
00055 public:
00056         UndistortTOF(const ros::NodeHandle& node_handle)
00057         : node_handle_(node_handle),
00058           sub_sync_(SyncPolicy(3))
00059           {
00060                 sub_sync_.connectInput(sub_pc2_, sub_camera_info_);
00061                 sub_sync_.registerCallback(boost::bind(&UndistortTOF::Undistort, this, _1, _2));
00062                 sub_pc2_.subscribe(node_handle_, "tof/point_cloud2", 1);
00063                 sub_camera_info_.subscribe(node_handle_, "tof/camera_info", 1);
00064                 pub_pc2_ = node_handle_.advertise<sensor_msgs::PointCloud2>("point_cloud_undistorted", 1);
00065           }
00066 
00067         // Return value is in m
00068         unsigned long GetCalibratedZSwissranger(int u, int v, int width, float& zCalibrated)
00069         {
00070                 //zCalibrated = (float) m_Z[v*width + u];
00071 
00072                 //return RET_OK;
00073         }
00074 
00075         // u and v are assumed to be distorted coordinates
00076         unsigned long GetCalibratedXYMatlab(int u, int v, float z, float& x, float& y)
00077         {
00078                 // Use intrinsic camera parameters
00079                 /*double fx, fy, cx, cy;
00080 
00081                 fx = m_intrinsicMatrix.at<double>(0, 0);
00082                 fy = m_intrinsicMatrix.at<double>(1, 1);
00083 
00084                 cx = m_intrinsicMatrix.at<double>(0, 2);
00085                 cy = m_intrinsicMatrix.at<double>(1, 2);
00086 
00087                 // Fundamental equation: u = (fx*x)/z + cx
00088                 if (fx == 0)
00089                 {
00090                         std::cerr << "ERROR - Swissranger::GetCalibratedXYZ:" << std::endl;
00091                         std::cerr << "\t ... fx is 0.\n";
00092                         return RET_FAILED;
00093                 }
00094                 x = (float) (z*(u-cx)/fx) ;
00095 
00096                 // Fundamental equation: v = (fy*y)/z + cy
00097                 if (fy == 0)
00098                 {
00099                         std::cerr << "ERROR - Swissranger::GetCalibratedXYZ:" << std::endl;
00100                         std::cerr << "\t ... fy is 0.\n";
00101                         return RET_FAILED;
00102                 }
00103                 y = (float) (z*(v-cy)/fy);
00104 
00105                 return RET_OK;*/
00106         }
00107 
00108         //void Undistort(const sensor_msgs::PointCloud2ConstPtr& tof_camera_data, const sensor_msgs::CameraInfoConstPtr& camera_info)
00109         void Undistort(const boost::shared_ptr<sensor_msgs::PointCloud2 const>& tof_camera_data, const sensor_msgs::CameraInfoConstPtr& camera_info)
00110         {
00111                 cv::Mat D = cv::Mat(1,4,CV_64FC1);
00112                 D.at<double>(0,0) = camera_info->D[0];
00113                 D.at<double>(0,1) = camera_info->D[1];
00114                 D.at<double>(0,2) = camera_info->D[2];
00115                 D.at<double>(0,3) = camera_info->D[3];
00116                 cv::Mat cam_matrix = cv::Mat::zeros(3,3,CV_64FC1);
00117                 cam_matrix.at<double>(0,0) = camera_info->K[0];
00118                 cam_matrix.at<double>(0,2) = camera_info->K[2];
00119                 cam_matrix.at<double>(1,1) = camera_info->K[4];
00120                 cam_matrix.at<double>(1,2) = camera_info->K[5];
00121                 cam_matrix.at<double>(2,2) = 1;
00122 
00123                 int z_offset = 0, i_offset = 0, c_offset = 0, x_offset = 0, y_offset = 0;;
00124                 for (size_t d = 0; d < tof_camera_data->fields.size(); ++d)
00125                 {
00126                         if(tof_camera_data->fields[d].name == "x")
00127                                 x_offset = tof_camera_data->fields[d].offset;
00128                         if(tof_camera_data->fields[d].name == "y")
00129                                 y_offset = tof_camera_data->fields[d].offset;
00130                         if(tof_camera_data->fields[d].name == "z")
00131                                 z_offset = tof_camera_data->fields[d].offset;
00132                         if(tof_camera_data->fields[d].name == "intensity")
00133                                 i_offset = tof_camera_data->fields[d].offset;
00134                         if(tof_camera_data->fields[d].name == "confidence")
00135                                 c_offset = tof_camera_data->fields[d].offset;
00136                 }
00137                 cv::Mat z_image = cv::Mat(tof_camera_data->height, tof_camera_data->width,CV_32FC1);
00138                 cv::Mat intensity_image = cv::Mat(tof_camera_data->height, tof_camera_data->width,CV_32FC1);
00139                 float* f_ptr = 0;
00140                 float* i_ptr = 0;
00141                 int pc_msg_idx=0;
00142                 for (int row = 0; row < z_image.rows; row++)
00143                 {
00144                         f_ptr = z_image.ptr<float>(row);
00145                         i_ptr = intensity_image.ptr<float>(row);
00146                         for (int col = 0; col < z_image.cols; col++, pc_msg_idx++)
00147                         {
00148                                 memcpy(&f_ptr[col], &tof_camera_data->data[pc_msg_idx * tof_camera_data->point_step + z_offset], sizeof(float));
00149                                 memcpy(&i_ptr[col], &tof_camera_data->data[pc_msg_idx * tof_camera_data->point_step + i_offset], sizeof(float));
00150                         }
00151                 }
00152 
00153                 cv::imshow("distorted", z_image);
00154                 // Undistort
00155                 cv::Mat z_image_undistorted;
00156                 cv::undistort(z_image, z_image_undistorted, cam_matrix, D);
00157                 cv::Mat intensity_image_undistorted;
00158                 cv::undistort(intensity_image, intensity_image_undistorted, cam_matrix, D);
00159 
00160                 cv::imshow("undistorted", z_image_undistorted);
00161                 cv::waitKey(20);
00162 
00163                 sensor_msgs::PointCloud2 pc_pub = *(tof_camera_data.get());
00164                 // Calculate X and Y based on instrinsic rotation and translation
00165                 double fx, fy, cx, cy;
00166 
00167                 fx = cam_matrix.at<double>(0,0);
00168                 fy = cam_matrix.at<double>(1, 1);
00169 
00170                 cx = cam_matrix.at<double>(0, 2);
00171                 cy = cam_matrix.at<double>(1, 2);
00172 
00173 
00174                 for (size_t d = 0; d < pc_pub.fields.size(); ++d)
00175                 {
00176                 }
00177                 for(unsigned int row=0; row<pc_pub.height; row++)
00178                 {
00179                         float* z =  z_image_undistorted.ptr<float>(row);
00180                         //f_ptr = (float*)(cartesianImageData + row*widthStepCartesianImage);
00181 
00182                         for (unsigned int col=0; col<pc_pub.width; col++)
00183                         {
00184                                 memcpy(&pc_pub.data[row * col * pc_pub.point_step + z_offset], &z[col], sizeof(float));
00185                                 float x = (float) (z[col]*(col-cx)/fx);
00186                                 float y =  (float) (z[col]*(row-cy)/fy);
00187                                 memcpy(&pc_pub.data[row * col * pc_pub.point_step + x_offset], &x, sizeof(float));
00188                                 memcpy(&pc_pub.data[row * col * pc_pub.point_step + y_offset], &y, sizeof(float));
00189                         }
00190                 }
00191                 pub_pc2_.publish(pc_pub);
00192         }
00193 
00194 };
00195 
00196 
00197 //#######################
00198 //#### main programm ####
00199 int main(int argc, char** argv)
00200 {
00202         ros::init(argc, argv, "undistort_tof");
00203 
00205         ros::NodeHandle nh;
00206 
00208         UndistortTOF undistort_tof(nh);
00209 
00211         //if (!camera_node.init()) return 0;
00212 
00213         ros::spin();
00214 
00215         return 0;
00216 }


cob_camera_sensors
Author(s): Jan Fischer , Richard Bormann
autogenerated on Sat Jun 8 2019 21:02:02