Class ThetaStarPlanner

Inheritance Relationships

Base Type

  • public nav2_core::GlobalPlanner

Class Documentation

class ThetaStarPlanner : public nav2_core::GlobalPlanner

Public Functions

virtual 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
virtual void cleanup() override
virtual void activate() override
virtual void deactivate() override
virtual nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override

Protected Functions

void getPlan(nav_msgs::msg::Path &global_path)

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

Returns:

global_path is the planned path to be taken

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

Callback executed when a paramter change is detected.

Parameters:

parameters – list of changed parameters

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::ThetaStar> planner_
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_

Protected Static 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

Parameters:
  • raw_path – is used to send in the path received from the planner

  • dist_bw_points – is 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