Class SmacPlannerLattice

Inheritance Relationships

Base Type

  • public nav2_core::GlobalPlanner

Class Documentation

class SmacPlannerLattice : public nav2_core::GlobalPlanner

Public Functions

SmacPlannerLattice()

constructor

~SmacPlannerLattice()

destructor

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.

Parameters:
  • parent – Lifecycle node pointer

  • name – Name of plugin map

  • tf – Shared ptr of TF2 buffer

  • costmap_ros – Costmap2DROS object

void cleanup() override

Cleanup lifecycle node.

void activate() override

Activate lifecycle node.

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.

Parameters:
  • start – Start pose

  • goal – Goal pose

  • cancel_checker – Function to check if the action has been canceled

Returns:

nav2_msgs::Path of the generated path

Protected Functions

rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)

Callback executed when a parameter change is detected.

Parameters:

parameters – list of changed parameters

Protected Attributes

std::unique_ptr<AStarAlgorithm<NodeLattice>> _a_star
GridCollisionChecker _collision_checker
std::unique_ptr<Smoother> _smoother
rclcpp::Clock::SharedPtr _clock
rclcpp::Logger _logger = {rclcpp::get_logger("SmacPlannerLattice")}
nav2_costmap_2d::Costmap2D *_costmap
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> _costmap_ros
MotionModel _motion_model
LatticeMetadata _metadata
std::string _global_frame
std::string _name
SearchInfo _search_info
bool _allow_unknown
int _max_iterations
int _max_on_approach_iterations
int _terminal_checking_interval
float _tolerance
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher
double _max_planning_time
double _lookup_table_size
bool _debug_visualizations
rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr _planned_footprints_publisher
rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr _smoothed_footprints_publisher
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseArray>::SharedPtr _expansions_publisher
GoalHeadingMode _goal_heading_mode
int _coarse_search_resolution
std::mutex _mutex
rclcpp_lifecycle::LifecycleNode::WeakPtr _node
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler