#include <velocity_smoother_nodelet.hpp>
|  | 
| double | median (std::vector< double > values) | 
|  | 
| void | odometryCB (const nav_msgs::Odometry::ConstPtr &msg) | 
|  | 
| void | reconfigCB (yocs_velocity_smoother::paramsConfig &config, uint32_t unused_level) | 
|  | 
| void | robotVelCB (const geometry_msgs::Twist::ConstPtr &msg) | 
|  | 
| double | sign (double x) | 
|  | 
| void | velocityCB (const geometry_msgs::Twist::ConstPtr &msg) | 
|  | 
      
        
          | yocs_velocity_smoother::VelocitySmoother::VelocitySmoother | ( | const std::string & | name | ) |  | 
      
 
 
  
  | 
        
          | yocs_velocity_smoother::VelocitySmoother::~VelocitySmoother | ( |  | ) |  |  | inline | 
 
 
      
        
          | bool yocs_velocity_smoother::VelocitySmoother::init | ( | ros::NodeHandle & | nh | ) |  | 
      
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::median | ( | std::vector< double > | values | ) |  |  | inlineprivate | 
 
 
  
  | 
        
          | void yocs_velocity_smoother::VelocitySmoother::odometryCB | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |  |  | private | 
 
 
  
  | 
        
          | void yocs_velocity_smoother::VelocitySmoother::reconfigCB | ( | yocs_velocity_smoother::paramsConfig & | config, |  
          |  |  | uint32_t | unused_level |  
          |  | ) |  |  |  | private | 
 
 
  
  | 
        
          | void yocs_velocity_smoother::VelocitySmoother::robotVelCB | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |  |  | private | 
 
 
  
  | 
        
          | void yocs_velocity_smoother::VelocitySmoother::shutdown | ( |  | ) |  |  | inline | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::sign | ( | double | x | ) |  |  | inlineprivate | 
 
 
      
        
          | void yocs_velocity_smoother::VelocitySmoother::spin | ( |  | ) |  | 
      
 
 
  
  | 
        
          | void yocs_velocity_smoother::VelocitySmoother::velocityCB | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |  |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::accel_lim_v |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::accel_lim_w |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::cb_avg_time |  | private | 
 
 
  
  | 
        
          | geometry_msgs::Twist yocs_velocity_smoother::VelocitySmoother::current_vel |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::decel_factor |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::decel_lim_v |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::decel_lim_w |  | private | 
 
 
  
  | 
        
          | dynamic_reconfigure::Server<yocs_velocity_smoother::paramsConfig>::CallbackType yocs_velocity_smoother::VelocitySmoother::dynamic_reconfigure_callback |  | private | 
 
 
  
  | 
        
          | dynamic_reconfigure::Server<yocs_velocity_smoother::paramsConfig>* yocs_velocity_smoother::VelocitySmoother::dynamic_reconfigure_server |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::frequency |  | private | 
 
 
  
  | 
        
          | bool yocs_velocity_smoother::VelocitySmoother::input_active |  | private | 
 
 
  
  | 
        
          | ros::Time yocs_velocity_smoother::VelocitySmoother::last_cb_time |  | private | 
 
 
  
  | 
        
          | geometry_msgs::Twist yocs_velocity_smoother::VelocitySmoother::last_cmd_vel |  | private | 
 
 
  
  | 
        
          | std::string yocs_velocity_smoother::VelocitySmoother::name |  | private | 
 
 
  
  | 
        
          | std::vector<double> yocs_velocity_smoother::VelocitySmoother::period_record |  | private | 
 
 
  
  | 
        
          | unsigned int yocs_velocity_smoother::VelocitySmoother::pr_next |  | private | 
 
 
  
  | 
        
          | bool yocs_velocity_smoother::VelocitySmoother::quiet |  | private | 
 
 
What source to use as robot velocity feedback 
 
 
  
  | 
        
          | bool yocs_velocity_smoother::VelocitySmoother::shutdown_req |  | private | 
 
 
  
  | 
        
          | ros::Publisher yocs_velocity_smoother::VelocitySmoother::smooth_vel_pub |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::speed_lim_v |  | private | 
 
 
  
  | 
        
          | double yocs_velocity_smoother::VelocitySmoother::speed_lim_w |  | private | 
 
 
  
  | 
        
          | geometry_msgs::Twist yocs_velocity_smoother::VelocitySmoother::target_vel |  | private | 
 
 
The documentation for this class was generated from the following files: