17 #include <dynamic_reconfigure/server.h>    18 #include <yocs_velocity_smoother/paramsConfig.h>    28 #define PERIOD_RECORD_SIZE    5    29 #define ZERO_VEL_COMMAND      geometry_msgs::Twist();    30 #define IS_ZERO_VEOCITY(a)   ((a.linear.x == 0.0) && (a.angular.z == 0.0))    48 , dynamic_reconfigure_server(NULL)
    54   ROS_INFO(
"Reconfigure request : %f %f %f %f %f",
    55            config.speed_lim_v, config.speed_lim_w, config.accel_lim_v, config.accel_lim_w, config.decel_factor);
   137         ROS_WARN_STREAM(
"Velocity Smoother : input got inactive leaving us a non-zero target velocity ("   157         ROS_WARN_STREAM(
"Velocity Smoother : using robot velocity feedback " <<
   159                         " instead of last command: " <<
   168     geometry_msgs::TwistPtr cmd_vel;
   174       cmd_vel.reset(
new geometry_msgs::Twist(
target_vel));
   176       double v_inc, w_inc, max_v_inc, max_w_inc;
   203       double MA = sqrt(    v_inc *     v_inc +     w_inc *     w_inc);
   204       double MB = sqrt(max_v_inc * max_v_inc + max_w_inc * max_w_inc);
   206       double Av = std::abs(v_inc) / MA;
   207       double Aw = std::abs(w_inc) / MA;
   208       double Bv = max_v_inc / MB;
   209       double Bw = max_w_inc / MB;
   210       double theta = atan2(Bw, Bv) - atan2(Aw, Av);
   215         max_v_inc = (max_w_inc*std::abs(v_inc))/std::abs(w_inc);
   220         max_w_inc = (max_v_inc*std::abs(w_inc))/std::abs(v_inc);
   223       if (std::abs(v_inc) > max_v_inc)
   229       if (std::abs(w_inc) > max_w_inc)
   267   nh.
param(
"robot_feedback", feedback, (
int)
NONE);
   269   if ((
int(feedback) < NONE) || (
int(feedback) > 
COMMANDS))
   271     ROS_WARN(
"Invalid robot feedback type (%d). Valid options are 0 (NONE, default), 1 (ODOMETRY) and 2 (COMMANDS)",
   282     ROS_ERROR(
"Missing velocity limit parameter(s)");
   289     ROS_ERROR(
"Missing acceleration limit parameter(s)");
   317     NODELET_DEBUG(
"Velocity Smoother : waiting for worker thread to finish...");
   318     vel_smoother_->shutdown();
   319     worker_thread_.join();
   323     size_t pos = name.find_last_of(
'/');
   324     return name.substr(pos + 1);
   332     std::string 
name = unresolvedName(resolved_name); 
   335     if (vel_smoother_->init(ph))
 const std::string & getUnresolvedNamespace() const 
VelocitySmootherNodelet()
ros::Publisher smooth_vel_pub
void robotVelCB(const geometry_msgs::Twist::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const 
ros::Subscriber raw_in_vel_sub
std::string unresolvedName(const std::string &name) const 
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
#define IS_ZERO_VEOCITY(a)
ecl::Thread worker_thread_
void velocityCB(const geometry_msgs::Twist::ConstPtr &msg)
enum yocs_velocity_smoother::VelocitySmoother::RobotFeedbackType robot_feedback
std::vector< double > period_record
geometry_msgs::Twist target_vel
VelocitySmoother(const std::string &name)
PLUGINLIB_EXPORT_CLASS(yocs_velocity_smoother::VelocitySmootherNodelet, nodelet::Nodelet)
#define NODELET_ERROR_STREAM(...)
void odometryCB(const nav_msgs::Odometry::ConstPtr &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
ros::Subscriber odometry_sub
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< VelocitySmoother > vel_smoother_
#define PERIOD_RECORD_SIZE
#define ROS_WARN_STREAM(args)
#define NODELET_DEBUG_STREAM(...)
void reconfigCB(yocs_velocity_smoother::paramsConfig &config, uint32_t unused_level)
bool init(ros::NodeHandle &nh)
geometry_msgs::Twist last_cmd_vel
dynamic_reconfigure::Server< yocs_velocity_smoother::paramsConfig >::CallbackType dynamic_reconfigure_callback
dynamic_reconfigure::Server< yocs_velocity_smoother::paramsConfig > * dynamic_reconfigure_server
bool getParam(const std::string &key, std::string &s) const 
geometry_msgs::Twist current_vel
double median(std::vector< double > values)
ros::Subscriber current_vel_sub
~VelocitySmootherNodelet()
Velocity smoother interface. 
#define NODELET_DEBUG(...)