36 #include <geometry_msgs/Twist.h>
37 #include <sensor_msgs/PointCloud2.h>
41 #include <gtest/gtest.h>
45 const float dt = 0.02;
46 const double ax = 2.0;
50 const float velocities[] = {-0.8, -0.4, 0.4, 0.8};
51 for (
const float vel : velocities)
55 const boost::function<void(
const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
56 [dt, ax, &x, &v, &stopped](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void
58 if (
msg->linear.x >= v)
60 v = std::min(v + ax * dt,
msg->linear.x);
64 v = std::max(v - ax * dt,
msg->linear.x);
68 if (std::abs(v) < 1e-4 && std::abs(x) > 0.5)
75 int count_after_stop = 10;
76 for (
float t = 0; t < 10.0 &&
ros::ok() && count_after_stop > 0; t += dt)
79 publishSinglePointPointcloud2(1.5 - x, 0, 0,
"base_link",
ros::Time::now());
81 publishSinglePointPointcloud2(-3.5 - x, 0, 0,
"base_link",
ros::Time::now());
82 publishWatchdogReset();
83 publishTwist(vel, 0.0);
84 broadcastTF(
"odom",
"base_link", x, 0.0);
112 int main(
int argc,
char** argv)
114 testing::InitGoogleTest(&argc, argv);
115 ros::init(argc, argv,
"test_safety_limiter");
117 return RUN_ALL_TESTS();