36 while(!isControllerAlive())
41 geometry_msgs::Twist cmd_vel;
42 cmd_vel.linear.x = 0.0;
43 cmd_vel.angular.z = 0.0;
47 nav_msgs::Odometry old_odom = getLastOdom();
49 cmd_vel.linear.x = 10.0;
54 nav_msgs::Odometry new_odom = getLastOdom();
58 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
60 cmd_vel.linear.x = 0.0;
67 while(!isControllerAlive())
72 geometry_msgs::Twist cmd_vel;
73 cmd_vel.linear.x = 0.0;
74 cmd_vel.angular.z = 0.0;
78 nav_msgs::Odometry old_odom = getLastOdom();
80 cmd_vel.linear.x = 10.0;
85 nav_msgs::Odometry new_odom = getLastOdom();
88 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.5 +
VELOCITY_TOLERANCE);
89 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
91 cmd_vel.linear.x = 0.0;
98 while(!isControllerAlive())
103 geometry_msgs::Twist cmd_vel;
104 cmd_vel.linear.x = 0.0;
105 cmd_vel.angular.z = 0.0;
109 nav_msgs::Odometry old_odom = getLastOdom();
111 cmd_vel.linear.x = 10.0;
116 nav_msgs::Odometry new_odom = getLastOdom();
119 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 1.0 +
VELOCITY_TOLERANCE);
120 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
122 cmd_vel.linear.x = 0.0;
162 while(!isControllerAlive())
167 geometry_msgs::Twist cmd_vel;
168 cmd_vel.linear.x = 0.0;
169 cmd_vel.angular.z = 0.0;
173 nav_msgs::Odometry old_odom = getLastOdom();
175 cmd_vel.angular.z = 10.0;
180 nav_msgs::Odometry new_odom = getLastOdom();
183 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 1.0 +
VELOCITY_TOLERANCE);
184 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x),
EPS);
186 cmd_vel.angular.z = 0.0;
193 while(!isControllerAlive())
198 geometry_msgs::Twist cmd_vel;
199 cmd_vel.linear.x = 0.0;
200 cmd_vel.angular.z = 0.0;
204 nav_msgs::Odometry old_odom = getLastOdom();
206 cmd_vel.angular.z = 10.0;
211 nav_msgs::Odometry new_odom = getLastOdom();
214 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 2.0 +
VELOCITY_TOLERANCE);
215 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x),
EPS);
217 cmd_vel.angular.z = 0.0;
221 int main(
int argc,
char** argv)
223 testing::InitGoogleTest(&argc, argv);
224 ros::init(argc, argv,
"diff_drive_limits_test");
229 int ret = RUN_ALL_TESTS();
const double VELOCITY_TOLERANCE
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST_F(DiffDriveControllerTest, testLinearJerkLimits)
const double JERK_LINEAR_VELOCITY_TOLERANCE
int main(int argc, char **argv)
ROSCPP_DECL void shutdown()