Program Listing for File nav2_smoother.hpp
↰ Return to documentation for file (include/nav2_smoother/nav2_smoother.hpp
)
// Copyright (c) 2021 RoboTech Vision
// Copyright (c) 2019 Intel Corporation
//
// 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_SMOOTHER__NAV2_SMOOTHER_HPP_
#define NAV2_SMOOTHER__NAV2_SMOOTHER_HPP_
#include <memory>
#include <string>
#include <thread>
#include <unordered_map>
#include <vector>
#include "nav2_core/smoother.hpp"
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
#include "nav2_costmap_2d/costmap_subscriber.hpp"
#include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
#include "nav2_costmap_2d/footprint_subscriber.hpp"
#include "nav2_msgs/action/smooth_path.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/robot_utils.hpp"
#include "nav2_util/simple_action_server.hpp"
#include "pluginlib/class_list_macros.hpp"
#include "pluginlib/class_loader.hpp"
namespace nav2_smoother
{
class SmootherServer : public nav2_util::LifecycleNode
{
public:
using SmootherMap = std::unordered_map<std::string, nav2_core::Smoother::Ptr>;
explicit SmootherServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
~SmootherServer();
protected:
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
bool loadSmootherPlugins();
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;
using Action = nav2_msgs::action::SmoothPath;
using ActionResult = Action::Result;
using ActionServer = nav2_util::SimpleActionServer<Action>;
void smoothPlan();
bool findSmootherId(const std::string & c_name, std::string & name);
bool validate(const nav_msgs::msg::Path & path);
// Our action server implements the SmoothPath action
std::unique_ptr<ActionServer> action_server_;
// Transforms
std::shared_ptr<tf2_ros::Buffer> tf_;
std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
// Publishers and subscribers
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_;
// Smoother Plugins
pluginlib::ClassLoader<nav2_core::Smoother> lp_loader_;
SmootherMap smoothers_;
std::vector<std::string> default_ids_;
std::vector<std::string> default_types_;
std::vector<std::string> smoother_ids_;
std::vector<std::string> smoother_types_;
std::string smoother_ids_concat_, current_smoother_;
// Utilities
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
};
} // namespace nav2_smoother
#endif // NAV2_SMOOTHER__NAV2_SMOOTHER_HPP_