An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins of different algorithms to compute plans.
More...
|
| | 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, std::function< bool()> cancel_checker) |
| | Method to get plan from the desired plugin. More...
|
| |
| | 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...
|
| |
|
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_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 (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...
|
| |
| 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. More...
|
| |
| 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. 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< rmw_request_id_t > request_header, 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...
|
| |
|
void | exceptionWarning (const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, const std::string &planner_id, const std::exception &ex, std::string &msg) |
| |
| rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
| | Callback executed when a parameter change is detected. More...
|
| |
|
void | printLifecycleNodeNotification () |
| | Print notifications for lifecycle node.
|
| |
| void | register_rcl_preshutdown_callback () |
| |
| void | runCleanups () |
| |
|
|
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_ |
| |
|
rclcpp::Duration | costmap_update_timeout_ |
| |
|
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_ |
| |
|
nav2_util::ServiceServer< nav2_msgs::srv::IsPathValid, std::shared_ptr< nav2_util::LifecycleNode > >::SharedPtr | is_path_valid_service_ |
| |
|
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > | rcl_preshutdown_cb_handle_ {nullptr} |
| |
|
std::shared_ptr< bond::Bond > | bond_ {nullptr} |
| |
|
double | bond_heartbeat_period |
| |
|
rclcpp::TimerBase::SharedPtr | autostart_timer_ |
| |
An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins of different algorithms to compute plans.
Definition at line 52 of file planner_server.hpp.
| void nav2_planner::PlannerServer::isPathValid |
( |
const std::shared_ptr< rmw_request_id_t > |
request_header, |
|
|
const std::shared_ptr< nav2_msgs::srv::IsPathValid::Request > |
request, |
|
|
std::shared_ptr< nav2_msgs::srv::IsPathValid::Response > |
response |
|
) |
| |
|
protected |