diff_drive_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 
00029 
00030 #include "test_common.h"
00031 #include <tf/transform_listener.h>
00032 
00033 // TEST CASES
00034 TEST_F(DiffDriveControllerTest, testForward)
00035 {
00036   // wait for ROS
00037   while(!isControllerAlive())
00038   {
00039     ros::Duration(0.1).sleep();
00040   }
00041   // zero everything before test
00042   geometry_msgs::Twist cmd_vel;
00043   cmd_vel.linear.x = 0.0;
00044   cmd_vel.angular.z = 0.0;
00045   publish(cmd_vel);
00046   ros::Duration(0.1).sleep();
00047   // get initial odom
00048   nav_msgs::Odometry old_odom = getLastOdom();
00049   // send a velocity command of 0.1 m/s
00050   cmd_vel.linear.x = 0.1;
00051   publish(cmd_vel);
00052   // wait for 10s
00053   ros::Duration(10.0).sleep();
00054 
00055   nav_msgs::Odometry new_odom = getLastOdom();
00056 
00057   // check if the robot traveled 1 meter in XY plane, changes in z should be ~~0
00058   const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x;
00059   const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y;
00060   const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z;
00061   EXPECT_NEAR(sqrt(dx*dx + dy*dy), 1.0, POSITION_TOLERANCE);
00062   EXPECT_LT(fabs(dz), EPS);
00063 
00064   // convert to rpy and test that way
00065   double roll_old, pitch_old, yaw_old;
00066   double roll_new, pitch_new, yaw_new;
00067   tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
00068   tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
00069   EXPECT_LT(fabs(roll_new - roll_old), EPS);
00070   EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
00071   EXPECT_LT(fabs(yaw_new - yaw_old), EPS);
00072   EXPECT_NEAR(fabs(new_odom.twist.twist.linear.x), cmd_vel.linear.x, EPS);
00073   EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
00074   EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
00075 
00076   EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
00077   EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
00078   EXPECT_LT(fabs(new_odom.twist.twist.angular.z), EPS);
00079 }
00080 
00081 TEST_F(DiffDriveControllerTest, testTurn)
00082 {
00083   // wait for ROS
00084   while(!isControllerAlive())
00085   {
00086     ros::Duration(0.1).sleep();
00087   }
00088   // zero everything before test
00089   geometry_msgs::Twist cmd_vel;
00090   cmd_vel.linear.x = 0.0;
00091   cmd_vel.angular.z = 0.0;
00092   publish(cmd_vel);
00093   ros::Duration(0.1).sleep();
00094   // get initial odom
00095   nav_msgs::Odometry old_odom = getLastOdom();
00096   // send a velocity command
00097   cmd_vel.angular.z = M_PI/10.0;
00098   publish(cmd_vel);
00099   // wait for 10s
00100   ros::Duration(10.0).sleep();
00101 
00102   nav_msgs::Odometry new_odom = getLastOdom();
00103 
00104   // check if the robot rotated PI around z, changes in the other fields should be ~~0
00105   EXPECT_LT(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x), EPS);
00106   EXPECT_LT(fabs(new_odom.pose.pose.position.y - old_odom.pose.pose.position.y), EPS);
00107   EXPECT_LT(fabs(new_odom.pose.pose.position.z - old_odom.pose.pose.position.z), EPS);
00108 
00109   // convert to rpy and test that way
00110   double roll_old, pitch_old, yaw_old;
00111   double roll_new, pitch_new, yaw_new;
00112   tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
00113   tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
00114   EXPECT_LT(fabs(roll_new - roll_old), EPS);
00115   EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
00116   EXPECT_NEAR(fabs(yaw_new - yaw_old), M_PI, ORIENTATION_TOLERANCE);
00117 
00118   EXPECT_LT(fabs(new_odom.twist.twist.linear.x), EPS);
00119   EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
00120   EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
00121 
00122   EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
00123   EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
00124   EXPECT_NEAR(fabs(new_odom.twist.twist.angular.z), M_PI/10.0, EPS);
00125 }
00126 
00127 TEST_F(DiffDriveControllerTest, testOdomFrame)
00128 {
00129   // wait for ROS
00130   while(!isControllerAlive())
00131   {
00132     ros::Duration(0.1).sleep();
00133   }
00134   // set up tf listener
00135   tf::TransformListener listener;
00136   ros::Duration(2.0).sleep();
00137   // check the odom frame exist
00138   EXPECT_TRUE(listener.frameExists("odom"));
00139 }
00140 
00141 int main(int argc, char** argv)
00142 {
00143   testing::InitGoogleTest(&argc, argv);
00144   ros::init(argc, argv, "diff_drive_test");
00145 
00146   ros::AsyncSpinner spinner(1);
00147   spinner.start();
00148   //ros::Duration(0.5).sleep();
00149   int ret = RUN_ALL_TESTS();
00150   spinner.stop();
00151   ros::shutdown();
00152   return ret;
00153 }


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Thu Jun 6 2019 18:58:48