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;
48 nav_msgs::Odometry old_odom = getLastOdom();
50 cmd_vel.linear.x = 10.0;
55 nav_msgs::Odometry new_odom = getLastOdom();
59 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
61 cmd_vel.linear.x = 0.0;
68 while(!isControllerAlive())
73 geometry_msgs::Twist cmd_vel;
74 cmd_vel.linear.x = 0.0;
75 cmd_vel.angular.z = 0.0;
79 nav_msgs::Odometry old_odom = getLastOdom();
81 cmd_vel.linear.x = 10.0;
86 nav_msgs::Odometry new_odom = getLastOdom();
89 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.5 +
VELOCITY_TOLERANCE);
90 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
92 cmd_vel.linear.x = 0.0;
99 while(!isControllerAlive())
104 geometry_msgs::Twist cmd_vel;
105 cmd_vel.linear.x = 0.0;
106 cmd_vel.angular.z = 0.0;
110 nav_msgs::Odometry old_odom = getLastOdom();
112 cmd_vel.linear.x = 10.0;
117 nav_msgs::Odometry new_odom = getLastOdom();
120 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 1.0 +
VELOCITY_TOLERANCE);
121 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z),
EPS);
123 cmd_vel.linear.x = 0.0;
130 while(!isControllerAlive())
135 geometry_msgs::Twist cmd_vel;
136 cmd_vel.linear.x = 0.0;
137 cmd_vel.angular.z = 0.0;
141 nav_msgs::Odometry old_odom = getLastOdom();
143 cmd_vel.angular.z = 10.0;
146 cmd_vel.linear.x = 0.1;
151 nav_msgs::Odometry new_odom = getLastOdom();
158 cmd_vel.angular.z = 0.0;
165 while(!isControllerAlive())
170 geometry_msgs::Twist cmd_vel;
171 cmd_vel.linear.x = 0.0;
172 cmd_vel.angular.z = 0.0;
176 nav_msgs::Odometry old_odom = getLastOdom();
178 cmd_vel.angular.z = 10.0;
181 cmd_vel.linear.x = 0.1;
186 nav_msgs::Odometry new_odom = getLastOdom();
189 EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 0.25 +
VELOCITY_TOLERANCE);
191 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.1 +
VELOCITY_TOLERANCE);
193 cmd_vel.angular.z = 0.0;
200 while(!isControllerAlive())
205 geometry_msgs::Twist cmd_vel;
206 cmd_vel.linear.x = 0.0;
207 cmd_vel.angular.z = 0.0;
211 nav_msgs::Odometry old_odom = getLastOdom();
212 cmd_vel.angular.z = 10.0;
215 cmd_vel.linear.x = 0.1;
220 nav_msgs::Odometry new_odom = getLastOdom();
225 EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.1 +
VELOCITY_TOLERANCE);
227 cmd_vel.angular.z = 0.0;
231 int main(
int argc,
char** argv)
233 testing::InitGoogleTest(&argc, argv);
234 ros::init(argc, argv,
"ackermann_steering_controller_limits_test");
239 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(AckermannSteeringControllerTest, testLinearJerkLimits)
const double JERK_ANGULAR_VELOCITY_TOLERANCE
int main(int argc, char **argv)
const double JERK_LINEAR_VELOCITY_TOLERANCE
const double ANGULAR_VELOCITY_TOLERANCE
ROSCPP_DECL void shutdown()