Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00027
00029
00030 #include "test_common.h"
00031
00032
00033 TEST_F(DiffDriveControllerTest, testLinearJerkLimits)
00034 {
00035
00036 while(!isControllerAlive())
00037 {
00038 ros::Duration(0.1).sleep();
00039 }
00040
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
00047 nav_msgs::Odometry old_odom = getLastOdom();
00048
00049 cmd_vel.linear.x = 10.0;
00050 publish(cmd_vel);
00051
00052 ros::Duration(0.5).sleep();
00053
00054 nav_msgs::Odometry new_odom = getLastOdom();
00055
00056
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
00067 while(!isControllerAlive())
00068 {
00069 ros::Duration(0.1).sleep();
00070 }
00071
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
00078 nav_msgs::Odometry old_odom = getLastOdom();
00079
00080 cmd_vel.linear.x = 10.0;
00081 publish(cmd_vel);
00082
00083 ros::Duration(0.5).sleep();
00084
00085 nav_msgs::Odometry new_odom = getLastOdom();
00086
00087
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
00098 while(!isControllerAlive())
00099 {
00100 ros::Duration(0.1).sleep();
00101 }
00102
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
00109 nav_msgs::Odometry old_odom = getLastOdom();
00110
00111 cmd_vel.linear.x = 10.0;
00112 publish(cmd_vel);
00113
00114 ros::Duration(5.0).sleep();
00115
00116 nav_msgs::Odometry new_odom = getLastOdom();
00117
00118
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 TEST_F(DiffDriveControllerTest, testAngularJerkLimits)
00127 {
00128
00129 while(!isControllerAlive())
00130 {
00131 ros::Duration(0.1).sleep();
00132 }
00133
00134 geometry_msgs::Twist cmd_vel;
00135 cmd_vel.linear.x = 0.0;
00136 cmd_vel.angular.z = 0.0;
00137 publish(cmd_vel);
00138 ros::Duration(2.0).sleep();
00139
00140 nav_msgs::Odometry old_odom = getLastOdom();
00141
00142 cmd_vel.angular.z = 10.0;
00143 publish(cmd_vel);
00144
00145 ros::Duration(0.5).sleep();
00146
00147 nav_msgs::Odometry new_odom = getLastOdom();
00148
00149
00150 EXPECT_NEAR(new_odom.twist.twist.angular.z, 0.7, JERK_ANGULAR_VELOCITY_TOLERANCE);
00151 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
00152
00153 cmd_vel.angular.z = 0.0;
00154 publish(cmd_vel);
00155 }
00156
00157 TEST_F(DiffDriveControllerTest, testAngularAccelerationLimits)
00158 {
00159
00160 while(!isControllerAlive())
00161 {
00162 ros::Duration(0.1).sleep();
00163 }
00164
00165 geometry_msgs::Twist cmd_vel;
00166 cmd_vel.linear.x = 0.0;
00167 cmd_vel.angular.z = 0.0;
00168 publish(cmd_vel);
00169 ros::Duration(2.0).sleep();
00170
00171 nav_msgs::Odometry old_odom = getLastOdom();
00172
00173 cmd_vel.angular.z = 10.0;
00174 publish(cmd_vel);
00175
00176 ros::Duration(0.5).sleep();
00177
00178 nav_msgs::Odometry new_odom = getLastOdom();
00179
00180
00181 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 1.0 + VELOCITY_TOLERANCE);
00182 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
00183
00184 cmd_vel.angular.z = 0.0;
00185 publish(cmd_vel);
00186 }
00187
00188 TEST_F(DiffDriveControllerTest, testAngularVelocityLimits)
00189 {
00190
00191 while(!isControllerAlive())
00192 {
00193 ros::Duration(0.1).sleep();
00194 }
00195
00196 geometry_msgs::Twist cmd_vel;
00197 cmd_vel.linear.x = 0.0;
00198 cmd_vel.angular.z = 0.0;
00199 publish(cmd_vel);
00200 ros::Duration(2.0).sleep();
00201
00202 nav_msgs::Odometry old_odom = getLastOdom();
00203
00204 cmd_vel.angular.z = 10.0;
00205 publish(cmd_vel);
00206
00207 ros::Duration(5.0).sleep();
00208
00209 nav_msgs::Odometry new_odom = getLastOdom();
00210
00211
00212 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 2.0 + VELOCITY_TOLERANCE);
00213 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
00214
00215 cmd_vel.angular.z = 0.0;
00216 publish(cmd_vel);
00217 }
00218
00219 int main(int argc, char** argv)
00220 {
00221 testing::InitGoogleTest(&argc, argv);
00222 ros::init(argc, argv, "diff_drive_limits_test");
00223
00224 ros::AsyncSpinner spinner(1);
00225 spinner.start();
00226
00227 int ret = RUN_ALL_TESTS();
00228 spinner.stop();
00229 ros::shutdown();
00230 return ret;
00231 }