Go to the documentation of this file.00001 #include "gtest/gtest.h"
00002 #include "grizzly_motion/dead_reckoning.h"
00003
00004 #include "ros/console.h"
00005
00006 TEST(DeadReckoning, simple_straight)
00007 {
00008 ros::Time::init();
00009 ros::Time start = ros::Time::now();
00010 double wheel_radius = 0.2;
00011
00012 DeadReckoning dr(1.0, wheel_radius);
00013 nav_msgs::Odometry odom;
00014 grizzly_msgs::DrivePtr encoders(new grizzly_msgs::Drive);
00015 encoders->header.stamp = start;
00016 encoders->front_left = encoders->rear_left = 1.1;
00017 encoders->front_right = encoders->rear_right = 1.1;
00018 dr.next(encoders, &odom);
00019
00020
00021 for(int step = 0; step < 500; step++)
00022 {
00023 encoders->header.stamp += ros::Duration(0.02);
00024 EXPECT_TRUE(dr.next(encoders, &odom));
00025 }
00026
00027
00028 EXPECT_NEAR(10 * 1.1 * wheel_radius, odom.pose.pose.position.x, 0.005);
00029 EXPECT_NEAR(0.0, odom.pose.pose.position.y, 0.005);
00030 EXPECT_EQ(odom.header.stamp, encoders->header.stamp);
00031 }
00032
00033 TEST(DeadReckoning, curved_path)
00034 {
00035 ros::Time::init();
00036 ros::Time start = ros::Time::now();
00037 double wheel_radius = 0.1;
00038 double vehicle_width = 1.0;
00039
00040
00041
00042 double left_travel = 3.5*2 * M_PI / 4;
00043 double right_travel = 2.5*2 * M_PI / 4;
00044
00045 DeadReckoning dr(vehicle_width, wheel_radius);
00046 nav_msgs::Odometry odom;
00047 grizzly_msgs::DrivePtr encoders(new grizzly_msgs::Drive);
00048 encoders->header.stamp = start;
00049 encoders->front_left = encoders->rear_left = left_travel / wheel_radius / 10.0;
00050 encoders->front_right = encoders->rear_right = right_travel / wheel_radius / 10.0;
00051 dr.next(encoders, &odom);
00052
00053
00054 for(int step = 0; step < 500; step++)
00055 {
00056 encoders->header.stamp += ros::Duration(0.02);
00057 EXPECT_TRUE(dr.next(encoders, &odom));
00058 ROS_DEBUG_STREAM("ENC " << encoders->front_left << " " << encoders->front_right);
00059 ROS_DEBUG_STREAM("POSE " << odom.pose.pose.position.x << " " << odom.pose.pose.position.y);
00060 }
00061
00062
00063
00064 EXPECT_NEAR(3, odom.pose.pose.position.x, 0.05);
00065 EXPECT_NEAR(-3, odom.pose.pose.position.y, 0.05);
00066 EXPECT_EQ(odom.header.stamp, encoders->header.stamp);
00067 }
00068
00069 TEST(DeadReckoning, timeout)
00070 {
00071 ros::Time::init();
00072 ros::Time start = ros::Time::now();
00073
00074 nav_msgs::Odometry odom;
00075 grizzly_msgs::DrivePtr encoders(new grizzly_msgs::Drive);
00076 encoders->header.stamp = start;
00077
00078 DeadReckoning dr(1.0, 1.0);
00079 dr.next(encoders, &odom);
00080
00081
00082 encoders->header.stamp += ros::Duration(0.09);
00083 EXPECT_TRUE(dr.next(encoders, &odom));
00084
00085
00086 encoders->header.stamp += ros::Duration(0.11);
00087 EXPECT_FALSE(dr.next(encoders, &odom));
00088 }
00089
00090 int main(int argc, char **argv)
00091 {
00092 ::testing::InitGoogleTest(&argc, argv);
00093 return RUN_ALL_TESTS();
00094 }