h264_video_encoder_test.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 
21 #include <aws/core/utils/logging/AWSLogging.h>
22 #include <aws/core/utils/logging/LogMacros.h>
23 #include <gtest/gtest.h>
27 #include <kinesis_video_msgs/KinesisImageMetadata.h>
28 #include <kinesis_video_msgs/KinesisVideoFrame.h>
29 #include <ros/ros.h>
31 
32 using namespace Aws::Utils::Encoding;
33 using namespace Aws::Utils::Logging;
34 
35 namespace Aws {
36 namespace Kinesis {
37 
38 void InitializeEncoder(const sensor_msgs::ImageConstPtr & msg,
39  std::unique_ptr<H264Encoder> & encoder,
40  const Aws::Client::ParameterReaderInterface & param_reader);
41 
42 void ImageCallback(const sensor_msgs::ImageConstPtr & msg, const H264Encoder * encoder,
43  uint64_t & frame_num, kinesis_video_msgs::KinesisImageMetadata & metadata,
44  ros::Publisher & pub);
45 
47  ros::Subscriber & metadata_sub,
48  image_transport::Subscriber & image_sub,
49  ros::Publisher & pub,
50  std::unique_ptr<H264Encoder> & encoder,
51  uint64_t & frame_num,
52  kinesis_video_msgs::KinesisImageMetadata & metadata,
54  );
55 
56 } // namespace Kinesis
57 } // namespace Aws
58 
59 constexpr static char kDefaultPublicationTopicName[] = "/video/encoded";
60 constexpr static char kDefaultSubscriptionTopicName[] = "/raspicam_node/image";
61 constexpr static char kDefaultMetadataTopicName[] = "/image_metadata";
62 constexpr static int kDefaultWidth = 410;
63 constexpr static int kDefaultHeight = 308;
64 constexpr static int kBytesPerPixel = 3; // 3 color channels (red, green, blue)
65 constexpr int kNumTestFrames = 30;
66 
67 
68 class H264EncoderNodeSuite : public ::testing::Test
69 {
70 public:
71 
72  constexpr static const std::string & kDefaultEncoding = sensor_msgs::image_encodings::RGB8;
73 
75 
76 protected:
77  void SetUp() override
78  {
80 
81  default_msg = boost::make_shared<sensor_msgs::Image>();
82  default_msg->header.seq = 0;
83  default_msg->header.frame_id = "";
84  default_msg->header.stamp = ros::Time::now();
85  default_msg->height = kDefaultHeight;
86  default_msg->width = kDefaultWidth;
87  default_msg->encoding = kDefaultEncoding;
88  default_msg->step = kBytesPerPixel * kDefaultWidth;
89  }
90 
91  void KinesisVideoCallback(const kinesis_video_msgs::KinesisVideoFrame::ConstPtr & frame)
92  {
93  if (frame->index > 0) {
94  EXPECT_GT(frame->index, prev_frame.index);
95  EXPECT_EQ(prev_frame.duration, frame->duration);
96  EXPECT_EQ(0, (frame->decoding_ts - prev_frame.decoding_ts) % frame->duration);
97  EXPECT_EQ(0, (frame->presentation_ts - prev_frame.presentation_ts) % frame->duration);
98  EXPECT_GT(frame->presentation_ts, prev_frame.presentation_ts);
99  }
100 
101  prev_frame = *frame;
102  if (0 == prev_frame.index) {
103  fwrite(prev_frame.codec_private_data.data(), 1,
104  prev_frame.codec_private_data.size(), debug_file);
105  }
106  fwrite(prev_frame.frame_data.data(), 1, prev_frame.frame_data.size(), debug_file);
107  }
108 
109  sensor_msgs::ImagePtr default_msg;
110  std::unique_ptr<H264Encoder> encoder;
112 
113  kinesis_video_msgs::KinesisVideoFrame prev_frame;
114  FILE * debug_file;
115 };
116 
121 {
122  std::unique_ptr<H264Encoder> invalid_encoder;
123  sensor_msgs::ImagePtr invalid_msg = boost::make_shared<sensor_msgs::Image>();
124  invalid_msg->encoding = "InvalidEncoding";
125  Aws::Kinesis::InitializeEncoder(invalid_msg, invalid_encoder, param_reader);
126  EXPECT_EQ(invalid_encoder, nullptr);
127  Aws::Kinesis::InitializeEncoder(default_msg, encoder, param_reader);
128  EXPECT_NE(encoder, nullptr);
129 }
130 
131 static void RainbowColor(const float h, uint8_t & r_out, uint8_t & g_out, uint8_t & b_out)
132 {
133  int i = 6.0f * h;
134  float f = 6.0f * h - i;
135  float t = f;
136  float q = 1.0f - f;
137 
138  float r, g, b;
139  switch (i % 6) {
140  case 0:
141  r = 1.0f;
142  g = t;
143  b = 0.0f;
144  break;
145  case 1:
146  r = q;
147  g = 1.0f;
148  b = 0.0f;
149  break;
150  case 2:
151  r = 0.0f;
152  g = 1.0f;
153  b = t;
154  break;
155  case 3:
156  r = 0.0f;
157  g = q;
158  b = 1.0f;
159  break;
160  case 4:
161  r = t;
162  g = 0.0f;
163  b = 1.0f;
164  break;
165  case 5:
166  r = 1.0f;
167  g = 0.0f;
168  b = q;
169  break;
170  }
171 
172  r_out = std::lround(255.0f * r);
173  g_out = std::lround(255.0f * g);
174  b_out = std::lround(255.0f * b);
175 }
176 
177 void CreateImageMsg(sensor_msgs::ImagePtr & msg, int frame_num)
178 {
179  ++msg->header.seq;
180  msg->header.stamp = ros::Time::now();
181 
182  // prepare a dummy image
183  int shift = static_cast<float>(frame_num) / (kNumTestFrames - 1) * kDefaultWidth;
184  for (int y = 0; y < kDefaultHeight; ++y) {
185  for (int x = 0; x < kDefaultWidth; ++x) {
186  uint8_t r, g, b;
187  RainbowColor(static_cast<float>((x + shift) % kDefaultWidth) / kDefaultWidth, r, g, b);
188  msg->data[kBytesPerPixel * y * kDefaultWidth + kBytesPerPixel * x + 0] = r;
189  msg->data[kBytesPerPixel * y * kDefaultWidth + kBytesPerPixel * x + 1] = g;
190  msg->data[kBytesPerPixel * y * kDefaultWidth + kBytesPerPixel * x + 2] = b;
191  }
192  }
193 }
194 
198 TEST_F(H264EncoderNodeSuite, EncoderCallback)
199 {
200  Aws::Kinesis::InitializeEncoder(default_msg, encoder, param_reader);
201  EXPECT_NE(encoder, nullptr);
202 
203  ros::NodeHandle pub_node;
204  ros::Publisher pub =
205  pub_node.advertise<kinesis_video_msgs::KinesisVideoFrame>(kDefaultPublicationTopicName, 100);
206 
207  ros::NodeHandle sub_node;
208  boost::function<void(const kinesis_video_msgs::KinesisVideoFrame::ConstPtr &)> callback;
209  callback = [this](const kinesis_video_msgs::KinesisVideoFrame::ConstPtr & frame) -> void {
210  this->KinesisVideoCallback(frame);
211  };
212  ros::Subscriber sub = sub_node.subscribe(kDefaultPublicationTopicName, 100, callback);
213 
214  default_msg->data.resize(kBytesPerPixel * kDefaultWidth * kDefaultHeight);
215  debug_file = fopen("frames_encodercallback.bin", "wb");
216 
217  // let's encode 30 frames
218  uint64_t prev_frame_index = 0, frame_index = 0;
219  kinesis_video_msgs::KinesisImageMetadata metadata;
220  for (int i = 0; i < kNumTestFrames; ++i) {
221  CreateImageMsg(default_msg, i);
222  Aws::Kinesis::ImageCallback(default_msg, encoder.get(), frame_index, metadata, pub);
223  ros::spinOnce();
224 
225  EXPECT_GE(frame_index, prev_frame_index);
226  prev_frame_index = frame_index;
227  }
228 
229  fclose(debug_file);
230  // you can dump the debug frames by executing: ffmpeg -i frames.bin -frames:v 10 -f image2
231  // frame%03d.png
232 }
233 
234 
239 TEST_F(H264EncoderNodeSuite, InitializeCommunicaiton)
240 {
241  ros::NodeHandle nh("~");
242  ros::Publisher pub;
243  image_transport::Subscriber image_sub;
244  ros::Subscriber metadata_sub;
245  uint64_t frame_num = 0;
246  kinesis_video_msgs::KinesisImageMetadata metadata;
248  Aws::Kinesis::InitializeCommunication(nh, metadata_sub, image_sub, pub,
249  encoder, frame_num, metadata, param_reader);
250 
251  EXPECT_EQ(kDefaultPublicationTopicName, pub.getTopic());
252  EXPECT_EQ(kDefaultSubscriptionTopicName, image_sub.getTopic());
253  EXPECT_EQ(kDefaultMetadataTopicName, metadata_sub.getTopic());
254 
255  // Test that callback function is properly set up
256  ros::NodeHandle sub_node;
257  boost::function<void(const kinesis_video_msgs::KinesisVideoFrame::ConstPtr &)> callback;
258  callback = [this](const kinesis_video_msgs::KinesisVideoFrame::ConstPtr & frame) -> void {
259  this->KinesisVideoCallback(frame);
260  };
261  ros::Subscriber sub = sub_node.subscribe(kDefaultPublicationTopicName, 100, callback);
262 
263  // setup the raw image source
264  default_msg->data.resize(kBytesPerPixel * kDefaultWidth * kDefaultHeight);
265  ros::NodeHandle pub_node("~");
266  ros::Publisher image_pub =
267  pub_node.advertise<sensor_msgs::Image>(kDefaultSubscriptionTopicName, 100);
268 
269  // let's encode 30 frames of the raw image
270  constexpr int kNumTestFrames = 30;
271  debug_file = fopen("frames_intialize_communication.bin", "wb");
272  uint64_t prev_frame_index = 0, frame_index = 0;
273  for (int i = 0; i < kNumTestFrames; ++i) {
274  CreateImageMsg(default_msg, i);
275  image_pub.publish(default_msg);
276  ros::spinOnce();
277  EXPECT_GE(frame_index, prev_frame_index);
278  prev_frame_index = frame_index;
279  }
280 
281  fclose(debug_file);
282 }
283 
284 
285 int main(int argc, char ** argv)
286 {
287 
288  testing::InitGoogleTest(&argc, argv);
289  ros::init(argc, argv, "test_h264_video_encoder");
290  return RUN_ALL_TESTS();
291 }
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
f
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static constexpr int kBytesPerPixel
static constexpr char kDefaultSubscriptionTopicName[]
kinesis_video_msgs::KinesisVideoFrame prev_frame
std::string getTopic() const
std::unique_ptr< H264Encoder > encoder
static void RainbowColor(const float h, uint8_t &r_out, uint8_t &g_out, uint8_t &b_out)
static void init()
void ImageCallback(const sensor_msgs::ImageConstPtr &msg, const H264Encoder *encoder, uint64_t &frame_num, kinesis_video_msgs::KinesisImageMetadata &metadata, ros::Publisher &pub)
std::string getTopic() const
void CreateImageMsg(sensor_msgs::ImagePtr &msg, int frame_num)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
constexpr int kNumTestFrames
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)
static constexpr char kDefaultPublicationTopicName[]
static constexpr char kDefaultMetadataTopicName[]
static Time now()
void KinesisVideoCallback(const kinesis_video_msgs::KinesisVideoFrame::ConstPtr &frame)
sensor_msgs::ImagePtr default_msg
std::string getTopic() const
int main(int argc, char **argv)
static constexpr int kDefaultHeight
Aws::Client::Ros1NodeParameterReader param_reader
TEST_F(H264EncoderNodeSuite, EncoderInit)
ROSCPP_DECL void spinOnce()
static constexpr int kDefaultWidth


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