Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
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
00040 void recv(const sensor_msgs::LaserScanConstPtr& msg) {}
00041
00042
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
00081 TEST(Main, subscribe_unsubscribe)
00082 {
00083 ros::NodeHandle nh;
00084 ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("velodyne_points", 2);
00085
00086
00087 ros::WallDuration(2.0).sleep();
00088 ros::spinOnce();
00089 EXPECT_EQ(0, pub.getNumSubscribers());
00090
00091
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
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
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 }