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

Public Member Functions

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
 
void cleanup () override
 Method to cleanup resources used on shutdown.
 
void activate () override
 Method to active planner and any threads involved in execution.
 
void deactivate () override
 Method to deactivate planner and any threads involved in execution.
 
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

void getPlan (nav_msgs::msg::Path &global_path, std::function< bool()> cancel_checker)
 the function responsible for calling the algorithm and retrieving a path from it More...
 
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Callback executed when a parameter change is detected. More...
 

Static Protected Member Functions

static nav_msgs::msg::Path linearInterpolation (const std::vector< coordsW > &raw_path, const double &dist_bw_points)
 interpolates points between the consecutive waypoints of the path More...
 

Protected Attributes

std::shared_ptr< tf2_ros::Buffer > tf_
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Logger logger_ {rclcpp::get_logger("ThetaStarPlanner")}
 
std::string global_frame_
 
std::string name_
 
bool use_final_approach_orientation_
 
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node_
 
std::unique_ptr< theta_star::ThetaStarplanner_
 
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
 

Additional Inherited Members

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

Detailed Description

Definition at line 43 of file theta_star_planner.hpp.

Member Function Documentation

◆ configure()

void nav2_theta_star_planner::ThetaStarPlanner::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
Parameters
parentpointer to user's node
nameThe name of this planner
tfA pointer to a TF buffer
costmap_rosA pointer to the costmap

Implements nav2_core::GlobalPlanner.

Definition at line 27 of file theta_star_planner.cpp.

◆ createPlan()

nav_msgs::msg::Path nav2_theta_star_planner::ThetaStarPlanner::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 100 of file theta_star_planner.cpp.

References getPlan().

Here is the call graph for this function:

◆ dynamicParametersCallback()

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

Callback executed when a parameter change is detected.

Parameters
parameterslist of changed parameters

Definition at line 237 of file theta_star_planner.cpp.

Referenced by activate().

Here is the caller graph for this function:

◆ getPlan()

void nav2_theta_star_planner::ThetaStarPlanner::getPlan ( nav_msgs::msg::Path &  global_path,
std::function< bool()>  cancel_checker 
)
protected

the function responsible for calling the algorithm and retrieving a path from it

Parameters
cancel_checkeris a function to check if the action has been canceled
Returns
global_path is the planned path to be taken

Definition at line 190 of file theta_star_planner.cpp.

References linearInterpolation().

Referenced by createPlan().

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

◆ linearInterpolation()

nav_msgs::msg::Path nav2_theta_star_planner::ThetaStarPlanner::linearInterpolation ( const std::vector< coordsW > &  raw_path,
const double &  dist_bw_points 
)
staticprotected

interpolates points between the consecutive waypoints of the path

Parameters
raw_pathis used to send in the path received from the planner
dist_bw_pointsis used to send in the interpolation_resolution (which has been set as the costmap resolution)
Returns
the final path with waypoints at a distance of the value of interpolation_resolution of each other

Definition at line 208 of file theta_star_planner.cpp.

Referenced by getPlan().

Here is the caller graph for this function:

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