34 #include <pcl/point_types.h>
35 #include <pcl/point_cloud.h>
40 #include <boost/bind.hpp>
41 #include <boost/scoped_ptr.hpp>
48 #include <gtest/gtest.h>
54 typedef pcl::PointCloud<pcl::PointXYZRGBNormal>
PCDType;
63 static const uint32_t mult = 1e6;
82 , expected_count_(expected_count)
112 msg->header.frame_id =
"frame2";
128 msg->header.frame_id =
"frame1";
149 msg->header.frame_id =
"frame2";
165 msg->header.frame_id =
"frame2";
189 std::uint64_t pcl_stamp;
192 for (
int i = 0; i < 20; ++i)
195 msg->header.stamp = pcl_stamp;
196 msg->header.frame_id =
"frame2";
224 msg->header.frame_id =
"frame2";
242 std::vector<std::string> target_frames;
243 target_frames.push_back(
"frame1");
244 target_frames.push_back(
"frame2");
254 msg->header.frame_id =
"frame3";
283 std::uint64_t pcl_stamp;
289 msg->header.frame_id =
"frame2";
290 msg->header.stamp = pcl_stamp;
297 transform.
stamp_ += offset*1.1;
307 msg->header.stamp = pcl_stamp;
331 msg->header.frame_id =
"frame2";
345 msg->header.frame_id =
"";
360 boost::scoped_ptr<tf::TransformListener> tf_listener;
361 boost::scoped_ptr<tf::MessageFilter<PCDType> > tf_filter;
364 for (
int i = 0; i < 3; ++i) {
369 "map", 5, threaded_nh,
380 int main(
int argc,
char** argv)
382 testing::InitGoogleTest(&argc, argv);
385 ros::init(argc, argv,
"test_message_filter");
388 int ret = RUN_ALL_TESTS();