Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
planner_server.hpp
1 // Copyright (c) 2019 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_PLANNER__PLANNER_SERVER_HPP_
16 #define NAV2_PLANNER__PLANNER_SERVER_HPP_
17 
18 #include <chrono>
19 #include <string>
20 #include <memory>
21 #include <vector>
22 #include <unordered_map>
23 #include <mutex>
24 
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_ros_common/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_ros_common/simple_action_server.hpp"
34 #include "nav2_ros_common/service_server.hpp"
35 #include "tf2_ros/transform_listener.hpp"
36 #include "tf2_ros/create_timer_ros.hpp"
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"
44 
45 namespace nav2_planner
46 {
53 {
54 public:
59  explicit PlannerServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
64 
65  using PlannerMap = std::unordered_map<std::string, nav2_core::GlobalPlanner::Ptr>;
66 
75  nav_msgs::msg::Path getPlan(
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);
80 
81 protected:
87  nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
93  nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
99  nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
105  nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
111  nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
112 
113  using ActionToPose = nav2_msgs::action::ComputePathToPose;
114  using ActionToPoseResult = ActionToPose::Result;
115  using ActionThroughPoses = nav2_msgs::action::ComputePathThroughPoses;
116  using ActionThroughPosesResult = ActionThroughPoses::Result;
119 
125  template<typename T>
126  bool isServerInactive(typename nav2::SimpleActionServer<T>::SharedPtr & action_server);
127 
133  template<typename T>
134  bool isCancelRequested(typename nav2::SimpleActionServer<T>::SharedPtr & action_server);
135 
140  void waitForCostmap();
141 
148  template<typename T>
150  typename nav2::SimpleActionServer<T>::SharedPtr & action_server,
151  typename std::shared_ptr<const typename T::Goal> goal);
152 
160  template<typename T>
161  bool getStartPose(
162  typename std::shared_ptr<const typename T::Goal> goal,
163  geometry_msgs::msg::PoseStamped & start);
164 
173  geometry_msgs::msg::PoseStamped & curr_start,
174  geometry_msgs::msg::PoseStamped & curr_goal);
175 
184  template<typename T>
185  bool validatePath(
186  const geometry_msgs::msg::PoseStamped & curr_goal,
187  const nav_msgs::msg::Path & path,
188  const std::string & planner_id);
189 
194  void computePlan();
195 
201 
207  void isPathValid(
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);
211 
216  void publishPlan(const nav_msgs::msg::Path & path);
217 
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,
223  std::string & msg);
224 
229  rcl_interfaces::msg::SetParametersResult
230  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
231 
232  // Our action server implements the ComputePathToPose action
233  typename ActionServerToPose::SharedPtr action_server_pose_;
234  typename ActionServerThroughPoses::SharedPtr action_server_poses_;
235 
236  // Dynamic parameters handler
237  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
238  std::mutex dynamic_params_lock_;
239 
240  // Planner
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_;
250 
251  // TF buffer
252  std::shared_ptr<tf2_ros::Buffer> tf_;
253 
254  // Global Costmap
255  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
256  std::unique_ptr<nav2::NodeThread> costmap_thread_;
257  nav2_costmap_2d::Costmap2D * costmap_;
258  std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
259  collision_checker_;
260 
261  // Publishers for the path
262  nav2::Publisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_;
263 
264  // Service to determine if the path is valid
265  nav2::ServiceServer<nav2_msgs::srv::IsPathValid>::SharedPtr is_path_valid_service_;
266 };
267 
268 } // namespace nav2_planner
269 
270 #endif // NAV2_PLANNER__PLANNER_SERVER_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
An action server wrapper to make applications simpler using Actions.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins...
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables and initializes planner.
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.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
bool isServerInactive(typename nav2::SimpleActionServer< T >::SharedPtr &action_server)
Check if an action server is valid / active.
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.
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.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
void computePlanThroughPoses()
The action server callback which calls planner to get the path ComputePathThroughPoses.
bool isCancelRequested(typename nav2::SimpleActionServer< T >::SharedPtr &action_server)
Check if an action server has a cancellation request pending.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
void getPreemptedGoalIfRequested(typename nav2::SimpleActionServer< T >::SharedPtr &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...
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::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate 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.