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>
29namespace undo_path_global_planner
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);
74 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal);
78 rclcpp_lifecycle::LifecycleNode::SharedPtr
nh_;
81 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr
planPub_;
83 rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
markersPub_;
92 void publishGoalMarker(
const geometry_msgs::msg::Pose & pose,
double r,
double g,
double b);
97 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal,
98 std::vector<geometry_msgs::msg::PoseStamped> & plan);
108 std::shared_ptr<tf2_ros::Buffer>
tf_;
rclcpp_lifecycle::LifecycleNode::SharedPtr nh_
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_
double skip_straight_motion_distance_
double puresSpinningRadStep_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
stored but almost not used
std::shared_ptr< tf2_ros::Buffer > tf_
rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path >::SharedPtr planPub_
virtual void activate()
Method to active planner and any threads involved in execution.
virtual ~UndoPathGlobalPlanner()
Virtual destructor.
void onForwardTrailMsg(const nav_msgs::msg::Path::SharedPtr trailMessage)
void publishGoalMarker(const geometry_msgs::msg::Pose &pose, double r, double g, double b)
double transform_tolerance_
virtual void createDefaultUndoPathPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::vector< geometry_msgs::msg::PoseStamped > &plan)
nav_msgs::msg::Path lastForwardPathMsg_