15 #ifndef NAV2_SMAC_PLANNER__SMAC_PLANNER_HYBRID_HPP_
16 #define NAV2_SMAC_PLANNER__SMAC_PLANNER_HYBRID_HPP_
22 #include "nav2_smac_planner/a_star.hpp"
23 #include "nav2_smac_planner/smoother.hpp"
24 #include "nav2_smac_planner/utils.hpp"
25 #include "nav2_smac_planner/costmap_downsampler.hpp"
26 #include "nav_msgs/msg/occupancy_grid.hpp"
27 #include "nav2_core/global_planner.hpp"
28 #include "nav_msgs/msg/path.hpp"
29 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
30 #include "nav2_costmap_2d/costmap_2d.hpp"
31 #include "geometry_msgs/msg/pose_stamped.hpp"
32 #include "geometry_msgs/msg/pose_array.hpp"
33 #include "nav2_ros_common/lifecycle_node.hpp"
34 #include "nav2_ros_common/node_utils.hpp"
35 #include "tf2/utils.hpp"
37 namespace nav2_smac_planner
61 const nav2::LifecycleNode::WeakPtr & parent,
62 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
63 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
88 const geometry_msgs::msg::PoseStamped & start,
89 const geometry_msgs::msg::PoseStamped & goal,
90 std::function<
bool()> cancel_checker)
override;
97 rcl_interfaces::msg::SetParametersResult
100 std::unique_ptr<AStarAlgorithm<NodeHybrid>> _a_star;
102 std::unique_ptr<Smoother> _smoother;
103 rclcpp::Clock::SharedPtr _clock;
104 rclcpp::Logger _logger{rclcpp::get_logger(
"SmacPlannerHybrid")};
106 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> _costmap_ros;
107 std::unique_ptr<CostmapDownsampler> _costmap_downsampler;
108 std::string _global_frame, _name;
109 float _lookup_table_dim;
111 bool _downsample_costmap;
112 int _downsampling_factor;
113 double _angle_bin_size;
114 unsigned int _angle_quantizations;
117 int _max_on_approach_iterations;
118 int _terminal_checking_interval;
120 double _max_planning_time;
121 double _lookup_table_size;
122 double _minimum_turning_radius_global_coords;
123 bool _debug_visualizations;
124 std::string _motion_model_for_search;
125 MotionModel _motion_model;
126 GoalHeadingMode _goal_heading_mode;
127 int _coarse_search_resolution;
128 nav2::Publisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
129 nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
130 _planned_footprints_publisher;
131 nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
132 _smoothed_footprints_publisher;
133 nav2::Publisher<geometry_msgs::msg::PoseArray>::SharedPtr
134 _expansions_publisher;
136 nav2::LifecycleNode::WeakPtr _node;
139 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler;
140 std::shared_ptr<rclcpp::ParameterEventHandler> _remote_param_subscriber;
141 std::shared_ptr<rclcpp::ParameterCallbackHandle> _remote_resolution_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 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.
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.
SmacPlannerHybrid()
constructor
void activate() override
Activate lifecycle node.
void cleanup() override
Cleanup lifecycle node.
void deactivate() override
Deactivate lifecycle node.
~SmacPlannerHybrid()
destructor
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Search properties and penalties.