compare_pose.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 
37 #include <gtest/gtest.h>
38 
39 TEST(ComparePose, Compare)
40 {
41  ros::NodeHandle nh("~");
42 
43  nav_msgs::Path path;
44  size_t i_path;
45 
46  double error_limit;
47  nh.param("error_limit", error_limit, 0.3);
48 
49  const boost::function<void(const nav_msgs::Path::ConstPtr&)> cb_path =
50  [&path, &i_path](const nav_msgs::Path::ConstPtr& msg) -> void
51  {
52  path = *msg;
53  i_path = 0;
54  fprintf(stderr, "compare_pose: reference received\n");
55  };
56  const boost::function<void(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr&)> cb_pose =
57  [&path, &i_path, &error_limit](const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg) -> void
58  {
59  if (path.poses.size() > 0 && path.poses[i_path].header.stamp < ros::Time::now())
60  {
61  const float x_error = path.poses[i_path].pose.position.x - msg->pose.pose.position.x;
62  const float y_error = path.poses[i_path].pose.position.y - msg->pose.pose.position.y;
63  const float z_error = path.poses[i_path].pose.position.z - msg->pose.pose.position.z;
64  const float error = std::sqrt(std::pow(x_error, 2) + std::pow(y_error, 2) + std::pow(z_error, 2));
65  const float x_sigma = std::sqrt(msg->pose.covariance[0 * 6 + 0]);
66  const float y_sigma = std::sqrt(msg->pose.covariance[1 * 6 + 1]);
67  const float z_sigma = std::sqrt(msg->pose.covariance[2 * 6 + 2]);
68 
69  fprintf(stderr, "compare_pose[%lu/%lu]:\n",
70  i_path, path.poses.size());
71  fprintf(stderr, " position error/limit=%0.3f/%0.3f\n", error, error_limit);
72  fprintf(stderr, " x error/3sigma=%0.3f/%0.3f\n", x_error, x_sigma * 3.0);
73  fprintf(stderr, " y error/3sigma=%0.3f/%0.3f\n", y_error, y_sigma * 3.0);
74  fprintf(stderr, " z error/3sigma=%0.3f/%0.3f\n", z_error, z_sigma * 3.0);
75 
76  i_path++;
77  if (i_path >= path.poses.size())
78  ros::shutdown();
79 
80  ASSERT_FALSE(error > error_limit)
81  << "Position error is larger then expected.";
82  ASSERT_FALSE(fabs(x_error) > x_sigma * 3.0)
83  << "Estimated variance is too small to continue tracking. (x)";
84  ASSERT_FALSE(fabs(y_error) > y_sigma * 3.0)
85  << "Estimated variance is too small to continue tracking. (y)";
86  ASSERT_FALSE(fabs(z_error) > z_sigma * 3.0)
87  << "Estimated variance is too small to continue tracking. (z)";
88  }
89  };
90 
91  ros::Subscriber sub_pose = nh.subscribe("/amcl_pose", 1, cb_pose);
92  ros::Subscriber sub_path = nh.subscribe("poses_ref", 1, cb_path);
93 
94  ros::Rate wait(10);
95 
96  while (ros::ok())
97  {
98  ros::spinOnce();
99  wait.sleep();
100  }
101  fprintf(stderr, "compare_pose finished\n");
102 }
103 
104 int main(int argc, char** argv)
105 {
106  testing::InitGoogleTest(&argc, argv);
107  ros::init(argc, argv, "compare_pose");
108 
109  return RUN_ALL_TESTS();
110 }
msg
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST(ComparePose, Compare)
int main(int argc, char **argv)
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)
static Time now()
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29