Skip to content

Commit

Permalink
reconfigurable transport scoped parameters for CompressedSubscriber
Browse files Browse the repository at this point in the history
- runtime reconfiguration
- <image>.<transport>.<param> as future replacement of  <image>.<param>
  - e.g. `image.compressed.mode` instead of `image.mode`
- support both ways for now
- emit deprecation warnings on setting through non-transport scoped parameter
- synchronize deprecated changes to new ones
  - this is necessary for dynamic reconfigure

Similar changes will be needed for:
- other transports

Related to ros-perception#140
  • Loading branch information
bmegli committed Apr 18, 2023
1 parent e4bf309 commit 9cc9441
Show file tree
Hide file tree
Showing 5 changed files with 232 additions and 140 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
*********************************************************************/

#include <string>
#include <vector>

#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
Expand Down Expand Up @@ -78,11 +79,7 @@ class CompressedPublisher : public image_transport::SimplePublisherPlugin<Compre

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,
void declareParameter(const std::string &base_name,
const ParameterDefinition &definition);

void onParameterEvent(ParameterEvent::SharedPtr event, std::string full_name, std::string base_name);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
*********************************************************************/

#include <string>
#include <vector>

#include <rclcpp/node.hpp>
#include <rclcpp/subscription_options.hpp>
Expand All @@ -41,8 +42,12 @@
#include <sensor_msgs/msg/compressed_image.hpp>
#include <image_transport/simple_subscriber_plugin.hpp>

#include "compressed_image_transport/compression_common.h"

namespace compressed_image_transport {

using ParameterEvent = rcl_interfaces::msg::ParameterEvent;

class CompressedSubscriber final : public image_transport::SimpleSubscriberPlugin<sensor_msgs::msg::CompressedImage>
{
public:
Expand All @@ -66,12 +71,21 @@ class CompressedSubscriber final : public image_transport::SimpleSubscriberPlugi
void internalCallback(const sensor_msgs::msg::CompressedImage::ConstSharedPtr& message,
const Callback& user_cb) override;

struct Config {
int imdecode_flag;
};

Config config_;
rclcpp::Logger logger_;
rclcpp::Node * node_;

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

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

int imdecodeFlagFromConfig();

void declareParameter(const std::string &base_name,
const ParameterDefinition &definition);

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

} //namespace image_transport
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,9 @@
#ifndef COMPRESSED_IMAGE_TRANSPORT_COMPRESSION_COMMON
#define COMPRESSED_IMAGE_TRANSPORT_COMPRESSION_COMMON

#include <rclcpp/parameter_value.hpp>
#include <rcl_interfaces/msg/parameter_descriptor.hpp>

namespace compressed_image_transport
{

Expand All @@ -47,19 +50,6 @@ 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;

Expand All @@ -69,70 +59,6 @@ struct ParameterDefinition
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, tiff]")
},
{ //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
119 changes: 93 additions & 26 deletions compressed_image_transport/src/compressed_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,80 @@ namespace enc = sensor_msgs::image_encodings;
namespace compressed_image_transport
{

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

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, tiff]")
},
{ //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)
}
};

void CompressedPublisher::advertiseImpl(
rclcpp::Node* node,
const std::string& base_topic,
Expand All @@ -65,7 +139,19 @@ void CompressedPublisher::advertiseImpl(
typedef image_transport::SimplePublisherPlugin<sensor_msgs::msg::CompressedImage> Base;
Base::advertiseImpl(node, base_topic, custom_qos, options);

declareParameters(node, base_topic);
// Declare Parameters
uint ns_len = node->get_effective_namespace().length();
std::string param_base_name = base_topic.substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');

using callbackT = std::function<void(ParameterEvent::SharedPtr event)>;
auto callback = std::bind(&CompressedPublisher::onParameterEvent, this, std::placeholders::_1,
node->get_fully_qualified_name(), param_base_name);

parameter_subscription_ = rclcpp::SyncParametersClient::on_parameter_event<callbackT>(node, callback);

for(const ParameterDefinition &pd : kParameters)
declareParameter(param_base_name, pd);
}

void CompressedPublisher::publish(
Expand Down Expand Up @@ -253,7 +339,6 @@ void CompressedPublisher::publish(
params.emplace_back(res_unit);

// Check input format

if ((bitDepth == 8) || (bitDepth == 16) || (bitDepth == 32))
{

Expand Down Expand Up @@ -300,29 +385,11 @@ void CompressedPublisher::publish(
}
}

void CompressedPublisher::declareParameters(rclcpp::Node* node, const std::string& base_topic)
{
uint ns_len = node->get_effective_namespace().length();
std::string param_base_name = base_topic.substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');
const std::string transport_name = getTransportName();

using callbackT = std::function<void(ParameterEvent::SharedPtr event)>;
auto callback = std::bind(&CompressedPublisher::onParameterEvent, this, std::placeholders::_1,
node->get_fully_qualified_name(), param_base_name);

parameter_subscription_ = rclcpp::SyncParametersClient::on_parameter_event<callbackT>(node, callback);

for(const ParameterDefinition &pd : kParameters)
declareParameter(node, param_base_name, transport_name, pd);
}

void CompressedPublisher::declareParameter(rclcpp::Node* node,
const std::string &base_name,
const std::string &transport_name,
void CompressedPublisher::declareParameter(const std::string &base_name,
const ParameterDefinition &definition)
{
//transport scoped parameter (e.g. image_raw.compressed.format)
const std::string transport_name = getTransportName();
const std::string param_name = base_name + "." + transport_name + "." + definition.descriptor.name;
parameters_.push_back(param_name);

Expand All @@ -333,18 +400,18 @@ void CompressedPublisher::declareParameter(rclcpp::Node* node,
rclcpp::ParameterValue param_value;

try {
param_value = node->declare_parameter(param_name, definition.defaultValue, definition.descriptor);
param_value = node_->declare_parameter(param_name, definition.defaultValue, definition.descriptor);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", definition.descriptor.name.c_str());
param_value = node->get_parameter(param_name).get_parameter_value();
param_value = node_->get_parameter(param_name).get_parameter_value();
}

// transport scoped parameter as default, otherwise we would overwrite
try {
node->declare_parameter(deprecated_name, param_value, definition.descriptor);
node_->declare_parameter(deprecated_name, param_value, definition.descriptor);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", definition.descriptor.name.c_str());
node->get_parameter(deprecated_name).get_parameter_value();
node_->get_parameter(deprecated_name).get_parameter_value();
}
}

Expand Down
Loading

0 comments on commit 9cc9441

Please sign in to comment.