steer_drive_controller_test.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2013, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics, Inc. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00030 
00031 #include "../common/include/test_common.h"
00032 #include <tf/transform_listener.h>
00033 
00034 // TEST CASES
00035 TEST_F(SteerDriveControllerTest, testForward)
00036 {
00037   // wait for ROS
00038   while(!isControllerAlive())
00039   {
00040     ros::Duration(0.1).sleep();
00041   }
00042   // zero everything before test
00043   geometry_msgs::Twist cmd_vel;
00044   cmd_vel.linear.x = 0.0;
00045   cmd_vel.angular.z = 0.0;
00046   publish(cmd_vel);
00047   ros::Duration(0.1).sleep();
00048   // get initial odom
00049   nav_msgs::Odometry old_odom = getLastOdom();
00050   // send a velocity command of 0.1 m/s
00051   cmd_vel.linear.x = 0.1;
00052   publish(cmd_vel);
00053   // wait for 10s
00054   ros::Duration(10.0).sleep();
00055 
00056   nav_msgs::Odometry new_odom = getLastOdom();
00057 
00058   // check if the robot traveled 1 meter in XY plane, changes in z should be ~~0
00059   const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x;
00060   const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y;
00061   const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z;
00062   EXPECT_NEAR(sqrt(dx*dx + dy*dy), 1.0, POSITION_TOLERANCE);
00063   EXPECT_LT(fabs(dz), EPS);
00064 
00065   // convert to rpy and test that way
00066   double roll_old, pitch_old, yaw_old;
00067   double roll_new, pitch_new, yaw_new;
00068   tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
00069   tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
00070   EXPECT_LT(fabs(roll_new - roll_old), EPS);
00071   EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
00072   EXPECT_LT(fabs(yaw_new - yaw_old), EPS);
00073   EXPECT_NEAR(fabs(new_odom.twist.twist.linear.x), cmd_vel.linear.x, EPS);
00074   EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
00075   EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
00076 
00077   EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
00078   EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
00079   EXPECT_LT(fabs(new_odom.twist.twist.angular.z), EPS);
00080 }
00081 
00082 TEST_F(SteerDriveControllerTest, testTurn)
00083 {
00084   // wait for ROS
00085   while(!isControllerAlive())
00086   {
00087     ros::Duration(0.1).sleep();
00088   }
00089   // zero everything before test
00090   geometry_msgs::Twist cmd_vel;
00091   cmd_vel.linear.x = 0.0;
00092   cmd_vel.angular.z = 0.0;
00093   publish(cmd_vel);
00094   ros::Duration(0.1).sleep();
00095   // get initial odom
00096   nav_msgs::Odometry old_odom = getLastOdom();
00097   // send a velocity command
00098   cmd_vel.angular.z = M_PI/10.0;
00099   // send linear command too 
00100   // because sending only angular command doesn't actuate wheels for steer drive mechanism
00101   cmd_vel.linear.x = 0.1;
00102   publish(cmd_vel);
00103   // wait for 10s
00104   ros::Duration(10.0).sleep();
00105 
00106   nav_msgs::Odometry new_odom = getLastOdom();
00107 
00108   // check if the robot rotated PI around z, changes in x should be ~~0 and in y should be y_answer
00109   double x_answer = 0.0;
00110   double y_answer = 2.0 * cmd_vel.linear.x / cmd_vel.angular.z; // R = v/w, D = 2R
00111   EXPECT_NEAR(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x), x_answer, POSITION_TOLERANCE);
00112   EXPECT_NEAR(fabs(new_odom.pose.pose.position.y - old_odom.pose.pose.position.y), y_answer, POSITION_TOLERANCE);
00113   EXPECT_LT(fabs(new_odom.pose.pose.position.z - old_odom.pose.pose.position.z), EPS);
00114 
00115   // convert to rpy and test that way
00116   double roll_old, pitch_old, yaw_old;
00117   double roll_new, pitch_new, yaw_new;
00118   tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
00119   tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
00120   EXPECT_LT(fabs(roll_new - roll_old), EPS);
00121   EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
00122   EXPECT_NEAR(fabs(yaw_new - yaw_old), M_PI, ORIENTATION_TOLERANCE);
00123 
00124   EXPECT_NEAR(new_odom.twist.twist.linear.x, 0.1, VELOCITY_TOLERANCE);
00125   EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
00126   EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
00127 
00128   EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
00129   EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
00130   EXPECT_NEAR(fabs(new_odom.twist.twist.angular.z), M_PI/10.0, EPS);
00131 }
00132 
00133 TEST_F(SteerDriveControllerTest, testOdomFrame)
00134 {
00135   // wait for ROS
00136   while(!isControllerAlive())
00137   {
00138     ros::Duration(0.1).sleep();
00139   }
00140   // set up tf listener
00141   tf::TransformListener listener;
00142   ros::Duration(2.0).sleep();
00143   // check the odom frame exist
00144   EXPECT_TRUE(listener.frameExists("odom"));
00145 }
00146 
00147 int main(int argc, char** argv)
00148 {
00149   testing::InitGoogleTest(&argc, argv);
00150   ros::init(argc, argv, "steer_drive_controller_test");
00151 
00152   ros::AsyncSpinner spinner(1);
00153   spinner.start();
00154   //ros::Duration(0.5).sleep();
00155   int ret = RUN_ALL_TESTS();
00156   spinner.stop();
00157   ros::shutdown();
00158   return ret;
00159 }


steer_drive_controller
Author(s): CIR-KIT , Masaru Morita
autogenerated on Sat Jun 8 2019 19:20:25