test_pointcloud_to_maps.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <string>
31 #include <vector>
32 
33 #include <ros/ros.h>
34 
35 #include <map_organizer_msgs/OccupancyGridArray.h>
36 #include <sensor_msgs/PointCloud2.h>
38 
39 #include <gtest/gtest.h>
40 
41 sensor_msgs::PointCloud2 generateMapCloud()
42 {
43  struct Point
44  {
45  float x, y, z;
46  Point(const float ax, const float ay, const float az)
47  : x(ax)
48  , y(ay)
49  , z(az)
50  {
51  }
52  };
53  std::vector<Point> points;
54  for (float x = 0.025; x < 1.0; x += 0.05)
55  {
56  for (float y = 0.025; y < 1.0; y += 0.05)
57  {
58  points.push_back(Point(x, y, 0.0));
59  }
60  }
61  for (float z = 0.05; z < 0.5; z += 0.05)
62  {
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));
67  }
68  for (float x = 0.425; x < 0.6; x += 0.05)
69  {
70  for (float y = 0.425; y < 0.6; y += 0.05)
71  {
72  points.push_back(Point(x, y, 0.5));
73  }
74  }
75  for (float x = 0.225; x < 0.8; x += 0.05)
76  {
77  for (float y = 0.225; y < 0.8; y += 0.05)
78  {
79  points.push_back(Point(x, y, 2.0));
80  }
81  }
82  for (float x = 0.225; x < 0.8; x += 0.05)
83  {
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));
88  }
89 
90  sensor_msgs::PointCloud2 cloud;
91  cloud.header.frame_id = "map";
92  cloud.is_bigendian = false;
93  cloud.is_dense = false;
94  sensor_msgs::PointCloud2Modifier modifier(cloud);
95  modifier.setPointCloud2Fields(
96  3,
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());
101  cloud.height = 1;
102  cloud.width = points.size();
103  sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
104  sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
105  sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
106  for (const Point& p : points)
107  {
108  *iter_x = p.x;
109  *iter_y = p.y;
110  *iter_z = p.z;
111  ++iter_x;
112  ++iter_y;
113  ++iter_z;
114  }
115  return cloud;
116 }
117 
118 TEST(PointcloudToMaps, Convert)
119 {
120  ros::NodeHandle nh;
121 
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
125  {
126  maps = msg;
127  };
128  ros::Subscriber sub = nh.subscribe("maps", 1, cb);
129  ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("mapcloud", 1, true);
130 
131  pub.publish(generateMapCloud());
132  ros::Rate rate(10.0);
133  for (int i = 0; i < 50 && ros::ok(); ++i)
134  {
135  rate.sleep();
136  ros::spinOnce();
137  if (maps)
138  break;
139  }
140  ASSERT_TRUE(static_cast<bool>(maps));
141  ASSERT_EQ(2u, maps->maps.size());
142  for (int i = 0; i < 2; ++i)
143  {
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);
147  }
148  ASSERT_NEAR(0.0, maps->maps[0].info.origin.position.z, 0.05);
149  for (int u = 0; u < 20; ++u)
150  {
151  for (int v = 0; v < 20; ++v)
152  {
153  if (8 <= u && u < 12 && 8 <= v && v < 12)
154  {
155  ASSERT_EQ(100, maps->maps[0].data[v * 20 + u])
156  << u << ", " << v;
157  }
158  else
159  {
160  ASSERT_EQ(0, maps->maps[0].data[v * 20 + u])
161  << u << ", " << v;
162  }
163  }
164  }
165  ASSERT_NEAR(2.0, maps->maps[1].info.origin.position.z, 0.05);
166  for (int u = 0; u < 20; ++u)
167  {
168  for (int v = 0; v < 20; ++v)
169  {
170  if (4 <= u && u < 16 && 4 <= v && v < 16)
171  {
172  if (4 == u || u == 15 || 4 == v || v == 15)
173  {
174  ASSERT_EQ(100, maps->maps[1].data[v * 20 + u])
175  << u << ", " << v;
176  }
177  else
178  {
179  ASSERT_EQ(0, maps->maps[1].data[v * 20 + u])
180  << u << ", " << v;
181  }
182  }
183  else
184  {
185  ASSERT_EQ(-1, maps->maps[1].data[v * 20 + u])
186  << u << ", " << v;
187  }
188  }
189  }
190 }
191 
192 int main(int argc, char** argv)
193 {
194  testing::InitGoogleTest(&argc, argv);
195  ros::init(argc, argv, "test_pointcloud_to_maps");
196 
197  return RUN_ALL_TESTS();
198 }
map_organizer_msgs::OccupancyGridArray maps
Definition: select_map.cpp:41
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,...)
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
TEST(PointcloudToMaps, Convert)
ROSCPP_DECL void spinOnce()


map_organizer
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:33