in kinesis_video_streamer/src/ros_stream_subscription_installer.cpp [24:48]
bool RosStreamSubscriptionInstaller::SetupImageTransport(const ImageTransportCallbackFn callback)
{
if (!callback) {
AWS_LOG_ERROR(__func__, "Invalid callback was provided at SetupImageTransport");
return false;
}
SubscriberSetupFn image_transport_setup_closure =
[this, callback](const StreamSubscriptionDescriptor & descriptor) -> bool {
auto callback_wrapper = [this, callback, descriptor]
(const sensor_msgs::msg::Image::ConstSharedPtr &image) -> void {
callback(*this->stream_manager_, descriptor.stream_name, image);
};
if (auto node_handle = handle_.lock()) {
image_transport::ImageTransport it(node_handle);
image_transport_subscribers_.push_back(
it.subscribe(descriptor.topic_name, descriptor.message_queue_size, callback_wrapper));
} else {
AWS_LOG_ERROR(__func__, "Cannot set up subscription - the node handle has been destroyed.");
return false;
}
return true;
};
installers_.insert({KINESIS_STREAM_INPUT_TYPE_IMAGE_TRANSPORT, image_transport_setup_closure});
return true;
}