Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_smac_planner::SmacPlannerHybrid Class Reference
Inheritance diagram for nav2_smac_planner::SmacPlannerHybrid:
Inheritance graph
[legend]
Collaboration diagram for nav2_smac_planner::SmacPlannerHybrid:
Collaboration graph
[legend]

Public Member Functions

 SmacPlannerHybrid ()
 constructor
 
 ~SmacPlannerHybrid ()
 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. More...
 
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. More...
 
- Public Member Functions inherited from nav2_core::GlobalPlanner
virtual ~GlobalPlanner ()
 Virtual destructor.
 

Protected Member Functions

rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Callback executed when a parameter change is detected. More...
 

Protected Attributes

std::unique_ptr< AStarAlgorithm< NodeHybrid > > _a_star
 
GridCollisionChecker _collision_checker
 
std::unique_ptr< Smoother_smoother
 
rclcpp::Clock::SharedPtr _clock
 
rclcpp::Logger _logger {rclcpp::get_logger("SmacPlannerHybrid")}
 
nav2_costmap_2d::Costmap2D_costmap
 
std::shared_ptr< nav2_costmap_2d::Costmap2DROS_costmap_ros
 
std::unique_ptr< CostmapDownsampler_costmap_downsampler
 
std::string _global_frame
 
std::string _name
 
float _lookup_table_dim
 
float _tolerance
 
bool _downsample_costmap
 
int _downsampling_factor
 
double _angle_bin_size
 
unsigned int _angle_quantizations
 
bool _allow_unknown
 
int _max_iterations
 
int _max_on_approach_iterations
 
int _terminal_checking_interval
 
SearchInfo _search_info
 
double _max_planning_time
 
double _lookup_table_size
 
double _minimum_turning_radius_global_coords
 
bool _debug_visualizations
 
std::string _motion_model_for_search
 
MotionModel _motion_model
 
GoalHeadingMode _goal_heading_mode
 
int _coarse_search_resolution
 
rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path >::SharedPtr _raw_plan_publisher
 
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
 
std::mutex _mutex
 
rclcpp_lifecycle::LifecycleNode::WeakPtr _node
 
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler
 
std::shared_ptr< rclcpp::ParameterEventHandler > _remote_param_subscriber
 
std::shared_ptr< rclcpp::ParameterCallbackHandle > _remote_resolution_handler
 

Additional Inherited Members

- Public Types inherited from nav2_core::GlobalPlanner
using Ptr = std::shared_ptr< GlobalPlanner >
 

Detailed Description

Definition at line 40 of file smac_planner_hybrid.hpp.

Member Function Documentation

◆ configure()

void nav2_smac_planner::SmacPlannerHybrid::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 
)
overridevirtual

Configuring plugin.

Parameters
parentLifecycle node pointer
nameName of plugin map
tfShared ptr of TF2 buffer
costmap_rosCostmap2DROS object

Implements nav2_core::GlobalPlanner.

Definition at line 50 of file smac_planner_hybrid.cpp.

References nav2_smac_planner::SmootherParams::get(), nav2_costmap_2d::Costmap2D::getResolution(), and nav2_smac_planner::GridCollisionChecker::setFootprint().

Here is the call graph for this function:

◆ createPlan()

nav_msgs::msg::Path nav2_smac_planner::SmacPlannerHybrid::createPlan ( const geometry_msgs::msg::PoseStamped &  start,
const geometry_msgs::msg::PoseStamped &  goal,
std::function< bool()>  cancel_checker 
)
overridevirtual

Creating a plan from start and goal poses.

Parameters
startStart pose
goalGoal pose
cancel_checkerFunction to check if the action has been canceled
Returns
nav2_msgs::Path of the generated path

Implements nav2_core::GlobalPlanner.

Definition at line 382 of file smac_planner_hybrid.cpp.

References nav2_costmap_2d::Costmap2D::getResolution(), nav2_costmap_2d::FootprintCollisionChecker< CostmapT >::setCostmap(), nav2_smac_planner::GridCollisionChecker::setFootprint(), and nav2_costmap_2d::Costmap2D::worldToMapContinuous().

Here is the call graph for this function:

◆ dynamicParametersCallback()

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

Callback executed when a parameter change is detected.

Parameters
parameterslist of changed parameters

Definition at line 612 of file smac_planner_hybrid.cpp.

References nav2_smac_planner::SmootherParams::get(), nav2_costmap_2d::Costmap2D::getResolution(), and nav2_smac_planner::GridCollisionChecker::setFootprint().

Referenced by activate().

Here is the call graph for this function:
Here is the caller graph for this function:

The documentation for this class was generated from the following files: