31 #include <geometry_msgs/Twist.h> 32 #include <sensor_msgs/PointCloud2.h> 37 #include <gtest/gtest.h> 43 geometry_msgs::Twist::ConstPtr cmd_vel;
44 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
45 [&cmd_vel](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 53 for (
int with_cloud = 0; with_cloud < 3; ++with_cloud)
55 for (
int with_watchdog_reset = 0; with_watchdog_reset < 2; ++with_watchdog_reset)
60 for (
int i = 0; i < 20; ++i)
64 if (with_watchdog_reset > 0)
65 publishWatchdogReset();
71 publishSinglePointPointcloud2(1000, 1000, 0,
"base_link",
ros::Time::now());
73 publishSinglePointPointcloud2(1000, 1000, 0,
"base_link",
ros::Time());
76 const float vel = 0.1;
77 const float ang_vel = 0.2;
78 publishTwist(vel, ang_vel);
85 if (with_watchdog_reset > 0 && with_cloud > 1)
87 ASSERT_EQ(cmd_vel->linear.x, vel);
88 ASSERT_EQ(cmd_vel->linear.y, 0.0);
89 ASSERT_EQ(cmd_vel->linear.z, 0.0);
90 ASSERT_EQ(cmd_vel->angular.x, 0.0);
91 ASSERT_EQ(cmd_vel->angular.y, 0.0);
92 ASSERT_EQ(cmd_vel->angular.z, ang_vel);
96 ASSERT_EQ(cmd_vel->linear.x, 0.0);
97 ASSERT_EQ(cmd_vel->linear.y, 0.0);
98 ASSERT_EQ(cmd_vel->linear.z, 0.0);
99 ASSERT_EQ(cmd_vel->angular.x, 0.0);
100 ASSERT_EQ(cmd_vel->angular.y, 0.0);
101 ASSERT_EQ(cmd_vel->angular.z, 0.0);
114 for (
int i = 0; i < 30 &&
ros::ok(); ++i)
116 publishSinglePointPointcloud2(0.5, 0, 0,
"base_link",
ros::Time::now());
117 publishWatchdogReset();
123 bool received =
false;
127 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
128 [&received, &failed, &en](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 134 ASSERT_NEAR(
msg->linear.x, 1.0, 1e-1);
139 for (
int i = 0; i < 60 * 6 &&
ros::ok() && !failed; ++i)
148 publishSinglePointPointcloud2(0.5, 0, 0,
"base_link",
ros::Time::now());
150 publishSinglePointPointcloud2(10, 0, 0,
"base_link",
ros::Time::now());
152 publishWatchdogReset();
153 publishTwist(2.0, 0);
158 ASSERT_TRUE(received);
166 for (
int i = 0; i < 10 &&
ros::ok(); ++i)
168 publishSinglePointPointcloud2(0.5, 0, 0,
"base_link",
ros::Time::now());
169 publishWatchdogReset();
175 for (
float vel = 0.0; vel < 2.0; vel += 0.4)
178 bool received =
false;
181 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
182 [&received, &failed, &en, vel](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 186 const float expected_vel = std::min<float>(vel, 1.0);
189 ASSERT_NEAR(
msg->linear.x, expected_vel, 1e-1);
194 for (
int i = 0; i < 10 &&
ros::ok() && !failed; ++i)
198 publishSinglePointPointcloud2(0.5, 0, 0,
"base_link",
ros::Time::now());
199 publishWatchdogReset();
200 publishTwist(vel, ((i % 5) - 2.0) * 0.01);
205 ASSERT_TRUE(received);
215 for (
int i = 0; i < 10 &&
ros::ok(); ++i)
217 publishSinglePointPointcloud2(-2.5, 0, 0,
"base_link",
ros::Time::now());
218 publishWatchdogReset();
224 for (
float vel = 0.0; vel > -2.0; vel -= 0.4)
227 bool received =
false;
230 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
231 [&received, &failed, &en, vel](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 235 const float expected_vel = std::max<float>(vel, -1.0);
238 ASSERT_NEAR(
msg->linear.x, expected_vel, 1e-1);
243 for (
int i = 0; i < 10 &&
ros::ok() && !failed; ++i)
247 publishSinglePointPointcloud2(-2.5, 0, 0,
"base_link",
ros::Time::now());
248 publishWatchdogReset();
249 publishTwist(vel, ((i % 5) - 2.0) * 0.01);
254 ASSERT_TRUE(received);
264 for (
int i = 0; i < 10 &&
ros::ok(); ++i)
266 publishSinglePointPointcloud2(-0.05, 0, 0,
"base_link",
ros::Time::now());
267 publishWatchdogReset();
273 const float vel_ref[] = { -0.2, -0.4, 0.2, 0.4 };
274 for (
const float vel : vel_ref)
277 bool received =
false;
280 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
281 [&received, &failed, &en, vel](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 289 ASSERT_NEAR(
msg->linear.x, vel, 1e-1);
292 ASSERT_NEAR(
msg->linear.x, 0.0, 1e-1);
297 for (
int i = 0; i < 10 &&
ros::ok() && !failed; ++i)
301 publishSinglePointPointcloud2(-0.05, 0, 0,
"base_link",
ros::Time::now());
302 publishWatchdogReset();
303 publishTwist(vel, 0.0);
308 ASSERT_TRUE(received);
318 for (
int i = 0; i < 10 &&
ros::ok(); ++i)
320 publishSinglePointPointcloud2(-1, -1, 0,
"base_link",
ros::Time::now());
321 publishWatchdogReset();
327 for (
float vel = 0.0; vel < M_PI; vel += M_PI / 10)
330 bool received =
false;
333 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
334 [&received, &failed, &en, vel](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 338 const float expected_vel = std::min<float>(vel, M_PI / 2);
341 ASSERT_NEAR(
msg->angular.z, expected_vel, M_PI / 20);
346 for (
int i = 0; i < 10 &&
ros::ok() && !failed; ++i)
350 publishSinglePointPointcloud2(-1, -1.1, 0,
"base_link",
ros::Time::now());
351 publishWatchdogReset();
352 publishTwist((i % 3) * 0.01, vel);
357 ASSERT_TRUE(received);
367 for (
int i = 0; i < 10 &&
ros::ok(); ++i)
369 publishSinglePointPointcloud2(-1, -0.09, 0,
"base_link",
ros::Time::now());
370 publishWatchdogReset();
376 const float vel_ref[] = { -0.2, -0.4, 0.2, 0.4 };
377 for (
const float vel : vel_ref)
380 bool received =
false;
383 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
384 [&received, &failed, &en, vel](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 392 ASSERT_NEAR(
msg->angular.z, vel, 1e-1);
395 ASSERT_NEAR(
msg->angular.z, 0.0, 1e-1);
400 for (
int i = 0; i < 10 &&
ros::ok() && !failed; ++i)
404 publishSinglePointPointcloud2(-1, -0.09, 0,
"base_link",
ros::Time::now());
405 publishWatchdogReset();
406 publishTwist(0.0, vel);
411 ASSERT_TRUE(received);
420 for (
float vel = 0.0; vel < 1.0; vel += 0.2)
422 for (
float ang_vel = 0.0; ang_vel < 1.0; ang_vel += 0.2)
424 bool received =
false;
427 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
428 [&received, &failed, &en, vel, ang_vel](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 432 ASSERT_NEAR(
msg->linear.x, vel, 1e-3);
433 ASSERT_NEAR(
msg->angular.z, ang_vel, 1e-3);
438 for (
int i = 0; i < 10 &&
ros::ok() && !failed; ++i)
442 publishSinglePointPointcloud2(1000, 1000, 0,
"base_link",
ros::Time::now());
443 publishWatchdogReset();
444 publishTwist(vel, ang_vel);
449 ASSERT_TRUE(received);
457 const float dt = 0.02;
460 const float velocities[] =
464 for (
const float vel : velocities)
468 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
469 [dt, &x, &stop](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 471 if (std::abs(
msg->linear.x) < 1e-4 && x > 0.5)
474 x += dt *
msg->linear.x;
478 for (
int i = 0; i < lround(10.0 / dt) &&
ros::ok() && !stop; ++i)
481 publishSinglePointPointcloud2(1.0 - x, 0, 0,
"base_link",
ros::Time::now());
483 publishSinglePointPointcloud2(-3.0 - x, 0, 0,
"base_link",
ros::Time::now());
485 publishWatchdogReset();
486 publishTwist(vel, 0.0);
505 int main(
int argc,
char** argv)
507 testing::InitGoogleTest(&argc, argv);
508 ros::init(argc, argv,
"test_safety_limiter");
510 return RUN_ALL_TESTS();
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
TEST_F(SafetyLimiterTest, Timeouts)
ROSCPP_DECL void spinOnce()