From e6604a1ebfc231a8e88b570cda6bb6088a53a837 Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Tue, 31 Dec 2024 14:42:24 +0100 Subject: [PATCH 1/7] fix typo --- src/CameraNode.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/CameraNode.cpp b/src/CameraNode.cpp index 4a01e523..6aac4164 100644 --- a/src/CameraNode.cpp +++ b/src/CameraNode.cpp @@ -270,7 +270,7 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options) : Node("camera", opti RCLCPP_DEBUG_STREAM(get_logger(), "found camera by name: \"" << name << "\""); } break; default: - RCLCPP_ERROR_STREAM(get_logger(), "unuspported camera parameter type: " + RCLCPP_ERROR_STREAM(get_logger(), "unsupported camera parameter type: " << get_parameter("camera").get_type_name()); break; } From c3115fc743a77ac857b5726bc60e3098f90dfd2c Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Tue, 24 Dec 2024 01:24:04 +0100 Subject: [PATCH 2/7] move LIBCAMERA_VER_GE macro to dedicated header file --- src/libcamera_version_utils.hpp | 8 ++++++++ src/type_extent.cpp | 9 +-------- 2 files changed, 9 insertions(+), 8 deletions(-) create mode 100644 src/libcamera_version_utils.hpp diff --git a/src/libcamera_version_utils.hpp b/src/libcamera_version_utils.hpp new file mode 100644 index 00000000..243d8279 --- /dev/null +++ b/src/libcamera_version_utils.hpp @@ -0,0 +1,8 @@ +#pragma once +#include + +#define LIBCAMERA_VER_GE(major, minor, patch) \ + ((major < LIBCAMERA_VERSION_MAJOR) || \ + (major == LIBCAMERA_VERSION_MAJOR && minor < LIBCAMERA_VERSION_MINOR) || \ + (major == LIBCAMERA_VERSION_MAJOR && minor == LIBCAMERA_VERSION_MINOR && \ + patch <= LIBCAMERA_VERSION_PATCH)) diff --git a/src/type_extent.cpp b/src/type_extent.cpp index b189cda4..ea6b9e7a 100644 --- a/src/type_extent.cpp +++ b/src/type_extent.cpp @@ -1,20 +1,13 @@ #include "type_extent.hpp" +#include "libcamera_version_utils.hpp" #include #include #include -#include #include #include #include -#define LIBCAMERA_VER_GE(major, minor, patch) \ - ((major < LIBCAMERA_VERSION_MAJOR) || \ - (major == LIBCAMERA_VERSION_MAJOR && minor < LIBCAMERA_VERSION_MINOR) || \ - (major == LIBCAMERA_VERSION_MAJOR && minor == LIBCAMERA_VERSION_MINOR && \ - patch <= LIBCAMERA_VERSION_PATCH)) - - template::value, bool> = true> std::size_t get_extent(const libcamera::Control &) From 02cb07c05cb3aa096e12500968b91c00e93ba251 Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Tue, 24 Dec 2024 00:35:33 +0100 Subject: [PATCH 3/7] replace 'is_arithmetic' with 'is_constructible' to determine template match --- src/cv_to_pv.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/cv_to_pv.cpp b/src/cv_to_pv.cpp index 23c43b80..43075493 100644 --- a/src/cv_to_pv.cpp +++ b/src/cv_to_pv.cpp @@ -35,25 +35,25 @@ extract_value(const libcamera::ControlValue &value) template< typename T, - std::enable_if_t::value || std::is_same::value, bool> = true> + std::enable_if_t>::value, bool> = true> rclcpp::ParameterValue cv_to_pv_array(const std::vector &values) { return rclcpp::ParameterValue(values); } -template::value && !std::is_same::value, - bool> = true> +template< + typename T, + std::enable_if_t>::value, bool> = true> rclcpp::ParameterValue cv_to_pv_array(const std::vector & /*values*/) { - throw invalid_conversion("ParameterValue only supported for arithmetic types"); + throw invalid_conversion("ParameterValue not constructible from complex type."); } template< typename T, - std::enable_if_t::value || std::is_same::value, bool> = true> + std::enable_if_t::value, bool> = true> rclcpp::ParameterValue cv_to_pv_scalar(const T &value) { From 41b820862b32b29a04ae15adc3612e4cf16eadd4 Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Tue, 31 Dec 2024 14:50:00 +0100 Subject: [PATCH 4/7] move custom exceptions to dedicated header file --- src/cv_to_pv.hpp | 9 +-------- src/exceptions.hpp | 9 +++++++++ 2 files changed, 10 insertions(+), 8 deletions(-) create mode 100644 src/exceptions.hpp diff --git a/src/cv_to_pv.hpp b/src/cv_to_pv.hpp index d71880cb..b288de78 100644 --- a/src/cv_to_pv.hpp +++ b/src/cv_to_pv.hpp @@ -1,6 +1,6 @@ #pragma once +#include "exceptions.hpp" #include -#include #include namespace libcamera @@ -10,13 +10,6 @@ class ControlValue; } // namespace libcamera -class invalid_conversion : public std::runtime_error -{ -public: - explicit invalid_conversion(const std::string &msg) : std::runtime_error(msg) {} -}; - - rclcpp::ParameterValue cv_to_pv(const libcamera::ControlValue &value); diff --git a/src/exceptions.hpp b/src/exceptions.hpp new file mode 100644 index 00000000..b3e10150 --- /dev/null +++ b/src/exceptions.hpp @@ -0,0 +1,9 @@ +#pragma once +#include + + +class invalid_conversion : public std::runtime_error +{ +public: + explicit invalid_conversion(const std::string &msg) : std::runtime_error(msg) {} +}; From 5ca1a08b96791af24ab6521b7a0b4ac3a747045f Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Mon, 30 Dec 2024 22:49:37 +0100 Subject: [PATCH 5/7] cv_to_pv_scalar for unsigned integer --- src/cv_to_pv.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/src/cv_to_pv.cpp b/src/cv_to_pv.cpp index 43075493..d98f3803 100644 --- a/src/cv_to_pv.cpp +++ b/src/cv_to_pv.cpp @@ -60,6 +60,18 @@ cv_to_pv_scalar(const T &value) return rclcpp::ParameterValue(value); } +rclcpp::ParameterValue +cv_to_pv_scalar(const uint16_t &val) +{ + return rclcpp::ParameterValue(static_cast(val)); +} + +rclcpp::ParameterValue +cv_to_pv_scalar(const uint32_t &val) +{ + return rclcpp::ParameterValue(static_cast(val)); +} + rclcpp::ParameterValue cv_to_pv_scalar(const libcamera::Rectangle &rectangle) { From ee98bdfcb970b4c2c8a662bbe65b68940f4b73bf Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Tue, 24 Dec 2024 01:26:45 +0100 Subject: [PATCH 6/7] replace streaming operator with function to avoid conflicting definition --- src/CameraNode.cpp | 4 ++-- src/pretty_print.cpp | 8 +++++--- src/pretty_print.hpp | 4 ++-- 3 files changed, 9 insertions(+), 7 deletions(-) diff --git a/src/CameraNode.cpp b/src/CameraNode.cpp index 6aac4164..8dc8b8aa 100644 --- a/src/CameraNode.cpp +++ b/src/CameraNode.cpp @@ -331,7 +331,7 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options) : Node("camera", opti const libcamera::Size size(get_parameter("width").as_int(), get_parameter("height").as_int()); if (size.isNull()) { - RCLCPP_INFO_STREAM(get_logger(), scfg); + RCLCPP_INFO_STREAM(get_logger(), list_format_sizes(scfg)); RCLCPP_WARN_STREAM(get_logger(), "no dimensions selected, auto-selecting: \"" << scfg.size << "\""); RCLCPP_WARN_STREAM(get_logger(), "set parameter 'width' or 'height' to silence this warning"); @@ -350,7 +350,7 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options) : Node("camera", opti if (selected_scfg.pixelFormat != scfg.pixelFormat) RCLCPP_INFO_STREAM(get_logger(), stream_formats); if (selected_scfg.size != scfg.size) - RCLCPP_INFO_STREAM(get_logger(), scfg); + RCLCPP_INFO_STREAM(get_logger(), list_format_sizes(scfg)); RCLCPP_WARN_STREAM(get_logger(), "stream configuration adjusted from \"" << selected_scfg.toString() << "\" to \"" << scfg.toString() << "\""); diff --git a/src/pretty_print.cpp b/src/pretty_print.cpp index f38975c0..caece2a9 100644 --- a/src/pretty_print.cpp +++ b/src/pretty_print.cpp @@ -9,6 +9,7 @@ #include #include #include +#include #include #include @@ -43,13 +44,14 @@ operator<<(std::ostream &out, const libcamera::StreamFormats &formats) return out; } -std::ostream & -operator<<(std::ostream &out, const libcamera::StreamConfiguration &configuration) +std::string +list_format_sizes(const libcamera::StreamConfiguration &configuration) { + std::ostringstream out; out << std::endl << ">> " << configuration.pixelFormat << " format sizes:"; for (const libcamera::Size &size : configuration.formats().sizes(configuration.pixelFormat)) out << std::endl << " - " << size.toString(); - return out; + return out.str(); } diff --git a/src/pretty_print.hpp b/src/pretty_print.hpp index 827a634a..238b28b0 100644 --- a/src/pretty_print.hpp +++ b/src/pretty_print.hpp @@ -15,5 +15,5 @@ operator<<(std::ostream &out, const libcamera::CameraManager &camera_manager); std::ostream & operator<<(std::ostream &out, const libcamera::StreamFormats &formats); -std::ostream & -operator<<(std::ostream &out, const libcamera::StreamConfiguration &configuration); +std::string +list_format_sizes(const libcamera::StreamConfiguration &configuration); From 2e974e067a7c59694b6e472db40e1ea25cb9c97f Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Tue, 24 Dec 2024 00:04:42 +0100 Subject: [PATCH 7/7] implement support for new control types --- src/CameraNode.cpp | 25 +++++++------ src/clamp.cpp | 55 ++++++++++++++++++++++++++++ src/cv_to_pv.cpp | 30 +++++++++++++++ src/exceptions.hpp | 6 +++ src/pv_to_cv.cpp | 91 ++++++++++++++++++++++++++++++++-------------- src/types.cpp | 5 +++ src/types.hpp | 6 +++ 7 files changed, 179 insertions(+), 39 deletions(-) diff --git a/src/CameraNode.cpp b/src/CameraNode.cpp index 8dc8b8aa..64e2269c 100644 --- a/src/CameraNode.cpp +++ b/src/CameraNode.cpp @@ -70,6 +70,12 @@ namespace rclcpp class NodeOptions; } +#define CASE_RANGE(T, R) \ + case libcamera::ControlType##T: \ + R.from_value = max(info.min()); \ + R.to_value = min(info.max()); \ + break; + namespace camera { @@ -528,18 +534,13 @@ CameraNode::declareParameters() rcl_interfaces::msg::FloatingPointRange range_float; switch (id->type()) { - case libcamera::ControlTypeInteger32: - range_int.from_value = max(info.min()); - range_int.to_value = min(info.max()); - break; - case libcamera::ControlTypeInteger64: - range_int.from_value = max(info.min()); - range_int.to_value = min(info.max()); - break; - case libcamera::ControlTypeFloat: - range_float.from_value = max(info.min()); - range_float.to_value = min(info.max()); - break; + CASE_RANGE(Integer32, range_int) + CASE_RANGE(Integer64, range_int) + CASE_RANGE(Float, range_float) +#if LIBCAMERA_VER_GE(0, 4, 0) + CASE_RANGE(Unsigned16, range_int) + CASE_RANGE(Unsigned32, range_int) +#endif default: break; } diff --git a/src/clamp.cpp b/src/clamp.cpp index 8a8b034e..c0a9ea15 100644 --- a/src/clamp.cpp +++ b/src/clamp.cpp @@ -1,3 +1,4 @@ +#include "libcamera_version_utils.hpp" #include "types.hpp" #include #include @@ -66,6 +67,12 @@ MIN(Float) MAX(Integer32) MAX(Integer64) MAX(Float) +#if LIBCAMERA_VER_GE(0, 4, 0) +MIN(Unsigned16) +MIN(Unsigned32) +MAX(Unsigned16) +MAX(Unsigned32) +#endif namespace std { @@ -79,6 +86,17 @@ clamp(const CTRectangle &val, const CTRectangle &lo, const CTRectangle &hi) return CTRectangle {x, y, width, height}; } + +#if LIBCAMERA_VER_GE(0, 4, 0) +CTPoint +clamp(const CTPoint &val, const CTPoint &lo, const CTPoint &hi) +{ + const int x = std::clamp(val.x, lo.x, hi.x); + const int y = std::clamp(val.y, lo.y, hi.y); + + return CTPoint {x, y}; +} +#endif } // namespace std @@ -135,6 +153,11 @@ clamp(const libcamera::ControlValue &value, const libcamera::ControlValue &min, CASE_CLAMP(String) CASE_CLAMP(Rectangle) CASE_CLAMP(Size) +#if LIBCAMERA_VER_GE(0, 4, 0) + CASE_CLAMP(Unsigned16) + CASE_CLAMP(Unsigned32) + CASE_CLAMP(Point) +#endif } return {}; @@ -157,6 +180,28 @@ operator>(const libcamera::Rectangle &lhs, const libcamera::Rectangle &rhs) (lhs.y + lhs.height) > (rhs.y + rhs.height); } +#if LIBCAMERA_VER_GE(0, 4, 0) +int +squared_sum(const libcamera::Point &p) +{ + return p.x * p.x + p.y * p.y; +} + +bool +operator<(const libcamera::Point &lhs, const libcamera::Point &rhs) +{ + // check if lhs point is closer to origin than rhs point + return squared_sum(lhs) < squared_sum(rhs); +} + +bool +operator>(const libcamera::Point &lhs, const libcamera::Point &rhs) +{ + // check if lhs point is further away from origin than rhs point + return squared_sum(lhs) > squared_sum(rhs); +} +#endif + template bool less(const libcamera::ControlValue &lhs, const libcamera::ControlValue &rhs) @@ -261,6 +306,11 @@ operator<(const libcamera::ControlValue &lhs, const libcamera::ControlValue &rhs CASE_LESS(String) CASE_LESS(Rectangle) CASE_LESS(Size) +#if LIBCAMERA_VER_GE(0, 4, 0) + CASE_LESS(Unsigned16) + CASE_LESS(Unsigned32) + CASE_LESS(Point) +#endif } throw std::runtime_error("unhandled control type " + std::to_string(lhs.type())); @@ -282,6 +332,11 @@ operator>(const libcamera::ControlValue &lhs, const libcamera::ControlValue &rhs CASE_GREATER(String) CASE_GREATER(Rectangle) CASE_GREATER(Size) +#if LIBCAMERA_VER_GE(0, 4, 0) + CASE_GREATER(Unsigned16) + CASE_GREATER(Unsigned32) + CASE_GREATER(Point) +#endif } throw std::runtime_error("unhandled control type " + std::to_string(lhs.type())); diff --git a/src/cv_to_pv.cpp b/src/cv_to_pv.cpp index d98f3803..9813bfbc 100644 --- a/src/cv_to_pv.cpp +++ b/src/cv_to_pv.cpp @@ -1,4 +1,5 @@ #include "cv_to_pv.hpp" +#include "libcamera_version_utils.hpp" #include "type_extent.hpp" #include "types.hpp" #include @@ -85,6 +86,14 @@ cv_to_pv_scalar(const libcamera::Size &size) return rclcpp::ParameterValue(std::vector {size.width, size.height}); } +#if LIBCAMERA_VER_GE(0, 4, 0) +rclcpp::ParameterValue +cv_to_pv_scalar(const libcamera::Point &point) +{ + return rclcpp::ParameterValue(std::vector {point.x, point.y}); +} +#endif + template rclcpp::ParameterValue cv_to_pv(const std::vector &values) @@ -115,6 +124,11 @@ cv_to_pv(const libcamera::ControlValue &value) CASE_CONVERT(String) CASE_CONVERT(Rectangle) CASE_CONVERT(Size) +#if LIBCAMERA_VER_GE(0, 4, 0) + CASE_CONVERT(Unsigned16) + CASE_CONVERT(Unsigned32) + CASE_CONVERT(Point) +#endif } return {}; @@ -130,6 +144,10 @@ cv_to_pv_type(const libcamera::ControlId *const id) case libcamera::ControlType::ControlTypeBool: return rclcpp::ParameterType::PARAMETER_BOOL; case libcamera::ControlType::ControlTypeByte: +#if LIBCAMERA_VER_GE(0, 4, 0) + case libcamera::ControlType::ControlTypeUnsigned16: + case libcamera::ControlType::ControlTypeUnsigned32: +#endif case libcamera::ControlType::ControlTypeInteger32: case libcamera::ControlType::ControlTypeInteger64: return rclcpp::ParameterType::PARAMETER_INTEGER; @@ -141,6 +159,10 @@ cv_to_pv_type(const libcamera::ControlId *const id) return rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY; case libcamera::ControlType::ControlTypeSize: return rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY; +#if LIBCAMERA_VER_GE(0, 4, 0) + case libcamera::ControlType::ControlTypePoint: + return rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY; +#endif } } else { @@ -150,6 +172,10 @@ cv_to_pv_type(const libcamera::ControlId *const id) case libcamera::ControlType::ControlTypeBool: return rclcpp::ParameterType::PARAMETER_BOOL_ARRAY; case libcamera::ControlType::ControlTypeByte: +#if LIBCAMERA_VER_GE(0, 4, 0) + case libcamera::ControlType::ControlTypeUnsigned16: + case libcamera::ControlType::ControlTypeUnsigned32: +#endif case libcamera::ControlType::ControlTypeInteger32: case libcamera::ControlType::ControlTypeInteger64: return rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY; @@ -161,6 +187,10 @@ cv_to_pv_type(const libcamera::ControlId *const id) return rclcpp::ParameterType::PARAMETER_NOT_SET; case libcamera::ControlType::ControlTypeSize: return rclcpp::ParameterType::PARAMETER_NOT_SET; +#if LIBCAMERA_VER_GE(0, 4, 0) + case libcamera::ControlType::ControlTypePoint: + return rclcpp::ParameterType::PARAMETER_NOT_SET; +#endif } } diff --git a/src/exceptions.hpp b/src/exceptions.hpp index b3e10150..f626a5d2 100644 --- a/src/exceptions.hpp +++ b/src/exceptions.hpp @@ -7,3 +7,9 @@ class invalid_conversion : public std::runtime_error public: explicit invalid_conversion(const std::string &msg) : std::runtime_error(msg) {} }; + +class should_not_reach : public std::runtime_error +{ +public: + explicit should_not_reach() : std::runtime_error("should not reach here") {} +}; diff --git a/src/pv_to_cv.cpp b/src/pv_to_cv.cpp index 471e2104..e0bd16da 100644 --- a/src/pv_to_cv.cpp +++ b/src/pv_to_cv.cpp @@ -1,4 +1,6 @@ #include "pv_to_cv.hpp" +#include "exceptions.hpp" +#include "libcamera_version_utils.hpp" #include "types.hpp" #include #include @@ -9,23 +11,50 @@ #include +#define CASE_CONVERT_INT(T) \ + case libcamera::ControlType##T: \ + return ControlTypeMap::type(parameter.as_int()); + +#define CASE_CONVERT_INT_ARRAY(T) \ + case libcamera::ControlType##T: \ + return libcamera::Span::type>(std::vector::type>(values.begin(), values.end())); + +#define CASE_NONE(T) \ + case libcamera::ControlType##T: \ + return {}; + +#define CASE_INVALID(T) \ + case libcamera::ControlType##T: \ + throw invalid_conversion("cannot convert integer array to ##T"); + + libcamera::ControlValue pv_to_cv_int_array(const std::vector &values, const libcamera::ControlType &type) { - // convert to Span (Integer32, Integer64) or geometric type Rectangle, Size + // convert to integer Span, geometric type Rectangle, Size, Point, or throw exception switch (type) { - case libcamera::ControlTypeInteger32: - return { - libcamera::Span(std::vector(values.begin(), values.end()))}; + CASE_NONE(None) + CASE_INVALID(Bool) + CASE_INVALID(Byte) + CASE_CONVERT_INT_ARRAY(Integer32) case libcamera::ControlTypeInteger64: - return {libcamera::Span(values)}; + return libcamera::Span(values); +#if LIBCAMERA_VER_GE(0, 4, 0) + CASE_CONVERT_INT_ARRAY(Unsigned16) + CASE_CONVERT_INT_ARRAY(Unsigned32) +#endif + CASE_CONVERT_INT_ARRAY(Float) + CASE_INVALID(String) case libcamera::ControlTypeRectangle: - return {libcamera::Rectangle(values[0], values[1], values[2], values[3])}; + return libcamera::Rectangle(values[0], values[1], values[2], values[3]); case libcamera::ControlTypeSize: - return {libcamera::Size(values[0], values[1])}; - default: - return {}; + return libcamera::Size(values[0], values[1]); +#if LIBCAMERA_VER_GE(0, 4, 0) + case libcamera::ControlTypePoint: + return libcamera::Point(values[0], values[1]); +#endif } + throw should_not_reach(); } libcamera::ControlValue @@ -35,33 +64,41 @@ pv_to_cv(const rclcpp::Parameter ¶meter, const libcamera::ControlType &type) case rclcpp::ParameterType::PARAMETER_NOT_SET: return {}; case rclcpp::ParameterType::PARAMETER_BOOL: - return {parameter.as_bool()}; + return parameter.as_bool(); case rclcpp::ParameterType::PARAMETER_INTEGER: - if (type == libcamera::ControlTypeInteger32) - return {CTInteger32(parameter.as_int())}; - else if (type == libcamera::ControlTypeInteger64) - return {CTInteger64(parameter.as_int())}; - else - return {}; + switch (type) { + CASE_NONE(None) + CASE_CONVERT_INT(Bool) + CASE_CONVERT_INT(Byte) + CASE_CONVERT_INT(Integer32) + CASE_CONVERT_INT(Integer64) + CASE_CONVERT_INT(Float) + CASE_NONE(String) + CASE_NONE(Rectangle) + CASE_NONE(Size) +#if LIBCAMERA_VER_GE(0, 4, 0) + CASE_CONVERT_INT(Unsigned16) + CASE_CONVERT_INT(Unsigned32) + CASE_NONE(Point) +#endif + } + throw should_not_reach(); case rclcpp::ParameterType::PARAMETER_DOUBLE: - return {CTFloat(parameter.as_double())}; + return CTFloat(parameter.as_double()); case rclcpp::ParameterType::PARAMETER_STRING: - return {parameter.as_string()}; + return CTString(parameter.as_string()); case rclcpp::ParameterType::PARAMETER_BYTE_ARRAY: - return {libcamera::Span(parameter.as_byte_array())}; + return libcamera::Span(parameter.as_byte_array()); case rclcpp::ParameterType::PARAMETER_BOOL_ARRAY: - return {}; + throw invalid_conversion("cannot convert bool array to control value"); case rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY: return pv_to_cv_int_array(parameter.as_integer_array(), type); case rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY: - { // convert to float vector - return {libcamera::Span( - std::vector(parameter.as_double_array().begin(), parameter.as_double_array().end()))}; - } + return libcamera::Span( + std::vector(parameter.as_double_array().begin(), parameter.as_double_array().end())); case rclcpp::ParameterType::PARAMETER_STRING_ARRAY: - return {libcamera::Span(parameter.as_string_array())}; - default: - return {}; + return libcamera::Span(parameter.as_string_array()); } + throw should_not_reach(); } diff --git a/src/types.cpp b/src/types.cpp index 29c2d440..86d2bb31 100644 --- a/src/types.cpp +++ b/src/types.cpp @@ -19,6 +19,11 @@ std::to_string(const libcamera::ControlType id) CASE_TYPE(String) CASE_TYPE(Rectangle) CASE_TYPE(Size) +#if LIBCAMERA_VER_GE(0, 4, 0) + CASE_TYPE(Unsigned16) + CASE_TYPE(Unsigned32) + CASE_TYPE(Point) +#endif } return {}; diff --git a/src/types.hpp b/src/types.hpp index 38e6d09f..738dc166 100644 --- a/src/types.hpp +++ b/src/types.hpp @@ -1,4 +1,5 @@ #pragma once +#include "libcamera_version_utils.hpp" #include #include #include @@ -34,3 +35,8 @@ MAP(float, Float) MAP(std::string, String) MAP(libcamera::Rectangle, Rectangle) MAP(libcamera::Size, Size) +#if LIBCAMERA_VER_GE(0, 4, 0) +MAP(uint16_t, Unsigned16) +MAP(uint32_t, Unsigned32) +MAP(libcamera::Point, Point) +#endif