Program Listing for File velocity_smoother.hpp
↰ Return to documentation for file (include/nav2_velocity_smoother/velocity_smoother.hpp
)
// Copyright (c) 2022 Samsung Research
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_VELOCITY_SMOOTHER__VELOCITY_SMOOTHER_HPP_
#define NAV2_VELOCITY_SMOOTHER__VELOCITY_SMOOTHER_HPP_
#include <chrono>
#include <limits>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/odometry_utils.hpp"
#include "nav2_util/robot_utils.hpp"
#include "nav2_util/twist_publisher.hpp"
#include "nav2_util/twist_subscriber.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
namespace nav2_velocity_smoother
{
class VelocitySmoother : public nav2_util::LifecycleNode
{
public:
explicit VelocitySmoother(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
~VelocitySmoother();
double findEtaConstraint(
const double v_curr, const double v_cmd,
const double accel, const double decel);
double applyConstraints(
const double v_curr, const double v_cmd,
const double accel, const double decel, const double eta);
protected:
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
void inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg);
void inputCommandStampedCallback(const geometry_msgs::msg::TwistStamped::SharedPtr msg);
void smootherTimer();
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
std::vector<rclcpp::Parameter> parameters);
// Network interfaces
std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
std::unique_ptr<nav2_util::TwistPublisher> smoothed_cmd_pub_;
std::unique_ptr<nav2_util::TwistSubscriber> cmd_sub_;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Clock::SharedPtr clock_;
geometry_msgs::msg::TwistStamped last_cmd_;
geometry_msgs::msg::TwistStamped::SharedPtr command_;
// Parameters
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_;
};
} // namespace nav2_velocity_smoother
#endif // NAV2_VELOCITY_SMOOTHER__VELOCITY_SMOOTHER_HPP_