15 #ifndef NAV2_SMAC_PLANNER__SMAC_PLANNER_2D_HPP_
16 #define NAV2_SMAC_PLANNER__SMAC_PLANNER_2D_HPP_
23 #include "nav2_smac_planner/a_star.hpp"
24 #include "nav2_smac_planner/smoother.hpp"
25 #include "nav2_smac_planner/utils.hpp"
26 #include "nav2_smac_planner/costmap_downsampler.hpp"
27 #include "nav_msgs/msg/occupancy_grid.hpp"
28 #include "nav2_core/global_planner.hpp"
29 #include "nav_msgs/msg/path.hpp"
30 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
31 #include "nav2_costmap_2d/costmap_2d.hpp"
32 #include "geometry_msgs/msg/pose_stamped.hpp"
33 #include "nav2_ros_common/lifecycle_node.hpp"
34 #include "nav2_ros_common/node_utils.hpp"
35 #include "tf2/utils.hpp"
36 #include "rcl_interfaces/msg/set_parameters_result.hpp"
38 namespace nav2_smac_planner
62 const nav2::LifecycleNode::WeakPtr & parent,
63 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
64 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
89 const geometry_msgs::msg::PoseStamped & start,
90 const geometry_msgs::msg::PoseStamped & goal,
91 std::function<
bool()> cancel_checker)
override;
98 rcl_interfaces::msg::SetParametersResult
101 std::unique_ptr<AStarAlgorithm<Node2D>> _a_star;
103 std::unique_ptr<Smoother> _smoother;
105 std::unique_ptr<CostmapDownsampler> _costmap_downsampler;
106 rclcpp::Clock::SharedPtr _clock;
107 rclcpp::Logger _logger{rclcpp::get_logger(
"SmacPlanner2D")};
108 std::string _global_frame, _name;
110 int _downsampling_factor;
111 bool _downsample_costmap;
112 nav2::Publisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
113 double _max_planning_time;
116 int _max_on_approach_iterations;
117 int _terminal_checking_interval;
118 bool _use_final_approach_orientation;
120 std::string _motion_model_for_search;
121 MotionModel _motion_model;
123 nav2::LifecycleNode::WeakPtr _node;
126 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler;
Abstract interface for global planners to adhere to with pluginlib.
A 2D costmap provides a mapping between points in the world and their associated "costs".
A costmap grid collision checker.
void activate() override
Activate lifecycle node.
SmacPlanner2D()
constructor
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
~SmacPlanner2D()
destructor
void cleanup() override
Cleanup lifecycle node.
void configure(const nav2::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configuring plugin.
void deactivate() override
Deactivate lifecycle node.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::function< bool()> cancel_checker) override
Creating a plan from start and goal poses.
Search properties and penalties.