33 #include <costmap_cspace_msgs/MapMetaData3D.h>
36 #include <gtest/gtest.h>
44 costmap_cspace_msgs::MapMetaData3D map_info;
46 map_info.height = 100;
48 map_info.linear_resolution = 1.0;
49 map_info.angular_resolution = M_PI * 2 / map_info.angle;
53 cost_estim_cache.
clear(0.0);
75 cost_estim_cache, cm, cm, cm,
84 std::vector<GridAstarModel3D::VecWithCost> starts;
85 starts.emplace_back(
start);
87 const float c_straight = model.
cost(
start, goal_straight, starts, goal_straight);
88 const float c_curve = model.
cost(
start, goal_curve, starts, goal_curve);
89 const float c_drift = model.
cost(
start, goal_drift, starts, goal_drift);
90 const float c_drift_curve = model.
cost(
start, goal_curve_drift, starts, goal_curve_drift);
92 EXPECT_LT(c_straight, c_curve);
93 EXPECT_LT(c_straight, c_drift);
94 EXPECT_LT(c_straight, c_drift_curve);
100 cm[occupied_waypoint] = 100;
102 EXPECT_LT(model.
cost(start2, occupied_waypoint, {GridAstarModel3D::VecWithCost(start2)}, occupied_waypoint), 0);
104 EXPECT_LT(model.
cost(occupied_waypoint, goal2, {GridAstarModel3D::VecWithCost(occupied_waypoint)}, goal2), 0);
112 EXPECT_GT(model.
cost(start3, waypoint3, {GridAstarModel3D::VecWithCost(start3)}, waypoint3),
113 model.
cost(waypoint3, goal3, {GridAstarModel3D::VecWithCost(waypoint3)}, goal3));
118 int main(
int argc,
char** argv)
120 testing::InitGoogleTest(&argc, argv);
122 return RUN_ALL_TESTS();