in h264_video_encoder/src/h264_video_encoder.cpp [110:159]
void InitializeCommunication(ros::NodeHandle & nh,
ros::Subscriber& metadata_sub,
image_transport::Subscriber& image_sub,
ros::Publisher& pub,
std::unique_ptr<H264Encoder>& encoder,
uint64_t & frame_num,
kinesis_video_msgs::KinesisImageMetadata & metadata,
Aws::Client::Ros1NodeParameterReader & param_reader)
{
//
// reading parameters
//
H264EncoderNodeParams params;
GetH264EncoderNodeParams(param_reader, params);
pub = nh.advertise<kinesis_video_msgs::KinesisVideoFrame>(params.publication_topic,
params.queue_size);
//
// subscribing to topic with callback
//
boost::function<void(const sensor_msgs::ImageConstPtr &)> image_callback;
image_callback = [&](const sensor_msgs::ImageConstPtr & msg) -> void {
if (0 < pub.getNumSubscribers()) {
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(nh);
image_sub =
it.subscribe(params.subscription_topic, params.queue_size, image_callback);
AWS_LOGSTREAM_INFO(__func__, "subscribed to " << params.subscription_topic << "...");
boost::function<void(const kinesis_video_msgs::KinesisImageMetadata::ConstPtr &)>
metadata_callback;
metadata_callback = [&](const kinesis_video_msgs::KinesisImageMetadata::ConstPtr & msg) -> void {
metadata.metadata.insert(metadata.metadata.end(), msg->metadata.begin(), msg->metadata.end());
};
metadata_sub =
nh.subscribe(params.metadata_topic, params.queue_size, metadata_callback);
AWS_LOGSTREAM_INFO(__func__, "subscribed to " << params.metadata_topic << " for metadata...");
}