compare_pose.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 
00034 #include <gtest/gtest.h>
00035 
00036 TEST(ComparePose, Compare)
00037 {
00038   ros::NodeHandle nh("~");
00039 
00040   nav_msgs::Path path;
00041   size_t i_path;
00042 
00043   double error_limit;
00044   nh.param("error_limit", error_limit, 0.3);
00045 
00046   const boost::function<void(const nav_msgs::Path::ConstPtr&)> cb_path =
00047       [&path, &i_path](const nav_msgs::Path::ConstPtr& msg) -> void
00048   {
00049     path = *msg;
00050     i_path = 0;
00051     fprintf(stderr, "compare_pose: reference received\n");
00052   };
00053   const boost::function<void(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr&)> cb_pose =
00054       [&path, &i_path, &error_limit](const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg) -> void
00055   {
00056     if (path.poses.size() > 0 && path.poses[i_path].header.stamp < ros::Time::now())
00057     {
00058       const float x_error = path.poses[i_path].pose.position.x - msg->pose.pose.position.x;
00059       const float y_error = path.poses[i_path].pose.position.y - msg->pose.pose.position.y;
00060       const float z_error = path.poses[i_path].pose.position.z - msg->pose.pose.position.z;
00061       const float error = sqrtf(powf(x_error, 2.0) + powf(y_error, 2.0) + powf(z_error, 2.0));
00062       const float x_sigma = sqrtf(msg->pose.covariance[0 * 6 + 0]);
00063       const float y_sigma = sqrtf(msg->pose.covariance[1 * 6 + 1]);
00064       const float z_sigma = sqrtf(msg->pose.covariance[2 * 6 + 2]);
00065 
00066       fprintf(stderr, "compare_pose[%lu/%lu]:\n",
00067               i_path, path.poses.size());
00068       fprintf(stderr, "  position error/limit=%0.3f/%0.3f\n", error, error_limit);
00069       fprintf(stderr, "  x error/3sigma=%0.3f/%0.3f\n", x_error, x_sigma * 3.0);
00070       fprintf(stderr, "  y error/3sigma=%0.3f/%0.3f\n", y_error, y_sigma * 3.0);
00071       fprintf(stderr, "  z error/3sigma=%0.3f/%0.3f\n", z_error, z_sigma * 3.0);
00072 
00073       i_path++;
00074       if (i_path >= path.poses.size())
00075         ros::shutdown();
00076 
00077       ASSERT_FALSE(error > error_limit)
00078           << "Position error is larger then expected.";
00079       ASSERT_FALSE(fabs(x_error) > x_sigma * 3.0)
00080           << "Estimated variance is too small to continue tracking. (x)";
00081       ASSERT_FALSE(fabs(y_error) > y_sigma * 3.0)
00082           << "Estimated variance is too small to continue tracking. (y)";
00083       ASSERT_FALSE(fabs(z_error) > z_sigma * 3.0)
00084           << "Estimated variance is too small to continue tracking. (z)";
00085     }
00086   };
00087 
00088   ros::Subscriber sub_pose = nh.subscribe("/amcl_pose", 1, cb_pose);
00089   ros::Subscriber sub_path = nh.subscribe("poses_ref", 1, cb_path);
00090 
00091   ros::Rate wait(10);
00092 
00093   while (ros::ok())
00094   {
00095     ros::spinOnce();
00096     wait.sleep();
00097   }
00098   fprintf(stderr, "compare_pose finished\n");
00099 }
00100 
00101 int main(int argc, char** argv)
00102 {
00103   testing::InitGoogleTest(&argc, argv);
00104   ros::init(argc, argv, "compare_pose");
00105 
00106   return RUN_ALL_TESTS();
00107 }


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