Public Member Functions | Private Types | Private Attributes | List of all members
VelocitySmootherNode Class Reference

Public Member Functions

void dynConfigCallback (Config &cfg, uint32_t level)
 
void timerCallback (const ros::TimerEvent &event)
 
ros::Duration timerDuration ()
 
void velCallback (const geometry_msgs::Twist::ConstPtr &msg)
 
 VelocitySmootherNode ()
 
 ~VelocitySmootherNode ()
 

Private Types

typedef cmd_vel_smoother::CmdVelSmootherConfig Config
 

Private Attributes

boost::mutex cfg_mutex_
 
int count_
 
double desired_rate_
 
boost::shared_ptr< dyn::Server< Config > > dyn_srv_
 
int interpolate_max_frame_
 
ros::Time latest_time_
 
geometry_msgs::Twist::ConstPtr latest_vel_
 
ros::NodeHandle nh_
 
ros::NodeHandle pnh_
 
ros::Publisher pub_
 
geometry_msgs::Twist::Ptr pub_vel_
 
ros::Subscriber sub_
 
ros::Timer timer_
 
double x_acc_lim_
 
double y_acc_lim_
 
double yaw_acc_lim_
 

Detailed Description

Definition at line 12 of file cmd_vel_smoother.cpp.

Member Typedef Documentation

typedef cmd_vel_smoother::CmdVelSmootherConfig VelocitySmootherNode::Config
private

Definition at line 20 of file cmd_vel_smoother.cpp.

Constructor & Destructor Documentation

VelocitySmootherNode::VelocitySmootherNode ( )
inline

Definition at line 93 of file cmd_vel_smoother.cpp.

VelocitySmootherNode::~VelocitySmootherNode ( )
inline

Definition at line 105 of file cmd_vel_smoother.cpp.

Member Function Documentation

void VelocitySmootherNode::dynConfigCallback ( Config cfg,
uint32_t  level 
)
inline

Definition at line 35 of file cmd_vel_smoother.cpp.

void VelocitySmootherNode::timerCallback ( const ros::TimerEvent event)
inline

Definition at line 59 of file cmd_vel_smoother.cpp.

ros::Duration VelocitySmootherNode::timerDuration ( )
inline

Definition at line 31 of file cmd_vel_smoother.cpp.

void VelocitySmootherNode::velCallback ( const geometry_msgs::Twist::ConstPtr &  msg)
inline

Definition at line 52 of file cmd_vel_smoother.cpp.

Member Data Documentation

boost::mutex VelocitySmootherNode::cfg_mutex_
private

Definition at line 19 of file cmd_vel_smoother.cpp.

int VelocitySmootherNode::count_
private

Definition at line 23 of file cmd_vel_smoother.cpp.

double VelocitySmootherNode::desired_rate_
private

Definition at line 24 of file cmd_vel_smoother.cpp.

boost::shared_ptr<dyn::Server<Config> > VelocitySmootherNode::dyn_srv_
private

Definition at line 21 of file cmd_vel_smoother.cpp.

int VelocitySmootherNode::interpolate_max_frame_
private

Definition at line 23 of file cmd_vel_smoother.cpp.

ros::Time VelocitySmootherNode::latest_time_
private

Definition at line 26 of file cmd_vel_smoother.cpp.

geometry_msgs::Twist::ConstPtr VelocitySmootherNode::latest_vel_
private

Definition at line 27 of file cmd_vel_smoother.cpp.

ros::NodeHandle VelocitySmootherNode::nh_
private

Definition at line 14 of file cmd_vel_smoother.cpp.

ros::NodeHandle VelocitySmootherNode::pnh_
private

Definition at line 14 of file cmd_vel_smoother.cpp.

ros::Publisher VelocitySmootherNode::pub_
private

Definition at line 15 of file cmd_vel_smoother.cpp.

geometry_msgs::Twist::Ptr VelocitySmootherNode::pub_vel_
private

Definition at line 28 of file cmd_vel_smoother.cpp.

ros::Subscriber VelocitySmootherNode::sub_
private

Definition at line 16 of file cmd_vel_smoother.cpp.

ros::Timer VelocitySmootherNode::timer_
private

Definition at line 17 of file cmd_vel_smoother.cpp.

double VelocitySmootherNode::x_acc_lim_
private

Definition at line 25 of file cmd_vel_smoother.cpp.

double VelocitySmootherNode::y_acc_lim_
private

Definition at line 25 of file cmd_vel_smoother.cpp.

double VelocitySmootherNode::yaw_acc_lim_
private

Definition at line 25 of file cmd_vel_smoother.cpp.


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


cmd_vel_smoother
Author(s): Yuki Furuta
autogenerated on Fri May 14 2021 02:51:38