20 #include <aws/core/utils/logging/AWSLogging.h> 21 #include <aws/core/utils/logging/LogMacros.h> 27 #include <kinesis_video_msgs/KinesisImageMetadata.h> 28 #include <kinesis_video_msgs/KinesisVideoFrame.h> 57 std::unique_ptr<H264Encoder> & encoder,
60 auto encoding_iter = SNSR_IMG_ENC_to_LIBAV_PIXEL_FRMT.find(msg->encoding);
61 if (encoding_iter == SNSR_IMG_ENC_to_LIBAV_PIXEL_FRMT.end()) {
62 AWS_LOGSTREAM_ERROR(__func__,
63 "Trying to work with unsupported encoding " << msg->encoding <<
"!");
67 encoder = std::unique_ptr<H264Encoder>(
new H264Encoder());
68 if (
nullptr != encoder) {
69 encoder->Initialize(msg->width, msg->height, encoding_iter->second, param_reader);
74 uint64_t & frame_num, kinesis_video_msgs::KinesisImageMetadata & metadata,
79 AwsError retcode = encoder->
Encode(msg->data.data(), encoder_output);
82 AWS_LOG_ERROR(__func__,
"Encoder received empty data!");
84 AWS_LOG_ERROR(__func__,
"Unknown encoding error occurred");
86 AWS_LOG_WARN(__func__,
"Encoder returned empty frame");
91 kinesis_video_msgs::KinesisVideoFrame frame;
92 frame.index = frame_num;
94 frame.decoding_ts = encoder_output.frame_dts;
95 frame.presentation_ts = encoder_output.frame_pts;
96 frame.duration = encoder_output.frame_duration / 2;
98 frame.frame_data = encoder_output.frame_data;
99 frame.metadata.swap(metadata.metadata);
103 constexpr
int kDbgMsgThrottlePeriod = 10;
104 ROS_DEBUG_THROTTLE(kDbgMsgThrottlePeriod,
"Published Frame #%lu (timestamp: %lu)\n", frame_num,
105 encoder_output.frame_pts);
114 std::unique_ptr<H264Encoder>& encoder,
115 uint64_t & frame_num,
116 kinesis_video_msgs::KinesisImageMetadata & metadata,
132 boost::function<void(const sensor_msgs::ImageConstPtr &)> image_callback;
133 image_callback = [&](
const sensor_msgs::ImageConstPtr & msg) ->
void {
135 if (
nullptr == encoder) {
138 if (
nullptr != encoder) {
151 boost::function<void(const kinesis_video_msgs::KinesisImageMetadata::ConstPtr &)>
153 metadata_callback = [&](
const kinesis_video_msgs::KinesisImageMetadata::ConstPtr & msg) ->
void {
154 metadata.metadata.insert(metadata.metadata.end(), msg->metadata.begin(), msg->metadata.end());
158 AWS_LOGSTREAM_INFO(__func__,
"subscribed to " << params.
metadata_topic <<
" for metadata...");
163 ros::init(argc, argv,
"h264_video_encoder");
166 Aws::Utils::Logging::InitializeAWSLogging(
167 Aws::MakeShared<Aws::Utils::Logging::AWSROSLogger>(
"h264_video_encoder"));
168 AWS_LOG_INFO(__func__,
"Starting H264 Video Node...");
173 std::unique_ptr<H264Encoder> encoder;
174 uint64_t frame_num = 0;
175 kinesis_video_msgs::KinesisImageMetadata metadata;
179 encoder, frame_num, metadata, param_reader);
185 AWS_LOG_INFO(__func__,
"Shutting down H264 Video Node...");
186 Aws::Utils::Logging::ShutdownAWSLogging();
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
std::string subscription_topic
void InitializeEncoder(const sensor_msgs::ImageConstPtr &msg, std::unique_ptr< H264Encoder > &encoder, const Aws::Client::ParameterReaderInterface ¶m_reader)
void publish(const boost::shared_ptr< M > &message) const
AwsError RunEncoderNode(int argc, char **argv)
std::vector< uint8_t > GetExtraData() const
#define ROS_DEBUG_THROTTLE(rate,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
void ImageCallback(const sensor_msgs::ImageConstPtr &msg, const H264Encoder *encoder, uint64_t &frame_num, kinesis_video_msgs::KinesisImageMetadata &metadata, ros::Publisher &pub)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string publication_topic
AwsError Encode(const uint8_t *img_data, H264EncoderResult &res) const
uint32_t getNumSubscribers() const
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 ¶m_reader)
Aws::AwsError GetH264EncoderNodeParams(const Aws::Client::ParameterReaderInterface ¶m_reader, H264EncoderNodeParams ¶ms)
const std::map< std::string, AVPixelFormat > SNSR_IMG_ENC_to_LIBAV_PIXEL_FRMT
std::string metadata_topic