Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
lifecycle_manager_client.hpp
1 // Copyright (c) 2019 Intel Corporation
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_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_
16 #define NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
22 #include "geometry_msgs/msg/quaternion.hpp"
23 #include "nav2_msgs/action/navigate_to_pose.hpp"
24 #include "rclcpp/rclcpp.hpp"
25 #include "rclcpp_action/rclcpp_action.hpp"
26 #include "std_srvs/srv/empty.hpp"
27 #include "nav2_msgs/srv/manage_lifecycle_nodes.hpp"
28 #include "std_srvs/srv/trigger.hpp"
29 #include "nav2_util/service_client.hpp"
30 
31 namespace nav2_lifecycle_manager
32 {
37 enum class SystemStatus {ACTIVE, INACTIVE, TIMEOUT};
44 {
45 public:
51  explicit LifecycleManagerClient(
52  const std::string & name,
53  std::shared_ptr<rclcpp::Node> parent_node);
54 
55  // Client-side interface to the Nav2 lifecycle manager
60  bool startup(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
65  bool shutdown(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
70  bool pause(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
75  bool resume(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
80  bool reset(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
85  SystemStatus is_active(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
86 
87 protected:
88  using ManageLifecycleNodes = nav2_msgs::srv::ManageLifecycleNodes;
89 
94  bool callService(
95  uint8_t command,
96  const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
97 
98  // The node to use for the service call
99  rclcpp::Node::SharedPtr node_;
100 
101  std::shared_ptr<nav2_util::ServiceClient<ManageLifecycleNodes>> manager_client_;
102  std::shared_ptr<nav2_util::ServiceClient<std_srvs::srv::Trigger>> is_active_client_;
103  std::string manage_service_name_;
104  std::string active_service_name_;
105 };
106 
107 } // namespace nav2_lifecycle_manager
108 
109 #endif // NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_
LifecycleManagerClient(const std::string &name, std::shared_ptr< rclcpp::Node > parent_node)
A constructor for LifeCycleMangerClient.
bool pause(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make pause service call.
SystemStatus is_active(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Check if lifecycle node manager server is active.
bool shutdown(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make shutdown service call.
bool reset(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make reset service call.
bool startup(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make start up service call.
bool callService(uint8_t command, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
A generic method used to call startup, shutdown, etc.
bool resume(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make resume service call.