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

backport a part of #73 #86

Merged
merged 1 commit into from
Feb 18, 2022
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.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
#include "image_transport/simple_publisher_plugin.h"
#include <image_transport/simple_publisher_plugin.hpp>

namespace compressed_depth_image_transport {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#include <rclcpp/node.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>
#include "image_transport/simple_subscriber_plugin.h"
#include <image_transport/simple_subscriber_plugin.hpp>

namespace compressed_depth_image_transport {

Expand Down
89 changes: 43 additions & 46 deletions compressed_image_transport/src/compressed_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@

#include "compressed_image_transport/compression_common.h"

#include <rclcpp/exceptions/exceptions.hpp>
#include <rclcpp/parameter_client.hpp>

#include <sstream>
Expand Down Expand Up @@ -69,59 +70,55 @@ void CompressedPublisher::advertiseImpl(
std::string param_base_name = base_topic.substr(ns_len);
std::replace(param_base_name.begin(), param_base_name.end(), '/', '.');
std::string format_param_name = param_base_name + ".format";
if (!node->has_parameter(format_param_name))
{
rcl_interfaces::msg::ParameterDescriptor format_description;
format_description.name = "format";
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]";
rcl_interfaces::msg::ParameterDescriptor format_description;
format_description.name = "format";
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]";
try {
config_.format = node->declare_parameter(format_param_name, kDefaultFormat, format_description);
}
else
{
RCLCPP_WARN(logger_, "%s was previously declared", format_param_name.c_str());
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", format_param_name.c_str());
config_.format = node->get_parameter(format_param_name).get_value<std::string>();
}

std::string png_level_param_name = param_base_name + ".png_level";
if (!node->has_parameter(png_level_param_name))
{
rcl_interfaces::msg::ParameterDescriptor png_level_description;
png_level_description.name = "png_level";
png_level_description.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
png_level_description.description = "Compression level for PNG format";
png_level_description.read_only = false;
rcl_interfaces::msg::IntegerRange png_range;
png_range.from_value = 0;
png_range.to_value = 9;
png_range.step = 1;
png_level_description.integer_range.push_back(png_range);
config_.png_level = node->declare_parameter(png_level_param_name, kDefaultPngLevel, png_level_description);
}
else
{
RCLCPP_WARN(logger_, "%s was previously delared", png_level_param_name.c_str());
rcl_interfaces::msg::ParameterDescriptor png_level_description;
png_level_description.name = "png_level";
png_level_description.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
png_level_description.description = "Compression level for PNG format";
png_level_description.read_only = false;
rcl_interfaces::msg::IntegerRange png_range;
png_range.from_value = 0;
png_range.to_value = 9;
png_range.step = 1;
png_level_description.integer_range.push_back(png_range);
try {
config_.png_level = node->declare_parameter(
png_level_param_name, kDefaultPngLevel, png_level_description);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", png_level_param_name.c_str());
config_.png_level = node->get_parameter(png_level_param_name).get_value<int64_t>();
}

std::string jpeg_quality_param_name = param_base_name + ".jpeg_quality";
if (!node->has_parameter(jpeg_quality_param_name))
{
rcl_interfaces::msg::ParameterDescriptor jpeg_quality_description;
jpeg_quality_description.name = "jpeg_quality";
jpeg_quality_description.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
jpeg_quality_description.description = "Image quality for JPEG format";
jpeg_quality_description.read_only = false;
rcl_interfaces::msg::IntegerRange jpeg_range;
jpeg_range.from_value = 1;
jpeg_range.to_value = 100;
jpeg_range.step = 1;
jpeg_quality_description.integer_range.push_back(jpeg_range);
config_.jpeg_quality = node->declare_parameter(jpeg_quality_param_name, kDefaultJpegQuality, jpeg_quality_description);
}
else
{
RCLCPP_WARN(logger_, "%s was previously delared", jpeg_quality_param_name.c_str());
rcl_interfaces::msg::ParameterDescriptor jpeg_quality_description;
jpeg_quality_description.name = "jpeg_quality";
jpeg_quality_description.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
jpeg_quality_description.description = "Image quality for JPEG format";
jpeg_quality_description.read_only = false;
rcl_interfaces::msg::IntegerRange jpeg_range;
jpeg_range.from_value = 1;
jpeg_range.to_value = 100;
jpeg_range.step = 1;
jpeg_quality_description.integer_range.push_back(jpeg_range);
try {
config_.jpeg_quality = node->declare_parameter(
jpeg_quality_param_name, kDefaultJpegQuality, jpeg_quality_description);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
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>();
}
}

Expand Down
14 changes: 11 additions & 3 deletions compressed_image_transport/src/compressed_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,14 +66,22 @@ void CompressedSubscriber::subscribeImpl(
logger_ = node->get_logger();
typedef image_transport::SimpleSubscriberPlugin<CompressedImage> Base;
Base::subscribeImpl(node, base_topic, callback, custom_qos);
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(), '/', '.');
std::string mode_param_name = param_base_name + ".mode";

std::string mode;
rcl_interfaces::msg::ParameterDescriptor mode_description;
mode_description.name = "mode";
mode_description.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
mode_description.description = "OpenCV imdecode flags to use";
mode_description.read_only = false;
mode_description.additional_constraints = "Supported values: [unchanged, gray, color]";
mode = node->declare_parameter("mode", kDefaultMode, mode_description);
try {
mode = node->declare_parameter(mode_param_name, kDefaultMode, mode_description);
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &) {
RCLCPP_DEBUG(logger_, "%s was previously declared", mode_param_name.c_str());
mode = node->get_parameter(mode_param_name).get_value<std::string>();
}

if (mode == "unchanged") {
config_.imdecode_flag = cv::IMREAD_UNCHANGED;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/compressed_image.hpp>

#include <image_transport/simple_publisher_plugin.h>
#include <image_transport/simple_publisher_plugin.hpp>
#include <cv_bridge/cv_bridge.h>
#include <std_msgs/msg/header.hpp>
#include <theora_image_transport/msg/packet.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <image_transport/simple_subscriber_plugin.h>
#include <image_transport/simple_subscriber_plugin.hpp>
#include <theora_image_transport/msg/packet.hpp>

#include <theora/codec.h>
Expand Down