#include <velocity_smoother.h>
|
double | median (std::vector< double > values) |
|
void | odometryCB (const nav_msgs::Odometry::ConstPtr &msg) |
|
void | reconfigCB (cob_base_velocity_smoother::paramsConfig &config, uint32_t unused_level) |
|
void | robotVelCB (const geometry_msgs::Twist::ConstPtr &msg) |
|
double | sign (double x) |
|
void | velocityCB (const geometry_msgs::Twist::ConstPtr &msg) |
|
Definition at line 40 of file velocity_smoother.h.
cob_base_velocity_smoother::VelocitySmoother::VelocitySmoother |
( |
const std::string & |
name | ) |
|
cob_base_velocity_smoother::VelocitySmoother::~VelocitySmoother |
( |
| ) |
|
|
inline |
bool cob_base_velocity_smoother::VelocitySmoother::init |
( |
ros::NodeHandle & |
nh | ) |
|
Initialise from a nodelet's private nodehandle.
- Parameters
-
- Returns
- bool : success or failure
Definition at line 300 of file velocity_smoother.cpp.
double cob_base_velocity_smoother::VelocitySmoother::median |
( |
std::vector< double > |
values | ) |
|
|
inlineprivate |
void cob_base_velocity_smoother::VelocitySmoother::odometryCB |
( |
const nav_msgs::Odometry::ConstPtr & |
msg | ) |
|
|
private |
void cob_base_velocity_smoother::VelocitySmoother::reconfigCB |
( |
cob_base_velocity_smoother::paramsConfig & |
config, |
|
|
uint32_t |
unused_level |
|
) |
| |
|
private |
void cob_base_velocity_smoother::VelocitySmoother::robotVelCB |
( |
const geometry_msgs::Twist::ConstPtr & |
msg | ) |
|
|
private |
void cob_base_velocity_smoother::VelocitySmoother::shutdown |
( |
| ) |
|
|
inline |
double cob_base_velocity_smoother::VelocitySmoother::sign |
( |
double |
x | ) |
|
|
inlineprivate |
void cob_base_velocity_smoother::VelocitySmoother::spin |
( |
| ) |
|
void cob_base_velocity_smoother::VelocitySmoother::velocityCB |
( |
const geometry_msgs::Twist::ConstPtr & |
msg | ) |
|
|
private |
double cob_base_velocity_smoother::VelocitySmoother::accel_lim_vx |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::accel_lim_vy |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::accel_lim_w |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::cb_avg_time |
|
private |
geometry_msgs::Twist cob_base_velocity_smoother::VelocitySmoother::current_vel |
|
private |
ros::Subscriber cob_base_velocity_smoother::VelocitySmoother::current_vel_sub |
|
private |
Current velocity from commands sent to the robot, not necessarily by this node
Definition at line 83 of file velocity_smoother.h.
double cob_base_velocity_smoother::VelocitySmoother::decel_factor |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::decel_factor_safe |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::decel_lim_vx |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::decel_lim_vx_safe |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::decel_lim_vy |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::decel_lim_vy_safe |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::decel_lim_w |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::decel_lim_w_safe |
|
private |
dynamic_reconfigure::Server<cob_base_velocity_smoother::paramsConfig>::CallbackType cob_base_velocity_smoother::VelocitySmoother::dynamic_reconfigure_callback |
|
private |
dynamic_reconfigure::Server<cob_base_velocity_smoother::paramsConfig>* cob_base_velocity_smoother::VelocitySmoother::dynamic_reconfigure_server |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::frequency |
|
private |
bool cob_base_velocity_smoother::VelocitySmoother::input_active |
|
private |
ros::Time cob_base_velocity_smoother::VelocitySmoother::last_cb_time |
|
private |
geometry_msgs::Twist cob_base_velocity_smoother::VelocitySmoother::last_cmd_vel |
|
private |
std::string cob_base_velocity_smoother::VelocitySmoother::name |
|
private |
std::vector<double> cob_base_velocity_smoother::VelocitySmoother::period_record |
|
private |
unsigned int cob_base_velocity_smoother::VelocitySmoother::pr_next |
|
private |
ros::Subscriber cob_base_velocity_smoother::VelocitySmoother::raw_in_vel_sub |
|
private |
What source to use as robot velocity feedback
bool cob_base_velocity_smoother::VelocitySmoother::shutdown_req |
|
private |
ros::Publisher cob_base_velocity_smoother::VelocitySmoother::smooth_vel_pub |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::speed_lim_vx |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::speed_lim_vy |
|
private |
double cob_base_velocity_smoother::VelocitySmoother::speed_lim_w |
|
private |
geometry_msgs::Twist cob_base_velocity_smoother::VelocitySmoother::target_vel |
|
private |
The documentation for this class was generated from the following files: