Template Class ServiceFactory

Inheritance Relationships

Base Type

Class Documentation

template<class ROS1_T, class ROS2_T>
class ServiceFactory : public ros1_bridge::ServiceFactoryInterface

Public Types

using ROS1Request = typename ROS1_T::Request
using ROS2Request = typename ROS2_T::Request
using ROS1Response = typename ROS1_T::Response
using ROS2Response = typename ROS2_T::Response

Public Functions

inline void forward_2_to_1(ros::ServiceClient client, rclcpp::Logger logger, const std::shared_ptr<rmw_request_id_t>, const std::shared_ptr<ROS2Request> request, std::shared_ptr<ROS2Response> response)
inline bool forward_1_to_2(rclcpp::ClientBase::SharedPtr cli, rclcpp::Logger logger, const ROS1Request &request1, ROS1Response &response1, int service_execution_timeout)
inline virtual ServiceBridge1to2 service_bridge_1_to_2(ros::NodeHandle &ros1_node, rclcpp::Node::SharedPtr ros2_node, const std::string &name, int service_execution_timeout)
inline virtual ServiceBridge2to1 service_bridge_2_to_1(ros::NodeHandle &ros1_node, rclcpp::Node::SharedPtr ros2_node, const std::string &name)