Skip to content

Commit 3f89f9a

Browse files
committed
use encoder/decoder instead of transport
1 parent 75801b7 commit 3f89f9a

File tree

3 files changed

+14
-8
lines changed

3 files changed

+14
-8
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ find_package(ament_cmake_ros REQUIRED)
2323

2424
set(ament_dependencies
2525
"cv_bridge"
26-
"ffmpeg_image_transport"
26+
"ffmpeg_encoder_decoder"
2727
"ffmpeg_image_transport_msgs"
2828
"rclcpp"
2929
"rosbag2_cpp"

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717

1818
<depend>cv_bridge</depend>
1919
<depend>rclcpp</depend>
20-
<depend>ffmpeg_image_transport</depend>
20+
<depend>ffmpeg_encoder_decoder</depend>
2121
<depend>ffmpeg_image_transport_msgs</depend>
2222
<depend>rosbag2_cpp</depend>
2323
<depend>rosbag2_storage</depend>

src/bag_to_frames.cpp

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
#else
2222
#include <cv_bridge/cv_bridge.h>
2323
#endif
24-
#include <ffmpeg_image_transport/ffmpeg_decoder.hpp>
24+
#include <ffmpeg_encoder_decoder/decoder.hpp>
2525
#include <ffmpeg_image_transport_msgs/msg/ffmpeg_packet.hpp>
2626
#include <ffmpeg_image_transport_tools/bag_processor.hpp>
2727
#include <ffmpeg_image_transport_tools/message_processor.hpp>
@@ -40,7 +40,7 @@ void usage()
4040
<< "[-T timestamp_file] [-s start_time] [-e end_time] " << std::endl;
4141
}
4242

43-
using ffmpeg_image_transport::FFMPEGDecoder;
43+
using ffmpeg_encoder_decoder::Decoder;
4444
using ffmpeg_image_transport_msgs::msg::FFMPEGPacket;
4545
using sensor_msgs::msg::Image;
4646
using Path = std::filesystem::path;
@@ -66,7 +66,7 @@ class FrameWriter : public ffmpeg_image_transport_tools::MessageProcessor<FFMPEG
6666
if (!decoder_.isInitialized()) {
6767
std::string dtype = decoder_type_;
6868
if (dtype.empty()) {
69-
const auto & decoderMap = FFMPEGDecoder::getDefaultEncoderToDecoderMap();
69+
const auto & decoderMap = Decoder::getDefaultEncoderToDecoderMap();
7070
auto decTypeIt = decoderMap.find(m->encoding);
7171
if (decTypeIt == decoderMap.end()) {
7272
std::cerr << "unknown encoding: " << m->encoding << std::endl;
@@ -75,13 +75,19 @@ class FrameWriter : public ffmpeg_image_transport_tools::MessageProcessor<FFMPEG
7575
dtype = decTypeIt->second;
7676
}
7777

78-
decoder_.initialize(m, std::bind(&FrameWriter::callback, this, std::placeholders::_1), dtype);
78+
decoder_.initialize(
79+
m->encoding, std::bind(&FrameWriter::callback, this, std::placeholders::_1), dtype);
7980
}
8081
if (!decoder_.isInitialized()) {
8182
std::cerr << "cannot init codec" << std::endl;
8283
throw(std::runtime_error("cannot init codec"));
8384
}
84-
decoder_.decodePacket(m);
85+
bool decodePacket(
86+
const std::string & encoding, const uint8_t * data, size_t size, uint64_t pts,
87+
const std::string & frame_id, const rclcpp::Time & stamp);
88+
89+
decoder_.decodePacket(
90+
m->encoding, m->data.data(), m->data.size(), m->pts, m->header.frame_id, m->header.stamp);
8591
ts_file_ << packet_number_++ << " " << m->pts << " " << Time(m->header.stamp).nanoseconds()
8692
<< " " << t << std::endl;
8793
}
@@ -112,7 +118,7 @@ class FrameWriter : public ffmpeg_image_transport_tools::MessageProcessor<FFMPEG
112118
std::string decoder_type_;
113119
std::ofstream ts_file_;
114120
size_t frame_number_{0};
115-
FFMPEGDecoder decoder_;
121+
Decoder decoder_;
116122
size_t packet_number_{0};
117123
};
118124

0 commit comments

Comments
 (0)