Skip to content

Commit

Permalink
move encoder->decoder map to decoder for public use
Browse files Browse the repository at this point in the history
  • Loading branch information
berndpfrommer committed Mar 11, 2024
1 parent 5cf934d commit c8de103
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 13 deletions.
12 changes: 8 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,10 @@ add_library(
src/utils.cpp
src/manifest.cpp)

target_include_directories(${LIBRARY_NAME} PRIVATE
target_include_directories(${LIBRARY_NAME} PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
"$<INSTALL_INTERFACE:include>")


ament_target_dependencies(${LIBRARY_NAME}
cv_bridge
Expand All @@ -90,6 +91,7 @@ ament_target_dependencies(test_encoder cv_bridge rclcpp sensor_msgs ffmpeg_image

ament_export_dependencies(
OpenCV
LIBAV
cv_bridge
image_transport
pluginlib
Expand All @@ -99,10 +101,12 @@ ament_export_dependencies(
std_msgs
ffmpeg_image_transport_msgs)

install(TARGETS ${LIBRARY_NAME} EXPORT export_${LIBRARY_NAME}
install(TARGETS ${LIBRARY_NAME}
EXPORT export_${LIBRARY_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)
RUNTIME DESTINATION bin
INCLUDES DESTINATION include)

install(TARGETS test_encoder
LIBRARY DESTINATION lib
Expand Down
1 change: 1 addition & 0 deletions include/ffmpeg_image_transport/ffmpeg_decoder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ class FFMPEGDecoder
void printTimers(const std::string & prefix) const;
void resetTimers();
void setLogger(rclcpp::Logger logger) { logger_ = logger; }
static const std::unordered_map<std::string, std::string> & getDefaultEncoderToDecoderMap();

private:
rclcpp::Logger logger_;
Expand Down
14 changes: 13 additions & 1 deletion src/ffmpeg_decoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,14 @@

namespace ffmpeg_image_transport
{
// default mappings
static const std::unordered_map<std::string, std::string> defaultMap{
{{"h264_nvenc", "h264"},
{"libx264", "h264"},
{"hevc_nvenc", "hevc_cuvid"},
{"h264_nvmpi", "h264"},
{"h264_vaapi", "h264"}}};

FFMPEGDecoder::FFMPEGDecoder() : logger_(rclcpp::get_logger("FFMPEGDecoder")) {}

FFMPEGDecoder::~FFMPEGDecoder() { reset(); }
Expand Down Expand Up @@ -57,7 +65,7 @@ bool FFMPEGDecoder::initialize(
{
std::string decoder = dec;
if (decoder.empty()) {
RCLCPP_INFO_STREAM(logger_, "unknown encoding: " << msg->encoding);
RCLCPP_INFO_STREAM(logger_, "no decoder for encoding: " << msg->encoding);
return (false);
}
callback_ = callback;
Expand Down Expand Up @@ -273,4 +281,8 @@ void FFMPEGDecoder::printTimers(const std::string & prefix) const
RCLCPP_INFO_STREAM(logger_, prefix << " total decode: " << tdiffTotal_);
}

const std::unordered_map<std::string, std::string> & FFMPEGDecoder::getDefaultEncoderToDecoderMap()
{
return (defaultMap);
}
} // namespace ffmpeg_image_transport
9 changes: 1 addition & 8 deletions src/ffmpeg_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,6 @@ using namespace std::placeholders;
namespace ffmpeg_image_transport
{
static const char nsc[] = "ffmpeg_image_transport.map.";
// default mappings
static const std::unordered_map<std::string, std::string> defaultMap{
{{"h264_nvenc", "h264"},
{"libx264", "h264"},
{"hevc_nvenc", "hevc_cuvid"},
{"h264_nvmpi", "h264"},
{"h264_vaapi", "h264"}}};

FFMPEGSubscriber::FFMPEGSubscriber() : logger_(rclcpp::get_logger("FFMPEGSubscriber")) {}

Expand Down Expand Up @@ -67,7 +60,7 @@ void FFMPEGSubscriber::initialize(rclcpp::Node * node)
node_ = node;

// create parameters from default map
for (const auto & kv : defaultMap) {
for (const auto & kv : FFMPEGDecoder::getDefaultEncoderToDecoderMap()) {
const std::string key = std::string(nsc) + kv.first;
if (!node_->has_parameter(key)) {
(void)node_->declare_parameter<std::string>(key, kv.second);
Expand Down

0 comments on commit c8de103

Please sign in to comment.