SMACC2
Loading...
Searching...
No Matches
forward_global_planner.hpp
Go to the documentation of this file.
1// Copyright 2025 Robosoft Inc.
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/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#pragma once
21
22#include <functional>
23#include <memory>
24#include <string>
25
26#include <nav2_core/global_planner.hpp>
27#include <nav_msgs/msg/path.hpp>
28#include <rclcpp/rclcpp.hpp>
29
30namespace cl_nav2z
31{
32namespace forward_global_planner
33{
34class ForwardGlobalPlanner : public nav2_core::GlobalPlanner
35{
36public:
37 using Ptr = std::shared_ptr<ForwardGlobalPlanner>;
38
40
44 virtual ~ForwardGlobalPlanner();
45
52 void configure(
53 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
54 const std::shared_ptr<tf2_ros::Buffer> tf,
55 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
56
60 virtual void cleanup();
61
65 virtual void activate();
66
70 virtual void deactivate();
71
79 virtual nav_msgs::msg::Path createPlan(
80 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal,
81 std::function<bool()> cancel_checker) override;
82
83private:
84 // rclcpp::Node::SharedPtr nh_;
85 rclcpp_lifecycle::LifecycleNode::SharedPtr nh_;
86
87 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> planPub_;
88
90 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
91
93
94 double puresSpinningRadStep_; // rads
95
96 std::string name_;
97
99
100 std::shared_ptr<tf2_ros::Buffer> tf_;
101};
102} // namespace forward_global_planner
103} // namespace cl_nav2z
virtual void deactivate()
Method to deactivate planner and any threads involved in execution.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr< tf2_ros::Buffer > tf, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_
virtual void cleanup()
Method to cleanup resources used on shutdown.
virtual nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::function< bool()> cancel_checker) override
Method create the plan from a starting and ending goal.
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
stored but almost not used
virtual void activate()
Method to active planner and any threads involved in execution.