in h264_video_encoder/src/h264_video_encoder.cpp [111:156]
void InitializeCommunication(rclcpp::Node::SharedPtr node,
std::shared_ptr<rclcpp::Subscription<kinesis_video_msgs::msg::KinesisImageMetadata>> & metadata_sub,
image_transport::Subscriber& image_sub,
std::shared_ptr<rclcpp::Publisher<kinesis_video_msgs::msg::KinesisVideoFrame>> & pub,
std::unique_ptr<H264Encoder>& encoder,
uint64_t & frame_num,
kinesis_video_msgs::msg::KinesisImageMetadata & metadata,
Aws::Client::Ros2NodeParameterReader & param_reader)
{
//
// reading parameters
//
H264EncoderNodeParams params;
GetH264EncoderNodeParams(param_reader, params);
pub = node->create_publisher<kinesis_video_msgs::msg::KinesisVideoFrame>(params.publication_topic,
params.queue_size);
//
// subscribing to topic with callback
//
auto image_callback = [&](const sensor_msgs::msg::Image::ConstSharedPtr msg) -> void {
if (0 < pub->get_subscription_count()) {
if (nullptr == encoder) {
InitializeEncoder(msg, encoder, param_reader);
}
if (nullptr != encoder) {
ImageCallback(msg, encoder.get(), frame_num, metadata, pub);
}
} else {
frame_num = 0;
}
};
image_transport::ImageTransport it(node);
image_sub =
it.subscribe(params.subscription_topic, params.queue_size, image_callback);
AWS_LOGSTREAM_INFO(__func__, "subscribed to " << params.subscription_topic << "...");
auto metadata_callback = [&](const kinesis_video_msgs::msg::KinesisImageMetadata::ConstPtr msg) -> void {
metadata.metadata.insert(metadata.metadata.end(), msg->metadata.begin(), msg->metadata.end());
};
metadata_sub = node->create_subscription<kinesis_video_msgs::msg::KinesisImageMetadata>(params.metadata_topic, params.queue_size, metadata_callback);
AWS_LOGSTREAM_INFO(__func__, "subscribed to " << params.metadata_topic << " for metadata...");
}