#include <cob_base_velocity_smoother.h>
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::Time > | cb_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_ |
Definition at line 46 of file cob_base_velocity_smoother.h.
| cob_base_velocity_smoother::cob_base_velocity_smoother | ( | ) |
Definition at line 47 of file cob_base_velocity_smoother.cpp.
| cob_base_velocity_smoother::~cob_base_velocity_smoother | ( | ) |
Definition at line 133 of file cob_base_velocity_smoother.cpp.
| void cob_base_velocity_smoother::calculationStep | ( | ) |
Definition at line 143 of file cob_base_velocity_smoother.cpp.
| bool cob_base_velocity_smoother::circBuffOutOfDate | ( | ros::Time | now | ) |
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.
|
private |
Definition at line 38 of file cob_base_velocity_smoother.cpp.
| double cob_base_velocity_smoother::getLoopRate | ( | ) |
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.
| double cob_base_velocity_smoother::meanValueX | ( | ) |
Definition at line 313 of file cob_base_velocity_smoother.cpp.
| double cob_base_velocity_smoother::meanValueY | ( | ) |
Definition at line 354 of file cob_base_velocity_smoother.cpp.
| double cob_base_velocity_smoother::meanValueZ | ( | ) |
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.
|
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.
| int cob_base_velocity_smoother::signum | ( | double | var | ) |
Definition at line 300 of file cob_base_velocity_smoother.cpp.
|
private |
Definition at line 56 of file cob_base_velocity_smoother.h.
|
private |
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.
| boost::circular_buffer<ros::Time> cob_base_velocity_smoother::cb_time_ |
Definition at line 86 of file cob_base_velocity_smoother.h.
| ros::Subscriber cob_base_velocity_smoother::geometry_msgs_sub_ |
Definition at line 89 of file cob_base_velocity_smoother.h.
|
private |
Definition at line 58 of file cob_base_velocity_smoother.h.
|
private |
Definition at line 66 of file cob_base_velocity_smoother.h.
|
private |
Definition at line 60 of file cob_base_velocity_smoother.h.
|
private |
Definition at line 67 of file cob_base_velocity_smoother.h.
| ros::NodeHandle cob_base_velocity_smoother::nh_ |
Definition at line 81 of file cob_base_velocity_smoother.h.
| ros::NodeHandle cob_base_velocity_smoother::pnh_ |
Definition at line 81 of file cob_base_velocity_smoother.h.
| ros::Publisher cob_base_velocity_smoother::pub_ |
Definition at line 92 of file cob_base_velocity_smoother.h.
|
private |
Definition at line 54 of file cob_base_velocity_smoother.h.
|
private |
Definition at line 52 of file cob_base_velocity_smoother.h.
|
private |
Definition at line 64 of file cob_base_velocity_smoother.h.
|
private |
Definition at line 62 of file cob_base_velocity_smoother.h.