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 #include <limits>
00034
00035
00036 TEST_F(DiffDriveControllerTest, testNaN)
00037 {
00038
00039 while(!isControllerAlive())
00040 {
00041 ros::Duration(0.1).sleep();
00042 }
00043
00044 geometry_msgs::Twist cmd_vel;
00045 cmd_vel.linear.x = 0.0;
00046 cmd_vel.angular.z = 0.0;
00047 publish(cmd_vel);
00048 ros::Duration(2.0).sleep();
00049
00050
00051 cmd_vel.linear.x = 0.1;
00052 ros::Duration(2.0).sleep();
00053
00054
00055 stop();
00056 ros::Duration(2.0).sleep();
00057
00058 nav_msgs::Odometry odom = getLastOdom();
00059
00060 EXPECT_NE(std::isnan(odom.twist.twist.linear.x), true);
00061 EXPECT_NE(std::isnan(odom.twist.twist.angular.z), true);
00062 EXPECT_NE(std::isnan(odom.pose.pose.position.x), true);
00063 EXPECT_NE(std::isnan(odom.pose.pose.position.y), true);
00064 EXPECT_NE(std::isnan(odom.pose.pose.orientation.z), true);
00065 EXPECT_NE(std::isnan(odom.pose.pose.orientation.w), true);
00066
00067
00068 start();
00069 ros::Duration(2.0).sleep();
00070
00071 odom = getLastOdom();
00072
00073 EXPECT_NE(std::isnan(odom.twist.twist.linear.x), true);
00074 EXPECT_NE(std::isnan(odom.twist.twist.angular.z), true);
00075 EXPECT_NE(std::isnan(odom.pose.pose.position.x), true);
00076 EXPECT_NE(std::isnan(odom.pose.pose.position.y), true);
00077 EXPECT_NE(std::isnan(odom.pose.pose.orientation.z), true);
00078 EXPECT_NE(std::isnan(odom.pose.pose.orientation.w), true);
00079 }
00080
00081 int main(int argc, char** argv)
00082 {
00083 testing::InitGoogleTest(&argc, argv);
00084 ros::init(argc, argv, "diff_drive_nan_test");
00085
00086 ros::AsyncSpinner spinner(1);
00087 spinner.start();
00088 int ret = RUN_ALL_TESTS();
00089 spinner.stop();
00090 ros::shutdown();
00091 return ret;
00092 }