31 #include "../common/include/test_common.h" 40 while(!isControllerAlive())
45 geometry_msgs::Twist cmd_vel;
46 cmd_vel.linear.x = 0.0;
47 cmd_vel.angular.z = 0.0;
52 cmd_vel.linear.x = 0.1;
59 nav_msgs::Odometry odom = getLastOdom();
61 EXPECT_NE(std::isnan(odom.twist.twist.linear.x),
true);
62 EXPECT_NE(std::isnan(odom.twist.twist.angular.z),
true);
63 EXPECT_NE(std::isnan(odom.pose.pose.position.x),
true);
64 EXPECT_NE(std::isnan(odom.pose.pose.position.y),
true);
65 EXPECT_NE(std::isnan(odom.pose.pose.orientation.z),
true);
66 EXPECT_NE(std::isnan(odom.pose.pose.orientation.w),
true);
74 EXPECT_NE(std::isnan(odom.twist.twist.linear.x),
true);
75 EXPECT_NE(std::isnan(odom.twist.twist.angular.z),
true);
76 EXPECT_NE(std::isnan(odom.pose.pose.position.x),
true);
77 EXPECT_NE(std::isnan(odom.pose.pose.position.y),
true);
78 EXPECT_NE(std::isnan(odom.pose.pose.orientation.z),
true);
79 EXPECT_NE(std::isnan(odom.pose.pose.orientation.w),
true);
82 int main(
int argc,
char** argv)
84 testing::InitGoogleTest(&argc, argv);
85 ros::init(argc, argv,
"ackermann_steering_controller_nan_test");
89 int ret = RUN_ALL_TESTS();
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
TEST_F(AckermannSteeringControllerTest, testNaN)
ROSCPP_DECL void shutdown()