compare_tf.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2016-2017, the mcl_3dl authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 #include <nav_msgs/Path.h>
00032 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00033 #include <geometry_msgs/TransformStamped.h>
00034 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00035 #include <tf2_ros/transform_listener.h>
00036 
00037 #include <gtest/gtest.h>
00038 
00039 TEST(CompareTf, Compare)
00040 {
00041   ros::NodeHandle nh("~");
00042   tf2_ros::Buffer tfbuf;
00043   tf2_ros::TransformListener tfl(tfbuf);
00044 
00045   int cnt = 0;
00046   int cnt_max;
00047   nh.param("cnt_max", cnt_max, 10);
00048   size_t tf_ex_cnt = 0;
00049 
00050   const boost::function<void(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr&)> cb_pose =
00051       [&tfbuf, &cnt, &cnt_max, &tf_ex_cnt](const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg) -> void
00052   {
00053     geometry_msgs::PoseStamped pose;
00054     try
00055     {
00056       geometry_msgs::PoseStamped pose_bl;
00057       pose_bl.header.frame_id = "base_link";
00058       pose_bl.header.stamp = msg->header.stamp;
00059       pose_bl.pose.orientation.w = 1.0;
00060       geometry_msgs::TransformStamped trans =
00061           tfbuf.lookupTransform("map", pose_bl.header.frame_id, pose_bl.header.stamp, ros::Duration(0.1));
00062       tf2::doTransform(pose_bl, pose, trans);
00063     }
00064     catch (tf2::TransformException& e)
00065     {
00066       tf_ex_cnt++;
00067       return;
00068     }
00069     const float x_error = pose.pose.position.x - msg->pose.pose.position.x;
00070     const float y_error = pose.pose.position.y - msg->pose.pose.position.y;
00071     const float z_error = pose.pose.position.z - msg->pose.pose.position.z;
00072     const float error = sqrtf(powf(x_error, 2.0) + powf(y_error, 2.0) + powf(z_error, 2.0));
00073 
00074     fprintf(stderr, "compare_tf[%d/%d]:\n", cnt, cnt_max);
00075     fprintf(stderr, "  error=%0.3f\n", error);
00076 
00077     cnt++;
00078     if (cnt >= cnt_max)
00079       ros::shutdown();
00080 
00081     ASSERT_FALSE(error > 0.05)
00082         << "tf output diverges from amcl_pose.";
00083   };
00084   ros::Subscriber sub_pose = nh.subscribe("/amcl_pose", 1, cb_pose);
00085 
00086   ros::Rate wait(1);
00087 
00088   while (ros::ok())
00089   {
00090     ros::spinOnce();
00091     wait.sleep();
00092   }
00093 
00094   ASSERT_FALSE(tf_ex_cnt > 1)
00095       << "tf exception occures more than once.";
00096 
00097   fprintf(stderr, "compare_tf finished\n");
00098 }
00099 
00100 int main(int argc, char** argv)
00101 {
00102   testing::InitGoogleTest(&argc, argv);
00103   ros::init(argc, argv, "compare_tf");
00104 
00105   return RUN_ALL_TESTS();
00106 }


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 20 2019 20:04:43