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 <cmath>
31 
32 #include <ros/ros.h>
33 
34 #include <nav_msgs/Path.h>
35 #include <geometry_msgs/PoseWithCovarianceStamped.h>
36 #include <geometry_msgs/TransformStamped.h>
39 
40 #include <gtest/gtest.h>
41 
42 TEST(CompareTf, Compare)
43 {
44  ros::NodeHandle nh("~");
45  tf2_ros::Buffer tfbuf;
46  tf2_ros::TransformListener tfl(tfbuf);
47 
48  int cnt = 0;
49  int cnt_max;
50  nh.param("cnt_max", cnt_max, 10);
51  size_t tf_ex_cnt = 0;
52 
53  const boost::function<void(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr&)> cb_pose =
54  [&tfbuf, &cnt, &cnt_max, &tf_ex_cnt](const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg) -> void
55  {
56  geometry_msgs::PoseStamped pose;
57  try
58  {
59  geometry_msgs::PoseStamped pose_bl;
60  pose_bl.header.frame_id = "base_link";
61  pose_bl.header.stamp = msg->header.stamp;
62  pose_bl.pose.orientation.w = 1.0;
63  geometry_msgs::TransformStamped trans =
64  tfbuf.lookupTransform("map", pose_bl.header.frame_id, pose_bl.header.stamp, ros::Duration(0.1));
65  tf2::doTransform(pose_bl, pose, trans);
66  }
67  catch (tf2::TransformException& e)
68  {
69  tf_ex_cnt++;
70  return;
71  }
72  const float x_error = pose.pose.position.x - msg->pose.pose.position.x;
73  const float y_error = pose.pose.position.y - msg->pose.pose.position.y;
74  const float z_error = pose.pose.position.z - msg->pose.pose.position.z;
75  const float error = std::sqrt(std::pow(x_error, 2) + std::pow(y_error, 2) + std::pow(z_error, 2));
76 
77  fprintf(stderr, "compare_tf[%d/%d]:\n", cnt, cnt_max);
78  fprintf(stderr, " error=%0.3f\n", error);
79 
80  cnt++;
81  if (cnt >= cnt_max)
82  ros::shutdown();
83 
84  ASSERT_FALSE(error > 0.05)
85  << "tf output diverges from amcl_pose.";
86  };
87  ros::Subscriber sub_pose = nh.subscribe("/amcl_pose", 1, cb_pose);
88 
89  ros::Rate wait(1);
90 
91  while (ros::ok())
92  {
93  ros::spinOnce();
94  wait.sleep();
95  }
96 
97  ASSERT_FALSE(tf_ex_cnt > 1)
98  << "tf exception occures more than once.";
99 
100  fprintf(stderr, "compare_tf finished\n");
101 }
102 
103 int main(int argc, char** argv)
104 {
105  testing::InitGoogleTest(&argc, argv);
106  ros::init(argc, argv, "compare_tf");
107 
108  return RUN_ALL_TESTS();
109 }
msg
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:42
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:103
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 Wed May 12 2021 02:16:29