31 #include "../common/include/test_common.h" 37 while(!isControllerAlive())
42 geometry_msgs::Twist cmd_vel;
43 cmd_vel.linear.x = 0.0;
44 cmd_vel.angular.z = 0.0;
49 nav_msgs::Odometry old_odom = getLastOdom();
51 cmd_vel.linear.x = 1.0;
56 nav_msgs::Odometry new_odom = getLastOdom();
59 EXPECT_LT(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x), 0.8);
62 int main(
int argc,
char** argv)
64 testing::InitGoogleTest(&argc, argv);
65 ros::init(argc, argv,
"ackermann_steering_controller_timeout_test");
69 int ret = RUN_ALL_TESTS();
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST_F(AckermannSteeringControllerTest, testTimeout)
int main(int argc, char **argv)
ROSCPP_DECL void shutdown()