Skip to content

Commit

Permalink
Add tiff compression support. (#75)
Browse files Browse the repository at this point in the history
* Add tiff compression support.
* Add parameter to configure resolution unit, x resolution and y resolution
* Fix: only do bit depth convertion when jpeg

Signed-off-by: Ivan Santiago Paunovic <[email protected]>
Co-authored-by: Jacob Perron <[email protected]>
  • Loading branch information
ivanpauno and jacobperron authored Jul 15, 2021
1 parent 07a5d70 commit 7ca9072
Show file tree
Hide file tree
Showing 4 changed files with 134 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class CompressedPublisher : public image_transport::SimplePublisherPlugin<Compre
const PublishFn& publish_fn) const;

struct Config {
// Compression format to use "jpeg" or "png"
// Compression format to use "jpeg", "png" or "tiff".
std::string format;

// PNG Compression Level from 0 to 9. A higher value means a smaller size.
Expand All @@ -76,6 +76,12 @@ class CompressedPublisher : public image_transport::SimplePublisherPlugin<Compre
// JPEG Quality from 0 to 100 (higher is better quality).
// Default to OpenCV default of 95.
int jpeg_quality;

// TIFF resolution unit
// Can be one of "none", "inch", "centimeter".
std::string tiff_res_unit;
int tiff_xdpi;
int tiff_ydpi;
};

Config config_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,10 @@ namespace compressed_image_transport
// Compression formats
enum compressionFormat
{
UNDEFINED = -1, JPEG, PNG
UNDEFINED = -1,
JPEG = 0,
PNG = 1,
TIFF = 2,
};

} //namespace compressed_image_transport
Expand Down
137 changes: 122 additions & 15 deletions compressed_image_transport/src/compressed_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ void CompressedPublisher::advertiseImpl(
format_description.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
format_description.description = "Compression method";
format_description.read_only = false;
format_description.additional_constraints = "Supported values: [jpeg, png]";
format_description.additional_constraints = "Supported values: [jpeg, png, tiff]";
try {
config_.format = node->declare_parameter(format_param_name, kDefaultFormat, format_description);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
Expand Down Expand Up @@ -120,6 +120,43 @@ void CompressedPublisher::advertiseImpl(
RCLCPP_DEBUG(logger_, "%s was previously declared", jpeg_quality_param_name.c_str());
config_.jpeg_quality = node->get_parameter(jpeg_quality_param_name).get_value<int64_t>();
}

std::string tiff_res_unit_param_name = param_base_name + ".tiff.res_unit";
rcl_interfaces::msg::ParameterDescriptor tiff_res_unit_description;
tiff_res_unit_description.description = "tiff resolution unit";
tiff_res_unit_description.read_only = false;
tiff_res_unit_description.additional_constraints = "Supported values: [none, inch, centimeter]";
try {
config_.tiff_res_unit = node->declare_parameter(
tiff_res_unit_param_name, "inch", tiff_res_unit_description);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", tiff_res_unit_param_name.c_str());
config_.tiff_res_unit = node->get_parameter(tiff_res_unit_param_name).get_value<std::string>();
}

std::string tiff_xdpi_param_name = param_base_name + ".tiff.xdpi";
rcl_interfaces::msg::ParameterDescriptor tiff_xdpi_description;
tiff_xdpi_description.description = "tiff xdpi";
tiff_xdpi_description.read_only = false;
try {
config_.tiff_xdpi = node->declare_parameter(
tiff_xdpi_param_name, -1, tiff_xdpi_description);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", tiff_xdpi_param_name.c_str());
config_.tiff_xdpi = node->get_parameter(tiff_xdpi_param_name).get_value<int64_t>();
}

std::string tiff_ydpi_param_name = param_base_name + ".tiff.ydpi";
rcl_interfaces::msg::ParameterDescriptor tiff_ydpi_description;
tiff_ydpi_description.description = "tiff ydpi";
tiff_ydpi_description.read_only = false;
try {
config_.tiff_ydpi = node->declare_parameter(
tiff_ydpi_param_name, -1, tiff_ydpi_description);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", tiff_ydpi_param_name.c_str());
config_.tiff_ydpi = node->get_parameter(tiff_xdpi_param_name).get_value<int64_t>();
}
}

void CompressedPublisher::publish(
Expand All @@ -133,14 +170,16 @@ void CompressedPublisher::publish(

// Compression settings
std::vector<int> params;
params.resize(3, 0);

// Get codec configuration
compressionFormat encodingFormat = UNDEFINED;
if (config_.format == "jpeg")
if (config_.format == "jpeg") {
encodingFormat = JPEG;
if (config_.format == "png")
} else if (config_.format == "png") {
encodingFormat = PNG;
} else if (config_.format == "tiff") {
encodingFormat = TIFF;
}

// Bit depth of image encoding
int bitDepth = enc::bitDepth(message.encoding);
Expand All @@ -150,8 +189,9 @@ void CompressedPublisher::publish(
// JPEG Compression
case JPEG:
{
params[0] = cv::IMWRITE_JPEG_QUALITY;
params[1] = config_.jpeg_quality;
params.reserve(2);
params.emplace_back(cv::IMWRITE_JPEG_QUALITY);
params.emplace_back(config_.jpeg_quality);

// Update ros message format header
compressed.format += "; jpeg compressed ";
Expand Down Expand Up @@ -202,18 +242,17 @@ void CompressedPublisher::publish(

// Publish message
publish_fn(compressed);
}
else
{
} else {
RCLCPP_ERROR(logger_, "Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: %s)", message.encoding.c_str());
}
break;
}
// PNG Compression
// PNG Compression
case PNG:
{
params[0] = cv::IMWRITE_PNG_COMPRESSION;
params[1] = config_.png_level;
params.reserve(2);
params.emplace_back(cv::IMWRITE_PNG_COMPRESSION);
params.emplace_back(config_.png_level);

// Update ros message format header
compressed.format += "; png compressed ";
Expand Down Expand Up @@ -263,14 +302,82 @@ void CompressedPublisher::publish(

// Publish message
publish_fn(compressed);
} else {
RCUTILS_LOG_ERROR(
"Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str());
}
break;
}
// TIFF Compression
case TIFF:
{
// Update ros message format header
compressed.format += "; tiff compressed ";
int res_unit = -1;
// See https://gitlab.com/libtiff/libtiff/-/blob/v4.3.0/libtiff/tiff.h#L282-284
if (config_.tiff_res_unit == "inch") {
res_unit = 2;
} else if (config_.tiff_res_unit == "centimeter") {
res_unit = 3;
} else if (config_.tiff_res_unit == "none") {
res_unit = 1;
} else {
RCLCPP_WARN(
logger_,
"tiff.res_unit parameter should be either 'inch', 'centimeter' or 'none'; "
"defaulting to 'inch'. Found '%s'", config_.tiff_res_unit.c_str());
}
params.reserve(3);
params.emplace_back(cv::IMWRITE_TIFF_XDPI);
params.emplace_back(config_.tiff_xdpi);
params.emplace_back(cv::IMWRITE_TIFF_YDPI);
params.emplace_back(config_.tiff_ydpi);
params.emplace_back(cv::IMWRITE_TIFF_RESUNIT);
params.emplace_back(res_unit);

// Check input format
if ((bitDepth == 8) || (bitDepth == 16) || (bitDepth == 32))
{

// OpenCV-ros bridge
try
{
cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, nullptr, "");

// Compress image
if (cv::imencode(".tiff", cv_ptr->image, compressed.data, params))
{
float cRatio = static_cast<float>((cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize()))
/ static_cast<float>((float)compressed.data.size());
RCUTILS_LOG_DEBUG("Compressed Image Transport - Codec: tiff, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
}
else
{
RCUTILS_LOG_ERROR("cv::imencode (tiff) failed on input image");
}
}
catch (cv_bridge::Exception& e)
{
RCUTILS_LOG_ERROR("%s", e.what());
return;
}
catch (cv::Exception& e)
{
RCUTILS_LOG_ERROR("%s", e.what());
return;
}

// Publish message
publish_fn(compressed);
} else {
RCUTILS_LOG_ERROR(
"Compressed Image Transport - TIFF compression requires 8/16/32-bit encoded color format (input format is: %s)", message.encoding.c_str());
}
else
RCUTILS_LOG_ERROR("Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str());
break;
}

default:
RCUTILS_LOG_ERROR("Unknown compression type '%s', valid options are 'jpeg' and 'png'", config_.format.c_str());
RCUTILS_LOG_ERROR("Unknown compression type '%s', valid options are 'jpeg', 'png' and 'tiff'", config_.format.c_str());
break;
}
}
Expand Down
2 changes: 1 addition & 1 deletion compressed_image_transport/src/compressed_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ void CompressedSubscriber::internalCallback(const CompressedImage::ConstSharedPt
cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA);
}
}
if (enc::bitDepth(image_encoding) == 16) {
if (message->format.find("jpeg") != std::string::npos && enc::bitDepth(image_encoding) == 16) {
cv_ptr->image.convertTo(cv_ptr->image, CV_16U, 256);
}
}
Expand Down

0 comments on commit 7ca9072

Please sign in to comment.