test_path_interpolator.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2022, 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 <list>
31 
32 #include <gtest/gtest.h>
33 
34 #include <costmap_cspace_msgs/MapMetaData3D.h>
35 
39 
40 namespace planner_cspace
41 {
42 namespace planner_3d
43 {
44 TEST(PathInterpolator, SimpleStraight)
45 {
47  pi.reset(4.0, 5);
48  const std::list<CyclicVecInt<3, 2>> in =
49  {
50  CyclicVecInt<3, 2>(0, 0, 0),
51  CyclicVecInt<3, 2>(1, 0, 0),
52  CyclicVecInt<3, 2>(2, 0, 0),
53  };
54  const std::list<CyclicVecFloat<3, 2>> out = pi.interpolate(in, 0.25, 0);
55 
56  const std::list<CyclicVecFloat<3, 2>> expected =
57  {
58  CyclicVecFloat<3, 2>(0.00f, 0.f, 0.f),
59  CyclicVecFloat<3, 2>(0.25f, 0.f, 0.f),
60  CyclicVecFloat<3, 2>(0.50f, 0.f, 0.f),
61  CyclicVecFloat<3, 2>(0.75f, 0.f, 0.f),
62  CyclicVecFloat<3, 2>(1.00f, 0.f, 0.f),
63  CyclicVecFloat<3, 2>(1.25f, 0.f, 0.f),
64  CyclicVecFloat<3, 2>(1.50f, 0.f, 0.f),
65  CyclicVecFloat<3, 2>(1.75f, 0.f, 0.f),
66  CyclicVecFloat<3, 2>(2.00f, 0.f, 0.f),
67  };
68 
69  ASSERT_EQ(expected, out);
70 }
71 
72 TEST(PathInterpolator, DuplicatedPose)
73 {
75  pi.reset(4.0, 5);
76  const std::list<CyclicVecInt<3, 2>> in =
77  {
78  CyclicVecInt<3, 2>(0, 0, 0),
79  CyclicVecInt<3, 2>(1, 0, 0),
80  CyclicVecInt<3, 2>(2, 0, 0),
81  };
82  const std::list<CyclicVecFloat<3, 2>> out = pi.interpolate(in, 0.4999999, 0);
83 
84  costmap_cspace_msgs::MapMetaData3D map_info;
85  map_info.linear_resolution = 0.1;
86  map_info.angular_resolution = M_PI / 2;
87  map_info.origin.position.x = -100.5;
88  map_info.origin.position.y = -200.5;
89 
90  CyclicVecFloat<3, 2> m_prev;
91  for (const auto& g : out)
92  {
94 
95  // Introduce quantization error
96  grid_metric_converter::grid2Metric<float>(
97  map_info,
98  g[0], g[1], g[2],
99  m[0], m[1], m[2]);
100 
101  ASSERT_NE(m_prev, m);
102  m_prev = m;
103  }
104 }
105 } // namespace planner_3d
106 } // namespace planner_cspace
107 
108 int main(int argc, char** argv)
109 {
110  testing::InitGoogleTest(&argc, argv);
111 
112  return RUN_ALL_TESTS();
113 }
f
TEST(CostmapBBF, ForEach)
std::list< CyclicVecFloat< 3, 2 > > interpolate(const std::list< CyclicVecInt< 3, 2 >> &path_grid, const float interval, const int local_range) const
int main(int argc, char **argv)
void reset(const float angular_resolution, const int range)


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:39:06