Class FactoryInterface

Inheritance Relationships

Derived Type

Class Documentation

class FactoryInterface

Subclassed by ros1_bridge::Factory< ROS1_T, ROS2_T >

Public Functions

virtual ros::Publisher create_ros1_publisher(ros::NodeHandle node, const std::string &topic_name, size_t queue_size, bool latch = false) = 0
virtual rclcpp::PublisherBase::SharedPtr create_ros2_publisher(rclcpp::Node::SharedPtr node, const std::string &topic_name, size_t queue_size) = 0
virtual rclcpp::PublisherBase::SharedPtr create_ros2_publisher(rclcpp::Node::SharedPtr node, const std::string &topic_name, const rmw_qos_profile_t &qos_profile) = 0
virtual rclcpp::PublisherBase::SharedPtr create_ros2_publisher(rclcpp::Node::SharedPtr node, const std::string &topic_name, const rclcpp::QoS &qos) = 0
virtual ros::Subscriber create_ros1_subscriber(ros::NodeHandle node, const std::string &topic_name, size_t queue_size, rclcpp::PublisherBase::SharedPtr ros2_pub, rclcpp::Logger logger) = 0
virtual rclcpp::SubscriptionBase::SharedPtr create_ros2_subscriber(rclcpp::Node::SharedPtr node, const std::string &topic_name, size_t queue_size, ros::Publisher ros1_pub, rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr) = 0
virtual rclcpp::SubscriptionBase::SharedPtr create_ros2_subscriber(rclcpp::Node::SharedPtr node, const std::string &topic_name, const rmw_qos_profile_t &qos_profile, ros::Publisher ros1_pub, rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr) = 0
virtual rclcpp::SubscriptionBase::SharedPtr create_ros2_subscriber(rclcpp::Node::SharedPtr node, const std::string &topic_name, const rclcpp::QoS &qos, ros::Publisher ros1_pub, rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr) = 0
virtual void convert_1_to_2(const void *ros1_msg, void *ros2_msg) const = 0
virtual void convert_2_to_1(const void *ros2_msg, void *ros1_msg) const = 0
virtual bool convert_2_to_1_generic(const rclcpp::SerializedMessage &ros2_msg, std::vector<uint8_t> &ros1_msg) const = 0
virtual bool convert_1_to_2_generic(const std::vector<uint8_t> &ros1_msg, rclcpp::SerializedMessage &ros2_msg) const = 0
virtual const char *get_ros1_md5sum() const = 0
virtual const char *get_ros1_data_type() const = 0
virtual const char *get_ros1_message_definition() const = 0