Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
waypoint_follower.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_WAYPOINT_FOLLOWER__WAYPOINT_FOLLOWER_HPP_
16 #define NAV2_WAYPOINT_FOLLOWER__WAYPOINT_FOLLOWER_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 #include <mutex>
22 
23 #include "nav2_util/lifecycle_node.hpp"
24 #include "nav2_msgs/action/navigate_to_pose.hpp"
25 #include "nav2_msgs/action/follow_waypoints.hpp"
26 #include "nav_msgs/msg/path.hpp"
27 #include "nav2_util/simple_action_server.hpp"
28 #include "rclcpp_action/rclcpp_action.hpp"
29 
30 #include "nav2_util/node_utils.hpp"
31 #include "nav2_core/waypoint_task_executor.hpp"
32 #include "pluginlib/class_loader.hpp"
33 #include "pluginlib/class_list_macros.hpp"
34 
35 namespace nav2_waypoint_follower
36 {
37 
38 enum class ActionStatus
39 {
40  UNKNOWN = 0,
41  PROCESSING = 1,
42  FAILED = 2,
43  SUCCEEDED = 3
44 };
45 
52 {
53 public:
54  using ActionT = nav2_msgs::action::FollowWaypoints;
55  using ClientT = nav2_msgs::action::NavigateToPose;
57  using ActionClient = rclcpp_action::Client<ClientT>;
58 
63  explicit WaypointFollower(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
68 
69 protected:
77  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
83  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
89  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
95  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
101  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
102 
106  void followWaypoints();
107 
112  void resultCallback(const rclcpp_action::ClientGoalHandle<ClientT>::WrappedResult & result);
113 
118  void goalResponseCallback(const rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr & goal);
119 
124  rcl_interfaces::msg::SetParametersResult
125  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
126 
127  // Dynamic parameters handler
128  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
129 
130  // Our action server
131  std::unique_ptr<ActionServer> action_server_;
132  ActionClient::SharedPtr nav_to_pose_client_;
133  rclcpp::CallbackGroup::SharedPtr callback_group_;
134  rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
135  std::shared_future<rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr> future_goal_handle_;
136  bool stop_on_failure_;
137  ActionStatus current_goal_status_;
138  int loop_rate_;
139  std::vector<int> failed_ids_;
140 
141  // Task Execution At Waypoint Plugin
142  pluginlib::ClassLoader<nav2_core::WaypointTaskExecutor>
143  waypoint_task_executor_loader_;
144  pluginlib::UniquePtr<nav2_core::WaypointTaskExecutor>
145  waypoint_task_executor_;
146  std::string waypoint_task_executor_id_;
147  std::string waypoint_task_executor_type_;
148 };
149 
150 } // namespace nav2_waypoint_follower
151 
152 #endif // NAV2_WAYPOINT_FOLLOWER__WAYPOINT_FOLLOWER_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
An action server wrapper to make applications simpler using Actions.
An action server that uses behavior tree for navigating a robot to its goal position.
void resultCallback(const rclcpp_action::ClientGoalHandle< ClientT >::WrappedResult &result)
Action client result callback.
~WaypointFollower()
A destructor for nav2_waypoint_follower::WaypointFollower class.
WaypointFollower(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_waypoint_follower::WaypointFollower class.
void goalResponseCallback(const rclcpp_action::ClientGoalHandle< ClientT >::SharedPtr &goal)
Action client goal response callback.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures member variables.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets member variables.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates action server.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates action server.
void followWaypoints()
Action server callbacks.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.