h264_video_encoder.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018 Amazon.com, Inc. or its affiliates. All Rights Reserved.
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
17  *
18  */
19 
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>
29 #include <ros/ros.h>
31 
32 #include <map>
33 #include <string>
34 #include <vector>
35 
36 using namespace Aws::Utils::Encoding;
37 using namespace Aws::Utils::Logging;
38 
39 namespace Aws {
40 namespace Kinesis {
41 
42 const std::map<std::string, AVPixelFormat> SNSR_IMG_ENC_to_LIBAV_PIXEL_FRMT = {
43  {sensor_msgs::image_encodings::RGB8, AV_PIX_FMT_RGB24},
44  {sensor_msgs::image_encodings::BGR8, AV_PIX_FMT_BGR24},
45  {sensor_msgs::image_encodings::RGBA8, AV_PIX_FMT_RGBA},
46  {sensor_msgs::image_encodings::BGRA8, AV_PIX_FMT_BGRA}};
47 
56 void InitializeEncoder(const sensor_msgs::ImageConstPtr & msg,
57  std::unique_ptr<H264Encoder> & encoder,
58  const Aws::Client::ParameterReaderInterface & param_reader)
59 {
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 << "!");
64  return;
65  }
66 
67  encoder = std::unique_ptr<H264Encoder>(new H264Encoder());
68  if (nullptr != encoder) {
69  encoder->Initialize(msg->width, msg->height, encoding_iter->second, param_reader);
70  }
71 }
72 
73 void ImageCallback(const sensor_msgs::ImageConstPtr & msg, const H264Encoder * encoder,
74  uint64_t & frame_num, kinesis_video_msgs::KinesisImageMetadata & metadata,
75  ros::Publisher & pub)
76 {
77  thread_local H264EncoderResult encoder_output;
78 
79  AwsError retcode = encoder->Encode(msg->data.data(), encoder_output);
80  if (retcode != AWS_ERR_OK) {
81  if (retcode == AWS_ERR_NULL_PARAM) {
82  AWS_LOG_ERROR(__func__, "Encoder received empty data!");
83  } else if (retcode == AWS_ERR_FAILURE) {
84  AWS_LOG_ERROR(__func__, "Unknown encoding error occurred");
85  } else if (retcode == AWS_ERR_EMPTY) {
86  AWS_LOG_WARN(__func__, "Encoder returned empty frame");
87  }
88  return;
89  }
90 
91  kinesis_video_msgs::KinesisVideoFrame frame;
92  frame.index = frame_num;
93  frame.flags = (encoder_output.key_frame) ? kKeyFrameFlag : kBPFrameFlag;
94  frame.decoding_ts = encoder_output.frame_dts;
95  frame.presentation_ts = encoder_output.frame_pts;
96  frame.duration = encoder_output.frame_duration / 2; // duration recommended to be set shorter
97  frame.codec_private_data = encoder->GetExtraData();
98  frame.frame_data = encoder_output.frame_data;
99  frame.metadata.swap(metadata.metadata);
100 
101  pub.publish(frame);
102 
103  constexpr int kDbgMsgThrottlePeriod = 10; // 10 seconds throttling period
104  ROS_DEBUG_THROTTLE(kDbgMsgThrottlePeriod, "Published Frame #%lu (timestamp: %lu)\n", frame_num,
105  encoder_output.frame_pts);
106 
107  ++frame_num;
108 }
109 
111  ros::Subscriber& metadata_sub,
112  image_transport::Subscriber& image_sub,
113  ros::Publisher& pub,
114  std::unique_ptr<H264Encoder>& encoder,
115  uint64_t & frame_num,
116  kinesis_video_msgs::KinesisImageMetadata & metadata,
118 {
119  //
120  // reading parameters
121  //
122  H264EncoderNodeParams params;
123  GetH264EncoderNodeParams(param_reader, params);
124 
125 
126  pub = nh.advertise<kinesis_video_msgs::KinesisVideoFrame>(params.publication_topic,
127  params.queue_size);
128 
129  //
130  // subscribing to topic with callback
131  //
132  boost::function<void(const sensor_msgs::ImageConstPtr &)> image_callback;
133  image_callback = [&](const sensor_msgs::ImageConstPtr & msg) -> void {
134  if (0 < pub.getNumSubscribers()) {
135  if (nullptr == encoder) {
136  InitializeEncoder(msg, encoder, param_reader);
137  }
138  if (nullptr != encoder) {
139  ImageCallback(msg, encoder.get(), frame_num, metadata, pub);
140  }
141  } else {
142  frame_num = 0;
143  }
144  };
145 
147  image_sub =
148  it.subscribe(params.subscription_topic, params.queue_size, image_callback);
149  AWS_LOGSTREAM_INFO(__func__, "subscribed to " << params.subscription_topic << "...");
150 
151  boost::function<void(const kinesis_video_msgs::KinesisImageMetadata::ConstPtr &)>
152  metadata_callback;
153  metadata_callback = [&](const kinesis_video_msgs::KinesisImageMetadata::ConstPtr & msg) -> void {
154  metadata.metadata.insert(metadata.metadata.end(), msg->metadata.begin(), msg->metadata.end());
155  };
156  metadata_sub =
157  nh.subscribe(params.metadata_topic, params.queue_size, metadata_callback);
158  AWS_LOGSTREAM_INFO(__func__, "subscribed to " << params.metadata_topic << " for metadata...");
159 }
160 
161 AwsError RunEncoderNode(int argc, char ** argv)
162 {
163  ros::init(argc, argv, "h264_video_encoder");
164  ros::NodeHandle nh("~");
165 
166  Aws::Utils::Logging::InitializeAWSLogging(
167  Aws::MakeShared<Aws::Utils::Logging::AWSROSLogger>("h264_video_encoder"));
168  AWS_LOG_INFO(__func__, "Starting H264 Video Node...");
169 
170  ros::Publisher pub;
171  image_transport::Subscriber image_sub;
172  ros::Subscriber metadata_sub;
173  std::unique_ptr<H264Encoder> encoder;
174  uint64_t frame_num = 0;
175  kinesis_video_msgs::KinesisImageMetadata metadata;
177 
178  InitializeCommunication(nh, metadata_sub, image_sub, pub,
179  encoder, frame_num, metadata, param_reader);
180 
181  //
182  // run the node
183  //
184  ros::spin();
185  AWS_LOG_INFO(__func__, "Shutting down H264 Video Node...");
186  Aws::Utils::Logging::ShutdownAWSLogging();
187  return AWS_ERR_OK;
188 }
189 
190 } // namespace Kinesis
191 } // namespace Aws
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())
kKeyFrameFlag
void InitializeEncoder(const sensor_msgs::ImageConstPtr &msg, std::unique_ptr< H264Encoder > &encoder, const Aws::Client::ParameterReaderInterface &param_reader)
void publish(const boost::shared_ptr< M > &message) const
kBPFrameFlag
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)
AWS_ERR_NULL_PARAM
void ImageCallback(const sensor_msgs::ImageConstPtr &msg, const H264Encoder *encoder, uint64_t &frame_num, kinesis_video_msgs::KinesisImageMetadata &metadata, ros::Publisher &pub)
AWS_ERR_EMPTY
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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 &param_reader)
Aws::AwsError GetH264EncoderNodeParams(const Aws::Client::ParameterReaderInterface &param_reader, H264EncoderNodeParams &params)
const std::map< std::string, AVPixelFormat > SNSR_IMG_ENC_to_LIBAV_PIXEL_FRMT
AWS_ERR_OK
AWS_ERR_FAILURE


h264_video_encoder
Author(s): AWS RoboMaker
autogenerated on Thu Mar 4 2021 03:33:17