39 geometry_msgs::Twist cmd_vel;
40 cmd_vel.linear.x = 0.0;
41 cmd_vel.angular.z = 0.0;
45 nav_msgs::Odometry old_odom = getLastOdom();
47 cmd_vel.linear.x = 10.0;
52 nav_msgs::Odometry new_odom = getLastOdom();
56 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
58 cmd_vel.linear.x = 0.0;
65 while(!isControllerAlive())
70 geometry_msgs::Twist cmd_vel;
71 cmd_vel.linear.x = 0.0;
72 cmd_vel.angular.z = 0.0;
76 nav_msgs::Odometry old_odom = getLastOdom();
78 cmd_vel.linear.x = 10.0;
83 nav_msgs::Odometry new_odom = getLastOdom();
86 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.5 +
VELOCITY_TOLERANCE);
87 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
89 cmd_vel.linear.x = 0.0;
96 while(!isControllerAlive())
101 geometry_msgs::Twist cmd_vel;
102 cmd_vel.linear.x = 0.0;
103 cmd_vel.angular.z = 0.0;
107 nav_msgs::Odometry old_odom = getLastOdom();
109 cmd_vel.linear.x = 10.0;
114 nav_msgs::Odometry new_odom = getLastOdom();
117 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 1.0 +
VELOCITY_TOLERANCE);
118 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
120 cmd_vel.linear.x = 0.0;
160 while(!isControllerAlive())
165 geometry_msgs::Twist cmd_vel;
166 cmd_vel.linear.x = 0.0;
167 cmd_vel.angular.z = 0.0;
171 nav_msgs::Odometry old_odom = getLastOdom();
173 cmd_vel.angular.z = 10.0;
178 nav_msgs::Odometry new_odom = getLastOdom();
181 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 1.0 +
VELOCITY_TOLERANCE);
182 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x),
EPS);
184 cmd_vel.angular.z = 0.0;
191 while(!isControllerAlive())
196 geometry_msgs::Twist cmd_vel;
197 cmd_vel.linear.x = 0.0;
198 cmd_vel.angular.z = 0.0;
202 nav_msgs::Odometry old_odom = getLastOdom();
204 cmd_vel.angular.z = 10.0;
209 nav_msgs::Odometry new_odom = getLastOdom();
212 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 2.0 +
VELOCITY_TOLERANCE);
213 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x),
EPS);
215 cmd_vel.angular.z = 0.0;
219 int main(
int argc,
char** argv)
221 testing::InitGoogleTest(&argc, argv);
222 ros::init(argc, argv,
"diff_drive_limits_test");
227 int ret = RUN_ALL_TESTS();