35 #include <gtest/gtest.h> 39 #include <costmap_cspace_msgs/MapMetaData3D.h> 50 using Vec3 = CyclicVecInt<3, 2>;
51 using Astar = GridAstar<3, 2>;
53 class DistanceMapTest :
public ::testing::Test
70 : ec_(0.5
f, 0.5
f, 0.2
f)
71 , dm_full_(cm_rough_, bbf_costmap_)
72 , dm_fast_(cm_rough_, bbf_costmap_)
75 const int local_range = 0;
76 omp_set_num_threads(2);
78 costmap_cspace_msgs::MapMetaData3D map_info;
82 map_info.linear_resolution = 1.0;
83 map_info.angular_resolution = M_PI * 2 /
angle_;
94 Astar::Gridmap<char, 0x40> cm;
95 Astar::Gridmap<char, 0x80> cm_hyst;
104 cm_hyst.reset(size3d);
105 cm_rough_.reset(size2d);
106 bbf_costmap_.reset(size2d);
111 bbf_costmap_.clear();
117 .local_range = local_range,
120 .resolution = map_info.linear_resolution,
122 dm_full_.
init(model, dmp);
123 dm_fast_.
init(model, dmp);
139 for (
int x = 1; x < w_ - 1; x++)
150 for (
int y = 0; y <
h_; y++)
152 for (
int x = 0; x <
w_; x++)
155 if (cm_rough_[pos] == 100)
159 EXPECT_NEAR(dm_full_[pos], dm_fast_[pos], 0.5) << msg +
" failed at " + xyStr(x, y);
160 if (::testing::Test::HasFailure())
190 fprintf(stderr,
"expected:\n");
222 fprintf(stderr,
"expected:\n");
235 fprintf(stderr,
"expected:\n");
252 if (!
validate(
"obstacle out of range"))
254 fprintf(stderr,
"expected:\n");
262 int main(
int argc,
char** argv)
264 testing::InitGoogleTest(&argc, argv);
266 return RUN_ALL_TESTS();
std::shared_ptr< GridAstarModel3D > Ptr
void init(const GridAstarModel3D::Ptr model, const Params &p)
CyclicVecInt< DIM, NONCYCLIC > Vec
float angle_resolution_aspect_
TEST_F(DistanceMapTest, Create)
CyclicVecInt< 3, 2 > Vec3
const Astar::Gridmap< float > & gridmap() const
void setParams(const CostCoeff &cc, const int num_cost_estim_task)
Astar::Gridmap< char, 0x80 > cm_rough_
bool validate(const std::string &msg) const
void create(const Astar::Vec &s, const Astar::Vec &e)
CyclicVecFloat< DIM, NONCYCLIC > Vecf
int main(int argc, char **argv)
void update(const Astar::Vec &s, const Astar::Vec &e, const Rect &rect)