30 #include <costmap_cspace_msgs/MapMetaData3D.h> 34 #include <gtest/gtest.h> 36 #define _USE_MATH_DEFINES 40 TEST(GridMetricConverter, SinglePose)
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;
48 const float metric[][3] =
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 },
55 { 100.01, 100.01, 2.1 * M_PI / 8 },
56 { 100.01, 100.01, 1.9 * M_PI / 8 }
68 for (
size_t i = 0; i <
sizeof(grid) /
sizeof(grid[0]); ++i)
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]);
80 float output_metric[3];
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);
90 TEST(GridMetricConverter, Path)
92 costmap_cspace_msgs::MapMetaData3D map_info;
93 map_info.linear_resolution = 0.1;
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;
99 const float metric_expected[][3] =
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 }
106 const int grid[][3] =
113 std::vector<CyclicVecFloat<3, 2>> path_grid;
114 for (
const auto& g : grid)
120 for (
const geometry_msgs::PoseStamped& p : path.poses)
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]);
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;
132 ASSERT_LT(diff_dist, map_info.linear_resolution * 2);
133 ASSERT_LT(fabs(diff_yaw), map_info.angular_resolution * 2);
135 if (diff_dist < map_info.linear_resolution / 2 &&
136 fabs(diff_yaw) < map_info.angular_resolution / 2)
139 if (ref ==
sizeof(metric_expected) /
sizeof(metric_expected[0]))
147 int main(
int argc,
char** argv)
149 testing::InitGoogleTest(&argc, argv);
151 return RUN_ALL_TESTS();
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)