lazy_subscriber.cpp
Go to the documentation of this file.
1 // Copyright (C) 2018, 2019 Kevin Hallenbeck, Joshua Whitley
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of {copyright_holder} nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
33 #include <gtest/gtest.h>
34 
35 #include <ros/ros.h>
36 #include <sensor_msgs/PointCloud2.h>
37 #include <sensor_msgs/LaserScan.h>
38 
39 // Subscriber receive callback
40 void recv(const sensor_msgs::LaserScanConstPtr& msg) {}
41 
42 // Build and publish a minimal PointCloud2 message
43 void publish(const ros::Publisher &pub)
44 {
45  const uint32_t POINT_STEP = 32;
46  sensor_msgs::PointCloud2 msg;
47  msg.header.frame_id = "";
48  msg.header.stamp = ros::Time::now();
49  msg.fields.resize(5);
50  msg.fields[0].name = "x";
51  msg.fields[0].offset = 0;
52  msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
53  msg.fields[0].count = 1;
54  msg.fields[1].name = "y";
55  msg.fields[1].offset = 4;
56  msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
57  msg.fields[1].count = 1;
58  msg.fields[2].name = "z";
59  msg.fields[2].offset = 8;
60  msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
61  msg.fields[2].count = 1;
62  msg.fields[3].name = "intensity";
63  msg.fields[3].offset = 16;
64  msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
65  msg.fields[3].count = 1;
66  msg.fields[4].name = "ring";
67  msg.fields[4].offset = 20;
68  msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
69  msg.fields[4].count = 1;
70  msg.data.resize(1 * POINT_STEP, 0x00);
71  msg.point_step = POINT_STEP;
72  msg.row_step = msg.data.size();
73  msg.height = 1;
74  msg.width = msg.row_step / POINT_STEP;
75  msg.is_bigendian = false;
76  msg.is_dense = true;
77  pub.publish(msg);
78 }
79 
80 // Verify correct handling of subscribe and unsubscribe events
81 TEST(Main, subscribe_unsubscribe)
82 {
83  ros::NodeHandle nh;
84  ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("velodyne_points", 2);
85 
86  // Wait for node to startup
87  ros::WallDuration(2.0).sleep();
88  ros::spinOnce();
89  EXPECT_EQ(0, pub.getNumSubscribers());
90 
91  // Subscribe to 'scan' and expect the node to subscribe to 'velodyne_points'
92  ros::Subscriber sub = nh.subscribe("scan", 2, recv);
93 
94  for (size_t i = 10; i > 0; i--)
95  {
96  publish(pub);
97  ros::WallDuration(0.1).sleep();
98  ros::spinOnce();
99  }
100 
101  EXPECT_EQ(1, sub.getNumPublishers());
102  EXPECT_EQ(1, pub.getNumSubscribers());
103 
104  // Unsubscribe from 'scan' and expect the node to unsubscribe from 'velodyne_points'
105  sub.shutdown();
106 
107  for (size_t i = 10; i > 0; i--)
108  {
109  publish(pub);
110  ros::WallDuration(0.1).sleep();
111  ros::spinOnce();
112  }
113 
114  EXPECT_EQ(0, sub.getNumPublishers());
115  EXPECT_EQ(0, pub.getNumSubscribers());
116 }
117 
118 // Run all the tests that were declared with TEST()
119 int main(int argc, char **argv)
120 {
121  testing::InitGoogleTest(&argc, argv);
122  ros::init(argc, argv, "test_lazy_subscriber");
123  return RUN_ALL_TESTS();
124 }
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())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publish(const ros::Publisher &pub)
TEST(Main, subscribe_unsubscribe)
bool sleep() const
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void recv(const sensor_msgs::LaserScanConstPtr &msg)
uint32_t getNumSubscribers() const
static Time now()
ROSCPP_DECL void spinOnce()


velodyne_laserscan
Author(s): Micho Radovnikovich, Kevin Hallenbeck
autogenerated on Thu Jul 4 2019 19:09:25