Skip to content

Commit

Permalink
implement proper lazy subscribers (#136)
Browse files Browse the repository at this point in the history
Fixes #119, works in Jazzy and later
  • Loading branch information
mikeferguson authored Feb 1, 2024
1 parent e84265c commit 01f3ddb
Showing 1 changed file with 31 additions and 9 deletions.
40 changes: 31 additions & 9 deletions openni2_camera/src/openni2_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,11 +139,6 @@ void OpenNI2Driver::periodic()
initialized_ = true;
}

// TODO: check subscriber counts, enable cameras
colorConnectCb();
depthConnectCb();
irConnectCb();

if (enable_reconnect_)
monitorConnection();
}
Expand All @@ -162,18 +157,45 @@ void OpenNI2Driver::advertiseROSTopics()
// Asus Xtion PRO does not have an RGB camera
if (device_->hasColorSensor())
{
pub_color_ = it.advertiseCamera("rgb/image_raw", 1);
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo&)
{
colorConnectCb();
};
rmw_qos_profile_t custom_qos = rmw_qos_profile_default;
custom_qos.depth = 1;
pub_color_ = image_transport::create_camera_publisher(this, "rgb/image_raw", custom_qos, pub_options);
}

if (device_->hasIRSensor())
{
pub_ir_ = it.advertiseCamera("ir/image", 1);
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo&)
{
irConnectCb();
};
rmw_qos_profile_t custom_qos = rmw_qos_profile_default;
custom_qos.depth = 1;
pub_ir_ = image_transport::create_camera_publisher(this, "ir/image_raw", custom_qos, pub_options);
}

if (device_->hasDepthSensor())
{
pub_depth_raw_ = it.advertiseCamera("depth/image_raw", 1);
pub_depth_ = it.advertiseCamera("depth/image", 1);
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo&)
{
depthConnectCb();
};
rmw_qos_profile_t custom_qos = rmw_qos_profile_default;
custom_qos.depth = 1;
pub_depth_raw_ = image_transport::create_camera_publisher(this, "depth/image_raw", custom_qos, pub_options);
pub_depth_ = image_transport::create_camera_publisher(this, "depth/image", custom_qos, pub_options);
pub_projector_info_ = this->create_publisher<sensor_msgs::msg::CameraInfo>("projector/camera_info", 1);
}

Expand Down

0 comments on commit 01f3ddb

Please sign in to comment.