Contents
The cob_base_velocity_smoother package provides two implementations for a velocity smoother that both read velocity messages (geometry_msgs::Twist) and then publish messages of the same type for "smoothed" velocity to avoid jerky behavior.
The two nodes available are:
cob_base_velocity_smoother
velocity_smoother
Hardware Requirements
To use this package you either need a real or a simulated Care-O-Bot (see cob_bringup and cob_bringup_sim respectively).
ROS API
The following states the ROS API for the cob_base_velocity_smoother node.
cob_base_velocity_smoother
The cob_base_velocity_smoother node takes in geometry_msgs/Twist messages from the navigation or teleoperation device and publishes recalculated geometry_msgs/Twist messages to avoid jerky behavior.Subscribed Topics
input (geometry_msgs/Twist)- movement command published by the navigation or teleoperation device.
Published Topics
output (geometry_msgs/Twist)- recalculated movement command
Parameters
~circular_buffer_capacity (int, default: 12 for cob3, 6 for raw3)- Specifies the capacity of the internal circular buffer (number of saved velocity messages).
- Specifies the maximal time delay for saved messages (older messages will be deleted).
- Specifies the threshold for the maximal allowed acceleration.
- Specifies the ros loop rate of the velocity smoother.
- Specifies the minimal input rate that is expected before filling the buffer with zeros.
- Specifies the maximal time-delay until stopping the robot when there are no incoming messages.
Usage
All hardware configuration is done in the cob_hardware_config package. Parameter files for both nodes have to be placed in "cob_hardware_config/$(env ROBOT)/config/" for each ROBOT.