Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add transport scoped parameters for CompressedPublisher #143

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,12 @@

#include <rclcpp/node.hpp>

#include "compressed_image_transport/compression_common.h"

namespace compressed_image_transport {

using CompressedImage = sensor_msgs::msg::CompressedImage;
using ParameterEvent = rcl_interfaces::msg::ParameterEvent;

class CompressedPublisher : public image_transport::SimplePublisherPlugin<CompressedImage>
{
Expand All @@ -66,35 +69,23 @@ class CompressedPublisher : public image_transport::SimplePublisherPlugin<Compre
void publish(const sensor_msgs::msg::Image& message,
const PublishFn& publish_fn) const override;

struct Config {
// 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.
// Default to OpenCV default of 3
int png_level;

// 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 get_updated_config_from_parameters() const;

Config config_;
std::string format_param_name_;
std::string png_level_param_name_;
std::string jpeg_quality_param_name_;
std::string tiff_res_unit_param_name_;
std::string tiff_xdpi_param_name_;
std::string tiff_ydpi_param_name_;
rclcpp::Logger logger_;
rclcpp::Node * node_;

private:
std::vector<std::string> parameters_;
std::vector<std::string> deprecatedParameters_;

rclcpp::Subscription<ParameterEvent>::SharedPtr parameter_subscription_;

void declareParameters(rclcpp::Node* node, const std::string& base_topic);

void declareParameter(rclcpp::Node* node,
const std::string &base_name,
const std::string &transport_name,
const ParameterDefinition &definition);

void onParameterEvent(ParameterEvent::SharedPtr event, std::string full_name, std::string base_name);
};

} //namespace compressed_image_transport
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,92 @@ enum compressionFormat
TIFF = 2,
};

// Parameters
// Note - what is below would be moved to separate file, e.g. `compressed_publisher_cfg.h`

enum compressedParameters
{
FORMAT = 0,
PNG_LEVEL,
JPEG_QUALITY,
TIFF_RESOLUTION_UNIT,
TIFF_XDPI,
TIFF_YDPI
};

using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
using ParameterValue = rclcpp::ParameterValue;

struct ParameterDefinition
{
const ParameterValue defaultValue;
const ParameterDescriptor descriptor;
};

const struct ParameterDefinition kParameters[] =
{
{ //FORMAT - Compression format to use "jpeg", "png" or "tiff".
ParameterValue("jpeg"),
ParameterDescriptor()
.set__name("format")
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
.set__description("Compression method")
.set__read_only(false)
.set__additional_constraints("Supported values: [jpeg, png]")
},
{ //PNG_LEVEL - PNG Compression Level from 0 to 9. A higher value means a smaller size.
ParameterValue((int)3), //Default to OpenCV default of 3
ParameterDescriptor()
.set__name("png_level")
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
.set__description("Compression level for PNG format")
.set__read_only(false)
.set__integer_range(
{rcl_interfaces::msg::IntegerRange()
.set__from_value(0)
.set__to_value(9)
.set__step(1)})
},
{ //JPEG_QUALITY - JPEG Quality from 0 to 100 (higher is better quality).
ParameterValue((int)95), //Default to OpenCV default of 95.
ParameterDescriptor()
.set__name("jpeg_quality")
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
.set__description("Image quality for JPEG format")
.set__read_only(false)
.set__integer_range(
{rcl_interfaces::msg::IntegerRange()
.set__from_value(1)
.set__to_value(100)
.set__step(1)})
},
{ //TIFF_RESOLUTION_UNIT - TIFF resolution unit, can be one of "none", "inch", "centimeter".
ParameterValue("inch"),
ParameterDescriptor()
.set__name("tiff.res_unit")
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
.set__description("tiff resolution unit")
.set__read_only(false)
.set__additional_constraints("Supported values: [none, inch, centimeter]")
},
{ //TIFF_XDPI
ParameterValue((int)-1),
ParameterDescriptor()
.set__name("tiff.xdpi")
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
.set__description("tiff xdpi")
.set__read_only(false)
},
{ //TIFF_YDPI
ParameterValue((int)-1),
ParameterDescriptor()
.set__name("tiff.ydpi")
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
.set__description("tiff ydpi")
.set__read_only(false)
}
};

} //namespace compressed_image_transport

#endif
Loading