Program Listing for File babel_fish_action_client.hpp

Return to documentation for file (include/ros_babel_fish/detail/babel_fish_action_client.hpp)

// Copyright (c) 2021 Stefan Fabian. All rights reserved.
// Licensed under the MIT license. See LICENSE file in the project root for full license information.

#ifndef ROS_BABEL_FISH_BABEL_FISH_ACTION_CLIENT_HPP
#define ROS_BABEL_FISH_BABEL_FISH_ACTION_CLIENT_HPP

#include "ros_babel_fish/messages/compound_message.hpp"
#include <rclcpp_action/client.hpp>

namespace ros_babel_fish
{
struct ActionTypeSupport;

namespace impl
{
struct BabelFishAction {
  using Feedback = CompoundMessage;
  using Goal = CompoundMessage;
  using Result = CompoundMessage;

  typedef struct Impl {
    struct CancelGoalService {
      using Request = CompoundMessage;
      using Response = CompoundMessage;
    };
  } Impl;
};
} // namespace impl
} // namespace ros_babel_fish

namespace rclcpp_action
{
template<>
class Client<ros_babel_fish::impl::BabelFishAction> : public rclcpp_action::ClientBase
{
public:
  RCLCPP_SMART_PTR_ALIASES_ONLY( Client<ros_babel_fish::impl::BabelFishAction> )

  using GoalHandle = rclcpp_action::ClientGoalHandle<ros_babel_fish::impl::BabelFishAction>;
  using WrappedResult = GoalHandle::WrappedResult;
  using GoalResponseCallback = std::function<void( typename GoalHandle::SharedPtr )>;
  using FeedbackCallback = GoalHandle::FeedbackCallback;
  using ResultCallback = GoalHandle::ResultCallback;
  using CancelRequest = ros_babel_fish::CompoundMessage;
  using CancelResponse = ros_babel_fish::CompoundMessage;
  using CancelCallback = std::function<void( CancelResponse )>;


  struct SendGoalOptions {

    GoalResponseCallback goal_response_callback;

    FeedbackCallback feedback_callback;

    ResultCallback result_callback;
  };

  Client( 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<const ros_babel_fish::ActionTypeSupport> type_support,
          const rcl_action_client_options_t &client_options = rcl_action_client_get_default_options() );

  ros_babel_fish::CompoundMessage create_goal() const;

  std::shared_future<GoalHandle::SharedPtr>
  async_send_goal( const ros_babel_fish::CompoundMessage &goal, const SendGoalOptions &options = {} );


  std::shared_future<WrappedResult> async_get_result( typename GoalHandle::SharedPtr goal_handle,
                                                      ResultCallback result_callback = nullptr );


  std::shared_future<CancelResponse> async_cancel_goal( GoalHandle::SharedPtr goal_handle,
                                                        CancelCallback cancel_callback = nullptr );


  std::shared_future<CancelResponse> async_cancel_all_goals( CancelCallback cancel_callback = nullptr );


  std::shared_future<CancelResponse>
  async_cancel_goals_before( const rclcpp::Time &stamp, CancelCallback cancel_callback = nullptr );

protected:
  std::shared_ptr<void> create_goal_response() const override;

  std::shared_ptr<void> create_result_response() const override;

  std::shared_ptr<void> create_cancel_response() const override;

  std::shared_ptr<void> create_feedback_message() const override;

  void handle_feedback_message( std::shared_ptr<void> message ) override;

  std::shared_ptr<void> create_status_message() const override;

  void handle_status_message( std::shared_ptr<void> message ) override;

  void make_result_aware( GoalHandle::SharedPtr goal_handle );

  std::shared_future<CancelResponse> async_cancel( CancelRequest cancel_request,
                                                   CancelCallback cancel_callback = nullptr );

private:
  std::shared_ptr<const ros_babel_fish::ActionTypeSupport> type_support_;
  std::mutex goal_handles_mutex_;
  std::map<GoalUUID, typename GoalHandle::WeakPtr> goal_handles_;
};
} // namespace rclcpp_action

namespace ros_babel_fish
{

using BabelFishActionClient = rclcpp_action::Client<impl::BabelFishAction>;

}

#endif // ROS_BABEL_FISH_BABEL_FISH_ACTION_CLIENT_HPP