$search
Public Member Functions | |
bool | CircBuffOutOfDate (ros::Time now) |
cob_base_velocity_smoother () | |
void | geometryCallback (const geometry_msgs::Twist &cmd_vel) |
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) |
Public Attributes | |
boost::circular_buffer < geometry_msgs::Twist > | cb |
boost::circular_buffer < geometry_msgs::Twist > | cb_out |
boost::circular_buffer< ros::Time > | cb_time |
ros::NodeHandle | n |
ros::Publisher | pub |
Private Attributes | |
int | buffer_capacity |
double | store_delay |
double | thresh |
geometry_msgs::Twist | zero_values |
Definition at line 73 of file cob_base_velocity_smoother.cpp.
cob_base_velocity_smoother::cob_base_velocity_smoother | ( | ) |
Definition at line 131 of file cob_base_velocity_smoother.cpp.
bool cob_base_velocity_smoother::CircBuffOutOfDate | ( | ros::Time | now | ) |
Definition at line 196 of file cob_base_velocity_smoother.cpp.
void cob_base_velocity_smoother::geometryCallback | ( | const geometry_msgs::Twist & | cmd_vel | ) |
Definition at line 504 of file cob_base_velocity_smoother.cpp.
bool cob_base_velocity_smoother::IsZeroMsg | ( | geometry_msgs::Twist | cmd_vel | ) |
Definition at line 217 of file cob_base_velocity_smoother.cpp.
void cob_base_velocity_smoother::limitAcceleration | ( | ros::Time | now, | |
geometry_msgs::Twist & | cmd_vel | |||
) |
Definition at line 433 of file cob_base_velocity_smoother.cpp.
double cob_base_velocity_smoother::meanValueX | ( | ) |
Definition at line 238 of file cob_base_velocity_smoother.cpp.
double cob_base_velocity_smoother::meanValueY | ( | ) |
Definition at line 280 of file cob_base_velocity_smoother.cpp.
double cob_base_velocity_smoother::meanValueZ | ( | ) |
Definition at line 322 of file cob_base_velocity_smoother.cpp.
void cob_base_velocity_smoother::reviseCircBuff | ( | ros::Time | now, | |
geometry_msgs::Twist | cmd_vel | |||
) |
Definition at line 365 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 481 of file cob_base_velocity_smoother.cpp.
int cob_base_velocity_smoother::signum | ( | double | var | ) |
Definition at line 227 of file cob_base_velocity_smoother.cpp.
int cob_base_velocity_smoother::buffer_capacity [private] |
Definition at line 77 of file cob_base_velocity_smoother.cpp.
boost::circular_buffer<geometry_msgs::Twist> cob_base_velocity_smoother::cb |
Definition at line 94 of file cob_base_velocity_smoother.cpp.
boost::circular_buffer<geometry_msgs::Twist> cob_base_velocity_smoother::cb_out |
Definition at line 95 of file cob_base_velocity_smoother.cpp.
boost::circular_buffer<ros::Time> cob_base_velocity_smoother::cb_time |
Definition at line 96 of file cob_base_velocity_smoother.cpp.
Definition at line 91 of file cob_base_velocity_smoother.cpp.
Definition at line 99 of file cob_base_velocity_smoother.cpp.
double cob_base_velocity_smoother::store_delay [private] |
Definition at line 79 of file cob_base_velocity_smoother.cpp.
double cob_base_velocity_smoother::thresh [private] |
Definition at line 81 of file cob_base_velocity_smoother.cpp.
Definition at line 83 of file cob_base_velocity_smoother.cpp.