38 #include <gtest/gtest.h>
40 #include "nav_msgs/Odometry.h"
41 #include "geometry_msgs/PoseWithCovarianceStamped.h"
43 #include <boost/thread.hpp>
79 if (odom_counter_ == 0)
80 odom_time_begin_ = odom->header.stamp;
92 if (ekf_counter_ == 0){
93 ekf_time_begin_ = ekf->header.stamp;
96 if (ekf->header.stamp.toSec() <
time_end)
121 ROS_INFO(
"Subscribing to robot_pose_ekf/odom_combined");
124 ROS_INFO(
"Subscribing to base_odometry/odom");
142 ROS_INFO(
"Waiting for bag to start playing");
143 while (odom_counter_ == 0)
145 ROS_INFO(
"Detected that bag is playing");
147 ROS_INFO(
"Waiting untile end time is reached");
148 while( odom_end_->header.stamp.toSec() <
time_end){
156 ROS_INFO(
"Number of ekf callbacks: %f", ekf_counter_);
157 EXPECT_GT(ekf_counter_, 500);
165 EXPECT_NEAR(ekf_time_begin_.toSec(), odom_time_begin_.toSec(), 1.0);
166 EXPECT_NEAR(ekf_end_->header.stamp.toSec(),
time_end, 1.0);
169 ROS_INFO(
"%f %f %f %f %f %f %f -- %f",ekf_end_->pose.pose.position.x, ekf_end_->pose.pose.position.y, ekf_end_->pose.pose.position.z,
170 ekf_end_->pose.pose.orientation.x, ekf_end_->pose.pose.orientation.y, ekf_end_->pose.pose.orientation.z, ekf_end_->pose.pose.orientation.w,
171 ekf_end_->header.stamp.toSec());
172 EXPECT_NEAR(ekf_end_->pose.pose.position.x, -0.0586126,
EPS_trans_x);
173 EXPECT_NEAR(ekf_end_->pose.pose.position.y, 0.0124321,
EPS_trans_y);
174 EXPECT_NEAR(ekf_end_->pose.pose.position.z, 0.0,
EPS_trans_z);
175 EXPECT_NEAR(ekf_end_->pose.pose.orientation.x, 0.00419421,
EPS_rot_x);
176 EXPECT_NEAR(ekf_end_->pose.pose.orientation.y, 0.00810739,
EPS_rot_y);
177 EXPECT_NEAR(ekf_end_->pose.pose.orientation.z, -0.0440686,
EPS_rot_z);
178 EXPECT_NEAR(ekf_end_->pose.pose.orientation.w, 0.998987,
EPS_rot_w);
186 int main(
int argc,
char** argv)
188 testing::InitGoogleTest(&argc, argv);
196 int res = RUN_ALL_TESTS();