lazy_subscriber.cpp
Go to the documentation of this file.
00001 // Copyright (C) 2018, 2019 Kevin Hallenbeck, Joshua Whitley
00002 // All rights reserved.
00003 //
00004 // Software License Agreement (BSD License 2.0)
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions
00008 // are met:
00009 //
00010 //  * Redistributions of source code must retain the above copyright
00011 //    notice, this list of conditions and the following disclaimer.
00012 //  * Redistributions in binary form must reproduce the above
00013 //    copyright notice, this list of conditions and the following
00014 //    disclaimer in the documentation and/or other materials provided
00015 //    with the distribution.
00016 //  * Neither the name of {copyright_holder} nor the names of its
00017 //    contributors may be used to endorse or promote products derived
00018 //    from this software without specific prior written permission.
00019 //
00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 // POSSIBILITY OF SUCH DAMAGE.
00032 
00033 #include <gtest/gtest.h>
00034 
00035 #include <ros/ros.h>
00036 #include <sensor_msgs/PointCloud2.h>
00037 #include <sensor_msgs/LaserScan.h>
00038 
00039 // Subscriber receive callback
00040 void recv(const sensor_msgs::LaserScanConstPtr& msg) {}
00041 
00042 // Build and publish a minimal PointCloud2 message
00043 void publish(const ros::Publisher &pub)
00044 {
00045   const uint32_t POINT_STEP = 32;
00046   sensor_msgs::PointCloud2 msg;
00047   msg.header.frame_id = "";
00048   msg.header.stamp = ros::Time::now();
00049   msg.fields.resize(5);
00050   msg.fields[0].name = "x";
00051   msg.fields[0].offset = 0;
00052   msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00053   msg.fields[0].count = 1;
00054   msg.fields[1].name = "y";
00055   msg.fields[1].offset = 4;
00056   msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00057   msg.fields[1].count = 1;
00058   msg.fields[2].name = "z";
00059   msg.fields[2].offset = 8;
00060   msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00061   msg.fields[2].count = 1;
00062   msg.fields[3].name = "intensity";
00063   msg.fields[3].offset = 16;
00064   msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
00065   msg.fields[3].count = 1;
00066   msg.fields[4].name = "ring";
00067   msg.fields[4].offset = 20;
00068   msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
00069   msg.fields[4].count = 1;
00070   msg.data.resize(1 * POINT_STEP, 0x00);
00071   msg.point_step = POINT_STEP;
00072   msg.row_step = msg.data.size();
00073   msg.height = 1;
00074   msg.width = msg.row_step / POINT_STEP;
00075   msg.is_bigendian = false;
00076   msg.is_dense = true;
00077   pub.publish(msg);
00078 }
00079 
00080 // Verify correct handling of subscribe and unsubscribe events
00081 TEST(Main, subscribe_unsubscribe)
00082 {
00083   ros::NodeHandle nh;
00084   ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("velodyne_points", 2);
00085 
00086   // Wait for node to startup
00087   ros::WallDuration(2.0).sleep();
00088   ros::spinOnce();
00089   EXPECT_EQ(0, pub.getNumSubscribers());
00090 
00091   // Subscribe to 'scan' and expect the node to subscribe to 'velodyne_points'
00092   ros::Subscriber sub = nh.subscribe("scan", 2, recv);
00093 
00094   for (size_t i = 10; i > 0; i--)
00095   {
00096     publish(pub);
00097     ros::WallDuration(0.1).sleep();
00098     ros::spinOnce();
00099   }
00100 
00101   EXPECT_EQ(1, sub.getNumPublishers());
00102   EXPECT_EQ(1, pub.getNumSubscribers());
00103 
00104   // Unsubscribe from 'scan' and expect the node to unsubscribe from 'velodyne_points'
00105   sub.shutdown();
00106 
00107   for (size_t i = 10; i > 0; i--)
00108   {
00109     publish(pub);
00110     ros::WallDuration(0.1).sleep();
00111     ros::spinOnce();
00112   }
00113 
00114   EXPECT_EQ(0, sub.getNumPublishers());
00115   EXPECT_EQ(0, pub.getNumSubscribers());
00116 }
00117 
00118 // Run all the tests that were declared with TEST()
00119 int main(int argc, char **argv)
00120 {
00121   testing::InitGoogleTest(&argc, argv);
00122   ros::init(argc, argv, "test_lazy_subscriber");
00123   return RUN_ALL_TESTS();
00124 }


velodyne_laserscan
Author(s): Micho Radovnikovich, Kevin Hallenbeck
autogenerated on Wed Jul 3 2019 19:32:17