Template Class Factory
- Defined in File factory.hpp 
Inheritance Relationships
Base Type
- public ros1_bridge::FactoryInterface(Class FactoryInterface)
Class Documentation
- 
template<typename ROS1_T, typename ROS2_T>
 class Factory : public ros1_bridge::FactoryInterface
- Public Functions - 
inline Factory(const std::string &ros1_type_name, const std::string &ros2_type_name)
 - 
inline virtual ros::Publisher create_ros1_publisher(ros::NodeHandle node, const std::string &topic_name, size_t queue_size, bool latch = false)
 - 
inline virtual void convert_1_to_2(const void *ros1_msg, void *ros2_msg) const override
 - 
inline virtual void convert_2_to_1(const void *ros2_msg, void *ros1_msg) const override
 - 
inline virtual const char *get_ros1_md5sum() const override
 - 
inline virtual const char *get_ros1_data_type() const override
 - 
inline virtual const char *get_ros1_message_definition() const override
 - 
inline virtual bool convert_2_to_1_generic(const rclcpp::SerializedMessage &ros2_msg, std::vector<uint8_t> &ros1_msg) const override
 - 
inline virtual bool convert_1_to_2_generic(const std::vector<uint8_t> &ros1_msg, rclcpp::SerializedMessage &ros2_msg) const override
 - 
void convert_1_to_2(const std_msgs::Duration &ros1_msg, builtin_interfaces::msg::Duration &ros2_msg)
 - 
void convert_2_to_1(const builtin_interfaces::msg::Duration &ros2_msg, std_msgs::Duration &ros1_msg)
 - 
void internal_stream_translate_helper(ros::serialization::OStream &stream, const builtin_interfaces::msg::Duration &msg)
 - 
void internal_stream_translate_helper(ros::serialization::IStream &stream, builtin_interfaces::msg::Duration &msg)
 - 
void internal_stream_translate_helper(ros::serialization::LStream &stream, const builtin_interfaces::msg::Duration &msg)
 - 
void convert_1_to_2(const std_msgs::Time &ros1_msg, builtin_interfaces::msg::Time &ros2_msg)
 - 
void convert_2_to_1(const builtin_interfaces::msg::Time &ros2_msg, std_msgs::Time &ros1_msg)
 - 
void internal_stream_translate_helper(ros::serialization::OStream &stream, const builtin_interfaces::msg::Time &msg)
 - 
void internal_stream_translate_helper(ros::serialization::IStream &stream, builtin_interfaces::msg::Time &msg)
 - 
void internal_stream_translate_helper(ros::serialization::LStream &stream, const builtin_interfaces::msg::Time &msg)
 - Public Members - 
std::string ros1_type_name_
 - 
std::string ros2_type_name_
 - 
std::shared_ptr<rcpputils::SharedLibrary> ts_lib_
 - 
const rosidl_message_type_support_t *type_support_ = nullptr
 - Public Static Functions - 
static void convert_2_to_1(const ROS2_T &msg, ros::serialization::OStream &out_stream)
- Writes (serializes) a ROS2 class directly to a ROS1 stream. 
 - 
static void convert_1_to_2(ros::serialization::IStream &in_stream, ROS2_T &msg)
- Reads (deserializes) a ROS2 class directly from a ROS1 stream. 
 - 
static uint32_t length_2_as_1_stream(const ROS2_T &msg)
- Determines the length of a ROS2 class if it was serialized to a ROS1 stream. 
 - 
static void internal_stream_translate_helper(ros::serialization::OStream &stream, const ROS2_T &msg)
- Internal helper functions conversion for ROS2 message types to/from ROS1 streams. - This function is not meant to be used externally. However, since this the internal helper functions call each other for sub messages they must be public. 
 - Protected Static Functions 
- 
inline Factory(const std::string &ros1_type_name, const std::string &ros2_type_name)