Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
velocity_smoother.hpp
1 // Copyright (c) 2022 Samsung Research
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_VELOCITY_SMOOTHER__VELOCITY_SMOOTHER_HPP_
16 #define NAV2_VELOCITY_SMOOTHER__VELOCITY_SMOOTHER_HPP_
17 
18 #include <chrono>
19 #include <limits>
20 #include <memory>
21 #include <string>
22 #include <utility>
23 #include <vector>
24 
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"
29 
30 namespace nav2_velocity_smoother
31 {
32 
38 {
39 public:
44  explicit VelocitySmoother(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
45 
50 
59  double findEtaConstraint(
60  const double v_curr, const double v_cmd,
61  const double accel, const double decel);
62 
72  double applyConstraints(
73  const double v_curr, const double v_cmd,
74  const double accel, const double decel, const double eta);
75 
76 protected:
82  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
83 
89  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
90 
96  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
97 
103  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
104 
110  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
111 
116  void inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg);
117 
121  void smootherTimer();
122 
127  rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
128  std::vector<rclcpp::Parameter> parameters);
129 
130  // Network interfaces
131  std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
132  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr
133  smoothed_cmd_pub_;
134  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_sub_;
135  rclcpp::TimerBase::SharedPtr timer_;
136 
137  rclcpp::Clock::SharedPtr clock_;
138  geometry_msgs::msg::Twist last_cmd_;
139  geometry_msgs::msg::Twist::SharedPtr command_;
140 
141  // Parameters
142  double smoothing_frequency_;
143  double odom_duration_;
144  std::string odom_topic_;
145  bool open_loop_;
146  bool stopped_{true};
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_;
155 
156  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
157 };
158 
159 } // namespace nav2_velocity_smoother
160 
161 #endif // NAV2_VELOCITY_SMOOTHER__VELOCITY_SMOOTHER_HPP_
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.