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 #include <tf/transform_listener.h>
00032
00033
00034 TEST_F(DiffDriveControllerTest, testForward)
00035 {
00036
00037 while(!isControllerAlive())
00038 {
00039 ros::Duration(0.1).sleep();
00040 }
00041
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
00048 nav_msgs::Odometry old_odom = getLastOdom();
00049
00050 cmd_vel.linear.x = 0.1;
00051 publish(cmd_vel);
00052
00053 ros::Duration(10.0).sleep();
00054
00055 nav_msgs::Odometry new_odom = getLastOdom();
00056
00057
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
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
00084 while(!isControllerAlive())
00085 {
00086 ros::Duration(0.1).sleep();
00087 }
00088
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
00095 nav_msgs::Odometry old_odom = getLastOdom();
00096
00097 cmd_vel.angular.z = M_PI/10.0;
00098 publish(cmd_vel);
00099
00100 ros::Duration(10.0).sleep();
00101
00102 nav_msgs::Odometry new_odom = getLastOdom();
00103
00104
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
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
00130 while(!isControllerAlive())
00131 {
00132 ros::Duration(0.1).sleep();
00133 }
00134
00135 tf::TransformListener listener;
00136 ros::Duration(2.0).sleep();
00137
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
00149 int ret = RUN_ALL_TESTS();
00150 spinner.stop();
00151 ros::shutdown();
00152 return ret;
00153 }