31 #include <nav_msgs/Path.h> 32 #include <geometry_msgs/PoseWithCovarianceStamped.h> 34 #include <gtest/gtest.h> 44 nh.
param(
"error_limit", error_limit, 0.3);
46 const boost::function<void(const nav_msgs::Path::ConstPtr&)> cb_path =
47 [&path, &i_path](
const nav_msgs::Path::ConstPtr& msg) ->
void 51 fprintf(stderr,
"compare_pose: reference received\n");
53 const boost::function<void(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr&)> cb_pose =
54 [&path, &i_path, &error_limit](
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg) ->
void 56 if (path.poses.size() > 0 && path.poses[i_path].header.stamp <
ros::Time::now())
58 const float x_error = path.poses[i_path].pose.position.x - msg->pose.pose.position.x;
59 const float y_error = path.poses[i_path].pose.position.y - msg->pose.pose.position.y;
60 const float z_error = path.poses[i_path].pose.position.z - msg->pose.pose.position.z;
61 const float error = sqrtf(powf(x_error, 2.0) + powf(y_error, 2.0) + powf(z_error, 2.0));
62 const float x_sigma = sqrtf(msg->pose.covariance[0 * 6 + 0]);
63 const float y_sigma = sqrtf(msg->pose.covariance[1 * 6 + 1]);
64 const float z_sigma = sqrtf(msg->pose.covariance[2 * 6 + 2]);
66 fprintf(stderr,
"compare_pose[%lu/%lu]:\n",
67 i_path, path.poses.size());
68 fprintf(stderr,
" position error/limit=%0.3f/%0.3f\n", error, error_limit);
69 fprintf(stderr,
" x error/3sigma=%0.3f/%0.3f\n", x_error, x_sigma * 3.0);
70 fprintf(stderr,
" y error/3sigma=%0.3f/%0.3f\n", y_error, y_sigma * 3.0);
71 fprintf(stderr,
" z error/3sigma=%0.3f/%0.3f\n", z_error, z_sigma * 3.0);
74 if (i_path >= path.poses.size())
77 ASSERT_FALSE(error > error_limit)
78 <<
"Position error is larger then expected.";
79 ASSERT_FALSE(fabs(x_error) > x_sigma * 3.0)
80 <<
"Estimated variance is too small to continue tracking. (x)";
81 ASSERT_FALSE(fabs(y_error) > y_sigma * 3.0)
82 <<
"Estimated variance is too small to continue tracking. (y)";
83 ASSERT_FALSE(fabs(z_error) > z_sigma * 3.0)
84 <<
"Estimated variance is too small to continue tracking. (z)";
98 fprintf(stderr,
"compare_pose finished\n");
101 int main(
int argc,
char** argv)
103 testing::InitGoogleTest(&argc, argv);
106 return RUN_ALL_TESTS();
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 ¶m_name, T ¶m_val, const T &default_val) const
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()