Class RouteServer

Inheritance Relationships

Base Type

  • public nav2_util::LifecycleNode

Class Documentation

class RouteServer : public nav2_util::LifecycleNode

An action server implements a Navigation Route-Graph planner to compliment free-space planning in the Planner Server.

Public Types

using ComputeRoute = nav2_msgs::action::ComputeRoute
using ComputeRouteGoal = ComputeRoute::Goal
using ComputeRouteResult = ComputeRoute::Result
using ComputeRouteServer = nav2_util::SimpleActionServer<ComputeRoute>
using ComputeAndTrackRoute = nav2_msgs::action::ComputeAndTrackRoute
using ComputeAndTrackRouteGoal = ComputeAndTrackRoute::Goal
using ComputeAndTrackRouteFeedback = ComputeAndTrackRoute::Feedback
using ComputeAndTrackRouteResult = ComputeAndTrackRoute::Result
using ComputeAndTrackRouteServer = nav2_util::SimpleActionServer<ComputeAndTrackRoute>

Public Functions

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

A constructor for nav2_route::RouteServer.

Parameters:

options – Additional options to control creation of the node.

~RouteServer() = default

A destructor for nav2_route::RouteServer.

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

void computeRoute()

Main route action server callbacks for computing and tracking a route.

void computeAndTrackRoute()
template<typename GoalT>
Route findRoute(const std::shared_ptr<const GoalT> goal, ReroutingState &rerouting_info)

Compute a route to the goal, incorporating rerouting information.

This method combines finding the starting and ending nodes with the route planner to determine the relevant node locations and compute the route. The provided ReroutingState can specify:

  • an updated starting node ID when tracking a previous route,

  • an overridden starting pose for rerouting,

  • optional constraints such as blocked elements to avoid (if provided).

This allows progress to continue smoothly when re-planning or recovering from partial execution of a previous route.

Parameters:
  • goal – The request goal information.

  • rerouting_info – State describing updated start and rerouting context.

Returns:

A route from the selected start node to the goal.

template<typename GoalT>
Route findRoute(const std::shared_ptr<const GoalT> goal)

Compute a route to the goal.

Parameters:

goal – The request goal information.

Returns:

A route from the selected start node to the goal.

template<typename ActionT>
void processRouteRequest(std::shared_ptr<nav2_util::SimpleActionServer<ActionT>> &action_server)

Main processing called by both action server callbacks to centralize the great deal of shared code between them.

rclcpp::Duration findPlanningDuration(const rclcpp::Time &start_time)

Find the planning duration of the request and log warnings.

Parameters:

start_time – Start of planning time

Returns:

Duration of planning time

template<typename ActionT>
bool isRequestValid(std::shared_ptr<nav2_util::SimpleActionServer<ActionT>> &action_server)

Find the routing request is valid (action server OK and not cancelled)

Parameters:

action_server – Actions server to check

Returns:

if the request is valid

void populateActionResult(std::shared_ptr<ComputeRoute::Result> result, const Route &route, const nav_msgs::msg::Path &path, const rclcpp::Duration &planning_duration)

Populate result for compute route action.

Parameters:
  • result – Result to populate

  • routeRoute to use to populate result

  • path – Path to use to populate result

  • planning_duration – Time to create a valid route

void populateActionResult(std::shared_ptr<ComputeAndTrackRoute::Result>, const Route&, const nav_msgs::msg::Path&, const rclcpp::Duration&)

Populate result for compute and track route action.

Parameters:
  • result – Result to populate

  • routeRoute to use to populate result

  • path – Path to use to populate result

  • planning_duration – Time to create a valid route

void setRouteGraph(const std::shared_ptr<rmw_request_id_t>, const std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Request> request, std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Response> response)

The service callback to set a new route graph.

Parameters:
  • request_header – to the service

  • request – to the service

  • response – from the service

template<typename GoalT>
void exceptionWarning(const std::shared_ptr<const GoalT> goal, const std::exception &ex)

Log exception warnings, templated by action message type.

Parameters:
  • goal – Goal that failed

  • exception – Exception message

Protected Attributes

std::shared_ptr<ComputeRouteServer> compute_route_server_
std::shared_ptr<ComputeAndTrackRouteServer> compute_and_track_route_server_
std::shared_ptr<tf2_ros::Buffer> tf_
std::shared_ptr<tf2_ros::TransformListener> transform_listener_
rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr graph_vis_publisher_
rclcpp::Service<nav2_msgs::srv::SetRouteGraph>::SharedPtr set_graph_service_
std::shared_ptr<GraphLoader> graph_loader_
std::shared_ptr<RoutePlanner> route_planner_
std::shared_ptr<RouteTracker> route_tracker_
std::shared_ptr<PathConverter> path_converter_
std::shared_ptr<GoalIntentExtractor> goal_intent_extractor_
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber_
Graph graph_
GraphToIDMap id_to_graph_map_
std::string route_frame_
std::string base_frame_
std::string global_frame_
double max_planning_time_