#include <cob_base_velocity_smoother.h>
◆ cob_base_velocity_smoother()
| cob_base_velocity_smoother::cob_base_velocity_smoother |
( |
| ) |
|
◆ ~cob_base_velocity_smoother()
| cob_base_velocity_smoother::~cob_base_velocity_smoother |
( |
| ) |
|
◆ calculationStep()
| void cob_base_velocity_smoother::calculationStep |
( |
| ) |
|
◆ circBuffOutOfDate()
| bool cob_base_velocity_smoother::circBuffOutOfDate |
( |
ros::Time |
now | ) |
|
◆ geometryCallback()
| void cob_base_velocity_smoother::geometryCallback |
( |
const geometry_msgs::Twist::ConstPtr & |
cmd_vel | ) |
|
◆ get_new_msg_received()
| bool cob_base_velocity_smoother::get_new_msg_received |
( |
| ) |
|
|
private |
◆ getLoopRate()
| double cob_base_velocity_smoother::getLoopRate |
( |
| ) |
|
◆ IsEqual()
| bool cob_base_velocity_smoother::IsEqual |
( |
geometry_msgs::Twist |
msg1, |
|
|
geometry_msgs::Twist |
msg2 |
|
) |
| |
◆ IsZeroMsg()
| bool cob_base_velocity_smoother::IsZeroMsg |
( |
geometry_msgs::Twist |
cmd_vel | ) |
|
◆ limitAcceleration()
| void cob_base_velocity_smoother::limitAcceleration |
( |
ros::Time |
now, |
|
|
geometry_msgs::Twist & |
cmd_vel |
|
) |
| |
◆ meanValueX()
| double cob_base_velocity_smoother::meanValueX |
( |
| ) |
|
◆ meanValueY()
| double cob_base_velocity_smoother::meanValueY |
( |
| ) |
|
◆ meanValueZ()
| double cob_base_velocity_smoother::meanValueZ |
( |
| ) |
|
◆ reviseCircBuff()
| void cob_base_velocity_smoother::reviseCircBuff |
( |
ros::Time |
now, |
|
|
geometry_msgs::Twist |
cmd_vel |
|
) |
| |
◆ set_new_msg_received()
| void cob_base_velocity_smoother::set_new_msg_received |
( |
bool |
received | ) |
|
|
private |
◆ setOutput()
| geometry_msgs::Twist cob_base_velocity_smoother::setOutput |
( |
ros::Time |
now, |
|
|
geometry_msgs::Twist |
cmd_vel |
|
) |
| |
◆ signum()
| int cob_base_velocity_smoother::signum |
( |
double |
var | ) |
|
◆ acc_limit_
| double cob_base_velocity_smoother::acc_limit_ |
|
private |
◆ buffer_capacity_
| int cob_base_velocity_smoother::buffer_capacity_ |
|
private |
◆ cb_
| boost::circular_buffer<geometry_msgs::Twist> cob_base_velocity_smoother::cb_ |
◆ cb_out_
| boost::circular_buffer<geometry_msgs::Twist> cob_base_velocity_smoother::cb_out_ |
◆ cb_time_
| boost::circular_buffer<ros::Time> cob_base_velocity_smoother::cb_time_ |
◆ geometry_msgs_sub_
◆ loop_rate_
| double cob_base_velocity_smoother::loop_rate_ |
|
private |
◆ m_mutex
| pthread_mutex_t cob_base_velocity_smoother::m_mutex |
|
private |
◆ max_delay_between_commands_
| double cob_base_velocity_smoother::max_delay_between_commands_ |
|
private |
◆ new_msg_received_
| bool cob_base_velocity_smoother::new_msg_received_ |
|
private |
◆ nh_
◆ pnh_
◆ pub_
◆ stop_delay_after_no_sub_
| double cob_base_velocity_smoother::stop_delay_after_no_sub_ |
|
private |
◆ store_delay_
| double cob_base_velocity_smoother::store_delay_ |
|
private |
◆ sub_msg_
| geometry_msgs::Twist cob_base_velocity_smoother::sub_msg_ |
|
private |
◆ zero_values_
| geometry_msgs::Twist cob_base_velocity_smoother::zero_values_ |
|
private |
The documentation for this class was generated from the following files: