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, testForward)
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(0.1).sleep();
00046
00047 nav_msgs::Odometry old_odom = getLastOdom();
00048
00049 cmd_vel.linear.x = 0.1;
00050 publish(cmd_vel);
00051
00052 ros::Duration(10.0).sleep();
00053
00054 nav_msgs::Odometry new_odom = getLastOdom();
00055
00056
00057 EXPECT_NEAR(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x), 1.0, POSITION_TOLERANCE);
00058 EXPECT_LT(fabs(new_odom.pose.pose.position.y - old_odom.pose.pose.position.y), EPS);
00059 EXPECT_LT(fabs(new_odom.pose.pose.position.z - old_odom.pose.pose.position.z), EPS);
00060
00061
00062 double roll_old, pitch_old, yaw_old;
00063 double roll_new, pitch_new, yaw_new;
00064 tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
00065 tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
00066 EXPECT_LT(fabs(roll_new - roll_old), EPS);
00067 EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
00068 EXPECT_LT(fabs(yaw_new - yaw_old), EPS);
00069 EXPECT_NEAR(fabs(new_odom.twist.twist.linear.x), 0.1, EPS);
00070 EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
00071 EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
00072
00073 EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
00074 EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
00075 EXPECT_LT(fabs(new_odom.twist.twist.angular.z), EPS);
00076 }
00077
00078 TEST_F(DiffDriveControllerTest, testTurn)
00079 {
00080
00081 while(!isControllerAlive())
00082 {
00083 ros::Duration(0.1).sleep();
00084 }
00085
00086 geometry_msgs::Twist cmd_vel;
00087 cmd_vel.linear.x = 0.0;
00088 cmd_vel.angular.z = 0.0;
00089 publish(cmd_vel);
00090 ros::Duration(0.1).sleep();
00091
00092 nav_msgs::Odometry old_odom = getLastOdom();
00093
00094 cmd_vel.angular.z = M_PI/10.0;
00095 publish(cmd_vel);
00096
00097 ros::Duration(10.0).sleep();
00098
00099 nav_msgs::Odometry new_odom = getLastOdom();
00100
00101
00102 EXPECT_LT(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x), EPS);
00103 EXPECT_LT(fabs(new_odom.pose.pose.position.y - old_odom.pose.pose.position.y), EPS);
00104 EXPECT_LT(fabs(new_odom.pose.pose.position.z - old_odom.pose.pose.position.z), EPS);
00105
00106
00107 double roll_old, pitch_old, yaw_old;
00108 double roll_new, pitch_new, yaw_new;
00109 tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
00110 tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
00111 EXPECT_LT(fabs(roll_new - roll_old), EPS);
00112 EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
00113 EXPECT_NEAR(fabs(yaw_new - yaw_old), M_PI, ORIENTATION_TOLERANCE);
00114
00115 EXPECT_LT(fabs(new_odom.twist.twist.linear.x), EPS);
00116 EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
00117 EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
00118
00119 EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
00120 EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
00121 EXPECT_NEAR(fabs(new_odom.twist.twist.angular.z), M_PI/10.0, EPS);
00122 }
00123
00124 int main(int argc, char** argv)
00125 {
00126 testing::InitGoogleTest(&argc, argv);
00127 ros::init(argc, argv, "diff_drive_test");
00128
00129 ros::AsyncSpinner spinner(1);
00130 spinner.start();
00131
00132 int ret = RUN_ALL_TESTS();
00133 spinner.stop();
00134 ros::shutdown();
00135 return ret;
00136 }