Nav2 Navigation Stack - rolling  main
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_ros_common/lifecycle_node.hpp"
26 #include "nav2_ros_common/node_utils.hpp"
27 #include "nav2_util/odometry_utils.hpp"
28 #include "nav2_util/robot_utils.hpp"
29 #include "nav2_util/twist_publisher.hpp"
30 #include "nav2_util/twist_subscriber.hpp"
31 #include "geometry_msgs/msg/twist.hpp"
32 #include "geometry_msgs/msg/twist_stamped.hpp"
33 
34 namespace nav2_velocity_smoother
35 {
36 
42 {
43 public:
48  explicit VelocitySmoother(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
49 
54 
63  double findEtaConstraint(
64  const double v_curr, const double v_cmd,
65  const double accel, const double decel);
66 
76  double applyConstraints(
77  const double v_curr, const double v_cmd,
78  const double accel, const double decel, const double eta);
79 
80 protected:
86  nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
87 
93  nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
94 
100  nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
101 
107  nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
108 
114  nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
115 
120  void inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg);
121  void inputCommandStampedCallback(const geometry_msgs::msg::TwistStamped::SharedPtr msg);
122 
126  void smootherTimer();
127 
132  rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
133  std::vector<rclcpp::Parameter> parameters);
134 
135  // Network interfaces
136  std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
137  std::unique_ptr<nav2_util::TwistPublisher> smoothed_cmd_pub_;
138  std::unique_ptr<nav2_util::TwistSubscriber> cmd_sub_;
139  rclcpp::TimerBase::SharedPtr timer_;
140 
141  rclcpp::Clock::SharedPtr clock_;
142  geometry_msgs::msg::TwistStamped last_cmd_;
143  geometry_msgs::msg::TwistStamped::SharedPtr command_;
144 
145  // Parameters
146  double smoothing_frequency_;
147  double odom_duration_;
148  std::string odom_topic_;
149  bool open_loop_;
150  bool stopped_{true};
151  bool scale_velocities_;
152  bool is_6dof_;
153  std::vector<double> max_velocities_;
154  std::vector<double> min_velocities_;
155  std::vector<double> max_accels_;
156  std::vector<double> max_decels_;
157  std::vector<double> deadband_velocities_;
158  rclcpp::Duration velocity_timeout_{0, 0};
159  rclcpp::Time last_command_time_;
160 
161  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
162 };
163 
164 } // namespace nav2_velocity_smoother
165 
166 #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::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
~VelocitySmoother()
Destructor for nav2_velocity_smoother::VelocitySmoother.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
VelocitySmoother(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_velocity_smoother::VelocitySmoother.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures parameters and member variables.
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.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Dynamic reconfigure callback.
void smootherTimer()
Main worker timer function.
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.