15 #include <gtest/gtest.h>
22 #if BELUGA_ROS_VERSION == 1
23 #include <boost/smart_ptr.hpp>
31 TEST(TestOccupancyGrid, Instantiation) {
32 constexpr std::size_t kWidth = 100;
33 constexpr std::size_t kHeight = 200;
35 #if BELUGA_ROS_VERSION == 2
36 auto message = std::make_shared<beluga_ros::msg::OccupancyGrid>();
37 #elif BELUGA_ROS_VERSION == 1
38 auto message = boost::make_shared<beluga_ros::msg::OccupancyGrid>();
40 #error BELUGA_ROS_VERSION is not defined or invalid
42 message->info.resolution = 0.1F;
45 message->info.origin.position.x = 1;
46 message->info.origin.position.y = 2;
47 message->info.origin.position.z = 0;
48 message->data = std::vector<std::int8_t>(kWidth * kHeight);
51 ASSERT_EQ(grid.resolution(),
message->info.resolution);
52 ASSERT_EQ(grid.size(),
message->data.size());
53 ASSERT_EQ(grid.width(), kWidth);
54 ASSERT_EQ(grid.height(), kHeight);
57 TEST(TestOccupancyGrid, ValueTraitsIsFree) {
64 TEST(TestOccupancyGrid, ValueTraitsIsUnkown) {
71 TEST(TestOccupancyGrid, ValueTraitsIsOccupied) {