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);
74 cost_estim_cache, cm, cm, cm,
83 std::vector<GridAstarModel3D::VecWithCost> starts;
84 starts.emplace_back(start);
86 const float c_straight = model.
cost(start, goal_straight, starts, goal_straight);
87 const float c_curve = model.
cost(start, goal_curve, starts, goal_curve);
88 const float c_drift = model.
cost(start, goal_drift, starts, goal_drift);
89 const float c_drift_curve = model.
cost(start, goal_curve_drift, starts, goal_curve_drift);
91 EXPECT_LT(c_straight, c_curve);
92 EXPECT_LT(c_straight, c_drift);
93 EXPECT_LT(c_straight, c_drift_curve);
98 int main(
int argc,
char** argv)
100 testing::InitGoogleTest(&argc, argv);
102 return RUN_ALL_TESTS();
int main(int argc, char **argv)
TEST(CostmapBBF, ForEach)
float weight_costmap_turn_
float cost(const Vec &cur, const Vec &next, const std::vector< VecWithCost > &start, const Vec &goal) const override
float angle_resolution_aspect_
float hysteresis_max_dist_