diff_drive_limits_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 
00032 // TEST CASES
00033 TEST_F(DiffDriveControllerTest, testLinearJerkLimits)
00034 {
00035   // wait for ROS
00036   while(!isControllerAlive())
00037   {
00038     ros::Duration(0.1).sleep();
00039   }
00040   // zero everything before test
00041   geometry_msgs::Twist cmd_vel;
00042   cmd_vel.linear.x = 0.0;
00043   cmd_vel.angular.z = 0.0;
00044   publish(cmd_vel);
00045   ros::Duration(2.0).sleep();
00046   // get initial odom
00047   nav_msgs::Odometry old_odom = getLastOdom();
00048   // send a big command
00049   cmd_vel.linear.x = 10.0;
00050   publish(cmd_vel);
00051   // wait for a while
00052   ros::Duration(0.5).sleep();
00053 
00054   nav_msgs::Odometry new_odom = getLastOdom();
00055 
00056   // check if the robot speed is now 0.37m.s-1
00057   EXPECT_NEAR(new_odom.twist.twist.linear.x, 0.37, JERK_LINEAR_VELOCITY_TOLERANCE);
00058   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
00059 
00060   cmd_vel.linear.x = 0.0;
00061   publish(cmd_vel);
00062 }
00063 
00064 TEST_F(DiffDriveControllerTest, testLinearAccelerationLimits)
00065 {
00066   // wait for ROS
00067   while(!isControllerAlive())
00068   {
00069     ros::Duration(0.1).sleep();
00070   }
00071   // zero everything before test
00072   geometry_msgs::Twist cmd_vel;
00073   cmd_vel.linear.x = 0.0;
00074   cmd_vel.angular.z = 0.0;
00075   publish(cmd_vel);
00076   ros::Duration(2.0).sleep();
00077   // get initial odom
00078   nav_msgs::Odometry old_odom = getLastOdom();
00079   // send a big command
00080   cmd_vel.linear.x = 10.0;
00081   publish(cmd_vel);
00082   // wait for a while
00083   ros::Duration(0.5).sleep();
00084 
00085   nav_msgs::Odometry new_odom = getLastOdom();
00086 
00087   // check if the robot speed is now 0.5 m.s-1, which is 1.0m.s-2 * 0.5s
00088   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.5 + VELOCITY_TOLERANCE);
00089   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
00090 
00091   cmd_vel.linear.x = 0.0;
00092   publish(cmd_vel);
00093 }
00094 
00095 TEST_F(DiffDriveControllerTest, testLinearVelocityLimits)
00096 {
00097   // wait for ROS
00098   while(!isControllerAlive())
00099   {
00100     ros::Duration(0.1).sleep();
00101   }
00102   // zero everything before test
00103   geometry_msgs::Twist cmd_vel;
00104   cmd_vel.linear.x = 0.0;
00105   cmd_vel.angular.z = 0.0;
00106   publish(cmd_vel);
00107   ros::Duration(2.0).sleep();
00108   // get initial odom
00109   nav_msgs::Odometry old_odom = getLastOdom();
00110   // send a big command
00111   cmd_vel.linear.x = 10.0;
00112   publish(cmd_vel);
00113   // wait for a while
00114   ros::Duration(5.0).sleep();
00115 
00116   nav_msgs::Odometry new_odom = getLastOdom();
00117 
00118   // check if the robot speed is now 1.0 m.s-1, the limit
00119   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 1.0 + VELOCITY_TOLERANCE);
00120   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
00121 
00122   cmd_vel.linear.x = 0.0;
00123   publish(cmd_vel);
00124 }
00125 
00126 /* This test has been failing on Travis for a long time due to timing issues however it works well when ran manually
00127 TEST_F(DiffDriveControllerTest, testAngularJerkLimits)
00128 {
00129   // wait for ROS
00130   while(!isControllerAlive())
00131   {
00132     ros::Duration(0.1).sleep();
00133   }
00134   // zero everything before test
00135   geometry_msgs::Twist cmd_vel;
00136   cmd_vel.linear.x = 0.0;
00137   cmd_vel.angular.z = 0.0;
00138   publish(cmd_vel);
00139   ros::Duration(2.0).sleep();
00140   // get initial odom
00141   nav_msgs::Odometry old_odom = getLastOdom();
00142   // send a big command
00143   cmd_vel.angular.z = 10.0;
00144   publish(cmd_vel);
00145   // wait for a while
00146   ros::Duration(0.5).sleep();
00147 
00148   nav_msgs::Odometry new_odom = getLastOdom();
00149 
00150   // check if the robot speed is now 0.7rad.s-1
00151   EXPECT_NEAR(new_odom.twist.twist.angular.z, 0.7, JERK_ANGULAR_VELOCITY_TOLERANCE);
00152   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
00153 
00154   cmd_vel.angular.z = 0.0;
00155   publish(cmd_vel);
00156 }
00157 */
00158 
00159 TEST_F(DiffDriveControllerTest, testAngularAccelerationLimits)
00160 {
00161   // wait for ROS
00162   while(!isControllerAlive())
00163   {
00164     ros::Duration(0.1).sleep();
00165   }
00166   // zero everything before test
00167   geometry_msgs::Twist cmd_vel;
00168   cmd_vel.linear.x = 0.0;
00169   cmd_vel.angular.z = 0.0;
00170   publish(cmd_vel);
00171   ros::Duration(2.0).sleep();
00172   // get initial odom
00173   nav_msgs::Odometry old_odom = getLastOdom();
00174   // send a big command
00175   cmd_vel.angular.z = 10.0;
00176   publish(cmd_vel);
00177   // wait for a while
00178   ros::Duration(0.5).sleep();
00179 
00180   nav_msgs::Odometry new_odom = getLastOdom();
00181 
00182   // check if the robot speed is now 1.0rad.s-1, which is 2.0rad.s-2 * 0.5s
00183   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 1.0 + VELOCITY_TOLERANCE);
00184   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
00185 
00186   cmd_vel.angular.z = 0.0;
00187   publish(cmd_vel);
00188 }
00189 
00190 TEST_F(DiffDriveControllerTest, testAngularVelocityLimits)
00191 {
00192   // wait for ROS
00193   while(!isControllerAlive())
00194   {
00195     ros::Duration(0.1).sleep();
00196   }
00197   // zero everything before test
00198   geometry_msgs::Twist cmd_vel;
00199   cmd_vel.linear.x = 0.0;
00200   cmd_vel.angular.z = 0.0;
00201   publish(cmd_vel);
00202   ros::Duration(2.0).sleep();
00203   // get initial odom
00204   nav_msgs::Odometry old_odom = getLastOdom();
00205   // send a big command
00206   cmd_vel.angular.z = 10.0;
00207   publish(cmd_vel);
00208   // wait for a while
00209   ros::Duration(5.0).sleep();
00210 
00211   nav_msgs::Odometry new_odom = getLastOdom();
00212 
00213   // check if the robot speed is now 2.0rad.s-1, the limit
00214   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 2.0 + VELOCITY_TOLERANCE);
00215   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
00216 
00217   cmd_vel.angular.z = 0.0;
00218   publish(cmd_vel);
00219 }
00220 
00221 int main(int argc, char** argv)
00222 {
00223   testing::InitGoogleTest(&argc, argv);
00224   ros::init(argc, argv, "diff_drive_limits_test");
00225 
00226   ros::AsyncSpinner spinner(1);
00227   spinner.start();
00228   //ros::Duration(0.5).sleep();
00229   int ret = RUN_ALL_TESTS();
00230   spinner.stop();
00231   ros::shutdown();
00232   return ret;
00233 }


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