SMACC2
Loading...
Searching...
No Matches
undo_path_global_planner.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI 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 <nav2_core/global_planner.hpp>
23#include <nav_msgs/msg/path.hpp>
24#include <rclcpp/rclcpp.hpp>
25#include <visualization_msgs/msg/marker_array.hpp>
26
27namespace cl_nav2z
28{
29namespace undo_path_global_planner
30{
31class UndoPathGlobalPlanner : public nav2_core::GlobalPlanner
32{
33public:
35
39 virtual ~UndoPathGlobalPlanner();
40
47 virtual void configure(
48 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
49 std::shared_ptr<tf2_ros::Buffer> tf,
50 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros);
51
55 virtual void cleanup();
56
60 virtual void activate();
61
65 virtual void deactivate();
66
73 virtual nav_msgs::msg::Path createPlan(
74 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal);
75
76private:
77 // rclcpp::Node::SharedPtr nh_;
78 rclcpp_lifecycle::LifecycleNode::SharedPtr nh_;
79 rclcpp::Subscription<nav_msgs::msg::Path>::SharedPtr forwardPathSub_;
80
81 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr planPub_;
82
83 rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr markersPub_;
84
85 nav_msgs::msg::Path lastForwardPathMsg_;
86
88 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
89
90 void onForwardTrailMsg(const nav_msgs::msg::Path::SharedPtr trailMessage);
91
92 void publishGoalMarker(const geometry_msgs::msg::Pose & pose, double r, double g, double b);
93
94 void clearGoalMarker();
95
96 virtual void createDefaultUndoPathPlan(
97 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal,
98 std::vector<geometry_msgs::msg::PoseStamped> & plan);
99
101
102 double puresSpinningRadStep_; // rads
103
105
106 std::string name_;
107
108 std::shared_ptr<tf2_ros::Buffer> tf_;
109};
110} // namespace undo_path_global_planner
111} // namespace cl_nav2z
virtual nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal)
Method create the plan from a starting and ending goal.
virtual void deactivate()
Method to deactivate planner and any threads involved in execution.
virtual void cleanup()
Method to cleanup resources used on shutdown.
rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray >::SharedPtr markersPub_
virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
rclcpp::Subscription< nav_msgs::msg::Path >::SharedPtr forwardPathSub_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
stored but almost not used
rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path >::SharedPtr planPub_
virtual void activate()
Method to active planner and any threads involved in execution.
void onForwardTrailMsg(const nav_msgs::msg::Path::SharedPtr trailMessage)
void publishGoalMarker(const geometry_msgs::msg::Pose &pose, double r, double g, double b)
virtual void createDefaultUndoPathPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::vector< geometry_msgs::msg::PoseStamped > &plan)