Template Class BridgePublisher

Class Documentation

template<class RosMsg, class SimMsg>
class BridgePublisher

Public Types

using ConvertFunc = std::function<void(std::shared_ptr<SimMsg>, std::deque<RosMsg>&)>
using CustomPublisher = typename std::conditional<std::is_same<RosMsg, ImageMsgs::Image>::value, std::shared_ptr<image_transport::Publisher>, typename rclcpp::Publisher<RosMsg>::SharedPtr>::type

Public Functions

BridgePublisher(std::shared_ptr<dai::DataOutputQueue> daiMessageQueue, std::shared_ptr<rclcpp::Node> node, std::string rosTopic, ConvertFunc converter, rclcpp::QoS qosSetting = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), bool lazyPublisher = true)
BridgePublisher(std::shared_ptr<dai::DataOutputQueue> daiMessageQueue, std::shared_ptr<rclcpp::Node> node, std::string rosTopic, ConvertFunc converter, size_t qosHistoryDepth, std::string cameraParamUri = "", std::string cameraName = "", bool lazyPublisher = true)
BridgePublisher(std::shared_ptr<dai::DataOutputQueue> daiMessageQueue, std::shared_ptr<rclcpp::Node> node, std::string rosTopic, ConvertFunc converter, size_t qosHistoryDepth, ImageMsgs::CameraInfo cameraInfoData, std::string cameraName, bool lazyPublisher = true)
std::shared_ptr<image_transport::Publisher> advertise(int queueSize, std::true_type)

Tag Dispacher function to to overload the Publisher to ImageTransport Publisher

rclcpp::Publisher<RosMsg>::SharedPtr advertise(int queueSize, std::false_type)

Tag Dispacher function to to overload the Publisher to use Default ros::Publisher

BridgePublisher(const BridgePublisher &other)
void addPublisherCallback()
void publishHelper(std::shared_ptr<SimMsg> inData)
void startPublisherThread()
~BridgePublisher()