00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00036
00037 #include <laser_joint_processor/joint_image_interpolator.h>
00038
00039 using namespace laser_joint_processor;
00040 using namespace std;
00041
00042 bool JointImageInterpolator::interp(const std::vector <calibration_msgs::ImagePoint>& points,
00043 IplImage* image, std::vector<float>& positions, std::vector<float>& velocities)
00044 {
00045 const unsigned int N = points.size();
00046
00047
00048 if (image->depth != IPL_DEPTH_32F)
00049 {
00050 ROS_ERROR("Expecting input image to have depth of IPL_DEPTH_32F");
00051 return false;
00052 }
00053 if (image->nChannels != 2)
00054 {
00055 ROS_ERROR("Expecting input image to have 2 channels. Instead had %i channels", image->nChannels);
00056 return false;
00057 }
00058
00059
00060 vector<float> map_x_vec(N);
00061 vector<float> map_y_vec(N);
00062 CvMat map_x_mat = cvMat(N, 1, CV_32FC1, &map_x_vec[0]);
00063 CvMat map_y_mat = cvMat(N, 1, CV_32FC1, &map_y_vec[0]);
00064
00065
00066 for (unsigned int i=0; i<N; i++)
00067 {
00068 map_x_vec[i] = points[i].x;
00069 map_y_vec[i] = points[i].y;
00070 }
00071
00072
00073 vector<float> dest_vec(2*N);
00074 CvMat dest_mat = cvMat(N, 1, CV_32FC2, &dest_vec[0]);
00075
00076
00077 cvRemap(image, &dest_mat, &map_x_mat, &map_y_mat);
00078
00079
00080 positions.resize(N);
00081 velocities.resize(N);
00082 for (unsigned int i=0; i<N; i++)
00083 {
00084 positions[i] = dest_vec[2*i+0];
00085 velocities[i] = dest_vec[2*i+1];
00086 }
00087
00088 return true;
00089 }
00090
00091
00092 bool laser_joint_processor::interpSnapshot(const std::vector <calibration_msgs::ImagePoint>& points,
00093 const calibration_msgs::DenseLaserSnapshot& snapshot,
00094 std::vector<float>& angles,
00095 std::vector<float>& ranges)
00096 {
00097 const unsigned int N = points.size();
00098
00099
00100 for (unsigned int i=0; i<N; i++)
00101 {
00102 if (points[i].x < 0 ||
00103 points[i].x > snapshot.readings_per_scan-1 ||
00104 points[i].y < 0 ||
00105 points[i].y > snapshot.num_scans-1 )
00106 {
00107 return false;
00108 }
00109 }
00110
00111
00112 CvMat range_image = cvMat(snapshot.num_scans, snapshot.readings_per_scan, CV_32FC1, (void*) &snapshot.ranges[0]);
00113
00114
00115 vector<float> map_x_vec(N);
00116 vector<float> map_y_vec(N);
00117 CvMat map_x_mat = cvMat(N, 1, CV_32FC1, &map_x_vec[0]);
00118 CvMat map_y_mat = cvMat(N, 1, CV_32FC1, &map_y_vec[0]);
00119
00120
00121 for (unsigned int i=0; i<N; i++)
00122 {
00123 map_x_vec[i] = points[i].x;
00124 map_y_vec[i] = points[i].y;
00125 }
00126
00127
00128 ranges.resize(N);
00129 CvMat ranges_mat = cvMat(N, 1, CV_32FC1, &ranges[0]);
00130
00131
00132 cvRemap(&range_image, &ranges_mat, &map_x_mat, &map_y_mat);
00133
00134
00135 angles.resize(N);
00136 for (unsigned int i=0; i<N; i++)
00137 angles[i] = snapshot.angle_min + points[i].x*snapshot.angle_increment;
00138
00139 return true;
00140 }
00141
00142
00143
00144
00145