test_tf_message_filter_pcl.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
34 #include <pcl/point_types.h>
35 #include <pcl/point_cloud.h>
36 
37 #include <tf/message_filter.h>
38 #include <tf/transform_listener.h>
39 
40 #include <boost/bind.hpp>
41 #include <boost/scoped_ptr.hpp>
42 
43 #include <pcl_ros/point_cloud.h>
45 
46 #include <ros/ros.h>
47 
48 #include <gtest/gtest.h>
49 
50 using namespace tf;
51 
52 // using a random point type, as we want to make sure that it does work with
53 // other points than just XYZ
54 typedef pcl::PointCloud<pcl::PointXYZRGBNormal> PCDType;
55 
56 
60 void setStamp(ros::Time &stamp, std::uint64_t &pcl_stamp)
61 {
62  // round to millisecond
63  static const uint32_t mult = 1e6;
64  stamp.nsec /= mult;
65  stamp.nsec *= mult;
66 
67  pcl_conversions::toPCL(stamp, pcl_stamp);
68 
69  // verify
70  {
71  ros::Time t;
72  pcl_conversions::fromPCL(pcl_stamp, t);
73  ROS_ASSERT_MSG(t==stamp, "%d/%d vs %d/%d", t.sec, t.nsec, stamp.sec, stamp.nsec);
74  }
75 }
76 
77 class Notification
78 {
79 public:
80  Notification(int expected_count)
81  : count_(0)
82  , expected_count_(expected_count)
83  , failure_count_(0)
84  {
85  }
86 
87  void notify(const MessageFilter<PCDType>::MConstPtr& /*message*/)
88  {
89  ++count_;
90  }
91 
92  void failure(const MessageFilter<PCDType>::MConstPtr& /*message*/, FilterFailureReason /*reason*/)
93  {
94  ++failure_count_;
95  }
96 
97  int count_;
98  int expected_count_;
99  int failure_count_;
100 };
101 
102 TEST(MessageFilter, noTransforms)
103 {
104  tf::TransformListener tf_client;
105  Notification n(1);
106  MessageFilter<PCDType> filter(tf_client, "frame1", 1);
107  filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
108 
110  ros::Time stamp = ros::Time::now();
111  setStamp(stamp, msg->header.stamp);
112  msg->header.frame_id = "frame2";
113  filter.add(msg);
114 
115  EXPECT_EQ(0, n.count_);
116 }
117 
118 TEST(MessageFilter, noTransformsSameFrame)
119 {
120  tf::TransformListener tf_client;
121  Notification n(1);
122  MessageFilter<PCDType> filter(tf_client, "frame1", 1);
123  filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
124 
126  ros::Time stamp = ros::Time::now();
127  setStamp(stamp, msg->header.stamp);
128  msg->header.frame_id = "frame1";
129  filter.add(msg);
130 
131  EXPECT_EQ(1, n.count_);
132 }
133 
134 TEST(MessageFilter, preexistingTransforms)
135 {
136  tf::TransformListener tf_client;
137  Notification n(1);
138  MessageFilter<PCDType> filter(tf_client, "frame1", 1);
139  filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
140 
142 
143  ros::Time stamp = ros::Time::now();
144  setStamp(stamp, msg->header.stamp);
145 
146  tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2");
147  tf_client.setTransform(transform);
148 
149  msg->header.frame_id = "frame2";
150  filter.add(msg);
151 
152  EXPECT_EQ(1, n.count_);
153 }
154 
155 TEST(MessageFilter, postTransforms)
156 {
157  tf::TransformListener tf_client;
158  Notification n(1);
159  MessageFilter<PCDType> filter(tf_client, "frame1", 1);
160  filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
161 
162  ros::Time stamp = ros::Time::now();
164  setStamp(stamp, msg->header.stamp);
165  msg->header.frame_id = "frame2";
166 
167  filter.add(msg);
168 
169  EXPECT_EQ(0, n.count_);
170 
171  tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2");
172  tf_client.setTransform(transform);
173 
174  ros::WallDuration(0.1).sleep();
175  ros::spinOnce();
176 
177  EXPECT_EQ(1, n.count_);
178 }
179 
180 TEST(MessageFilter, queueSize)
181 {
182  tf::TransformListener tf_client;
183  Notification n(10);
184  MessageFilter<PCDType> filter(tf_client, "frame1", 10);
185  filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
186  filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2));
187 
188  ros::Time stamp = ros::Time::now();
189  std::uint64_t pcl_stamp;
190  setStamp(stamp, pcl_stamp);
191 
192  for (int i = 0; i < 20; ++i)
193  {
195  msg->header.stamp = pcl_stamp;
196  msg->header.frame_id = "frame2";
197 
198  filter.add(msg);
199  }
200 
201  EXPECT_EQ(0, n.count_);
202  EXPECT_EQ(10, n.failure_count_);
203 
204  tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2");
205  tf_client.setTransform(transform);
206 
207  ros::WallDuration(0.1).sleep();
208  ros::spinOnce();
209 
210  EXPECT_EQ(10, n.count_);
211 }
212 
213 TEST(MessageFilter, setTargetFrame)
214 {
215  tf::TransformListener tf_client;
216  Notification n(1);
217  MessageFilter<PCDType> filter(tf_client, "frame1", 1);
218  filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
219  filter.setTargetFrame("frame1000");
220 
221  ros::Time stamp = ros::Time::now();
223  setStamp(stamp, msg->header.stamp);
224  msg->header.frame_id = "frame2";
225 
226  tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1000", "frame2");
227  tf_client.setTransform(transform);
228 
229  filter.add(msg);
230 
231 
232  EXPECT_EQ(1, n.count_);
233 }
234 
235 TEST(MessageFilter, multipleTargetFrames)
236 {
237  tf::TransformListener tf_client;
238  Notification n(1);
239  MessageFilter<PCDType> filter(tf_client, "", 1);
240  filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
241 
242  std::vector<std::string> target_frames;
243  target_frames.push_back("frame1");
244  target_frames.push_back("frame2");
245  filter.setTargetFrames(target_frames);
246 
247  ros::Time stamp = ros::Time::now();
249  setStamp(stamp, msg->header.stamp);
250 
251  tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame3");
252  tf_client.setTransform(transform);
253 
254  msg->header.frame_id = "frame3";
255  filter.add(msg);
256 
257  ros::WallDuration(0.1).sleep();
258  ros::spinOnce();
259 
260  EXPECT_EQ(0, n.count_); // frame1->frame3 exists, frame2->frame3 does not (yet)
261 
262  //ros::Time::setNow(ros::Time::now() + ros::Duration(1.0));
263 
264  transform.child_frame_id_ = "frame2";
265  tf_client.setTransform(transform);
266 
267  ros::WallDuration(0.1).sleep();
268  ros::spinOnce();
269 
270  EXPECT_EQ(1, n.count_); // frame2->frame3 now exists
271 }
272 
273 TEST(MessageFilter, tolerance)
274 {
275  ros::Duration offset(0.2);
276  tf::TransformListener tf_client;
277  Notification n(1);
278  MessageFilter<PCDType> filter(tf_client, "frame1", 1);
279  filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
280  filter.setTolerance(offset);
281 
282  ros::Time stamp = ros::Time::now();
283  std::uint64_t pcl_stamp;
284  setStamp(stamp, pcl_stamp);
285  tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2");
286  tf_client.setTransform(transform);
287 
289  msg->header.frame_id = "frame2";
290  msg->header.stamp = pcl_stamp;
291  filter.add(msg);
292 
293  EXPECT_EQ(0, n.count_); //No return due to lack of space for offset
294 
295  //ros::Time::setNow(ros::Time::now() + ros::Duration(0.1));
296 
297  transform.stamp_ += offset*1.1;
298  tf_client.setTransform(transform);
299 
300  ros::WallDuration(0.1).sleep();
301  ros::spinOnce();
302 
303  EXPECT_EQ(1, n.count_); // Now have data for the message published earlier
304 
305  stamp += offset;
306  setStamp(stamp, pcl_stamp);
307  msg->header.stamp = pcl_stamp;
308 
309  filter.add(msg);
310 
311  EXPECT_EQ(1, n.count_); // Latest message is off the end of the offset
312 }
313 
314 TEST(MessageFilter, outTheBackFailure)
315 {
316  tf::TransformListener tf_client;
317  Notification n(1);
318  MessageFilter<PCDType> filter(tf_client, "frame1", 1);
319  filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2));
320 
321  ros::Time stamp = ros::Time::now();
323  setStamp(stamp, msg->header.stamp);
324 
325  tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2");
326  tf_client.setTransform(transform);
327 
328  transform.stamp_ = stamp + ros::Duration(10000);
329  tf_client.setTransform(transform);
330 
331  msg->header.frame_id = "frame2";
332  filter.add(msg);
333 
334  EXPECT_EQ(1, n.failure_count_);
335 }
336 
337 TEST(MessageFilter, emptyFrameIDFailure)
338 {
339  tf::TransformListener tf_client;
340  Notification n(1);
341  MessageFilter<PCDType> filter(tf_client, "frame1", 1);
342  filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2));
343 
345  msg->header.frame_id = "";
346  filter.add(msg);
347 
348  EXPECT_EQ(1, n.failure_count_);
349 }
350 
351 TEST(MessageFilter, removeCallback)
352 {
353  // Callback queue in separate thread
354  ros::CallbackQueue cbqueue;
355  ros::AsyncSpinner spinner(1, &cbqueue);
356  ros::NodeHandle threaded_nh;
357  threaded_nh.setCallbackQueue(&cbqueue);
358 
359  // TF filters; no data needs to be published
360  boost::scoped_ptr<tf::TransformListener> tf_listener;
361  boost::scoped_ptr<tf::MessageFilter<PCDType> > tf_filter;
362 
363  spinner.start();
364  for (int i = 0; i < 3; ++i) {
365  tf_listener.reset(new tf::TransformListener());
366  // Have callback fire at high rate to increase chances of race condition
367  tf_filter.reset(
368  new tf::MessageFilter<PCDType>(*tf_listener,
369  "map", 5, threaded_nh,
370  ros::Duration(0.000001)));
371 
372  // Sleep and reset; sleeping increases chances of race condition
373  ros::Duration(0.001).sleep();
374  tf_filter.reset();
375  tf_listener.reset();
376  }
377  spinner.stop();
378 }
379 
380 int main(int argc, char** argv)
381 {
382  testing::InitGoogleTest(&argc, argv);
383 
385  ros::init(argc, argv, "test_message_filter");
386  ros::NodeHandle nh;
387 
388  int ret = RUN_ALL_TESTS();
389 
390  return ret;
391 }
void setStamp(ros::Time &stamp, std::uint64_t &pcl_stamp)
void add(const MEvent &evt)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool setTransform(const StampedTransform &transform, const std::string &authority="default_authority")
static void setNow(const Time &new_now)
void spinner()
std::string child_frame_id_
void setTargetFrames(const std::vector< std::string > &target_frames)
void setCallbackQueue(CallbackQueueInterface *queue)
#define ROS_ASSERT_MSG(cond,...)
int main(int argc, char **argv)
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
bool sleep() const
void notify(const geometry_msgs::PointStamped::ConstPtr &message)
FilterFailureReason
static Time now()
void setTargetFrame(const std::string &target_frame)
bool sleep() const
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
void failure(const geometry_msgs::PointStamped::ConstPtr &message, FilterFailureReason reason)
ROSCPP_DECL void spinOnce()
void setTolerance(const ros::Duration &tolerance)
TEST(MessageFilter, noTransforms)
Connection registerCallback(const C &callback)
pcl::PointCloud< pcl::PointXYZRGBNormal > PCDType


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Feb 16 2023 03:08:02