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


obj_to_pointcloud
Author(s): Atsushi Watanabe
autogenerated on Wed Mar 19 2025 02:14:10