38 while (!isControllerAlive()) {
42 geometry_msgs::Twist cmd_vel;
43 cmd_vel.linear.x = 0.0;
44 cmd_vel.angular.z = 0.0;
49 cmd_vel.linear.x = 0.1;
56 nav_msgs::Odometry odom = getLastOdom();
58 EXPECT_FALSE(std::isnan(odom.twist.twist.linear.x));
59 EXPECT_FALSE(std::isnan(odom.twist.twist.angular.z));
60 EXPECT_FALSE(std::isnan(odom.pose.pose.position.x));
61 EXPECT_FALSE(std::isnan(odom.pose.pose.position.y));
62 EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.z));
63 EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.w));
71 EXPECT_FALSE(std::isnan(odom.twist.twist.linear.x));
72 EXPECT_FALSE(std::isnan(odom.twist.twist.angular.z));
73 EXPECT_FALSE(std::isnan(odom.pose.pose.position.x));
74 EXPECT_FALSE(std::isnan(odom.pose.pose.position.y));
75 EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.z));
76 EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.w));
81 while (!isControllerAlive()) {
85 geometry_msgs::Twist cmd_vel;
86 cmd_vel.linear.x = 0.0;
87 cmd_vel.angular.z = 0.0;
92 for (
int i = 0; i < 10; ++i) {
93 geometry_msgs::Twist cmd_vel;
94 cmd_vel.linear.x = NAN;
95 cmd_vel.angular.z = NAN;
97 geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut();
98 EXPECT_FALSE(std::isnan(odom_msg.twist.linear.x));
99 EXPECT_FALSE(std::isnan(odom_msg.twist.angular.z));
103 nav_msgs::Odometry odom = getLastOdom();
104 EXPECT_DOUBLE_EQ(odom.twist.twist.linear.x, 0.0);
105 EXPECT_DOUBLE_EQ(odom.pose.pose.position.x, 0.0);
106 EXPECT_DOUBLE_EQ(odom.pose.pose.position.y, 0.0);
108 geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut();
109 EXPECT_DOUBLE_EQ(odom_msg.twist.linear.x, 0.0);
112 int main(
int argc,
char **argv) {
113 testing::InitGoogleTest(&argc, argv);
114 ros::init(argc, argv,
"diff_drive_nan_test");
118 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()