36 #include <geometry_msgs/Twist.h> 37 #include <sensor_msgs/PointCloud2.h> 41 #include <gtest/gtest.h> 45 const float dt = 0.02;
48 const float velocities[] =
52 for (
const float vel : velocities)
56 const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
57 [dt, &x, &stop](
const geometry_msgs::Twist::ConstPtr&
msg) ->
void 59 if (std::abs(
msg->linear.x) < 1e-4 && x > 0.5)
62 x += dt *
msg->linear.x;
66 for (
int i = 0; i < std::lround(10.0 / dt) &&
ros::ok() && !stop; ++i)
69 publishSinglePointPointcloud2(1.0 - x, 0, 0,
"base_link",
ros::Time::now());
71 publishSinglePointPointcloud2(-3.0 - x, 0, 0,
"base_link",
ros::Time::now());
72 publishWatchdogReset();
73 publishTwist(vel, 0.0);
74 broadcastTF(
"odom",
"base_link", x, 0.0);
94 int main(
int argc,
char** argv)
96 testing::InitGoogleTest(&argc, argv);
97 ros::init(argc, argv,
"test_safety_limiter");
99 return RUN_ALL_TESTS();
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST_F(SafetyLimiterTest, SafetyLimitLinearSimpleSimulationWithMargin)
TFSIMD_FORCE_INLINE const tfScalar & x() const
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()