An action server implements a Navigation Route-Graph planner to compliment free-space planning in the Planner Server.
More...
|
using | ComputeRoute = nav2_msgs::action::ComputeRoute |
|
using | ComputeRouteGoal = ComputeRoute::Goal |
|
using | ComputeRouteResult = ComputeRoute::Result |
|
using | ComputeRouteServer = nav2::SimpleActionServer< ComputeRoute > |
|
using | ComputeAndTrackRoute = nav2_msgs::action::ComputeAndTrackRoute |
|
using | ComputeAndTrackRouteGoal = ComputeAndTrackRoute::Goal |
|
using | ComputeAndTrackRouteFeedback = ComputeAndTrackRoute::Feedback |
|
using | ComputeAndTrackRouteResult = ComputeAndTrackRoute::Result |
|
using | ComputeAndTrackRouteServer = nav2::SimpleActionServer< ComputeAndTrackRoute > |
|
using | SharedPtr = std::shared_ptr< nav2::LifecycleNode > |
|
using | WeakPtr = std::weak_ptr< nav2::LifecycleNode > |
|
using | SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode > |
|
|
| RouteServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) |
| A constructor for nav2_route::RouteServer. More...
|
|
| ~RouteServer ()=default |
| A destructor for nav2_route::RouteServer.
|
|
| LifecycleNode (const std::string &node_name, const std::string &ns, const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) |
| A lifecycle node constructor. More...
|
|
| LifecycleNode (const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) |
| A lifecycle node constructor with no namespace. More...
|
|
template<typename ParamType > |
ParamType | declare_or_get_parameter (const std::string ¶meter_name, const ParamType &default_value, const ParameterDescriptor ¶meter_descriptor=ParameterDescriptor()) |
| Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise declares it and returns the default value. More...
|
|
template<typename MessageT , typename CallbackT > |
nav2::Subscription< MessageT >::SharedPtr | create_subscription (const std::string &topic_name, CallbackT &&callback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr) |
| Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions. More...
|
|
template<typename MessageT > |
nav2::Publisher< MessageT >::SharedPtr | create_publisher (const std::string &topic_name, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr) |
| Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions. More...
|
|
template<typename ServiceT > |
nav2::ServiceClient< ServiceT >::SharedPtr | create_client (const std::string &service_name, bool use_internal_executor=false) |
| Create a ServiceClient to interface with a service. More...
|
|
template<typename ServiceT > |
nav2::ServiceServer< ServiceT >::SharedPtr | create_service (const std::string &service_name, typename nav2::ServiceServer< ServiceT >::CallbackType cb, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr) |
| Create a ServiceServer to host with a service. More...
|
|
template<typename ActionT > |
nav2::SimpleActionServer< ActionT >::SharedPtr | create_action_server (const std::string &action_name, typename nav2::SimpleActionServer< ActionT >::ExecuteCallback execute_callback, typename nav2::SimpleActionServer< ActionT >::CompletionCallback compl_cb=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const bool realtime=false) |
| Create a SimpleActionServer to host with an action. More...
|
|
template<typename ActionT > |
nav2::ActionClient< ActionT >::SharedPtr | create_action_client (const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr) |
| Create a ActionClient to call an action using. More...
|
|
nav2::LifecycleNode::SharedPtr | shared_from_this () |
| Get a shared pointer of this.
|
|
nav2::LifecycleNode::WeakPtr | weak_from_this () |
| Get a shared pointer of this.
|
|
nav2::CallbackReturn | on_error (const rclcpp_lifecycle::State &) |
| Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More...
|
|
void | autostart () |
| Automatically configure and active the node.
|
|
virtual void | on_rcl_preshutdown () |
| Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine.
|
|
void | createBond () |
| Create bond connection to lifecycle manager.
|
|
void | destroyBond () |
| Destroy bond connection to lifecycle manager.
|
|
|
nav2::CallbackReturn | on_configure (const rclcpp_lifecycle::State &state) override |
| Configure member variables and initializes planner. More...
|
|
nav2::CallbackReturn | on_activate (const rclcpp_lifecycle::State &state) override |
| Activate member variables. More...
|
|
nav2::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &state) override |
| Deactivate member variables. More...
|
|
nav2::CallbackReturn | on_cleanup (const rclcpp_lifecycle::State &state) override |
| Reset member variables. More...
|
|
nav2::CallbackReturn | on_shutdown (const rclcpp_lifecycle::State &state) override |
| Called when in shutdown state. More...
|
|
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=ReroutingState()) |
| Abstract method combining finding the starting/ending nodes and the route planner to find the Node locations of interest and route to the goal. More...
|
|
template<typename ActionT > |
void | processRouteRequest (typename nav2::SimpleActionServer< ActionT >::SharedPtr &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. More...
|
|
template<typename ActionT > |
bool | isRequestValid (typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server) |
| Find the routing request is valid (action server OK and not cancelled) More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
template<typename GoalT > |
void | exceptionWarning (const std::shared_ptr< const GoalT > goal, const std::exception &ex) |
| Log exception warnings, templated by action message type. More...
|
|
void | printLifecycleNodeNotification () |
| Print notifications for lifecycle node.
|
|
void | register_rcl_preshutdown_callback () |
|
void | runCleanups () |
|
|
ComputeRouteServer::SharedPtr | compute_route_server_ |
|
ComputeAndTrackRouteServer::SharedPtr | compute_and_track_route_server_ |
|
std::shared_ptr< tf2_ros::Buffer > | tf_ |
|
std::shared_ptr< tf2_ros::TransformListener > | transform_listener_ |
|
nav2::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr | graph_vis_publisher_ |
|
nav2::ServiceServer< 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_ |
|
double | max_planning_time_ |
|
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > | rcl_preshutdown_cb_handle_ {nullptr} |
|
std::shared_ptr< bond::Bond > | bond_ {nullptr} |
|
double | bond_heartbeat_period {0.1} |
|
rclcpp::TimerBase::SharedPtr | autostart_timer_ |
|
An action server implements a Navigation Route-Graph planner to compliment free-space planning in the Planner Server.
Definition at line 55 of file route_server.hpp.