15 #ifndef NAV2_VELOCITY_SMOOTHER__VELOCITY_SMOOTHER_HPP_
16 #define NAV2_VELOCITY_SMOOTHER__VELOCITY_SMOOTHER_HPP_
25 #include "nav2_util/lifecycle_node.hpp"
26 #include "nav2_util/node_utils.hpp"
27 #include "nav2_util/odometry_utils.hpp"
28 #include "nav2_util/robot_utils.hpp"
30 namespace nav2_velocity_smoother
44 explicit VelocitySmoother(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
60 const double v_curr,
const double v_cmd,
61 const double accel,
const double decel);
73 const double v_curr,
const double v_cmd,
74 const double accel,
const double decel,
const double eta);
82 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
89 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
96 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
103 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
110 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
128 std::vector<rclcpp::Parameter> parameters);
131 std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
132 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr
134 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_sub_;
135 rclcpp::TimerBase::SharedPtr timer_;
137 rclcpp::Clock::SharedPtr clock_;
138 geometry_msgs::msg::Twist last_cmd_;
139 geometry_msgs::msg::Twist::SharedPtr command_;
142 double smoothing_frequency_;
143 double odom_duration_;
144 std::string odom_topic_;
147 bool scale_velocities_;
148 std::vector<double> max_velocities_;
149 std::vector<double> min_velocities_;
150 std::vector<double> max_accels_;
151 std::vector<double> max_decels_;
152 std::vector<double> deadband_velocities_;
153 rclcpp::Duration velocity_timeout_{0, 0};
154 rclcpp::Time last_command_time_;
156 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
This class that smooths cmd_vel velocities for robot bases.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
~VelocitySmoother()
Destructor for nav2_velocity_smoother::VelocitySmoother.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures parameters and member variables.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
VelocitySmoother(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_velocity_smoother::VelocitySmoother.
void inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg)
Callback for incoming velocity commands.
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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Dynamic reconfigure callback.
void smootherTimer()
Main worker timer function.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
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.