15 #ifndef NAV2_SMAC_PLANNER__SMAC_PLANNER_LATTICE_HPP_
16 #define NAV2_SMAC_PLANNER__SMAC_PLANNER_LATTICE_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 "nav_msgs/msg/occupancy_grid.hpp"
26 #include "nav2_core/global_planner.hpp"
27 #include "nav_msgs/msg/path.hpp"
28 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
29 #include "nav2_costmap_2d/costmap_2d.hpp"
30 #include "geometry_msgs/msg/pose_stamped.hpp"
31 #include "nav2_util/lifecycle_node.hpp"
32 #include "nav2_util/node_utils.hpp"
33 #include "tf2/utils.h"
35 namespace nav2_smac_planner
59 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
60 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
61 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
85 const geometry_msgs::msg::PoseStamped & start,
86 const geometry_msgs::msg::PoseStamped & goal)
override;
93 rcl_interfaces::msg::SetParametersResult
96 std::unique_ptr<AStarAlgorithm<NodeLattice>> _a_star;
98 std::unique_ptr<Smoother> _smoother;
99 rclcpp::Clock::SharedPtr _clock;
100 rclcpp::Logger _logger{rclcpp::get_logger(
"SmacPlannerLattice")};
102 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> _costmap_ros;
103 MotionModel _motion_model;
105 std::string _global_frame, _name;
109 int _max_on_approach_iterations;
111 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
112 double _max_planning_time;
113 double _lookup_table_size;
115 rclcpp_lifecycle::LifecycleNode::WeakPtr _node;
118 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 deactivate() override
Deactivate lifecycle node.
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) override
Configuring plugin.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override
Creating a plan from start and goal poses.
~SmacPlannerLattice()
destructor
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
void cleanup() override
Cleanup lifecycle node.
SmacPlannerLattice()
constructor
void activate() override
Activate lifecycle node.
Search properties and penalties.