steer_drive_controller_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 
00030 
00031 #include "../common/include/test_common.h"
00032 
00033 // TEST CASES
00034 TEST_F(SteerDriveControllerTest, testLinearJerkLimits)
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(2.0).sleep();
00047   // get initial odom
00048   nav_msgs::Odometry old_odom = getLastOdom();
00049   // send a big command
00050   cmd_vel.linear.x = 10.0;
00051   publish(cmd_vel);
00052   // wait for a while
00053   ros::Duration(0.5).sleep();
00054 
00055   nav_msgs::Odometry new_odom = getLastOdom();
00056 
00057   // check if the robot speed is now 0.37m.s-1
00058   EXPECT_NEAR(new_odom.twist.twist.linear.x, 0.37, JERK_LINEAR_VELOCITY_TOLERANCE);
00059   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
00060 
00061   cmd_vel.linear.x = 0.0;
00062   publish(cmd_vel);
00063 }
00064 
00065 TEST_F(SteerDriveControllerTest, testLinearAccelerationLimits)
00066 {
00067   // wait for ROS
00068   while(!isControllerAlive())
00069   {
00070     ros::Duration(0.1).sleep();
00071   }
00072   // zero everything before test
00073   geometry_msgs::Twist cmd_vel;
00074   cmd_vel.linear.x = 0.0;
00075   cmd_vel.angular.z = 0.0;
00076   publish(cmd_vel);
00077   ros::Duration(2.0).sleep();
00078   // get initial odom
00079   nav_msgs::Odometry old_odom = getLastOdom();
00080   // send a big command
00081   cmd_vel.linear.x = 10.0;
00082   publish(cmd_vel);
00083   // wait for a while
00084   ros::Duration(0.5).sleep();
00085 
00086   nav_msgs::Odometry new_odom = getLastOdom();
00087 
00088   // check if the robot speed is now 0.5 m.s-1, which is 1.0m.s-2 * 0.5s
00089   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.5 + VELOCITY_TOLERANCE);
00090   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
00091 
00092   cmd_vel.linear.x = 0.0;
00093   publish(cmd_vel);
00094 }
00095 
00096 TEST_F(SteerDriveControllerTest, testLinearVelocityLimits)
00097 {
00098   // wait for ROS
00099   while(!isControllerAlive())
00100   {
00101     ros::Duration(0.1).sleep();
00102   }
00103   // zero everything before test
00104   geometry_msgs::Twist cmd_vel;
00105   cmd_vel.linear.x = 0.0;
00106   cmd_vel.angular.z = 0.0;
00107   publish(cmd_vel);
00108   ros::Duration(2.0).sleep();
00109   // get initial odom
00110   nav_msgs::Odometry old_odom = getLastOdom();
00111   // send a big command
00112   cmd_vel.linear.x = 10.0;
00113   publish(cmd_vel);
00114   // wait for a while
00115   ros::Duration(5.0).sleep();
00116 
00117   nav_msgs::Odometry new_odom = getLastOdom();
00118 
00119   // check if the robot speed is now 1.0 m.s-1, the limit
00120   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 1.0 + VELOCITY_TOLERANCE);
00121   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
00122 
00123   cmd_vel.linear.x = 0.0;
00124   publish(cmd_vel);
00125 }
00126 
00127 TEST_F(SteerDriveControllerTest, 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   // send linear command too 
00145   // because sending only angular command doesn't actuate wheels for steer drive mechanism
00146   cmd_vel.linear.x = 0.1;
00147   publish(cmd_vel);
00148   // wait for a while
00149   ros::Duration(0.5).sleep();
00150 
00151   nav_msgs::Odometry new_odom = getLastOdom();
00152 
00153   // check if the robot speed is now 0.18rad.s-1
00154   EXPECT_NEAR(new_odom.twist.twist.angular.z, 0.18, JERK_ANGULAR_VELOCITY_TOLERANCE);
00155   // check if the robot speed is now 0.1m.s-1
00156   EXPECT_NEAR(new_odom.twist.twist.linear.x, 0.1, VELOCITY_TOLERANCE);
00157 
00158   cmd_vel.angular.z = 0.0;
00159   publish(cmd_vel);
00160 }
00161 
00162 TEST_F(SteerDriveControllerTest, testAngularAccelerationLimits)
00163 {
00164   // wait for ROS
00165   while(!isControllerAlive())
00166   {
00167     ros::Duration(0.1).sleep();
00168   }
00169   // zero everything before test
00170   geometry_msgs::Twist cmd_vel;
00171   cmd_vel.linear.x = 0.0;
00172   cmd_vel.angular.z = 0.0;
00173   publish(cmd_vel);
00174   ros::Duration(2.0).sleep();
00175   // get initial odom
00176   nav_msgs::Odometry old_odom = getLastOdom();
00177   // send a big command
00178   cmd_vel.angular.z = 10.0;
00179   // send linear command too 
00180   // because sending only angular command doesn't actuate wheels for steer drive mechanism
00181   cmd_vel.linear.x = 0.1;
00182   publish(cmd_vel);
00183   // wait for a while
00184   ros::Duration(0.5).sleep();
00185 
00186   nav_msgs::Odometry new_odom = getLastOdom();
00187 
00188   // check if the robot speed is now 0.25rad.s-1, which is 0.5.s-2 * 0.5s
00189   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 0.25 + VELOCITY_TOLERANCE);
00190   // check if the robot speed is now 0.1m.s-1
00191   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.1 + VELOCITY_TOLERANCE);
00192 
00193   cmd_vel.angular.z = 0.0;
00194   publish(cmd_vel);
00195 }
00196 
00197 TEST_F(SteerDriveControllerTest, testAngularVelocityLimits)
00198 {
00199   // wait for ROS
00200   while(!isControllerAlive())
00201   {
00202     ros::Duration(0.1).sleep();
00203   }
00204   // zero everything before test
00205   geometry_msgs::Twist cmd_vel;
00206   cmd_vel.linear.x = 0.0;
00207   cmd_vel.angular.z = 0.0;
00208   publish(cmd_vel);
00209   ros::Duration(2.0).sleep();
00210   // get initial odom
00211   nav_msgs::Odometry old_odom = getLastOdom();
00212   cmd_vel.angular.z = 10.0;
00213   // send linear command too 
00214   // because sending only angular command doesn't actuate wheels for steer drive mechanism
00215   cmd_vel.linear.x = 0.1;
00216   publish(cmd_vel);
00217   // wait for a while
00218   ros::Duration(5.0).sleep();
00219 
00220   nav_msgs::Odometry new_odom = getLastOdom();
00221 
00222   // check if the robot speed is now 0.5rad.s-1, the limit
00223   EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 0.5 + ANGULAR_VELOCITY_TOLERANCE);
00224   // check if the robot speed is now 0.1m.s-1
00225   EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.1 + VELOCITY_TOLERANCE);
00226 
00227   cmd_vel.angular.z = 0.0;
00228   publish(cmd_vel);
00229 }
00230 
00231 int main(int argc, char** argv)
00232 {
00233   testing::InitGoogleTest(&argc, argv);
00234   ros::init(argc, argv, "steer_drive_controller_limits_test");
00235 
00236   ros::AsyncSpinner spinner(1);
00237   spinner.start();
00238   //ros::Duration(0.5).sleep();
00239   int ret = RUN_ALL_TESTS();
00240   spinner.stop();
00241   ros::shutdown();
00242   return ret;
00243 }


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