Class VelocitySmoother

Inheritance Relationships

Base Type

  • public nav2_util::LifecycleNode

Class Documentation

class VelocitySmoother : public nav2_util::LifecycleNode

This class that smooths cmd_vel velocities for robot bases.

Public Functions

explicit VelocitySmoother(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

A constructor for nav2_velocity_smoother::VelocitySmoother.

Parameters:

options – Additional options to control creation of the node.

~VelocitySmoother()

Destructor for nav2_velocity_smoother::VelocitySmoother.

double findEtaConstraint(const double v_curr, const double v_cmd, const double accel, const double decel)

Find the scale factor, eta, which scales axis into acceleration range.

Parameters:
  • v_curr – current velocity

  • v_cmd – commanded velocity

  • accel – maximum acceleration

  • decel – maximum deceleration

Returns:

Scale factor, eta

double applyConstraints(const double v_curr, const double v_cmd, const double accel, const double decel, const double eta)

Apply acceleration and scale factor constraints.

Parameters:
  • v_curr – current velocity

  • v_cmd – commanded velocity

  • accel – maximum acceleration

  • decel – maximum deceleration

  • eta – Scale factor

Returns:

Velocity command

Protected Functions

nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

Configures parameters and member variables.

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

Activates member variables.

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

Deactivates member variables.

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

Calls clean up states and resets member variables.

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Called when in Shutdown state.

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

void inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg)

Callback for incoming velocity commands.

Parameters:

msg – Twist message

void smootherTimer()

Main worker timer function.

rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)

Dynamic reconfigure callback.

Parameters:

parametersParameter list to change

Protected Attributes

std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr smoothed_cmd_pub_
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_sub_
rclcpp::TimerBase::SharedPtr timer_
rclcpp::Clock::SharedPtr clock_
geometry_msgs::msg::Twist last_cmd_
geometry_msgs::msg::Twist::SharedPtr command_
double smoothing_frequency_
double odom_duration_
std::string odom_topic_
bool open_loop_
bool stopped_ = {true}
bool scale_velocities_
std::vector<double> max_velocities_
std::vector<double> min_velocities_
std::vector<double> max_accels_
std::vector<double> max_decels_
std::vector<double> deadband_velocities_
rclcpp::Duration velocity_timeout_ = {0, 0}
rclcpp::Time last_command_time_
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_