18 #ifndef VELOCITY_SMOOTHER_HPP_
19 #define VELOCITY_SMOOTHER_HPP_
26 #include <dynamic_reconfigure/server.h>
27 #include <cob_base_velocity_smoother/paramsConfig.h>
28 #include <nav_msgs/Odometry.h>
40 class VelocitySmoother
87 void velocityCB(
const geometry_msgs::Twist::ConstPtr& msg);
88 void robotVelCB(
const geometry_msgs::Twist::ConstPtr& msg);
89 void odometryCB(
const nav_msgs::Odometry::ConstPtr& msg);
91 double sign(
double x) {
return x < 0.0 ? -1.0 : +1.0; };
93 double median(std::vector<double> values) {
95 nth_element(values.begin(), values.begin() + values.size()/2, values.end());
96 return values[values.size()/2];
104 void reconfigCB(cob_base_velocity_smoother::paramsConfig &config, uint32_t unused_level);