test_track_odometry.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2018, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <string>
00031 
00032 #include <ros/ros.h>
00033 #include <nav_msgs/Odometry.h>
00034 #include <sensor_msgs/Imu.h>
00035 #include <tf2/utils.h>
00036 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00037 
00038 #include <gtest/gtest.h>
00039 
00040 class TrackOdometryTest : public ::testing::TestWithParam<const char*>
00041 {
00042 public:
00043   void initializeNode(const std::string& ns)
00044   {
00045     ros::NodeHandle nh(ns);
00046     pub_odom_ = nh.advertise<nav_msgs::Odometry>("odom_raw", 10);
00047     pub_imu_ = nh.advertise<sensor_msgs::Imu>("imu/data", 10);
00048     sub_odom_ = nh.subscribe("odom", 10, &TrackOdometryTest::cbOdom, this);
00049   }
00050   void initializeTrackOdometry(
00051       nav_msgs::Odometry& odom_raw,
00052       sensor_msgs::Imu& imu)
00053   {
00054     ros::Duration(0.1).sleep();
00055     ros::Rate rate(100);
00056     odom_ = nullptr;
00057     for (int i = 0; i < 100 && ros::ok(); ++i)
00058     {
00059       imu.header.stamp = odom_raw.header.stamp = ros::Time::now();
00060       pub_odom_.publish(odom_raw);
00061       pub_imu_.publish(imu);
00062       rate.sleep();
00063       ros::spinOnce();
00064       if (odom_ && i > 50)
00065         break;
00066     }
00067   }
00068   bool run(
00069       nav_msgs::Odometry& odom_raw,
00070       sensor_msgs::Imu& imu,
00071       const float dt, const int steps)
00072   {
00073     ros::Rate rate(1.0 / dt);
00074     int cnt(0);
00075 
00076     imu.header.stamp = odom_raw.header.stamp = ros::Time::now();
00077     while (ros::ok())
00078     {
00079       tf2::Quaternion quat_odom;
00080       tf2::fromMsg(odom_raw.pose.pose.orientation, quat_odom);
00081       odom_raw.pose.pose.orientation =
00082           tf2::toMsg(
00083               quat_odom *
00084               tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), dt * odom_raw.twist.twist.angular.z));
00085       tf2::Quaternion quat_imu;
00086       tf2::fromMsg(imu.orientation, quat_imu);
00087       imu.orientation =
00088           tf2::toMsg(
00089               quat_imu *
00090               tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), dt * imu.angular_velocity.z));
00091 
00092       const double yaw = tf2::getYaw(odom_raw.pose.pose.orientation);
00093       odom_raw.pose.pose.position.x += cos(yaw) * dt * odom_raw.twist.twist.linear.x;
00094       odom_raw.pose.pose.position.y += sin(yaw) * dt * odom_raw.twist.twist.linear.x;
00095 
00096       stepAndPublish(odom_raw, imu, dt);
00097 
00098       rate.sleep();
00099       ros::spinOnce();
00100       if (++cnt >= steps)
00101         break;
00102     }
00103     return ros::ok();
00104   }
00105   void stepAndPublish(
00106       nav_msgs::Odometry& odom_raw,
00107       sensor_msgs::Imu& imu,
00108       const float dt)
00109   {
00110     odom_raw.header.stamp += ros::Duration(dt);
00111     imu.header.stamp += ros::Duration(dt);
00112     pub_odom_.publish(odom_raw);
00113     pub_imu_.publish(imu);
00114   }
00115   void waitAndSpinOnce()
00116   {
00117     ros::Duration(0.1).sleep();
00118     ros::spinOnce();
00119   }
00120 
00121 protected:
00122   ros::Publisher pub_odom_;
00123   ros::Publisher pub_imu_;
00124   ros::Subscriber sub_odom_;
00125   nav_msgs::Odometry::ConstPtr odom_;
00126 
00127   void cbOdom(const nav_msgs::Odometry::ConstPtr& msg)
00128   {
00129     odom_ = msg;
00130   };
00131 };
00132 
00133 TEST_F(TrackOdometryTest, OdomImuFusion)
00134 {
00135   initializeNode("");
00136 
00137   const float dt = 0.02;
00138   const int steps = 100;
00139 
00140   nav_msgs::Odometry odom_raw;
00141   odom_raw.header.frame_id = "odom";
00142   odom_raw.pose.pose.orientation.w = 1;
00143 
00144   sensor_msgs::Imu imu;
00145   imu.header.frame_id = "base_link";
00146   imu.orientation.w = 1;
00147   imu.linear_acceleration.z = 9.8;
00148 
00149   initializeTrackOdometry(odom_raw, imu);
00150 
00151   // Go forward for 1m
00152   odom_raw.twist.twist.linear.x = 0.5;
00153   ASSERT_TRUE(run(odom_raw, imu, dt, steps));
00154 
00155   odom_raw.twist.twist.linear.x = 0.0;
00156   stepAndPublish(odom_raw, imu, dt);
00157 
00158   waitAndSpinOnce();
00159   ASSERT_NEAR(odom_->pose.pose.position.x, 1.0, 1e-3);
00160   ASSERT_NEAR(odom_->pose.pose.position.y, 0.0, 1e-3);
00161   ASSERT_NEAR(odom_->pose.pose.position.z, 0.0, 1e-3);
00162   ASSERT_NEAR(tf2::getYaw(odom_->pose.pose.orientation), 0.0, 1e-3);
00163 
00164   // Turn 90 degrees with 10% of odometry errors
00165   imu.angular_velocity.z = M_PI * 0.25;
00166   odom_raw.twist.twist.angular.z = imu.angular_velocity.z * 1.1;  // Odometry with error
00167   ASSERT_TRUE(run(odom_raw, imu, dt, steps));
00168 
00169   imu.angular_velocity.z = 0;
00170   odom_raw.twist.twist.angular.z = 0;
00171   imu.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), M_PI / 2));
00172   stepAndPublish(odom_raw, imu, dt);
00173 
00174   waitAndSpinOnce();
00175   ASSERT_NEAR(odom_->pose.pose.position.x, 1.0, 1e-2);
00176   ASSERT_NEAR(odom_->pose.pose.position.y, 0.0, 1e-2);
00177   ASSERT_NEAR(odom_->pose.pose.position.z, 0.0, 1e-2);
00178   ASSERT_NEAR(tf2::getYaw(odom_->pose.pose.orientation), M_PI / 2, 1e-2);
00179 
00180   // Go forward for 1m
00181   odom_raw.twist.twist.linear.x = 0.5;
00182   ASSERT_TRUE(run(odom_raw, imu, dt, steps));
00183 
00184   odom_raw.twist.twist.linear.x = 0.0;
00185   stepAndPublish(odom_raw, imu, dt);
00186 
00187   waitAndSpinOnce();
00188   ASSERT_NEAR(odom_->pose.pose.position.x, 1.0, 5e-2);
00189   ASSERT_NEAR(odom_->pose.pose.position.y, 1.0, 5e-2);
00190   ASSERT_NEAR(odom_->pose.pose.position.z, 0.0, 5e-2);
00191   ASSERT_NEAR(tf2::getYaw(odom_->pose.pose.orientation), M_PI / 2, 1e-2);
00192 }
00193 
00194 TEST_P(TrackOdometryTest, ZFilterOff)
00195 {
00196   const std::string ns_postfix(GetParam());
00197   initializeNode("no_z_filter" + ns_postfix);
00198 
00199   const float dt = 0.02;
00200   const int steps = 100;
00201 
00202   nav_msgs::Odometry odom_raw;
00203   odom_raw.header.frame_id = "odom";
00204   odom_raw.pose.pose.orientation.w = 1;
00205 
00206   sensor_msgs::Imu imu;
00207   imu.header.frame_id = "base_link";
00208   imu.orientation.y = sin(-M_PI / 4);
00209   imu.orientation.w = cos(-M_PI / 4);
00210   imu.linear_acceleration.x = -9.8;
00211 
00212   initializeTrackOdometry(odom_raw, imu);
00213 
00214   // Go forward for 1m
00215   odom_raw.twist.twist.linear.x = 0.5;
00216   ASSERT_TRUE(run(odom_raw, imu, dt, steps));
00217 
00218   odom_raw.twist.twist.linear.x = 0.0;
00219   stepAndPublish(odom_raw, imu, dt);
00220 
00221   waitAndSpinOnce();
00222   ASSERT_NEAR(odom_->pose.pose.position.x, 0.0, 1e-3);
00223   ASSERT_NEAR(odom_->pose.pose.position.y, 0.0, 1e-3);
00224   ASSERT_NEAR(odom_->pose.pose.position.z, 1.0, 1e-3);
00225 }
00226 
00227 TEST_P(TrackOdometryTest, ZFilterOn)
00228 {
00229   const std::string ns_postfix(GetParam());
00230   initializeNode("z_filter" + ns_postfix);
00231 
00232   const float dt = 0.02;
00233   const int steps = 100;
00234 
00235   nav_msgs::Odometry odom_raw;
00236   odom_raw.header.frame_id = "odom";
00237   odom_raw.pose.pose.orientation.w = 1;
00238 
00239   sensor_msgs::Imu imu;
00240   imu.header.frame_id = "base_link";
00241   imu.orientation.y = sin(-M_PI / 4);
00242   imu.orientation.w = cos(-M_PI / 4);
00243   imu.linear_acceleration.x = -9.8;
00244 
00245   initializeTrackOdometry(odom_raw, imu);
00246 
00247   // Go forward for 1m
00248   odom_raw.twist.twist.linear.x = 0.5;
00249   ASSERT_TRUE(run(odom_raw, imu, dt, steps));
00250 
00251   odom_raw.twist.twist.linear.x = 0.0;
00252   stepAndPublish(odom_raw, imu, dt);
00253 
00254   waitAndSpinOnce();
00255   ASSERT_NEAR(odom_->pose.pose.position.z, 1.0 - 1.0 / M_E, 5e-2);
00256 }
00257 
00258 INSTANTIATE_TEST_CASE_P(
00259     TrackOdometryTestInstance, TrackOdometryTest,
00260     ::testing::Values("", "_old_param"));
00261 
00262 int main(int argc, char** argv)
00263 {
00264   testing::InitGoogleTest(&argc, argv);
00265   ros::init(argc, argv, "test_track_odometry");
00266 
00267   return RUN_ALL_TESTS();
00268 }


track_odometry
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:23