Program Listing for File generic_client.hpp
↰ Return to documentation for file (include/rclcpp_action/generic_client.hpp)
// Copyright 2025 Sony Group 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 RCLCPP_ACTION__GENERIC_CLIENT_HPP_
#define RCLCPP_ACTION__GENERIC_CLIENT_HPP_
#include <cstddef>
#include <functional>
#include <future>
#include <map>
#include <memory>
#include <mutex>
#include <string>
#include "action_msgs/srv/cancel_goal.hpp"
#include "action_msgs/msg/goal_info.hpp"
#include "action_msgs/msg/goal_status_array.hpp"
#include "rclcpp_action/client_base.hpp"
#include "rclcpp_action/generic_client_goal_handle.hpp"
#include "rcpputils/shared_library.hpp"
#include "rosidl_typesupport_introspection_cpp/identifier.hpp"
#include "rosidl_typesupport_introspection_cpp/message_introspection.hpp"
#include "unique_identifier_msgs/msg/uuid.hpp"
namespace rclcpp_action
{
class GenericClient : public ClientBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(GenericClient)
using Goal = void *; // Deserialized data pointer of goal
using GoalRequest = void *; // Deserialized data pointer of goal request (uuid + Goal)
using CancelRequest = typename action_msgs::srv::CancelGoal_Request;
using CancelResponse = typename action_msgs::srv::CancelGoal_Response;
using WrappedResult = typename GenericClientGoalHandle::WrappedResult;
using GoalResponseCallback = std::function<void (typename GenericClientGoalHandle::SharedPtr)>;
using FeedbackCallback = typename GenericClientGoalHandle::FeedbackCallback;
using ResultCallback = typename GenericClientGoalHandle::ResultCallback;
using CancelCallback = std::function<void (CancelResponse::SharedPtr)>;
using IntrospectionMessageMembersPtr =
const rosidl_typesupport_introspection_cpp::MessageMembers *;
struct SendGoalOptions
{
SendGoalOptions()
: goal_response_callback(nullptr),
feedback_callback(nullptr),
result_callback(nullptr)
{
}
GoalResponseCallback goal_response_callback;
FeedbackCallback feedback_callback;
ResultCallback result_callback;
};
RCLCPP_ACTION_PUBLIC
GenericClient(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
const std::string & action_name,
std::shared_ptr<rcpputils::SharedLibrary> typesupport_lib,
const rosidl_action_type_support_t * action_typesupport_handle,
const rcl_action_client_options_t & client_options = rcl_action_client_get_default_options());
RCLCPP_ACTION_PUBLIC
std::shared_future<typename GenericClientGoalHandle::SharedPtr>
async_send_goal(
const Goal goal,
size_t goal_size,
const SendGoalOptions & options = SendGoalOptions());
RCLCPP_ACTION_PUBLIC
std::shared_future<typename GenericClientGoalHandle::SharedPtr>
async_send_goal(
const GoalRequest goal_request,
const SendGoalOptions & options = SendGoalOptions());
RCLCPP_ACTION_PUBLIC
std::shared_future<WrappedResult>
async_get_result(
typename GenericClientGoalHandle::SharedPtr goal_handle,
ResultCallback result_callback = nullptr);
RCLCPP_ACTION_PUBLIC
std::shared_future<typename CancelResponse::SharedPtr>
async_cancel_goal(
typename GenericClientGoalHandle::SharedPtr goal_handle,
CancelCallback cancel_callback = nullptr);
RCLCPP_ACTION_PUBLIC
std::shared_future<typename CancelResponse::SharedPtr>
async_cancel_all_goals(CancelCallback cancel_callback = nullptr);
RCLCPP_ACTION_PUBLIC
void
stop_callbacks(typename GenericClientGoalHandle::SharedPtr goal_handle);
RCLCPP_ACTION_PUBLIC
void
stop_callbacks(const GoalUUID & goal_id);
RCLCPP_ACTION_PUBLIC
std::shared_future<typename CancelResponse::SharedPtr>
async_cancel_goals_before(
const rclcpp::Time & stamp,
CancelCallback cancel_callback = nullptr);
RCLCPP_ACTION_PUBLIC
virtual
~GenericClient();
private:
std::shared_ptr<void>
create_message(IntrospectionMessageMembersPtr message_members) const;
std::shared_ptr<void>
create_goal_response() const override
{
return create_message(goal_service_response_type_members_);
}
std::shared_ptr<void>
create_result_request() const
{
return create_message(result_service_request_type_members_);
}
std::shared_ptr<void>
create_result_response() const override
{
return create_message(result_service_response_type_members_);
}
std::shared_ptr<void>
create_cancel_response() const override
{
return create_message(cancel_service_response_type_members_);
}
std::shared_ptr<void>
create_feedback_message() const override
{
return create_message(feedback_type_members_);
}
void
handle_feedback_message(std::shared_ptr<void> message) override;
std::shared_ptr<void>
create_status_message() const override
{
using GoalStatusMessage = action_msgs::msg::GoalStatusArray;
return std::shared_ptr<void>(new GoalStatusMessage());
}
void
handle_status_message(std::shared_ptr<void> message) override;
void
make_result_aware(typename GenericClientGoalHandle::SharedPtr goal_handle);
std::shared_future<typename CancelResponse::SharedPtr>
async_cancel(
typename CancelRequest::SharedPtr cancel_request,
CancelCallback cancel_callback = nullptr);
std::shared_ptr<rcpputils::SharedLibrary> ts_lib_;
IntrospectionMessageMembersPtr goal_service_request_type_members_;
IntrospectionMessageMembersPtr goal_service_response_type_members_;
IntrospectionMessageMembersPtr result_service_request_type_members_;
IntrospectionMessageMembersPtr result_service_response_type_members_;
IntrospectionMessageMembersPtr cancel_service_response_type_members_;
IntrospectionMessageMembersPtr feedback_type_members_;
std::map<GoalUUID, typename GenericClientGoalHandle::WeakPtr> goal_handles_;
std::recursive_mutex goal_handles_mutex_;
};
} // namespace rclcpp_action
#endif // RCLCPP_ACTION__GENERIC_CLIENT_HPP_