Nav2 Navigation Stack - rolling  main
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_ros_common/lifecycle_node.hpp"
30 #include "nav2_ros_common/service_client.hpp"
31 
32 namespace nav2_lifecycle_manager
33 {
38 enum class SystemStatus {ACTIVE, INACTIVE, TIMEOUT};
45 {
46 public:
52  template<typename NodeT>
54  const std::string & name,
55  NodeT parent_node)
56  {
57  manage_service_name_ = name + std::string("/manage_nodes");
58  active_service_name_ = name + std::string("/is_active");
59 
60  // Use parent node for service call and logging
61  logger_ = parent_node->get_logger();
62 
63  // Create the service clients
64  // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the
65  // subscription to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode
66  manager_client_ = nav2::interfaces::create_client<ManageLifecycleNodes>(
67  parent_node, manage_service_name_, true /*creates and spins an internal executor*/);
68  is_active_client_ = nav2::interfaces::create_client<std_srvs::srv::Trigger>(
69  parent_node, active_service_name_, true /*creates and spins an internal executor*/);
70  }
71 
72  // Client-side interface to the Nav2 lifecycle manager
77  bool startup(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
82  bool shutdown(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
87  bool pause(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
92  bool resume(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
97  bool reset(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
102  bool configure(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
107  bool cleanup(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
112  SystemStatus is_active(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
113 
114 protected:
115  using ManageLifecycleNodes = nav2_msgs::srv::ManageLifecycleNodes;
116 
121  bool callService(
122  uint8_t command,
123  const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
124 
125  // The node to use for the service call
126  rclcpp::Node::SharedPtr node_;
127  rclcpp::Logger logger_{rclcpp::get_logger("nav2_lifecycle_manager_client")};
128 
129  nav2::ServiceClient<ManageLifecycleNodes>::SharedPtr manager_client_;
130  nav2::ServiceClient<std_srvs::srv::Trigger>::SharedPtr is_active_client_;
131  std::string manage_service_name_;
132  std::string active_service_name_;
133 };
134 
135 } // namespace nav2_lifecycle_manager
136 
137 #endif // NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_
bool cleanup(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make cleanup service call.
LifecycleManagerClient(const std::string &name, NodeT 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 configure(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make configure 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.