summaryrefslogtreecommitdiff
path: root/src/ipa/rkisp1
diff options
context:
space:
mode:
Diffstat (limited to 'src/ipa/rkisp1')
-rw-r--r--src/ipa/rkisp1/algorithms/awb.cpp67
-rw-r--r--src/ipa/rkisp1/algorithms/awb.h7
-rw-r--r--src/ipa/rkisp1/algorithms/ccm.cpp4
-rw-r--r--src/ipa/rkisp1/algorithms/lux.cpp80
-rw-r--r--src/ipa/rkisp1/algorithms/lux.h36
-rw-r--r--src/ipa/rkisp1/algorithms/meson.build1
-rw-r--r--src/ipa/rkisp1/ipa_context.h5
-rw-r--r--src/ipa/rkisp1/meson.build1
-rw-r--r--src/ipa/rkisp1/utils.cpp42
-rw-r--r--src/ipa/rkisp1/utils.h65
10 files changed, 187 insertions, 121 deletions
diff --git a/src/ipa/rkisp1/algorithms/awb.cpp b/src/ipa/rkisp1/algorithms/awb.cpp
index 4bb4f5b8..cffaa06a 100644
--- a/src/ipa/rkisp1/algorithms/awb.cpp
+++ b/src/ipa/rkisp1/algorithms/awb.cpp
@@ -33,6 +33,10 @@ namespace ipa::rkisp1::algorithms {
LOG_DEFINE_CATEGORY(RkISP1Awb)
+constexpr int32_t kMinColourTemperature = 2500;
+constexpr int32_t kMaxColourTemperature = 10000;
+constexpr int32_t kDefaultColourTemperature = 5000;
+
/* Minimum mean value below which AWB can't operate. */
constexpr double kMeanMinThreshold = 2.0;
@@ -42,6 +46,29 @@ Awb::Awb()
}
/**
+ * \copydoc libcamera::ipa::Algorithm::init
+ */
+int Awb::init(IPAContext &context, const YamlObject &tuningData)
+{
+ auto &cmap = context.ctrlMap;
+ cmap[&controls::ColourTemperature] = ControlInfo(kMinColourTemperature,
+ kMaxColourTemperature,
+ kDefaultColourTemperature);
+
+ Interpolator<Vector<double, 2>> gainCurve;
+ int ret = gainCurve.readYaml(tuningData["colourGains"], "ct", "gains");
+ if (ret < 0)
+ LOG(RkISP1Awb, Warning)
+ << "Failed to parse 'colourGains' "
+ << "parameter from tuning file; "
+ << "manual colour temperature will not work properly";
+ else
+ colourGainCurve_ = gainCurve;
+
+ return 0;
+}
+
+/**
* \copydoc libcamera::ipa::Algorithm::configure
*/
int Awb::configure(IPAContext &context,
@@ -50,6 +77,7 @@ int Awb::configure(IPAContext &context,
context.activeState.awb.gains.manual = RGB<double>{ 1.0 };
context.activeState.awb.gains.automatic = RGB<double>{ 1.0 };
context.activeState.awb.autoEnabled = true;
+ context.activeState.awb.temperatureK = kDefaultColourTemperature;
/*
* Define the measurement window for AWB as a centered rectangle
@@ -83,19 +111,37 @@ void Awb::queueRequest(IPAContext &context,
<< (*awbEnable ? "Enabling" : "Disabling") << " AWB";
}
+ frameContext.awb.autoEnabled = awb.autoEnabled;
+
+ if (awb.autoEnabled)
+ return;
+
const auto &colourGains = controls.get(controls::ColourGains);
- if (colourGains && !awb.autoEnabled) {
+ const auto &colourTemperature = controls.get(controls::ColourTemperature);
+ bool update = false;
+ if (colourGains) {
awb.gains.manual.r() = (*colourGains)[0];
awb.gains.manual.b() = (*colourGains)[1];
+ /*
+ * \todo: Colour temperature reported in metadata is now
+ * incorrect, as we can't deduce the temperature from the gains.
+ * This will be fixed with the bayes AWB algorithm.
+ */
+ update = true;
+ } else if (colourTemperature && colourGainCurve_) {
+ const auto &gains = colourGainCurve_->getInterpolated(*colourTemperature);
+ awb.gains.manual.r() = gains[0];
+ awb.gains.manual.b() = gains[1];
+ awb.temperatureK = *colourTemperature;
+ update = true;
+ }
+ if (update)
LOG(RkISP1Awb, Debug)
<< "Set colour gains to " << awb.gains.manual;
- }
-
- frameContext.awb.autoEnabled = awb.autoEnabled;
- if (!awb.autoEnabled)
- frameContext.awb.gains = awb.gains.manual;
+ frameContext.awb.gains = awb.gains.manual;
+ frameContext.awb.temperatureK = awb.temperatureK;
}
/**
@@ -108,8 +154,10 @@ void Awb::prepare(IPAContext &context, const uint32_t frame,
* This is the latest time we can read the active state. This is the
* most up-to-date automatic values we can read.
*/
- if (frameContext.awb.autoEnabled)
+ if (frameContext.awb.autoEnabled) {
frameContext.awb.gains = context.activeState.awb.gains.automatic;
+ frameContext.awb.temperatureK = context.activeState.awb.temperatureK;
+ }
auto gainConfig = params->block<BlockType::AwbGain>();
gainConfig.setEnabled(true);
@@ -188,7 +236,7 @@ void Awb::process(IPAContext &context,
static_cast<float>(frameContext.awb.gains.r()),
static_cast<float>(frameContext.awb.gains.b())
});
- metadata.set(controls::ColourTemperature, activeState.awb.temperatureK);
+ metadata.set(controls::ColourTemperature, frameContext.awb.temperatureK);
if (!stats || !(stats->meas_type & RKISP1_CIF_ISP_STAT_AWB)) {
LOG(RkISP1Awb, Error) << "AWB data is missing in statistics";
@@ -263,9 +311,6 @@ void Awb::process(IPAContext &context,
activeState.awb.temperatureK = estimateCCT(rgbMeans);
- /* Metadata shall contain the up to date measurement */
- metadata.set(controls::ColourTemperature, activeState.awb.temperatureK);
-
/*
* Estimate the red and blue gains to apply in a grey world. The green
* gain is hardcoded to 1.0. Avoid divisions by zero by clamping the
diff --git a/src/ipa/rkisp1/algorithms/awb.h b/src/ipa/rkisp1/algorithms/awb.h
index 6ac3a5c3..e4248048 100644
--- a/src/ipa/rkisp1/algorithms/awb.h
+++ b/src/ipa/rkisp1/algorithms/awb.h
@@ -7,6 +7,11 @@
#pragma once
+#include <optional>
+
+#include "libipa/interpolator.h"
+#include "libipa/vector.h"
+
#include "algorithm.h"
namespace libcamera {
@@ -19,6 +24,7 @@ public:
Awb();
~Awb() = default;
+ int init(IPAContext &context, const YamlObject &tuningData) override;
int configure(IPAContext &context, const IPACameraSensorInfo &configInfo) override;
void queueRequest(IPAContext &context, const uint32_t frame,
IPAFrameContext &frameContext,
@@ -32,6 +38,7 @@ public:
ControlList &metadata) override;
private:
+ std::optional<Interpolator<Vector<double, 2>>> colourGainCurve_;
bool rgbMode_;
};
diff --git a/src/ipa/rkisp1/algorithms/ccm.cpp b/src/ipa/rkisp1/algorithms/ccm.cpp
index 6b7d2e2c..e2b5cf4d 100644
--- a/src/ipa/rkisp1/algorithms/ccm.cpp
+++ b/src/ipa/rkisp1/algorithms/ccm.cpp
@@ -18,7 +18,7 @@
#include "libcamera/internal/yaml_parser.h"
-#include "../utils.h"
+#include "libipa/fixedpoint.h"
#include "libipa/interpolator.h"
/**
@@ -72,7 +72,7 @@ void Ccm::setParameters(struct rkisp1_cif_isp_ctk_config &config,
for (unsigned int i = 0; i < 3; i++) {
for (unsigned int j = 0; j < 3; j++)
config.coeff[i][j] =
- utils::floatingToFixedPoint<4, 7, uint16_t, double>(matrix[i][j]);
+ floatingToFixedPoint<4, 7, uint16_t, double>(matrix[i][j]);
}
for (unsigned int i = 0; i < 3; i++)
diff --git a/src/ipa/rkisp1/algorithms/lux.cpp b/src/ipa/rkisp1/algorithms/lux.cpp
new file mode 100644
index 00000000..b0f74963
--- /dev/null
+++ b/src/ipa/rkisp1/algorithms/lux.cpp
@@ -0,0 +1,80 @@
+/* SPDX-License-Identifier: LGPL-2.1-or-later */
+/*
+ * Copyright (C) 2024, Ideas On Board
+ *
+ * lux.cpp - RkISP1 Lux control
+ */
+
+#include "lux.h"
+
+#include <libcamera/base/log.h>
+
+#include <libcamera/control_ids.h>
+
+#include "libipa/histogram.h"
+#include "libipa/lux.h"
+
+/**
+ * \file lux.h
+ */
+
+namespace libcamera {
+
+namespace ipa::rkisp1::algorithms {
+
+/**
+ * \class Lux
+ * \brief RkISP1 Lux control
+ *
+ * The Lux algorithm is responsible for estimating the lux level of the image.
+ * It doesn't take or generate any controls, but it provides a lux level for
+ * other algorithms (such as AGC) to use.
+ */
+
+/**
+ * \brief Construct an rkisp1 Lux algo module
+ *
+ * The Lux helper is initialized to 65535 as that is the max bin count on the
+ * rkisp1.
+ */
+Lux::Lux()
+ : lux_(65535)
+{
+}
+
+/**
+ * \copydoc libcamera::ipa::Algorithm::init
+ */
+int Lux::init([[maybe_unused]] IPAContext &context, const YamlObject &tuningData)
+{
+ return lux_.parseTuningData(tuningData);
+}
+
+/**
+ * \copydoc libcamera::ipa::Algorithm::process
+ */
+void Lux::process(IPAContext &context,
+ [[maybe_unused]] const uint32_t frame,
+ IPAFrameContext &frameContext,
+ const rkisp1_stat_buffer *stats,
+ ControlList &metadata)
+{
+ utils::Duration exposureTime = context.configuration.sensor.lineDuration
+ * frameContext.sensor.exposure;
+ double gain = frameContext.sensor.gain;
+
+ /* \todo Deduplicate the histogram calculation from AGC */
+ const rkisp1_cif_isp_stat *params = &stats->params;
+ Histogram yHist({ params->hist.hist_bins, context.hw->numHistogramBins },
+ [](uint32_t x) { return x >> 4; });
+
+ double lux = lux_.estimateLux(exposureTime, gain, 1.0, yHist);
+ frameContext.lux.lux = lux;
+ metadata.set(controls::Lux, lux);
+}
+
+REGISTER_IPA_ALGORITHM(Lux, "Lux")
+
+} /* namespace ipa::rkisp1::algorithms */
+
+} /* namespace libcamera */
diff --git a/src/ipa/rkisp1/algorithms/lux.h b/src/ipa/rkisp1/algorithms/lux.h
new file mode 100644
index 00000000..8a90de55
--- /dev/null
+++ b/src/ipa/rkisp1/algorithms/lux.h
@@ -0,0 +1,36 @@
+/* SPDX-License-Identifier: LGPL-2.1-or-later */
+/*
+ * Copyright (C) 2024, Ideas On Board
+ *
+ * lux.h - RkISP1 Lux control
+ */
+
+#pragma once
+
+#include <sys/types.h>
+
+#include "libipa/lux.h"
+
+#include "algorithm.h"
+
+namespace libcamera {
+
+namespace ipa::rkisp1::algorithms {
+
+class Lux : public Algorithm
+{
+public:
+ Lux();
+
+ int init(IPAContext &context, const YamlObject &tuningData) override;
+ void process(IPAContext &context, const uint32_t frame,
+ IPAFrameContext &frameContext,
+ const rkisp1_stat_buffer *stats,
+ ControlList &metadata) override;
+
+private:
+ ipa::Lux lux_;
+};
+
+} /* namespace ipa::rkisp1::algorithms */
+} /* namespace libcamera */
diff --git a/src/ipa/rkisp1/algorithms/meson.build b/src/ipa/rkisp1/algorithms/meson.build
index 1734a667..c66b0b70 100644
--- a/src/ipa/rkisp1/algorithms/meson.build
+++ b/src/ipa/rkisp1/algorithms/meson.build
@@ -12,4 +12,5 @@ rkisp1_ipa_algorithms = files([
'goc.cpp',
'gsl.cpp',
'lsc.cpp',
+ 'lux.cpp',
])
diff --git a/src/ipa/rkisp1/ipa_context.h b/src/ipa/rkisp1/ipa_context.h
index deb8c196..b83c1822 100644
--- a/src/ipa/rkisp1/ipa_context.h
+++ b/src/ipa/rkisp1/ipa_context.h
@@ -135,6 +135,7 @@ struct IPAFrameContext : public FrameContext {
struct {
RGB<double> gains;
bool autoEnabled;
+ unsigned int temperatureK;
} awb;
struct {
@@ -168,6 +169,10 @@ struct IPAFrameContext : public FrameContext {
struct {
Matrix<float, 3, 3> ccm;
} ccm;
+
+ struct {
+ double lux;
+ } lux;
};
struct IPAContext {
diff --git a/src/ipa/rkisp1/meson.build b/src/ipa/rkisp1/meson.build
index 34844f14..26a9fa40 100644
--- a/src/ipa/rkisp1/meson.build
+++ b/src/ipa/rkisp1/meson.build
@@ -9,7 +9,6 @@ rkisp1_ipa_sources = files([
'ipa_context.cpp',
'params.cpp',
'rkisp1.cpp',
- 'utils.cpp',
])
rkisp1_ipa_sources += rkisp1_ipa_algorithms
diff --git a/src/ipa/rkisp1/utils.cpp b/src/ipa/rkisp1/utils.cpp
deleted file mode 100644
index 960ec64e..00000000
--- a/src/ipa/rkisp1/utils.cpp
+++ /dev/null
@@ -1,42 +0,0 @@
-/* SPDX-License-Identifier: LGPL-2.1-or-later */
-/*
- * Copyright (C) 2024, Paul Elder <paul.elder@ideasonboard.com>
- *
- * Miscellaneous utility functions specific to rkisp1
- */
-
-#include "utils.h"
-
-/**
- * \file utils.h
- */
-
-namespace libcamera {
-
-namespace ipa::rkisp1::utils {
-
-/**
- * \fn R floatingToFixedPoint(T number)
- * \brief Convert a floating point number to a fixed-point representation
- * \tparam I Bit width of the integer part of the fixed-point
- * \tparam F Bit width of the fractional part of the fixed-point
- * \tparam R Return type of the fixed-point representation
- * \tparam T Input type of the floating point representation
- * \param number The floating point number to convert to fixed point
- * \return The converted value
- */
-
-/**
- * \fn R fixedToFloatingPoint(T number)
- * \brief Convert a fixed-point number to a floating point representation
- * \tparam I Bit width of the integer part of the fixed-point
- * \tparam F Bit width of the fractional part of the fixed-point
- * \tparam R Return type of the floating point representation
- * \tparam T Input type of the fixed-point representation
- * \param number The fixed point number to convert to floating point
- * \return The converted value
- */
-
-} /* namespace ipa::rkisp1::utils */
-
-} /* namespace libcamera */
diff --git a/src/ipa/rkisp1/utils.h b/src/ipa/rkisp1/utils.h
deleted file mode 100644
index 5f38b50b..00000000
--- a/src/ipa/rkisp1/utils.h
+++ /dev/null
@@ -1,65 +0,0 @@
-/* SPDX-License-Identifier: LGPL-2.1-or-later */
-/*
- * Copyright (C) 2024, Paul Elder <paul.elder@ideasonboard.com>
- *
- * Miscellaneous utility functions specific to rkisp1
- */
-
-#pragma once
-
-#include <cmath>
-#include <type_traits>
-
-namespace libcamera {
-
-namespace ipa::rkisp1::utils {
-
-#ifndef __DOXYGEN__
-template<unsigned int I, unsigned int F, typename R, typename T,
- std::enable_if_t<std::is_integral_v<R> &&
- std::is_floating_point_v<T>> * = nullptr>
-#else
-template<unsigned int I, unsigned int F, typename R, typename T>
-#endif
-constexpr R floatingToFixedPoint(T number)
-{
- static_assert(sizeof(int) >= sizeof(R));
- static_assert(I + F <= sizeof(R) * 8);
-
- /*
- * The intermediate cast to int is needed on arm platforms to properly
- * cast negative values. See
- * https://embeddeduse.com/2013/08/25/casting-a-negative-float-to-an-unsigned-int/
- */
- R mask = (1 << (F + I)) - 1;
- R frac = static_cast<R>(static_cast<int>(std::round(number * (1 << F)))) & mask;
-
- return frac;
-}
-
-#ifndef __DOXYGEN__
-template<unsigned int I, unsigned int F, typename R, typename T,
- std::enable_if_t<std::is_floating_point_v<R> &&
- std::is_integral_v<T>> * = nullptr>
-#else
-template<unsigned int I, unsigned int F, typename R, typename T>
-#endif
-constexpr R fixedToFloatingPoint(T number)
-{
- static_assert(sizeof(int) >= sizeof(T));
- static_assert(I + F <= sizeof(T) * 8);
-
- /*
- * Recreate the upper bits in case of a negative number by shifting the sign
- * bit from the fixed point to the first bit of the unsigned and then right shifting
- * by the same amount which keeps the sign bit in place.
- * This can be optimized by the compiler quite well.
- */
- int remaining_bits = sizeof(int) * 8 - (I + F);
- int t = static_cast<int>(static_cast<unsigned>(number) << remaining_bits) >> remaining_bits;
- return static_cast<R>(t) / static_cast<R>(1 << F);
-}
-
-} /* namespace ipa::rkisp1::utils */
-
-} /* namespace libcamera */