|
33 | 33 | #include <map>
|
34 | 34 | #include <memory>
|
35 | 35 | #include <mutex>
|
| 36 | +#include <opencv2/imgcodecs.hpp> |
36 | 37 | #include <optional>
|
37 | 38 | #include <rcl/context.h>
|
38 | 39 | #include <rcl_interfaces/msg/detail/floating_point_range__struct.hpp>
|
|
48 | 49 | #include <rclcpp/qos_event.hpp>
|
49 | 50 | #include <rclcpp/time.hpp>
|
50 | 51 | #include <rclcpp_components/register_node_macro.hpp>
|
| 52 | +#include <sensor_msgs/image_encodings.hpp> |
51 | 53 | #include <sensor_msgs/msg/detail/camera_info__struct.hpp>
|
52 | 54 | #include <sensor_msgs/msg/detail/compressed_image__struct.hpp>
|
53 | 55 | #include <sensor_msgs/msg/detail/image__struct.hpp>
|
|
60 | 62 | #include <unordered_map>
|
61 | 63 | #include <utility>
|
62 | 64 | #include <vector>
|
| 65 | +namespace enc = sensor_msgs::image_encodings; |
63 | 66 | namespace rclcpp
|
64 | 67 | {
|
65 | 68 | class NodeOptions;
|
@@ -108,6 +111,8 @@ class CameraNode : public rclcpp::Node
|
108 | 111 | // keep track of set parameters
|
109 | 112 | ParameterMap parameters_full;
|
110 | 113 | std::mutex parameters_lock;
|
| 114 | + // compression quality parameter |
| 115 | + std::atomic_uint8_t jpeg_quality; |
111 | 116 |
|
112 | 117 | void
|
113 | 118 | declareParameters();
|
@@ -164,6 +169,18 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options) : Node("camera", opti
|
164 | 169 | // camera ID
|
165 | 170 | declare_parameter("camera", rclcpp::ParameterValue {}, param_descr_ro.set__dynamic_typing(true));
|
166 | 171 |
|
| 172 | + rcl_interfaces::msg::ParameterDescriptor jpeg_quality_description; |
| 173 | + jpeg_quality_description.name = "jpeg_quality"; |
| 174 | + jpeg_quality_description.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; |
| 175 | + jpeg_quality_description.description = "Image quality for JPEG format"; |
| 176 | + jpeg_quality_description.read_only = false; |
| 177 | + rcl_interfaces::msg::IntegerRange jpeg_range; |
| 178 | + jpeg_range.from_value = 1; |
| 179 | + jpeg_range.to_value = 100; |
| 180 | + jpeg_range.step = 1; |
| 181 | + jpeg_quality_description.integer_range = {jpeg_range}; |
| 182 | + // default to 95 |
| 183 | + jpeg_quality = declare_parameter<uint8_t>("jpeg_quality", 95, jpeg_quality_description); |
167 | 184 | // publisher for raw and compressed image
|
168 | 185 | pub_image = this->create_publisher<sensor_msgs::msg::Image>("~/image_raw", 1);
|
169 | 186 | pub_image_compressed =
|
@@ -481,6 +498,40 @@ CameraNode::declareParameters()
|
481 | 498 | set_parameters(parameters_init_list);
|
482 | 499 | }
|
483 | 500 |
|
| 501 | +// The following function "compressImageMsg" is adapted from "CvImage::toCompressedImageMsg" |
| 502 | +// (https://github.com/ros-perception/vision_opencv/blob/066793a23e5d06d76c78ca3d69824a501c3554fd/cv_bridge/src/cv_bridge.cpp#L512-L535) |
| 503 | +// and covered by the BSD-3-Clause licence. |
| 504 | +void |
| 505 | +compressImageMsg(const sensor_msgs::msg::Image &source, |
| 506 | + sensor_msgs::msg::CompressedImage &destination, |
| 507 | + const std::vector<int> ¶ms = std::vector<int>()) |
| 508 | +{ |
| 509 | + std::shared_ptr<CameraNode> tracked_object; |
| 510 | + cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(source, tracked_object); |
| 511 | + |
| 512 | + destination.header = source.header; |
| 513 | + cv::Mat image; |
| 514 | + if (cv_ptr->encoding == enc::BGR8 || cv_ptr->encoding == enc::BGRA8 || |
| 515 | + cv_ptr->encoding == enc::MONO8 || cv_ptr->encoding == enc::MONO16) |
| 516 | + { |
| 517 | + image = cv_ptr->image; |
| 518 | + } |
| 519 | + else { |
| 520 | + cv_bridge::CvImagePtr tempThis = std::make_shared<cv_bridge::CvImage>(*cv_ptr); |
| 521 | + cv_bridge::CvImagePtr temp; |
| 522 | + if (enc::hasAlpha(cv_ptr->encoding)) { |
| 523 | + temp = cv_bridge::cvtColor(tempThis, enc::BGRA8); |
| 524 | + } |
| 525 | + else { |
| 526 | + temp = cv_bridge::cvtColor(tempThis, enc::BGR8); |
| 527 | + } |
| 528 | + image = temp->image; |
| 529 | + } |
| 530 | + |
| 531 | + destination.format = "jpg"; |
| 532 | + cv::imencode(".jpg", image, destination.data, params); |
| 533 | +} |
| 534 | + |
484 | 535 | void
|
485 | 536 | CameraNode::requestComplete(libcamera::Request *request)
|
486 | 537 | {
|
@@ -523,7 +574,7 @@ CameraNode::requestComplete(libcamera::Request *request)
|
523 | 574 |
|
524 | 575 | // compress to jpeg
|
525 | 576 | if (pub_image_compressed->get_subscription_count())
|
526 |
| - cv_bridge::toCvCopy(*msg_img)->toCompressedImageMsg(*msg_img_compressed); |
| 577 | + compressImageMsg(*msg_img, *msg_img_compressed, {cv::IMWRITE_JPEG_QUALITY, jpeg_quality}); |
527 | 578 | }
|
528 | 579 | else if (format_type(cfg.pixelFormat) == FormatType::COMPRESSED) {
|
529 | 580 | // compressed image
|
@@ -634,6 +685,9 @@ CameraNode::onParameterChange(const std::vector<rclcpp::Parameter> ¶meters)
|
634 | 685 | parameters_full[parameter.get_name()] = parameter.get_parameter_value();
|
635 | 686 | }
|
636 | 687 | }
|
| 688 | + else if (!parameter.get_name().compare("jpeg_quality")) { |
| 689 | + jpeg_quality = parameter.get_parameter_value().get<uint8_t>(); |
| 690 | + } |
637 | 691 | }
|
638 | 692 |
|
639 | 693 | return result;
|
|
0 commit comments