bool RosStreamSubscriptionInstaller::SetupRekognitionEnabledKinesisVideoFrameTransport()

in kinesis_video_streamer/src/ros_stream_subscription_installer.cpp [79:114]


bool RosStreamSubscriptionInstaller::SetupRekognitionEnabledKinesisVideoFrameTransport(
        const RekognitionEnabledKinesisVideoFrameTransportCallbackFn callback)
{
    if (!callback) {
        AWS_LOG_ERROR(__func__, "Invalid callback was provided");
        return false;
    }
    SubscriberSetupFn rekognition_kinesis_video_frame_setup_closure =
        [this, callback](const StreamSubscriptionDescriptor & descriptor) -> bool {
            if (descriptor.rekognition_topic_name.empty()) {
                AWS_LOG_ERROR(__func__, "Can't set up subscription: Rekognition topic name is empty.");
                return false;
            }
            if (auto node_handle = handle_.lock()) {
                auto publisher = node_handle->create_publisher<std_msgs::msg::String>(
                        descriptor.rekognition_topic_name, descriptor.message_queue_size);
                auto callback_wrapper = [this, callback, descriptor, publisher](
                        const kinesis_video_msgs::msg::KinesisVideoFrame::ConstSharedPtr frame) -> void {
                    callback(*this->stream_manager_, descriptor.stream_name, frame, publisher);
                };
                /* Use sensor data default QoS settings (volatile, best effort - typical for streaming) */
                rclcpp::QoS kinesis_qos_profile = rclcpp::SensorDataQoS().keep_last(descriptor.message_queue_size);
                standard_subscribers_.push_back(
                  node_handle->create_subscription<kinesis_video_msgs::msg::KinesisVideoFrame>(
                      descriptor.topic_name, kinesis_qos_profile, callback_wrapper));
                publishers_[descriptor.topic_name] = publisher;
            } 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_REKOGNITION_ENABLED_KINESIS_VIDEO_FRAME,
                        rekognition_kinesis_video_frame_setup_closure});
    return true;
}