Class PlannerServer

Inheritance Relationships

Base Type

  • public nav2_util::LifecycleNode

Class Documentation

class PlannerServer : public nav2_util::LifecycleNode

An action server implements the behavior tree’s ComputePathToPose interface and hosts various plugins of different algorithms to compute plans.

Public Types

using PlannerMap = std::unordered_map<std::string, nav2_core::GlobalPlanner::Ptr>

Public Functions

explicit PlannerServer(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

A constructor for nav2_planner::PlannerServer.

Parameters:

options – Additional options to control creation of the node.

~PlannerServer()

A destructor for nav2_planner::PlannerServer.

nav_msgs::msg::Path getPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, const std::string &planner_id)

Method to get plan from the desired plugin.

Parameters:
  • start – starting pose

  • goal – goal request

Returns:

Path

Protected Types

using ActionToPose = nav2_msgs::action::ComputePathToPose
using ActionToPoseGoal = ActionToPose::Goal
using ActionThroughPoses = nav2_msgs::action::ComputePathThroughPoses
using ActionThroughPosesGoal = ActionThroughPoses::Goal
using ActionServerToPose = nav2_util::SimpleActionServer<ActionToPose>
using ActionServerThroughPoses = nav2_util::SimpleActionServer<ActionThroughPoses>

Protected Functions

nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

Configure member variables and initializes planner.

Parameters:

state – Reference to LifeCycle node state

Returns:

SUCCESS or FAILURE

nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

Activate member variables.

Parameters:

state – Reference to LifeCycle node state

Returns:

SUCCESS or FAILURE

nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

Deactivate member variables.

Parameters:

state – Reference to LifeCycle node state

Returns:

SUCCESS or FAILURE

nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

Reset member variables.

Parameters:

state – Reference to LifeCycle node state

Returns:

SUCCESS or FAILURE

nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Called when in shutdown state.

Parameters:

state – Reference to LifeCycle node state

Returns:

SUCCESS or FAILURE

template<typename T>
bool isServerInactive(std::unique_ptr<nav2_util::SimpleActionServer<T>> &action_server)

Check if an action server is valid / active.

Parameters:

action_server – Action server to test

Returns:

SUCCESS or FAILURE

template<typename T>
bool isCancelRequested(std::unique_ptr<nav2_util::SimpleActionServer<T>> &action_server)

Check if an action server has a cancellation request pending.

Parameters:

action_server – Action server to test

Returns:

SUCCESS or FAILURE

void waitForCostmap()

Wait for costmap to be valid with updated sensor data or repopulate after a clearing recovery. Blocks until true without timeout.

template<typename T>
void getPreemptedGoalIfRequested(std::unique_ptr<nav2_util::SimpleActionServer<T>> &action_server, typename std::shared_ptr<const typename T::Goal> goal)

Check if an action server has a preemption request and replaces the goal with the new preemption goal.

Parameters:
  • action_server – Action server to get updated goal if required

  • goal – Goal to overwrite

template<typename T>
bool getStartPose(typename std::shared_ptr<const typename T::Goal> goal, geometry_msgs::msg::PoseStamped &start)

Get the starting pose from costmap or message, if valid.

Parameters:
  • action_server – Action server to terminate if required

  • goal – Goal to find start from

  • start – The starting pose to use

Returns:

bool If successful in finding a valid starting pose

bool transformPosesToGlobalFrame(geometry_msgs::msg::PoseStamped &curr_start, geometry_msgs::msg::PoseStamped &curr_goal)

Transform start and goal poses into the costmap global frame for path planning plugins to utilize.

Parameters:
  • start – The starting pose to transform

  • goal – Goal pose to transform

Returns:

bool If successful in transforming poses

template<typename T>
bool validatePath(const geometry_msgs::msg::PoseStamped &curr_goal, const nav_msgs::msg::Path &path, const std::string &planner_id)

Validate that the path contains a meaningful path.

Parameters:
  • action_server – Action server to terminate if required

  • goal – Goal Current goal

  • path – Current path

  • planner_id – The planner ID used to generate the path

Returns:

bool If path is valid

void computePlan()

The action server callback which calls planner to get the path ComputePathToPose.

void computePlanThroughPoses()

The action server callback which calls planner to get the path ComputePathThroughPoses.

void isPathValid(const std::shared_ptr<nav2_msgs::srv::IsPathValid::Request> request, std::shared_ptr<nav2_msgs::srv::IsPathValid::Response> response)

The service callback to determine if the path is still valid.

Parameters:
  • request – to the service

  • response – from the service

void publishPlan(const nav_msgs::msg::Path &path)

Publish a path for visualization purposes.

Parameters:

path – Reference to Global Path

void exceptionWarning(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, const std::string &planner_id, const std::exception &ex)
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)

Callback executed when a parameter change is detected.

Parameters:

event – ParameterEvent message

Protected Attributes

std::unique_ptr<ActionServerToPose> action_server_pose_
std::unique_ptr<ActionServerThroughPoses> action_server_poses_
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
std::mutex dynamic_params_lock_
PlannerMap planners_
pluginlib::ClassLoader<nav2_core::GlobalPlanner> gp_loader_
std::vector<std::string> default_ids_
std::vector<std::string> default_types_
std::vector<std::string> planner_ids_
std::vector<std::string> planner_types_
double max_planner_duration_
std::string planner_ids_concat_
rclcpp::Clock steady_clock_ = {RCL_STEADY_TIME}
std::shared_ptr<tf2_ros::Buffer> tf_
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_
std::unique_ptr<nav2_util::NodeThread> costmap_thread_
nav2_costmap_2d::Costmap2D *costmap_
std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D*>> collision_checker_
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_
rclcpp::Service<nav2_msgs::srv::IsPathValid>::SharedPtr is_path_valid_service_