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> 39 std::unique_ptr<H264Encoder> & encoder,
43 uint64_t & frame_num, kinesis_video_msgs::KinesisImageMetadata & metadata,
50 std::unique_ptr<H264Encoder> & encoder,
52 kinesis_video_msgs::KinesisImageMetadata & metadata,
81 default_msg = boost::make_shared<sensor_msgs::Image>();
82 default_msg->header.seq = 0;
83 default_msg->header.frame_id =
"";
87 default_msg->encoding = kDefaultEncoding;
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);
102 if (0 == prev_frame.index) {
103 fwrite(prev_frame.codec_private_data.data(), 1,
104 prev_frame.codec_private_data.size(), debug_file);
106 fwrite(prev_frame.frame_data.data(), 1, prev_frame.frame_data.size(), debug_file);
122 std::unique_ptr<H264Encoder> invalid_encoder;
123 sensor_msgs::ImagePtr invalid_msg = boost::make_shared<sensor_msgs::Image>();
124 invalid_msg->encoding =
"InvalidEncoding";
126 EXPECT_EQ(invalid_encoder,
nullptr);
128 EXPECT_NE(encoder,
nullptr);
131 static void RainbowColor(
const float h, uint8_t & r_out, uint8_t & g_out, uint8_t & b_out)
134 float f = 6.0f * h - i;
172 r_out = std::lround(255.0f * r);
173 g_out = std::lround(255.0f * g);
174 b_out = std::lround(255.0f * b);
187 RainbowColor(static_cast<float>((x + shift) % kDefaultWidth) / kDefaultWidth, r, g, b);
201 EXPECT_NE(encoder,
nullptr);
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);
212 ros::Subscriber sub = sub_node.subscribe(kDefaultPublicationTopicName, 100, callback);
215 debug_file = fopen(
"frames_encodercallback.bin",
"wb");
218 uint64_t prev_frame_index = 0, frame_index = 0;
219 kinesis_video_msgs::KinesisImageMetadata metadata;
225 EXPECT_GE(frame_index, prev_frame_index);
226 prev_frame_index = frame_index;
245 uint64_t frame_num = 0;
246 kinesis_video_msgs::KinesisImageMetadata metadata;
249 encoder, frame_num, metadata, param_reader);
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);
271 debug_file = fopen(
"frames_intialize_communication.bin",
"wb");
272 uint64_t prev_frame_index = 0, frame_index = 0;
275 image_pub.
publish(default_msg);
277 EXPECT_GE(frame_index, prev_frame_index);
278 prev_frame_index = frame_index;
285 int main(
int argc,
char ** argv)
288 testing::InitGoogleTest(&argc, argv);
289 ros::init(argc, argv,
"test_h264_video_encoder");
290 return RUN_ALL_TESTS();
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
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)
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 ¶m_reader)
static constexpr char kDefaultPublicationTopicName[]
static constexpr char kDefaultMetadataTopicName[]
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