39 while(!isControllerAlive())
44 geometry_msgs::Twist cmd_vel;
45 cmd_vel.linear.x = 0.0;
46 cmd_vel.angular.z = 0.0;
51 cmd_vel.linear.x = 0.1;
58 nav_msgs::Odometry odom = getLastOdom();
60 EXPECT_NE(std::isnan(odom.twist.twist.linear.x),
true);
61 EXPECT_NE(std::isnan(odom.twist.twist.angular.z),
true);
62 EXPECT_NE(std::isnan(odom.pose.pose.position.x),
true);
63 EXPECT_NE(std::isnan(odom.pose.pose.position.y),
true);
64 EXPECT_NE(std::isnan(odom.pose.pose.orientation.z),
true);
65 EXPECT_NE(std::isnan(odom.pose.pose.orientation.w),
true);
73 EXPECT_NE(std::isnan(odom.twist.twist.linear.x),
true);
74 EXPECT_NE(std::isnan(odom.twist.twist.angular.z),
true);
75 EXPECT_NE(std::isnan(odom.pose.pose.position.x),
true);
76 EXPECT_NE(std::isnan(odom.pose.pose.position.y),
true);
77 EXPECT_NE(std::isnan(odom.pose.pose.orientation.z),
true);
78 EXPECT_NE(std::isnan(odom.pose.pose.orientation.w),
true);
81 int main(
int argc,
char** argv)
83 testing::InitGoogleTest(&argc, argv);
84 ros::init(argc, argv,
"diff_drive_nan_test");
88 int ret = RUN_ALL_TESTS();
TEST_F(DiffDriveControllerTest, testNaN)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ROSCPP_DECL void shutdown()