Classes | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
cob_base_velocity_smoother Class Reference

#include <cob_base_velocity_smoother.h>

List of all members.

Classes

class  VelocitySmoother

Public Member Functions

void calculationStep ()
bool circBuffOutOfDate (ros::Time now)
 cob_base_velocity_smoother ()
void geometryCallback (const geometry_msgs::Twist::ConstPtr &cmd_vel)
double getLoopRate ()
bool IsEqual (geometry_msgs::Twist msg1, geometry_msgs::Twist msg2)
bool IsZeroMsg (geometry_msgs::Twist cmd_vel)
void limitAcceleration (ros::Time now, geometry_msgs::Twist &cmd_vel)
double meanValueX ()
double meanValueY ()
double meanValueZ ()
void reviseCircBuff (ros::Time now, geometry_msgs::Twist cmd_vel)
geometry_msgs::Twist setOutput (ros::Time now, geometry_msgs::Twist cmd_vel)
int signum (double var)
 ~cob_base_velocity_smoother ()

Public Attributes

boost::circular_buffer
< geometry_msgs::Twist > 
cb_
boost::circular_buffer
< geometry_msgs::Twist > 
cb_out_
boost::circular_buffer< ros::Timecb_time_
ros::Subscriber geometry_msgs_sub_
ros::NodeHandle nh_
ros::NodeHandle pnh_
ros::Publisher pub_

Private Member Functions

bool get_new_msg_received ()
void set_new_msg_received (bool received)

Private Attributes

double acc_limit_
int buffer_capacity_
double loop_rate_
pthread_mutex_t m_mutex
double max_delay_between_commands_
bool new_msg_received_
double stop_delay_after_no_sub_
double store_delay_
geometry_msgs::Twist sub_msg_
geometry_msgs::Twist zero_values_

Detailed Description

Definition at line 46 of file cob_base_velocity_smoother.h.


Constructor & Destructor Documentation

Definition at line 47 of file cob_base_velocity_smoother.cpp.

Definition at line 133 of file cob_base_velocity_smoother.cpp.


Member Function Documentation

Definition at line 143 of file cob_base_velocity_smoother.cpp.

Definition at line 269 of file cob_base_velocity_smoother.cpp.

void cob_base_velocity_smoother::geometryCallback ( const geometry_msgs::Twist::ConstPtr &  cmd_vel)

Definition at line 136 of file cob_base_velocity_smoother.cpp.

Definition at line 38 of file cob_base_velocity_smoother.cpp.

Definition at line 436 of file cob_base_velocity_smoother.cpp.

bool cob_base_velocity_smoother::IsEqual ( geometry_msgs::Twist  msg1,
geometry_msgs::Twist  msg2 
)

Definition at line 442 of file cob_base_velocity_smoother.cpp.

bool cob_base_velocity_smoother::IsZeroMsg ( geometry_msgs::Twist  cmd_vel)

Definition at line 289 of file cob_base_velocity_smoother.cpp.

void cob_base_velocity_smoother::limitAcceleration ( ros::Time  now,
geometry_msgs::Twist &  cmd_vel 
)

Definition at line 455 of file cob_base_velocity_smoother.cpp.

Definition at line 313 of file cob_base_velocity_smoother.cpp.

Definition at line 354 of file cob_base_velocity_smoother.cpp.

Definition at line 395 of file cob_base_velocity_smoother.cpp.

void cob_base_velocity_smoother::reviseCircBuff ( ros::Time  now,
geometry_msgs::Twist  cmd_vel 
)

Definition at line 200 of file cob_base_velocity_smoother.cpp.

void cob_base_velocity_smoother::set_new_msg_received ( bool  received) [private]

Definition at line 31 of file cob_base_velocity_smoother.cpp.

geometry_msgs::Twist cob_base_velocity_smoother::setOutput ( ros::Time  now,
geometry_msgs::Twist  cmd_vel 
)

Definition at line 178 of file cob_base_velocity_smoother.cpp.

Definition at line 300 of file cob_base_velocity_smoother.cpp.


Member Data Documentation

Definition at line 56 of file cob_base_velocity_smoother.h.

Definition at line 50 of file cob_base_velocity_smoother.h.

boost::circular_buffer<geometry_msgs::Twist> cob_base_velocity_smoother::cb_

Definition at line 84 of file cob_base_velocity_smoother.h.

boost::circular_buffer<geometry_msgs::Twist> cob_base_velocity_smoother::cb_out_

Definition at line 85 of file cob_base_velocity_smoother.h.

Definition at line 86 of file cob_base_velocity_smoother.h.

Definition at line 89 of file cob_base_velocity_smoother.h.

Definition at line 58 of file cob_base_velocity_smoother.h.

pthread_mutex_t cob_base_velocity_smoother::m_mutex [private]

Definition at line 66 of file cob_base_velocity_smoother.h.

Definition at line 60 of file cob_base_velocity_smoother.h.

Definition at line 67 of file cob_base_velocity_smoother.h.

Definition at line 81 of file cob_base_velocity_smoother.h.

Definition at line 81 of file cob_base_velocity_smoother.h.

Definition at line 92 of file cob_base_velocity_smoother.h.

Definition at line 54 of file cob_base_velocity_smoother.h.

Definition at line 52 of file cob_base_velocity_smoother.h.

geometry_msgs::Twist cob_base_velocity_smoother::sub_msg_ [private]

Definition at line 64 of file cob_base_velocity_smoother.h.

geometry_msgs::Twist cob_base_velocity_smoother::zero_values_ [private]

Definition at line 62 of file cob_base_velocity_smoother.h.


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


cob_base_velocity_smoother
Author(s): Florian Mirus , Benjamin Maidel
autogenerated on Thu Jun 6 2019 21:18:55