35 #include <map_organizer_msgs/OccupancyGridArray.h> 36 #include <sensor_msgs/PointCloud2.h> 39 #include <gtest/gtest.h> 46 Point(
const float ax,
const float ay,
const float az)
53 std::vector<Point> points;
54 for (
float x = 0.025; x < 1.0; x += 0.05)
56 for (
float y = 0.025; y < 1.0; y += 0.05)
58 points.push_back(Point(x, y, 0.0));
61 for (
float z = 0.05; z < 0.5; z += 0.05)
63 points.push_back(Point(0.425, 0.425, z));
64 points.push_back(Point(0.575, 0.425, z));
65 points.push_back(Point(0.425, 0.575, z));
66 points.push_back(Point(0.575, 0.575, z));
68 for (
float x = 0.425; x < 0.6; x += 0.05)
70 for (
float y = 0.425; y < 0.6; y += 0.05)
72 points.push_back(Point(x, y, 0.5));
75 for (
float x = 0.225; x < 0.8; x += 0.05)
77 for (
float y = 0.225; y < 0.8; y += 0.05)
79 points.push_back(Point(x, y, 2.0));
82 for (
float x = 0.225; x < 0.8; x += 0.05)
84 points.push_back(Point(x, 0.225, 2.5));
85 points.push_back(Point(x, 0.775, 2.5));
86 points.push_back(Point(0.225, x, 2.5));
87 points.push_back(Point(0.775, x, 2.5));
90 sensor_msgs::PointCloud2 cloud;
91 cloud.header.frame_id =
"map";
92 cloud.is_bigendian =
false;
93 cloud.is_dense =
false;
97 "x", 1, sensor_msgs::PointField::FLOAT32,
98 "y", 1, sensor_msgs::PointField::FLOAT32,
99 "z", 1, sensor_msgs::PointField::FLOAT32);
100 modifier.
resize(points.size());
102 cloud.width = points.size();
106 for (
const Point& p : points)
118 TEST(PointcloudToMaps, Convert)
122 map_organizer_msgs::OccupancyGridArray::ConstPtr
maps;
123 const boost::function<void(const map_organizer_msgs::OccupancyGridArray::ConstPtr&)>
124 cb = [&
maps](
const map_organizer_msgs::OccupancyGridArray::ConstPtr& msg) ->
void 133 for (
int i = 0; i < 50 &&
ros::ok(); ++i)
140 ASSERT_TRUE(static_cast<bool>(maps));
141 ASSERT_EQ(2u, maps->maps.size());
142 for (
int i = 0; i < 2; ++i)
144 ASSERT_EQ(
"map", maps->maps[i].header.frame_id);
145 ASSERT_EQ(20u, maps->maps[i].info.width);
146 ASSERT_EQ(20u, maps->maps[i].info.height);
148 ASSERT_NEAR(0.0, maps->maps[0].info.origin.position.z, 0.05);
149 for (
int u = 0; u < 20; ++u)
151 for (
int v = 0; v < 20; ++v)
153 if (8 <= u && u < 12 && 8 <= v && v < 12)
155 ASSERT_EQ(100, maps->maps[0].data[v * 20 + u])
160 ASSERT_EQ(0, maps->maps[0].data[v * 20 + u])
165 ASSERT_NEAR(2.0, maps->maps[1].info.origin.position.z, 0.05);
166 for (
int u = 0; u < 20; ++u)
168 for (
int v = 0; v < 20; ++v)
170 if (4 <= u && u < 16 && 4 <= v && v < 16)
172 if (4 == u || u == 15 || 4 == v || v == 15)
174 ASSERT_EQ(100, maps->maps[1].data[v * 20 + u])
179 ASSERT_EQ(0, maps->maps[1].data[v * 20 + u])
185 ASSERT_EQ(-1, maps->maps[1].data[v * 20 + u])
192 int main(
int argc,
char** argv)
194 testing::InitGoogleTest(&argc, argv);
195 ros::init(argc, argv,
"test_pointcloud_to_maps");
197 return RUN_ALL_TESTS();
map_organizer_msgs::OccupancyGridArray maps
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
sensor_msgs::PointCloud2 generateMapCloud()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setPointCloud2Fields(int n_fields,...)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TEST(PointcloudToMaps, Convert)
ROSCPP_DECL void spinOnce()