test_grid_metric_converter.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <costmap_cspace_msgs/MapMetaData3D.h>
32 #include <tf2/utils.h>
33 
34 #include <gtest/gtest.h>
35 
36 #define _USE_MATH_DEFINES
37 #include <cmath>
38 #include <vector>
39 
40 TEST(GridMetricConverter, SinglePose)
41 {
42  costmap_cspace_msgs::MapMetaData3D map_info;
43  map_info.linear_resolution = 0.1;
44  map_info.angular_resolution = M_PI / 8;
45  map_info.origin.position.x = 100.0;
46  map_info.origin.position.y = 100.0;
47 
48  const float metric[][3] =
49  {
50  { 100.01, 100.01, M_PI / 8 },
51  { 100.01, 100.01, -M_PI / 8 },
52  { 105.01, 102.09, M_PI / 2 },
53  { 100.21, 102.51, -M_PI / 2 },
54  { 99.99, 100.01, 0 },
55  { 100.01, 100.01, 2.1 * M_PI / 8 },
56  { 100.01, 100.01, 1.9 * M_PI / 8 }
57  };
58  const int grid[][3] =
59  {
60  { 0, 0, 1 },
61  { 0, 0, -1 },
62  { 50, 20, 4 },
63  { 2, 25, -4 }, // angle must not normalized
64  { -1, 0, 0 }, // x, y must be rounded downword
65  { 0, 0, 2 }, // angle must be rounded to nearest integer
66  { 0, 0, 2 } // angle must be rounded to nearest integer
67  };
68  for (size_t i = 0; i < sizeof(grid) / sizeof(grid[0]); ++i)
69  {
70  // Convert metric to grid
71  int output_grid[3];
73  map_info,
74  output_grid[0], output_grid[1], output_grid[2],
75  metric[i][0], metric[i][1], metric[i][2]);
76  for (size_t j = 0; j < 3; ++j)
77  ASSERT_EQ(output_grid[j], grid[i][j]);
78 
79  // Convert grid to metric
80  float output_metric[3];
82  map_info,
83  grid[i][0], grid[i][1], grid[i][2],
84  output_metric[0], output_metric[1], output_metric[2]);
85  for (size_t j = 0; j < 3; ++j)
86  ASSERT_NEAR(output_metric[j], metric[i][j], map_info.linear_resolution / 2);
87  }
88 }
89 
90 TEST(GridMetricConverter, Path)
91 {
92  costmap_cspace_msgs::MapMetaData3D map_info;
93  map_info.linear_resolution = 0.1;
94  map_info.angle = 8;
95  map_info.angular_resolution = M_PI / map_info.angle;
96  map_info.origin.position.x = 100.0;
97  map_info.origin.position.y = 100.0;
98 
99  const float metric_expected[][3] =
100  {
101  { 100.15, 100.15, M_PI / 8 },
102  { 100.15, 100.25, M_PI / 8 },
103  { 100.25, 100.35, M_PI / 8 },
104  { 100.35, 100.35, 2 * M_PI / 8 }
105  };
106  const int grid[][3] =
107  {
108  { 1, 1, 1 },
109  { 1, 2, 1 },
110  { 2, 3, 1 },
111  { 3, 3, 2 }
112  };
113  std::vector<CyclicVecFloat<3, 2>> path_grid;
114  for (const auto& g : grid)
115  path_grid.push_back(CyclicVecFloat<3, 2>(g[0], g[1], g[2]));
116 
117  nav_msgs::Path path;
118  grid_metric_converter::grid2MetricPath(map_info, path_grid, path);
119  size_t ref = 0;
120  for (const geometry_msgs::PoseStamped& p : path.poses)
121  {
122  const double diff_dist = hypotf(
123  metric_expected[ref][0] - p.pose.position.x,
124  metric_expected[ref][1] - p.pose.position.y);
125  double diff_yaw = fabs(tf2::getYaw(p.pose.orientation) - metric_expected[ref][2]);
126 
127  if (diff_yaw < -M_PI)
128  diff_yaw += 2.0 * M_PI;
129  else if (diff_yaw > M_PI)
130  diff_yaw -= 2.0 * M_PI;
131 
132  ASSERT_LT(diff_dist, map_info.linear_resolution * 2);
133  ASSERT_LT(fabs(diff_yaw), map_info.angular_resolution * 2);
134 
135  if (diff_dist < map_info.linear_resolution / 2 &&
136  fabs(diff_yaw) < map_info.angular_resolution / 2)
137  {
138  ++ref;
139  if (ref == sizeof(metric_expected) / sizeof(metric_expected[0]))
140  return;
141  }
142  }
143  // some reference points are not met
144  ASSERT_TRUE(false);
145 }
146 
147 int main(int argc, char** argv)
148 {
149  testing::InitGoogleTest(&argc, argv);
150 
151  return RUN_ALL_TESTS();
152 }
TEST(GridMetricConverter, SinglePose)
void metric2Grid(const costmap_cspace_msgs::MapMetaData3D &map_info, int &x, int &y, int &yaw, const float gx, const float gy, const float gyaw)
double getYaw(const A &a)
void grid2Metric(const costmap_cspace_msgs::MapMetaData3D &map_info, const T x, const T y, const T yaw, float &gx, float &gy, float &gyaw)
int main(int argc, char **argv)
void grid2MetricPath(const costmap_cspace_msgs::MapMetaData3D &map_info, const STL_CONTAINER< CyclicVecFloat< 3, 2 >, std::allocator< CyclicVecFloat< 3, 2 >>> &path_grid, nav_msgs::Path &path)


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:13