test_obj_to_pointcloud.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 <ros/ros.h>
31 #include <sensor_msgs/PointCloud2.h>
33 
34 #include <string>
35 
36 #include <gtest/gtest.h>
37 
38 constexpr float TOLERANCE = 1e-6;
39 
40 bool isOnBottomSurface(const float x, const float y, const float z)
41 {
42  return -TOLERANCE <= x && x <= 0.5 + TOLERANCE &&
43  -TOLERANCE <= y && y <= 0.1 + TOLERANCE &&
44  -TOLERANCE <= z && z <= 0.001 + TOLERANCE;
45 }
46 bool isOnSideSurface(const float x, const float y, const float z)
47 {
48  return -TOLERANCE <= x && x <= 0.001 + TOLERANCE &&
49  -TOLERANCE <= y && y <= 0.1 + TOLERANCE &&
50  -TOLERANCE <= z && z <= 0.2 + TOLERANCE;
51 }
52 bool isOnCorner(const float x, const float y, const float z)
53 {
54  return -TOLERANCE <= x && x <= 0.05 + TOLERANCE &&
55  -TOLERANCE <= y && y <= 0.1 + TOLERANCE &&
56  -TOLERANCE <= z && z <= 0.05 + TOLERANCE;
57 }
58 
59 TEST(ObjToPointCloud, PointCloud)
60 {
61  ros::NodeHandle nh;
62  sensor_msgs::PointCloud2::ConstPtr cloud;
63 
64  const boost::function<void(const sensor_msgs::PointCloud2::ConstPtr&)> cb =
65  [&cloud](const sensor_msgs::PointCloud2::ConstPtr& msg) -> void
66  {
67  cloud = msg;
68  };
69  ros::Subscriber sub = nh.subscribe("mapcloud", 1, cb);
70 
71  ros::Rate rate(10.0);
72  for (int i = 0; i < 30 && ros::ok(); ++i)
73  {
74  rate.sleep();
75  ros::spinOnce();
76  if (cloud)
77  break;
78  }
79  ASSERT_TRUE(static_cast<bool>(cloud));
80  ASSERT_NEAR(
81  cloud->width * cloud->height,
82  lround((0.5 * 0.1 + 0.1 * 0.2) / (0.05 * 0.05)),
83  10);
84 
85  for (sensor_msgs::PointCloud2ConstIterator<float> iter_x(*cloud, "x"), iter_y(*cloud, "y"), iter_z(*cloud, "z");
86  iter_x != iter_x.end();
87  ++iter_x, ++iter_y, ++iter_z)
88  {
89  ASSERT_TRUE(
90  isOnBottomSurface(*iter_x, *iter_y, *iter_z) ||
91  isOnSideSurface(*iter_x, *iter_y, *iter_z) ||
92  isOnCorner(*iter_x, *iter_y, *iter_z))
93  << *iter_x << ", " << *iter_y << ", " << *iter_z << " is not on the expected surface";
94  }
95 }
96 
97 int main(int argc, char** argv)
98 {
99  testing::InitGoogleTest(&argc, argv);
100  ros::init(argc, argv, "test_obj_to_pointcloud");
101 
102  return RUN_ALL_TESTS();
103 }
constexpr float TOLERANCE
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool isOnCorner(const float x, const float y, const float z)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool isOnBottomSurface(const float x, const float y, const float z)
int main(int argc, char **argv)
TEST(ObjToPointCloud, PointCloud)
bool isOnSideSurface(const float x, const float y, const float z)
ROSCPP_DECL bool ok()
bool sleep()
ROSCPP_DECL void spinOnce()


obj_to_pointcloud
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:59