|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins of different algorithms to compute plans. More...
#include <nav2_planner/include/nav2_planner/planner_server.hpp>


Public Types | |
| using | PlannerMap = std::unordered_map< std::string, nav2_core::GlobalPlanner::Ptr > |
Public Member Functions | |
| PlannerServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
| A constructor for nav2_planner::PlannerServer. More... | |
| ~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. More... | |
Public Member Functions inherited from nav2_util::LifecycleNode | |
| LifecycleNode (const std::string &node_name, const std::string &ns="", const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
| A lifecycle node constructor. More... | |
| void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
| Declare a parameter that has no integer or floating point range constraints. More... | |
| void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const floating_point_range fp_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
| Declare a parameter that has a floating point range constraint. More... | |
| void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const integer_range int_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
| Declare a parameter that has an integer range constraint. More... | |
| std::shared_ptr< nav2_util::LifecycleNode > | shared_from_this () |
| Get a shared pointer of this. | |
| nav2_util::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... | |
| 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. | |
Protected Types | |
| using | ActionToPose = nav2_msgs::action::ComputePathToPose |
| using | ActionThroughPoses = nav2_msgs::action::ComputePathThroughPoses |
| using | ActionServerToPose = nav2_util::SimpleActionServer< ActionToPose > |
| using | ActionServerThroughPoses = nav2_util::SimpleActionServer< ActionThroughPoses > |
Protected Member Functions | |
| nav2_util::CallbackReturn | on_configure (const rclcpp_lifecycle::State &state) override |
| Configure member variables and initializes planner. More... | |
| nav2_util::CallbackReturn | on_activate (const rclcpp_lifecycle::State &state) override |
| Activate member variables. More... | |
| nav2_util::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &state) override |
| Deactivate member variables. More... | |
| nav2_util::CallbackReturn | on_cleanup (const rclcpp_lifecycle::State &state) override |
| Reset member variables. More... | |
| nav2_util::CallbackReturn | on_shutdown (const rclcpp_lifecycle::State &state) override |
| Called when in shutdown state. More... | |
| template<typename T > | |
| bool | isServerInactive (std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server) |
| Check if an action server is valid / active. More... | |
| template<typename T > | |
| bool | isCancelRequested (std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server) |
| Check if an action server has a cancellation request pending. More... | |
| 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. More... | |
| template<typename T > | |
| bool | getStartPose (std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server, typename std::shared_ptr< const typename T::Goal > goal, geometry_msgs::msg::PoseStamped &start) |
| Get the starting pose from costmap or message, if valid. More... | |
| template<typename T > | |
| bool | transformPosesToGlobalFrame (std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server, 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. More... | |
| template<typename T > | |
| bool | validatePath (std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server, 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. More... | |
| 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. More... | |
| void | publishPlan (const nav_msgs::msg::Path &path) |
| Publish a path for visualization purposes. More... | |
| rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
| Callback executed when a parameter change is detected. More... | |
Protected Member Functions inherited from nav2_util::LifecycleNode | |
| void | printLifecycleNodeNotification () |
| Print notifications for lifecycle node. | |
| void | register_rcl_preshutdown_callback () |
| void | runCleanups () |
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_ |
| 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_ |
Protected Attributes inherited from nav2_util::LifecycleNode | |
| std::unique_ptr< rclcpp::PreShutdownCallbackHandle > | rcl_preshutdown_cb_handle_ {nullptr} |
| std::unique_ptr< bond::Bond > | bond_ {nullptr} |
An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins of different algorithms to compute plans.
Definition at line 51 of file planner_server.hpp.
|
explicit |
A constructor for nav2_planner::PlannerServer.
| options | Additional options to control creation of the node. |
Definition at line 44 of file planner_server.cpp.
|
protected |
Callback executed when a parameter change is detected.
| event | ParameterEvent message |
Definition at line 630 of file planner_server.cpp.
Referenced by on_activate().

| nav_msgs::msg::Path nav2_planner::PlannerServer::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.
| start | starting pose |
| goal | goal request |
Definition at line 519 of file planner_server.cpp.
Referenced by computePlan(), and computePlanThroughPoses().

|
protected |
Check if an action server has a preemption request and replaces the goal with the new preemption goal.
| action_server | Action server to get updated goal if required |
| goal | Goal to overwrite |
Definition at line 297 of file planner_server.cpp.
Referenced by computePlan(), and computePlanThroughPoses().

|
protected |
Get the starting pose from costmap or message, if valid.
| action_server | Action server to terminate if required |
| goal | Goal to find start from |
| start | The starting pose to use |
Definition at line 307 of file planner_server.cpp.
Referenced by computePlan(), and computePlanThroughPoses().

|
protected |
Check if an action server has a cancellation request pending.
| action_server | Action server to test |
Definition at line 284 of file planner_server.cpp.
Referenced by computePlan(), and computePlanThroughPoses().

|
protected |
The service callback to determine if the path is still valid.
| request | to the service |
| response | from the service |
The lethal check starts at the closest point to avoid points that have already been passed and may have become occupied
Definition at line 558 of file planner_server.cpp.
References nav2_costmap_2d::Costmap2D::getCost(), and nav2_costmap_2d::Costmap2D::worldToMap().
Referenced by on_activate().


|
protected |
Check if an action server is valid / active.
| action_server | Action server to test |
Definition at line 263 of file planner_server.cpp.
Referenced by computePlan(), and computePlanThroughPoses().

|
overrideprotected |
Activate member variables.
| state | Reference to LifeCycle node state |
Definition at line 169 of file planner_server.cpp.
References nav2_util::LifecycleNode::createBond(), dynamicParametersCallback(), isPathValid(), and nav2_util::LifecycleNode::shared_from_this().

|
overrideprotected |
Reset member variables.
| state | Reference to LifeCycle node state |
Definition at line 233 of file planner_server.cpp.
|
overrideprotected |
Configure member variables and initializes planner.
| state | Reference to LifeCycle node state |
Definition at line 80 of file planner_server.cpp.
References computePlan(), computePlanThroughPoses(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), and nav2_util::LifecycleNode::shared_from_this().

|
overrideprotected |
Deactivate member variables.
| state | Reference to LifeCycle node state |
Definition at line 202 of file planner_server.cpp.
References nav2_util::LifecycleNode::destroyBond().

|
overrideprotected |
Called when in shutdown state.
| state | Reference to LifeCycle node state |
Definition at line 256 of file planner_server.cpp.
|
protected |
Publish a path for visualization purposes.
| path | Reference to Global Path |
Definition at line 550 of file planner_server.cpp.
Referenced by computePlan(), and computePlanThroughPoses().

|
protected |
Transform start and goal poses into the costmap global frame for path planning plugins to utilize.
| action_server | Action server to terminate if required |
| start | The starting pose to transform |
| goal | Goal pose to transform |
Definition at line 323 of file planner_server.cpp.
Referenced by computePlan(), and computePlanThroughPoses().

|
protected |
Validate that the path contains a meaningful path.
| 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 |
Definition at line 341 of file planner_server.cpp.
Referenced by computePlan(), and computePlanThroughPoses().
