joint_image_interpolator.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
36 
37 #include <opencv2/imgproc/imgproc.hpp>
38 
40 #include <ros/console.h>
41 
42 using namespace laser_joint_processor;
43 using namespace std;
44 
45 bool JointImageInterpolator::interp(const std::vector <geometry_msgs::Point>& points,
46  cv::Mat_<cv::Vec2f> image, std::vector<float>& positions, std::vector<float>& velocities)
47 {
48  const unsigned int N = points.size();
49 
50  // Allocate Maps
51  cv::Mat_<float> map_x_mat(N, 1);
52  cv::Mat_<float> map_y_mat(N, 1);
53 
54  // Set up maps
55  for (unsigned int i=0; i<N; i++)
56  {
57  map_x_mat(i) = points[i].x;
58  map_y_mat(i) = points[i].y;
59  }
60 
61  // Allocate Destination Image
62  cv::Mat_<cv::Vec2f> dest_mat(N, 1);
63 
64  // Perform the OpenCV interpolation
65  cv::remap(image, dest_mat, map_x_mat, map_y_mat, cv::INTER_LINEAR, cv::BORDER_WRAP);
66 
67  // Copy results into output vectors
68  positions.resize(N);
69  velocities.resize(N);
70  for (unsigned int i=0; i<N; i++)
71  {
72  positions[i] = dest_mat(i)[0];
73  velocities[i] = dest_mat(i)[1];
74  }
75 
76  return true;
77 }
78 
79 
80 bool laser_joint_processor::interpSnapshot(const std::vector <geometry_msgs::Point>& points,
81  const calibration_msgs::DenseLaserSnapshot& snapshot,
82  std::vector<float>& angles,
83  std::vector<float>& ranges)
84 {
85  const unsigned int N = points.size();
86 
87  // Check to make sure points are in range
88  for (unsigned int i=0; i<N; i++)
89  {
90  if (points[i].x < 0 ||
91  points[i].x > snapshot.readings_per_scan-1 ||
92  points[i].y < 0 ||
93  points[i].y > snapshot.num_scans-1 )
94  {
95  return false;
96  }
97  }
98 
99  // Set up input image
100  cv::Mat_<float> range_image(snapshot.num_scans, snapshot.readings_per_scan, const_cast<float*>(&snapshot.ranges[0]));
101 
102  // Allocate Maps
103  cv::Mat_<float> map_x_mat(N, 1);
104  cv::Mat_<float> map_y_mat(N, 1);
105 
106  // Set up maps
107  for (unsigned int i=0; i<N; i++)
108  {
109  map_x_mat(i) = points[i].x;
110  map_y_mat(i) = points[i].y;
111  }
112 
113  // Allocate Destination Image
114  ranges.resize(N);
115  cv::Mat_<float> ranges_mat(N, 1, &ranges[0]);
116 
117  // Perform the OpenCV interpolation
118  cv::remap(range_image, ranges_mat, map_x_mat, map_y_mat, cv::INTER_LINEAR, cv::BORDER_WRAP);
119 
120  // Do angle interp manually
121  angles.resize(N);
122  for (unsigned int i=0; i<N; i++)
123  angles[i] = snapshot.angle_min + points[i].x*snapshot.angle_increment;
124 
125  return true;
126 }
127 
128 
129 
130 
131 
bool interpSnapshot(const std::vector< geometry_msgs::Point > &points, const calibration_msgs::DenseLaserSnapshot &snapshot, std::vector< float > &pointing_angles, std::vector< float > &ranges)
bool interp(const std::vector< geometry_msgs::Point > &points, cv::Mat_< cv::Vec2f > image, std::vector< float > &positions, std::vector< float > &velocities)


laser_joint_processor
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:55