Template Class BridgePublisher
Defined in File BridgePublisher.hpp
Class Documentation
-
template<class RosMsg, class DaiMsg>
class BridgePublisher Public Types
-
using CustomPublisher = std::conditional_t<std::is_same_v<RosMsg, ImageMsgs::Image>, std::shared_ptr<image_transport::CameraPublisher>, std::conditional_t<std::is_same_v<RosMsg, geometry_msgs::msg::TransformStamped>, std::shared_ptr<tf2_ros::TransformBroadcaster>, typename rclcpp::Publisher<RosMsg>::SharedPtr>>
Public Functions
Constructor for BridgePublisher with default QoS settings.
- Parameters:
daiMessageQueue – Shared pointer to the DepthAI message queue.
node – Shared pointer to the ROS 2 node.
rosTopic – The ROS topic to publish messages to.
converter – Function to convert DepthAI messages to ROS messages.
qosSetting – QoS settings for the ROS publisher.
lazyPublisher – Flag to enable lazy publishing.
Constructor for BridgePublisher with custom QoS history depth.
- Parameters:
daiMessageQueue – Shared pointer to the DepthAI message queue.
node – Shared pointer to the ROS 2 node.
rosTopic – The ROS topic to publish messages to.
converter – Function to convert DepthAI messages to ROS messages.
qosHistoryDepth – History depth for the QoS settings.
cameraParamUri – URI for the camera parameters.
cameraName – Name of the camera.
lazyPublisher – Flag to enable lazy publishing.
Constructor for BridgePublisher with custom camera info data.
- Parameters:
daiMessageQueue – Shared pointer to the DepthAI message queue.
node – Shared pointer to the ROS 2 node.
rosTopic – The ROS topic to publish messages to.
converter – Function to convert DepthAI messages to ROS messages.
qosHistoryDepth – History depth for the QoS settings.
cameraInfoData – Camera info data for the ROS messages.
cameraName – Name of the camera.
lazyPublisher – Flag to enable lazy publishing.
-
std::shared_ptr<image_transport::CameraPublisher> 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()
-
inline void enableTransformPub()
-
void startPublisherThread()
-
~BridgePublisher()
-
using CustomPublisher = std::conditional_t<std::is_same_v<RosMsg, ImageMsgs::Image>, std::shared_ptr<image_transport::CameraPublisher>, std::conditional_t<std::is_same_v<RosMsg, geometry_msgs::msg::TransformStamped>, std::shared_ptr<tf2_ros::TransformBroadcaster>, typename rclcpp::Publisher<RosMsg>::SharedPtr>>