Program Listing for File lifecycle_manager_client.hpp
↰ Return to documentation for file (include/nav2_lifecycle_manager/lifecycle_manager_client.hpp
)
// Copyright (c) 2019 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_
#define NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_
#include <memory>
#include <string>
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
#include "geometry_msgs/msg/quaternion.hpp"
#include "nav2_msgs/action/navigate_to_pose.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "std_srvs/srv/empty.hpp"
#include "nav2_msgs/srv/manage_lifecycle_nodes.hpp"
#include "std_srvs/srv/trigger.hpp"
#include "nav2_util/service_client.hpp"
namespace nav2_lifecycle_manager
{
enum class SystemStatus {ACTIVE, INACTIVE, TIMEOUT};
class LifecycleManagerClient
{
public:
explicit LifecycleManagerClient(
const std::string & name,
std::shared_ptr<rclcpp::Node> parent_node);
// Client-side interface to the Nav2 lifecycle manager
bool startup(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
bool shutdown(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
bool pause(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
bool resume(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
bool reset(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
bool configure(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
bool cleanup(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
SystemStatus is_active(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
protected:
using ManageLifecycleNodes = nav2_msgs::srv::ManageLifecycleNodes;
bool callService(
uint8_t command,
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
// The node to use for the service call
rclcpp::Node::SharedPtr node_;
std::shared_ptr<nav2_util::ServiceClient<ManageLifecycleNodes>> manager_client_;
std::shared_ptr<nav2_util::ServiceClient<std_srvs::srv::Trigger>> is_active_client_;
std::string manage_service_name_;
std::string active_service_name_;
};
} // namespace nav2_lifecycle_manager
#endif // NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_