compare_tf.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2017, the mcl_3dl authors
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 copyright holder 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 
30 #include <ros/ros.h>
31 #include <nav_msgs/Path.h>
32 #include <geometry_msgs/PoseWithCovarianceStamped.h>
33 #include <geometry_msgs/TransformStamped.h>
36 
37 #include <gtest/gtest.h>
38 
39 TEST(CompareTf, Compare)
40 {
41  ros::NodeHandle nh("~");
42  tf2_ros::Buffer tfbuf;
43  tf2_ros::TransformListener tfl(tfbuf);
44 
45  int cnt = 0;
46  int cnt_max;
47  nh.param("cnt_max", cnt_max, 10);
48  size_t tf_ex_cnt = 0;
49 
50  const boost::function<void(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr&)> cb_pose =
51  [&tfbuf, &cnt, &cnt_max, &tf_ex_cnt](const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg) -> void
52  {
53  geometry_msgs::PoseStamped pose;
54  try
55  {
56  geometry_msgs::PoseStamped pose_bl;
57  pose_bl.header.frame_id = "base_link";
58  pose_bl.header.stamp = msg->header.stamp;
59  pose_bl.pose.orientation.w = 1.0;
60  geometry_msgs::TransformStamped trans =
61  tfbuf.lookupTransform("map", pose_bl.header.frame_id, pose_bl.header.stamp, ros::Duration(0.1));
62  tf2::doTransform(pose_bl, pose, trans);
63  }
64  catch (tf2::TransformException& e)
65  {
66  tf_ex_cnt++;
67  return;
68  }
69  const float x_error = pose.pose.position.x - msg->pose.pose.position.x;
70  const float y_error = pose.pose.position.y - msg->pose.pose.position.y;
71  const float z_error = pose.pose.position.z - msg->pose.pose.position.z;
72  const float error = sqrtf(powf(x_error, 2.0) + powf(y_error, 2.0) + powf(z_error, 2.0));
73 
74  fprintf(stderr, "compare_tf[%d/%d]:\n", cnt, cnt_max);
75  fprintf(stderr, " error=%0.3f\n", error);
76 
77  cnt++;
78  if (cnt >= cnt_max)
79  ros::shutdown();
80 
81  ASSERT_FALSE(error > 0.05)
82  << "tf output diverges from amcl_pose.";
83  };
84  ros::Subscriber sub_pose = nh.subscribe("/amcl_pose", 1, cb_pose);
85 
86  ros::Rate wait(1);
87 
88  while (ros::ok())
89  {
90  ros::spinOnce();
91  wait.sleep();
92  }
93 
94  ASSERT_FALSE(tf_ex_cnt > 1)
95  << "tf exception occures more than once.";
96 
97  fprintf(stderr, "compare_tf finished\n");
98 }
99 
100 int main(int argc, char** argv)
101 {
102  testing::InitGoogleTest(&argc, argv);
103  ros::init(argc, argv, "compare_tf");
104 
105  return RUN_ALL_TESTS();
106 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
TEST(CompareTf, Compare)
Definition: compare_tf.cpp:39
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
int main(int argc, char **argv)
Definition: compare_tf.cpp:100
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
bool sleep()
void wait(int seconds)
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36