23 #include <dynamic_reconfigure/server.h>
26 #include <boost/thread.hpp>
32 #define PERIOD_RECORD_SIZE 5
33 #define ZERO_VEL_COMMAND geometry_msgs::Twist();
34 #define IS_ZERO_VEOCITY(a) ((a.linear.x == 0.0) && (a.linear.y == 0.0) && (a.angular.z == 0.0))
51 , dynamic_reconfigure_server(NULL)
57 ROS_INFO(
"Reconfigure request : %f %f %f %f %f %f %f %f",
58 config.speed_lim_vx, config.speed_lim_vy, config.speed_lim_w, config.accel_lim_vx, config.accel_lim_vy, config.accel_lim_w, config.decel_factor, config.decel_factor_safe);
153 ROS_WARN_STREAM(
"Velocity Smoother : input got inactive leaving us a non-zero target velocity ("
186 ROS_WARN(
"Using robot velocity feedback (%s) instead of last command: %f, %f, %f, %f",
195 geometry_msgs::TwistPtr cmd_vel;
202 cmd_vel.reset(
new geometry_msgs::Twist(
target_vel));
204 double vx_inc, vy_inc, w_inc, max_vx_inc, max_vy_inc, max_w_inc;
210 max_vx_inc = decel_vx*period;
221 max_vy_inc = decel_vy*period;
232 max_w_inc = decel_w*period;
263 if (std::abs(vx_inc) > max_vx_inc)
269 if (std::abs(vy_inc) > max_vy_inc)
275 if (std::abs(w_inc) > max_w_inc)
313 nh.
param(
"robot_feedback", feedback, (
int)
NONE);
315 if ((
int(feedback) <
NONE) || (
int(feedback) >
COMMANDS))
317 ROS_WARN(
"Invalid robot feedback type (%d). Valid options are 0 (NONE, default), 1 (ODOMETRY) and 2 (COMMANDS)",
329 ROS_ERROR(
"Missing velocity limit parameter(s)");
337 ROS_ERROR(
"Missing acceleration limit parameter(s)");