15 #ifndef NAV2_PLANNER__PLANNER_SERVER_HPP_
16 #define NAV2_PLANNER__PLANNER_SERVER_HPP_
22 #include <unordered_map>
25 #include "geometry_msgs/msg/point.hpp"
26 #include "geometry_msgs/msg/pose_stamped.hpp"
27 #include "nav_msgs/msg/path.hpp"
28 #include "nav2_util/lifecycle_node.hpp"
29 #include "nav2_msgs/action/compute_path_to_pose.hpp"
30 #include "nav2_msgs/action/compute_path_through_poses.hpp"
31 #include "nav2_msgs/msg/costmap.hpp"
32 #include "nav2_util/robot_utils.hpp"
33 #include "nav2_util/simple_action_server.hpp"
34 #include "nav2_util/service_server.hpp"
35 #include "tf2_ros/transform_listener.h"
36 #include "tf2_ros/create_timer_ros.h"
37 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
38 #include "pluginlib/class_loader.hpp"
39 #include "pluginlib/class_list_macros.hpp"
40 #include "nav2_core/global_planner.hpp"
41 #include "nav2_msgs/srv/is_path_valid.hpp"
42 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
43 #include "nav2_core/planner_exceptions.hpp"
45 namespace nav2_planner
59 explicit PlannerServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
65 using PlannerMap = std::unordered_map<std::string, nav2_core::GlobalPlanner::Ptr>;
76 const geometry_msgs::msg::PoseStamped & start,
77 const geometry_msgs::msg::PoseStamped & goal,
78 const std::string & planner_id,
79 std::function<
bool()> cancel_checker);
87 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
93 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
99 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
105 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
111 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
113 using ActionToPose = nav2_msgs::action::ComputePathToPose;
114 using ActionToPoseResult = ActionToPose::Result;
115 using ActionThroughPoses = nav2_msgs::action::ComputePathThroughPoses;
116 using ActionThroughPosesResult = ActionThroughPoses::Result;
151 typename std::shared_ptr<const typename T::Goal> goal);
162 typename std::shared_ptr<const typename T::Goal> goal,
163 geometry_msgs::msg::PoseStamped & start);
173 geometry_msgs::msg::PoseStamped & curr_start,
174 geometry_msgs::msg::PoseStamped & curr_goal);
186 const geometry_msgs::msg::PoseStamped & curr_goal,
187 const nav_msgs::msg::Path & path,
188 const std::string & planner_id);
208 const std::shared_ptr<rmw_request_id_t> request_header,
209 const std::shared_ptr<nav2_msgs::srv::IsPathValid::Request> request,
210 std::shared_ptr<nav2_msgs::srv::IsPathValid::Response> response);
216 void publishPlan(
const nav_msgs::msg::Path & path);
218 void exceptionWarning(
219 const geometry_msgs::msg::PoseStamped & start,
220 const geometry_msgs::msg::PoseStamped & goal,
221 const std::string & planner_id,
222 const std::exception & ex,
229 rcl_interfaces::msg::SetParametersResult
233 std::unique_ptr<ActionServerToPose> action_server_pose_;
234 std::unique_ptr<ActionServerThroughPoses> action_server_poses_;
237 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
238 std::mutex dynamic_params_lock_;
241 PlannerMap planners_;
242 pluginlib::ClassLoader<nav2_core::GlobalPlanner> gp_loader_;
243 std::vector<std::string> default_ids_;
244 std::vector<std::string> default_types_;
245 std::vector<std::string> planner_ids_;
246 std::vector<std::string> planner_types_;
247 double max_planner_duration_;
248 rclcpp::Duration costmap_update_timeout_;
249 std::string planner_ids_concat_;
252 std::shared_ptr<tf2_ros::Buffer> tf_;
255 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
256 std::unique_ptr<nav2_util::NodeThread> costmap_thread_;
258 std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
262 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_;
266 std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr is_path_valid_service_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins...
void publishPlan(const nav_msgs::msg::Path &path)
Publish a path for visualization purposes.
void computePlan()
The action server callback which calls planner to get the path ComputePathToPose.
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...
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
void waitForCostmap()
Wait for costmap to be valid with updated sensor data or repopulate after a clearing recovery....
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.
PlannerServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_planner::PlannerServer.
~PlannerServer()
A destructor for nav2_planner::PlannerServer.
bool isServerInactive(std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server)
Check if an action server is valid / active.
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.
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.
void computePlanThroughPoses()
The action server callback which calls planner to get the path ComputePathThroughPoses.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
bool isCancelRequested(std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server)
Check if an action server has a cancellation request pending.
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.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables and initializes planner.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
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.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
A simple wrapper on ROS2 services server.
An action server wrapper to make applications simpler using Actions.