test_robot_pose_ekf_gps.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Wim Meeussen 
00036    Prasenjit Mukherjee (Clearpath Robotics)
00037 */
00038 
00039 #include <string>
00040 #include <gtest/gtest.h>
00041 #include "ros/ros.h"
00042 #include "nav_msgs/Odometry.h"
00043 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00044 
00045 #include <boost/thread.hpp>
00046 
00047 using namespace ros;
00048 static const double time_end     = 1368022016.0;
00049 static const double ekf_duration = 40;
00050 static const double EPS_trans_x    = 0.1;
00051 static const double EPS_trans_y    = 0.1;
00052 static const double EPS_trans_z    = 0.00001;
00053 static const double EPS_rot_x      = 0.005;
00054 static const double EPS_rot_y      = 0.005;
00055 static const double EPS_rot_z      = 0.005;
00056 static const double EPS_rot_w      = 0.005;
00057 
00058 int g_argc;
00059 char** g_argv;
00060 
00061 typedef boost::shared_ptr<nav_msgs::Odometry const> OdomConstPtr;
00062 typedef boost::shared_ptr<geometry_msgs::PoseWithCovarianceStamped const> EkfConstPtr;
00063 
00064 
00065 class TestEKF : public testing::Test
00066 {
00067 public:
00068   NodeHandle node_;
00069   ros::Subscriber odom_sub_, ekf_sub_;
00070   EkfConstPtr ekf_begin_, ekf_end_;
00071   OdomConstPtr odom_end_;
00072   double ekf_counter_, odom_counter_;
00073   Time ekf_time_begin_, odom_time_begin_;
00074 
00075   void OdomCallback(const OdomConstPtr& odom)
00076   {
00077     // get initial time
00078     if (odom_counter_ == 0)
00079       odom_time_begin_ = odom->header.stamp;
00080 
00081     odom_end_ = odom;
00082 
00083     // count number of callbacks
00084     odom_counter_++;
00085   }
00086 
00087   void EKFCallback(const EkfConstPtr& ekf)
00088   {
00089     // get initial time
00090     if (ekf_counter_ == 0){
00091       ekf_time_begin_ = ekf->header.stamp;
00092       ekf_begin_ = ekf;
00093     }
00094     if (ekf->header.stamp.toSec() < time_end)
00095       ekf_end_ = ekf;
00096 
00097     // count number of callbacks
00098     ekf_counter_++;
00099   }
00100 
00101 
00102 protected:
00104   TestEKF()
00105   {
00106     ekf_counter_ = 0;
00107     odom_counter_ = 0;
00108 
00109   }
00110 
00111 
00113   ~TestEKF()
00114   {
00115   }
00116 
00117   void SetUp()
00118   {
00119     ROS_INFO("Subscribing to robot_pose_ekf/odom_combined");
00120     ekf_sub_ = node_.subscribe("/robot_pose_ekf/odom_combined", 10, &TestEKF::EKFCallback, (TestEKF*)this);
00121 
00122     ROS_INFO("Subscribing to wheel odometry");
00123     odom_sub_ = node_.subscribe("/encoder", 10 , &TestEKF::OdomCallback, (TestEKF*)this);
00124   }
00125 
00126   void TearDown()
00127   {
00128     odom_sub_.shutdown();
00129     ekf_sub_.shutdown();
00130   }
00131 };
00132 
00133 
00134 TEST_F(TestEKF, test)
00135 {
00136   Duration d(0.01);
00137   // wait while bag is played back
00138   ROS_INFO("Waiting for bag to start playing");
00139   while (odom_counter_ == 0)
00140     d.sleep();
00141   ROS_INFO("Detected that bag is playing");
00142 
00143   ROS_INFO("Waiting until end time is reached");
00144   while( odom_end_->header.stamp.toSec() < time_end){
00145     ROS_INFO("waitinf for end");
00146     d.sleep();
00147   }
00148   ROS_INFO("End time reached");
00149   // give filter some time to catch up
00150   //WallDuration(2.0).sleep();
00151 
00152   // check if callback was called enough times
00153   ROS_INFO("Number of ekf callbacks: %f", ekf_counter_);
00154   EXPECT_GT(ekf_counter_, 200);
00155 
00156   // check if time interval is correct
00157   ROS_INFO("Ekf duration: %f", ekf_duration);
00158   EXPECT_LT(Duration(ekf_end_->header.stamp - ekf_time_begin_).toSec(), ekf_duration * 1.3);
00159   EXPECT_GT(Duration(ekf_end_->header.stamp - ekf_time_begin_).toSec(), ekf_duration * 0.80);
00160 
00161   // check if ekf time is same as odom time
00162   EXPECT_NEAR(ekf_time_begin_.toSec(),  odom_time_begin_.toSec(), 2.5);
00163   EXPECT_NEAR(ekf_end_->header.stamp.toSec(), time_end, 1.0);
00164 
00165   // check filter result
00166   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,
00167             ekf_end_->pose.pose.orientation.x, ekf_end_->pose.pose.orientation.y, ekf_end_->pose.pose.orientation.z, ekf_end_->pose.pose.orientation.w,
00168             ekf_end_->header.stamp.toSec());
00169 
00170 
00171   EXPECT_NEAR(ekf_end_->pose.pose.position.x, 1.669542, EPS_trans_x);
00172   EXPECT_NEAR(ekf_end_->pose.pose.position.y, -3.849846, EPS_trans_y);
00173   EXPECT_NEAR(ekf_end_->pose.pose.position.z, 0.0, EPS_trans_z);
00174   EXPECT_NEAR(ekf_end_->pose.pose.orientation.x, -0.007353,  EPS_rot_x);
00175   EXPECT_NEAR(ekf_end_->pose.pose.orientation.y, -0.007765, EPS_rot_y);
00176   EXPECT_NEAR(ekf_end_->pose.pose.orientation.z, -0.597720,  EPS_rot_z);
00177   EXPECT_NEAR(ekf_end_->pose.pose.orientation.w, 0.801634,  EPS_rot_w);
00178 
00179   SUCCEED();
00180 }
00181 
00182 
00183 
00184 
00185 int main(int argc, char** argv)
00186 {
00187   testing::InitGoogleTest(&argc, argv);
00188   g_argc = argc;
00189   g_argv = argv;
00190 
00191   init(g_argc, g_argv, "testEKF");
00192 
00193   boost::thread spinner(boost::bind(&ros::spin));
00194 
00195   int res = RUN_ALL_TESTS();
00196   spinner.interrupt();
00197   spinner.join();
00198 
00199   return res;
00200 }
00201 
00202 


robot_pose_ekf
Author(s): Wim Meeussen
autogenerated on Sat Dec 28 2013 17:14:32