Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
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 }