33 #include <gtest/gtest.h> 36 #include <sensor_msgs/PointCloud2.h> 37 #include <sensor_msgs/LaserScan.h> 40 void recv(
const sensor_msgs::LaserScanConstPtr& msg) {}
45 const uint32_t POINT_STEP = 32;
46 sensor_msgs::PointCloud2 msg;
47 msg.header.frame_id =
"";
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();
74 msg.width = msg.row_step / POINT_STEP;
75 msg.is_bigendian =
false;
81 TEST(Main, subscribe_unsubscribe)
94 for (
size_t i = 10; i > 0; i--)
101 EXPECT_EQ(1, sub.getNumPublishers());
107 for (
size_t i = 10; i > 0; i--)
114 EXPECT_EQ(0, sub.getNumPublishers());
119 int main(
int argc,
char **argv)
121 testing::InitGoogleTest(&argc, argv);
122 ros::init(argc, argv,
"test_lazy_subscriber");
123 return RUN_ALL_TESTS();
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)
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
ROSCPP_DECL void spinOnce()