-
Notifications
You must be signed in to change notification settings - Fork 65
Description
Hello!
I have being using velocity_smoother
in cob_base_velocity_smoother
for controlling holonomic clearpath ridgeback. I'm testing manual control with velocity_smoother by using a bluetooth joystick. The joystick publishes commands with a high frequency(at least >70hz, the angular command has even higher frequency, >100hz).
But the rqt_plot of output commands filtered by velocity_smoother
sometimes has "peaks" shown in the images below(the red line ridgeback_velocity_controller/cmd_vel/linear/x
). And every time I have peaks, I have errors like:
[ WARN] [1680516774.181529930]: Velocity Smoother : input got inactive leaving us a non-zero target velocity (-0.4, -0, -0), zeroing...[velocity_smoother]
[ WARN] [1680516774.881578308]: Velocity Smoother : input got inactive leaving us a non-zero target velocity (-0.4, 0.0581249, -0), zeroing...[velocity_smoother]
From my understanding,this is because of codes of line140-143 in cob_base_velocity_smoother/src/cob_base_velocity_smoother/velocity_smoother.cpp
while (! shutdown_req && ros::ok())
{
if ((input_active == true) && (cb_avg_time > 0.0) &&
((ros::Time::now() - last_cb_time).toSec() > std::min(3.0*cb_avg_time, 0.5)))
For a joystick with high frequency, it is very easy to have a (ros::Time::now() - last_cb_time).toSec() > std::min(3.0*cb_avg_time, 0.5)
because cb_avg_time
is very small. After I change 3.0 into a higher value like 10 or 35, I don't have the "peaks" and errors like Velocity Smoother : input got inactive
anymore.
In order to generalize this package, should we make the 3.0
as a ros parameter instead of a hardcoded number?
Like:
while (! shutdown_req && ros::ok())
{
if ((input_active == true) && (cb_avg_time > 0.0) &&
((ros::Time::now() - last_cb_time).toSec() > std::min(amplitude*cb_avg_time, 0.5)))
...
nh.param("amplitude", amplitude, 3.0);
This is my very naive way to avoid this bug. To solve this problem, should I use a larger amplitude
, or I still need to fine-tune parameters like frequency
? I'm also a bit confused about how does line 140-157 work. It is also appreciated if someone can explain it to me.
Images:
# Optional parameters
frequency: 10
decel_factor: 0.5 #1
# Robot velocity feedback type:
# 0 - none
# 1 - odometry
# 2 - end robot commands
robot_feedback: 1
parameters:
# Optional parameters
frequency: 20
decel_factor: 0.5 #1
# Robot velocity feedback type:
# 0 - none
# 1 - odometry
# 2 - end robot commands
robot_feedback: 1
parameters:
# Optional parameters
frequency: 20
decel_factor: 0.5 #1
# Robot velocity feedback type:
# 0 - none
# 1 - odometry
# 2 - end robot commands
robot_feedback: 1
and with
while (! shutdown_req && ros::ok())
{
if ((input_active == true) && (cb_avg_time > 0.0) &&
((ros::Time::now() - last_cb_time).toSec() > std::min(10.0*cb_avg_time, 0.5)))
There are hardly any "peaks" in the plot
Here is the rqt_graph for ridgeback along with velocity_smoother