Public Member Functions | Private Types | Private Member Functions | Private Attributes
yocs_velocity_smoother::VelocitySmoother Class Reference

#include <velocity_smoother_nodelet.hpp>

List of all members.

Public Member Functions

bool init (ros::NodeHandle &nh)
void shutdown ()
void spin ()
 VelocitySmoother (const std::string &name)
 ~VelocitySmoother ()

Private Types

enum  RobotFeedbackType { NONE, ODOMETRY, COMMANDS }

Private Member Functions

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)

Private Attributes

double accel_lim_v
double accel_lim_w
double cb_avg_time
geometry_msgs::Twist current_vel
ros::Subscriber current_vel_sub
double decel_factor
double decel_lim_v
double decel_lim_w
dynamic_reconfigure::Server
< yocs_velocity_smoother::paramsConfig >
::CallbackType 
dynamic_reconfigure_callback
dynamic_reconfigure::Server
< yocs_velocity_smoother::paramsConfig > * 
dynamic_reconfigure_server
double frequency
bool input_active
ros::Time last_cb_time
geometry_msgs::Twist last_cmd_vel
std::string name
ros::Subscriber odometry_sub
std::vector< double > period_record
unsigned int pr_next
ros::Subscriber raw_in_vel_sub
enum
yocs_velocity_smoother::VelocitySmoother::RobotFeedbackType 
robot_feedback
bool shutdown_req
ros::Publisher smooth_vel_pub
double speed_lim_v
double speed_lim_w
geometry_msgs::Twist target_vel

Detailed Description

Definition at line 33 of file velocity_smoother_nodelet.hpp.


Member Enumeration Documentation

Enumerator:
NONE 
ODOMETRY 
COMMANDS 

Definition at line 50 of file velocity_smoother_nodelet.hpp.


Constructor & Destructor Documentation

yocs_velocity_smoother::VelocitySmoother::VelocitySmoother ( const std::string &  name) [inline]

Definition at line 36 of file velocity_smoother_nodelet.hpp.

Definition at line 39 of file velocity_smoother_nodelet.hpp.


Member Function Documentation

Initialise from a nodelet's private nodehandle.

Parameters:
nh: private nodehandle
Returns:
bool : success or failure

Definition at line 239 of file velocity_smoother_nodelet.cpp.

double yocs_velocity_smoother::VelocitySmoother::median ( std::vector< double >  values) [inline, private]

Definition at line 86 of file velocity_smoother_nodelet.hpp.

void yocs_velocity_smoother::VelocitySmoother::odometryCB ( const nav_msgs::Odometry::ConstPtr &  msg) [private]

Definition at line 93 of file velocity_smoother_nodelet.cpp.

void yocs_velocity_smoother::VelocitySmoother::reconfigCB ( yocs_velocity_smoother::paramsConfig &  config,
uint32_t  unused_level 
) [private]

Definition at line 42 of file velocity_smoother_nodelet.cpp.

void yocs_velocity_smoother::VelocitySmoother::robotVelCB ( const geometry_msgs::Twist::ConstPtr &  msg) [private]

Definition at line 101 of file velocity_smoother_nodelet.cpp.

Definition at line 47 of file velocity_smoother_nodelet.hpp.

double yocs_velocity_smoother::VelocitySmoother::sign ( double  x) [inline, private]

Definition at line 84 of file velocity_smoother_nodelet.hpp.

Definition at line 109 of file velocity_smoother_nodelet.cpp.

void yocs_velocity_smoother::VelocitySmoother::velocityCB ( const geometry_msgs::Twist::ConstPtr &  msg) [private]

Definition at line 56 of file velocity_smoother_nodelet.cpp.


Member Data Documentation

Definition at line 58 of file velocity_smoother_nodelet.hpp.

Definition at line 59 of file velocity_smoother_nodelet.hpp.

Definition at line 70 of file velocity_smoother_nodelet.hpp.

Definition at line 65 of file velocity_smoother_nodelet.hpp.

Current velocity from commands sent to the robot, not necessarily by this node

Definition at line 76 of file velocity_smoother_nodelet.hpp.

Definition at line 60 of file velocity_smoother_nodelet.hpp.

Definition at line 58 of file velocity_smoother_nodelet.hpp.

Definition at line 59 of file velocity_smoother_nodelet.hpp.

dynamic_reconfigure::Server<yocs_velocity_smoother::paramsConfig>::CallbackType yocs_velocity_smoother::VelocitySmoother::dynamic_reconfigure_callback [private]

Definition at line 96 of file velocity_smoother_nodelet.hpp.

dynamic_reconfigure::Server<yocs_velocity_smoother::paramsConfig>* yocs_velocity_smoother::VelocitySmoother::dynamic_reconfigure_server [private]

Definition at line 90 of file velocity_smoother_nodelet.hpp.

Definition at line 62 of file velocity_smoother_nodelet.hpp.

Definition at line 69 of file velocity_smoother_nodelet.hpp.

Definition at line 71 of file velocity_smoother_nodelet.hpp.

Definition at line 64 of file velocity_smoother_nodelet.hpp.

Definition at line 57 of file velocity_smoother_nodelet.hpp.

Current velocity from odometry

Definition at line 75 of file velocity_smoother_nodelet.hpp.

Historic of latest periods between velocity commands

Definition at line 72 of file velocity_smoother_nodelet.hpp.

Next position to fill in the periods record buffer

Definition at line 73 of file velocity_smoother_nodelet.hpp.

Incoming raw velocity commands

Definition at line 77 of file velocity_smoother_nodelet.hpp.

What source to use as robot velocity feedback

Shutdown requested by nodelet; kill worker thread

Definition at line 68 of file velocity_smoother_nodelet.hpp.

Outgoing smoothed velocity commands

Definition at line 78 of file velocity_smoother_nodelet.hpp.

Definition at line 58 of file velocity_smoother_nodelet.hpp.

Definition at line 59 of file velocity_smoother_nodelet.hpp.

Definition at line 66 of file velocity_smoother_nodelet.hpp.


The documentation for this class was generated from the following files:


yocs_velocity_smoother
Author(s): Jorge Santos Simon
autogenerated on Thu Jun 6 2019 21:47:39