summaryrefslogtreecommitdiff
path: root/src/ipa/ipu3
diff options
context:
space:
mode:
Diffstat (limited to 'src/ipa/ipu3')
-rw-r--r--src/ipa/ipu3/ipu3.cpp349
-rw-r--r--src/ipa/ipu3/ipu3_agc.cpp205
-rw-r--r--src/ipa/ipu3/ipu3_agc.h71
-rw-r--r--src/ipa/ipu3/ipu3_awb.cpp382
-rw-r--r--src/ipa/ipu3/ipu3_awb.h91
-rw-r--r--src/ipa/ipu3/meson.build27
6 files changed, 1125 insertions, 0 deletions
diff --git a/src/ipa/ipu3/ipu3.cpp b/src/ipa/ipu3/ipu3.cpp
new file mode 100644
index 00000000..71698d36
--- /dev/null
+++ b/src/ipa/ipu3/ipu3.cpp
@@ -0,0 +1,349 @@
+/* SPDX-License-Identifier: LGPL-2.1-or-later */
+/*
+ * Copyright (C) 2020, Google Inc.
+ *
+ * ipu3.cpp - IPU3 Image Processing Algorithms
+ */
+
+#include <stdint.h>
+#include <sys/mman.h>
+
+#include <linux/intel-ipu3.h>
+#include <linux/v4l2-controls.h>
+
+#include <libcamera/base/log.h>
+
+#include <libcamera/control_ids.h>
+#include <libcamera/framebuffer.h>
+#include <libcamera/ipa/ipa_interface.h>
+#include <libcamera/ipa/ipa_module_info.h>
+#include <libcamera/ipa/ipu3_ipa_interface.h>
+#include <libcamera/request.h>
+
+#include "libcamera/internal/framebuffer.h"
+
+#include "ipu3_agc.h"
+#include "ipu3_awb.h"
+#include "libipa/camera_sensor_helper.h"
+
+static constexpr uint32_t kMaxCellWidthPerSet = 160;
+static constexpr uint32_t kMaxCellHeightPerSet = 56;
+
+namespace libcamera {
+
+LOG_DEFINE_CATEGORY(IPAIPU3)
+
+namespace ipa::ipu3 {
+
+class IPAIPU3 : public IPAIPU3Interface
+{
+public:
+ int init(const IPASettings &settings) override;
+ int start() override;
+ void stop() override {}
+
+ int configure(const IPAConfigInfo &configInfo) override;
+
+ void mapBuffers(const std::vector<IPABuffer> &buffers) override;
+ void unmapBuffers(const std::vector<unsigned int> &ids) override;
+ void processEvent(const IPU3Event &event) override;
+
+private:
+ void processControls(unsigned int frame, const ControlList &controls);
+ void fillParams(unsigned int frame, ipu3_uapi_params *params);
+ void parseStatistics(unsigned int frame,
+ int64_t frameTimestamp,
+ const ipu3_uapi_stats_3a *stats);
+
+ void setControls(unsigned int frame);
+ void calculateBdsGrid(const Size &bdsOutputSize);
+
+ std::map<unsigned int, MappedFrameBuffer> buffers_;
+
+ ControlInfoMap ctrls_;
+
+ IPACameraSensorInfo sensorInfo_;
+
+ /* Camera sensor controls. */
+ uint32_t defVBlank_;
+ uint32_t exposure_;
+ uint32_t minExposure_;
+ uint32_t maxExposure_;
+ uint32_t gain_;
+ uint32_t minGain_;
+ uint32_t maxGain_;
+
+ /* Interface to the AWB algorithm */
+ std::unique_ptr<IPU3Awb> awbAlgo_;
+ /* Interface to the AEC/AGC algorithm */
+ std::unique_ptr<IPU3Agc> agcAlgo_;
+ /* Interface to the Camera Helper */
+ std::unique_ptr<CameraSensorHelper> camHelper_;
+
+ /* Local parameter storage */
+ struct ipu3_uapi_params params_;
+
+ struct ipu3_uapi_grid_config bdsGrid_;
+};
+
+int IPAIPU3::init(const IPASettings &settings)
+{
+ camHelper_ = CameraSensorHelperFactory::create(settings.sensorModel);
+ if (camHelper_ == nullptr) {
+ LOG(IPAIPU3, Error) << "Failed to create camera sensor helper for " << settings.sensorModel;
+ return -ENODEV;
+ }
+
+ return 0;
+}
+
+int IPAIPU3::start()
+{
+ setControls(0);
+
+ return 0;
+}
+
+/**
+ * This method calculates a grid for the AWB algorithm in the IPU3 firmware.
+ * Its input is the BDS output size calculated in the ImgU.
+ * It is limited for now to the simplest method: find the lesser error
+ * with the width/height and respective log2 width/height of the cells.
+ *
+ * \todo The frame is divided into cells which can be 8x8 => 128x128.
+ * As a smaller cell improves the algorithm precision, adapting the
+ * x_start and y_start parameters of the grid would provoke a loss of
+ * some pixels but would also result in more accurate algorithms.
+ */
+void IPAIPU3::calculateBdsGrid(const Size &bdsOutputSize)
+{
+ uint32_t minError = std::numeric_limits<uint32_t>::max();
+ Size best;
+ Size bestLog2;
+ bdsGrid_ = {};
+
+ for (uint32_t widthShift = 3; widthShift <= 7; ++widthShift) {
+ uint32_t width = std::min(kMaxCellWidthPerSet,
+ bdsOutputSize.width >> widthShift);
+ width = width << widthShift;
+ for (uint32_t heightShift = 3; heightShift <= 7; ++heightShift) {
+ int32_t height = std::min(kMaxCellHeightPerSet,
+ bdsOutputSize.height >> heightShift);
+ height = height << heightShift;
+ uint32_t error = std::abs(static_cast<int>(width - bdsOutputSize.width))
+ + std::abs(static_cast<int>(height - bdsOutputSize.height));
+
+ if (error > minError)
+ continue;
+
+ minError = error;
+ best.width = width;
+ best.height = height;
+ bestLog2.width = widthShift;
+ bestLog2.height = heightShift;
+ }
+ }
+
+ bdsGrid_.width = best.width >> bestLog2.width;
+ bdsGrid_.block_width_log2 = bestLog2.width;
+ bdsGrid_.height = best.height >> bestLog2.height;
+ bdsGrid_.block_height_log2 = bestLog2.height;
+
+ LOG(IPAIPU3, Debug) << "Best grid found is: ("
+ << (int)bdsGrid_.width << " << " << (int)bdsGrid_.block_width_log2 << ") x ("
+ << (int)bdsGrid_.height << " << " << (int)bdsGrid_.block_height_log2 << ")";
+}
+
+int IPAIPU3::configure(const IPAConfigInfo &configInfo)
+{
+ if (configInfo.entityControls.empty()) {
+ LOG(IPAIPU3, Error) << "No controls provided";
+ return -ENODATA;
+ }
+
+ sensorInfo_ = configInfo.sensorInfo;
+
+ ctrls_ = configInfo.entityControls.at(0);
+
+ const auto itExp = ctrls_.find(V4L2_CID_EXPOSURE);
+ if (itExp == ctrls_.end()) {
+ LOG(IPAIPU3, Error) << "Can't find exposure control";
+ return -EINVAL;
+ }
+
+ const auto itGain = ctrls_.find(V4L2_CID_ANALOGUE_GAIN);
+ if (itGain == ctrls_.end()) {
+ LOG(IPAIPU3, Error) << "Can't find gain control";
+ return -EINVAL;
+ }
+
+ const auto itVBlank = ctrls_.find(V4L2_CID_VBLANK);
+ if (itVBlank == ctrls_.end()) {
+ LOG(IPAIPU3, Error) << "Can't find VBLANK control";
+ return -EINVAL;
+ }
+
+ minExposure_ = std::max(itExp->second.min().get<int32_t>(), 1);
+ maxExposure_ = itExp->second.max().get<int32_t>();
+ exposure_ = minExposure_;
+
+ minGain_ = std::max(itGain->second.min().get<int32_t>(), 1);
+ maxGain_ = itGain->second.max().get<int32_t>();
+ gain_ = minGain_;
+
+ defVBlank_ = itVBlank->second.def().get<int32_t>();
+
+ params_ = {};
+
+ calculateBdsGrid(configInfo.bdsOutputSize);
+
+ awbAlgo_ = std::make_unique<IPU3Awb>();
+ awbAlgo_->initialise(params_, configInfo.bdsOutputSize, bdsGrid_);
+
+ agcAlgo_ = std::make_unique<IPU3Agc>();
+ agcAlgo_->initialise(bdsGrid_, sensorInfo_);
+
+ return 0;
+}
+
+void IPAIPU3::mapBuffers(const std::vector<IPABuffer> &buffers)
+{
+ for (const IPABuffer &buffer : buffers) {
+ const FrameBuffer fb(buffer.planes);
+ buffers_.emplace(buffer.id,
+ MappedFrameBuffer(&fb, PROT_READ | PROT_WRITE));
+ }
+}
+
+void IPAIPU3::unmapBuffers(const std::vector<unsigned int> &ids)
+{
+ for (unsigned int id : ids) {
+ auto it = buffers_.find(id);
+ if (it == buffers_.end())
+ continue;
+
+ buffers_.erase(it);
+ }
+}
+
+void IPAIPU3::processEvent(const IPU3Event &event)
+{
+ switch (event.op) {
+ case EventProcessControls: {
+ processControls(event.frame, event.controls);
+ break;
+ }
+ case EventStatReady: {
+ auto it = buffers_.find(event.bufferId);
+ if (it == buffers_.end()) {
+ LOG(IPAIPU3, Error) << "Could not find stats buffer!";
+ return;
+ }
+
+ Span<uint8_t> mem = it->second.maps()[0];
+ const ipu3_uapi_stats_3a *stats =
+ reinterpret_cast<ipu3_uapi_stats_3a *>(mem.data());
+
+ parseStatistics(event.frame, event.frameTimestamp, stats);
+ break;
+ }
+ case EventFillParams: {
+ auto it = buffers_.find(event.bufferId);
+ if (it == buffers_.end()) {
+ LOG(IPAIPU3, Error) << "Could not find param buffer!";
+ return;
+ }
+
+ Span<uint8_t> mem = it->second.maps()[0];
+ ipu3_uapi_params *params =
+ reinterpret_cast<ipu3_uapi_params *>(mem.data());
+
+ fillParams(event.frame, params);
+ break;
+ }
+ default:
+ LOG(IPAIPU3, Error) << "Unknown event " << event.op;
+ break;
+ }
+}
+
+void IPAIPU3::processControls([[maybe_unused]] unsigned int frame,
+ [[maybe_unused]] const ControlList &controls)
+{
+ /* \todo Start processing for 'frame' based on 'controls'. */
+}
+
+void IPAIPU3::fillParams(unsigned int frame, ipu3_uapi_params *params)
+{
+ if (agcAlgo_->updateControls())
+ awbAlgo_->updateWbParameters(params_, agcAlgo_->gamma());
+
+ *params = params_;
+
+ IPU3Action op;
+ op.op = ActionParamFilled;
+
+ queueFrameAction.emit(frame, op);
+}
+
+void IPAIPU3::parseStatistics(unsigned int frame,
+ [[maybe_unused]] int64_t frameTimestamp,
+ [[maybe_unused]] const ipu3_uapi_stats_3a *stats)
+{
+ ControlList ctrls(controls::controls);
+
+ double gain = camHelper_->gain(gain_);
+ agcAlgo_->process(stats, exposure_, gain);
+ gain_ = camHelper_->gainCode(gain);
+
+ awbAlgo_->calculateWBGains(stats);
+
+ if (agcAlgo_->updateControls())
+ setControls(frame);
+
+ /* \todo Use VBlank value calculated from each frame exposure. */
+ int64_t frameDuration = sensorInfo_.lineLength * (defVBlank_ + sensorInfo_.outputSize.height) /
+ (sensorInfo_.pixelRate / 1e6);
+ ctrls.set(controls::FrameDuration, frameDuration);
+
+ IPU3Action op;
+ op.op = ActionMetadataReady;
+ op.controls = ctrls;
+
+ queueFrameAction.emit(frame, op);
+}
+
+void IPAIPU3::setControls(unsigned int frame)
+{
+ IPU3Action op;
+ op.op = ActionSetSensorControls;
+
+ ControlList ctrls(ctrls_);
+ ctrls.set(V4L2_CID_EXPOSURE, static_cast<int32_t>(exposure_));
+ ctrls.set(V4L2_CID_ANALOGUE_GAIN, static_cast<int32_t>(gain_));
+ op.controls = ctrls;
+
+ queueFrameAction.emit(frame, op);
+}
+
+} /* namespace ipa::ipu3 */
+
+/*
+ * External IPA module interface
+ */
+
+extern "C" {
+const struct IPAModuleInfo ipaModuleInfo = {
+ IPA_MODULE_API_VERSION,
+ 1,
+ "PipelineHandlerIPU3",
+ "ipu3",
+};
+
+IPAInterface *ipaCreate()
+{
+ return new ipa::ipu3::IPAIPU3();
+}
+}
+
+} /* namespace libcamera */
diff --git a/src/ipa/ipu3/ipu3_agc.cpp b/src/ipa/ipu3/ipu3_agc.cpp
new file mode 100644
index 00000000..6253ab94
--- /dev/null
+++ b/src/ipa/ipu3/ipu3_agc.cpp
@@ -0,0 +1,205 @@
+/* SPDX-License-Identifier: LGPL-2.1-or-later */
+/*
+ * Copyright (C) 2021, Ideas On Board
+ *
+ * ipu3_agc.cpp - AGC/AEC control algorithm
+ */
+
+#include "ipu3_agc.h"
+
+#include <algorithm>
+#include <cmath>
+#include <numeric>
+
+#include <libcamera/base/log.h>
+
+#include <libcamera/ipa/core_ipa_interface.h>
+
+#include "libipa/histogram.h"
+
+namespace libcamera {
+
+using namespace std::literals::chrono_literals;
+
+namespace ipa::ipu3 {
+
+LOG_DEFINE_CATEGORY(IPU3Agc)
+
+/* Number of frames to wait before calculating stats on minimum exposure */
+static constexpr uint32_t kInitialFrameMinAECount = 4;
+/* Number of frames to wait between new gain/exposure estimations */
+static constexpr uint32_t kFrameSkipCount = 6;
+
+/* Maximum ISO value for analogue gain */
+static constexpr uint32_t kMinISO = 100;
+static constexpr uint32_t kMaxISO = 1500;
+
+/* Maximum analogue gain value
+ * \todo grab it from a camera helper */
+static constexpr uint32_t kMinGain = kMinISO / 100;
+static constexpr uint32_t kMaxGain = kMaxISO / 100;
+
+/* \todo use calculated value based on sensor */
+static constexpr uint32_t kMinExposure = 1;
+static constexpr uint32_t kMaxExposure = 1976;
+
+/* Histogram constants */
+static constexpr uint32_t knumHistogramBins = 256;
+static constexpr double kEvGainTarget = 0.5;
+
+/* A cell is 8 bytes and contains averages for RGB values and saturation ratio */
+static constexpr uint8_t kCellSize = 8;
+
+IPU3Agc::IPU3Agc()
+ : frameCount_(0), lastFrame_(0), converged_(false),
+ updateControls_(false), iqMean_(0.0), gamma_(1.0),
+ lineDuration_(0s), maxExposureTime_(0s),
+ prevExposure_(0s), prevExposureNoDg_(0s),
+ currentExposure_(0s), currentExposureNoDg_(0s)
+{
+}
+
+void IPU3Agc::initialise(struct ipu3_uapi_grid_config &bdsGrid, const IPACameraSensorInfo &sensorInfo)
+{
+ aeGrid_ = bdsGrid;
+
+ lineDuration_ = sensorInfo.lineLength * 1.0s / sensorInfo.pixelRate;
+ maxExposureTime_ = kMaxExposure * lineDuration_;
+}
+
+void IPU3Agc::processBrightness(const ipu3_uapi_stats_3a *stats)
+{
+ const struct ipu3_uapi_grid_config statsAeGrid = stats->stats_4a_config.awb_config.grid;
+ Rectangle aeRegion = { statsAeGrid.x_start,
+ statsAeGrid.y_start,
+ static_cast<unsigned int>(statsAeGrid.x_end - statsAeGrid.x_start) + 1,
+ static_cast<unsigned int>(statsAeGrid.y_end - statsAeGrid.y_start) + 1 };
+ Point topleft = aeRegion.topLeft();
+ int topleftX = topleft.x >> aeGrid_.block_width_log2;
+ int topleftY = topleft.y >> aeGrid_.block_height_log2;
+
+ /* Align to the grid cell width and height */
+ uint32_t startX = topleftX << aeGrid_.block_width_log2;
+ uint32_t startY = topleftY * aeGrid_.width << aeGrid_.block_width_log2;
+ uint32_t endX = (startX + (aeRegion.size().width >> aeGrid_.block_width_log2)) << aeGrid_.block_width_log2;
+ uint32_t i, j;
+ uint32_t count = 0;
+
+ uint32_t hist[knumHistogramBins] = { 0 };
+ for (j = topleftY;
+ j < topleftY + (aeRegion.size().height >> aeGrid_.block_height_log2);
+ j++) {
+ for (i = startX + startY; i < endX + startY; i += kCellSize) {
+ /*
+ * The grid width (and maybe height) is not reliable.
+ * We observed a bit shift which makes the value 160 to be 32 in the stats grid.
+ * Use the one passed at init time.
+ */
+ if (stats->awb_raw_buffer.meta_data[i + 4 + j * aeGrid_.width] == 0) {
+ uint8_t Gr = stats->awb_raw_buffer.meta_data[i + 0 + j * aeGrid_.width];
+ uint8_t Gb = stats->awb_raw_buffer.meta_data[i + 3 + j * aeGrid_.width];
+ hist[(Gr + Gb) / 2]++;
+ count++;
+ }
+ }
+ }
+
+ /* Limit the gamma effect for now */
+ gamma_ = 1.1;
+
+ /* Estimate the quantile mean of the top 2% of the histogram */
+ iqMean_ = Histogram(Span<uint32_t>(hist)).interQuantileMean(0.98, 1.0);
+}
+
+void IPU3Agc::filterExposure()
+{
+ double speed = 0.2;
+ if (prevExposure_ == 0s) {
+ /* DG stands for digital gain.*/
+ prevExposure_ = currentExposure_;
+ prevExposureNoDg_ = currentExposureNoDg_;
+ } else {
+ /*
+ * If we are close to the desired result, go faster to avoid making
+ * multiple micro-adjustments.
+ * \ todo: Make this customisable?
+ */
+ if (prevExposure_ < 1.2 * currentExposure_ &&
+ prevExposure_ > 0.8 * currentExposure_)
+ speed = sqrt(speed);
+
+ prevExposure_ = speed * currentExposure_ +
+ prevExposure_ * (1.0 - speed);
+ prevExposureNoDg_ = speed * currentExposureNoDg_ +
+ prevExposureNoDg_ * (1.0 - speed);
+ }
+ /*
+ * We can't let the no_dg exposure deviate too far below the
+ * total exposure, as there might not be enough digital gain available
+ * in the ISP to hide it (which will cause nasty oscillation).
+ */
+ double fastReduceThreshold = 0.4;
+ if (prevExposureNoDg_ <
+ prevExposure_ * fastReduceThreshold)
+ prevExposureNoDg_ = prevExposure_ * fastReduceThreshold;
+ LOG(IPU3Agc, Debug) << "After filtering, total_exposure " << prevExposure_;
+}
+
+void IPU3Agc::lockExposureGain(uint32_t &exposure, double &gain)
+{
+ updateControls_ = false;
+
+ /* Algorithm initialization should wait for first valid frames */
+ /* \todo - have a number of frames given by DelayedControls ?
+ * - implement a function for IIR */
+ if ((frameCount_ < kInitialFrameMinAECount) || (frameCount_ - lastFrame_ < kFrameSkipCount))
+ return;
+
+ /* Are we correctly exposed ? */
+ if (std::abs(iqMean_ - kEvGainTarget * knumHistogramBins) <= 1) {
+ LOG(IPU3Agc, Debug) << "!!! Good exposure with iqMean = " << iqMean_;
+ converged_ = true;
+ } else {
+ double newGain = kEvGainTarget * knumHistogramBins / iqMean_;
+
+ /* extracted from Rpi::Agc::computeTargetExposure */
+ libcamera::utils::Duration currentShutter = exposure * lineDuration_;
+ currentExposureNoDg_ = currentShutter * gain;
+ LOG(IPU3Agc, Debug) << "Actual total exposure " << currentExposureNoDg_
+ << " Shutter speed " << currentShutter
+ << " Gain " << gain;
+ currentExposure_ = currentExposureNoDg_ * newGain;
+ libcamera::utils::Duration maxTotalExposure = maxExposureTime_ * kMaxGain;
+ currentExposure_ = std::min(currentExposure_, maxTotalExposure);
+ LOG(IPU3Agc, Debug) << "Target total exposure " << currentExposure_;
+
+ /* \todo: estimate if we need to desaturate */
+ filterExposure();
+
+ libcamera::utils::Duration newExposure = 0.0s;
+ if (currentShutter < maxExposureTime_) {
+ exposure = std::clamp(static_cast<uint32_t>(exposure * currentExposure_ / currentExposureNoDg_), kMinExposure, kMaxExposure);
+ newExposure = currentExposure_ / exposure;
+ gain = std::clamp(static_cast<uint32_t>(gain * currentExposure_ / newExposure), kMinGain, kMaxGain);
+ updateControls_ = true;
+ } else if (currentShutter >= maxExposureTime_) {
+ gain = std::clamp(static_cast<uint32_t>(gain * currentExposure_ / currentExposureNoDg_), kMinGain, kMaxGain);
+ newExposure = currentExposure_ / gain;
+ exposure = std::clamp(static_cast<uint32_t>(exposure * currentExposure_ / newExposure), kMinExposure, kMaxExposure);
+ updateControls_ = true;
+ }
+ LOG(IPU3Agc, Debug) << "Adjust exposure " << exposure * lineDuration_ << " and gain " << gain;
+ }
+ lastFrame_ = frameCount_;
+}
+
+void IPU3Agc::process(const ipu3_uapi_stats_3a *stats, uint32_t &exposure, double &gain)
+{
+ processBrightness(stats);
+ lockExposureGain(exposure, gain);
+ frameCount_++;
+}
+
+} /* namespace ipa::ipu3 */
+
+} /* namespace libcamera */
diff --git a/src/ipa/ipu3/ipu3_agc.h b/src/ipa/ipu3/ipu3_agc.h
new file mode 100644
index 00000000..3deca3ae
--- /dev/null
+++ b/src/ipa/ipu3/ipu3_agc.h
@@ -0,0 +1,71 @@
+/* SPDX-License-Identifier: LGPL-2.1-or-later */
+/*
+ * Copyright (C) 2021, Ideas On Board
+ *
+ * ipu3_agc.h - IPU3 AGC/AEC control algorithm
+ */
+#ifndef __LIBCAMERA_IPU3_AGC_H__
+#define __LIBCAMERA_IPU3_AGC_H__
+
+#include <array>
+#include <unordered_map>
+
+#include <linux/intel-ipu3.h>
+
+#include <libcamera/base/utils.h>
+
+#include <libcamera/geometry.h>
+
+#include "libipa/algorithm.h"
+
+namespace libcamera {
+
+struct IPACameraSensorInfo;
+
+namespace ipa::ipu3 {
+
+using utils::Duration;
+
+class IPU3Agc : public Algorithm
+{
+public:
+ IPU3Agc();
+ ~IPU3Agc() = default;
+
+ void initialise(struct ipu3_uapi_grid_config &bdsGrid, const IPACameraSensorInfo &sensorInfo);
+ void process(const ipu3_uapi_stats_3a *stats, uint32_t &exposure, double &gain);
+ bool converged() { return converged_; }
+ bool updateControls() { return updateControls_; }
+ /* \todo Use a metadata exchange between IPAs */
+ double gamma() { return gamma_; }
+
+private:
+ void processBrightness(const ipu3_uapi_stats_3a *stats);
+ void filterExposure();
+ void lockExposureGain(uint32_t &exposure, double &gain);
+
+ struct ipu3_uapi_grid_config aeGrid_;
+
+ uint64_t frameCount_;
+ uint64_t lastFrame_;
+
+ bool converged_;
+ bool updateControls_;
+
+ double iqMean_;
+ double gamma_;
+
+ Duration lineDuration_;
+ Duration maxExposureTime_;
+
+ Duration prevExposure_;
+ Duration prevExposureNoDg_;
+ Duration currentExposure_;
+ Duration currentExposureNoDg_;
+};
+
+} /* namespace ipa::ipu3 */
+
+} /* namespace libcamera */
+
+#endif /* __LIBCAMERA_IPU3_AGC_H__ */
diff --git a/src/ipa/ipu3/ipu3_awb.cpp b/src/ipa/ipu3/ipu3_awb.cpp
new file mode 100644
index 00000000..9b409c8f
--- /dev/null
+++ b/src/ipa/ipu3/ipu3_awb.cpp
@@ -0,0 +1,382 @@
+/* SPDX-License-Identifier: LGPL-2.1-or-later */
+/*
+ * Copyright (C) 2021, Ideas On Board
+ *
+ * ipu3_awb.cpp - AWB control algorithm
+ */
+#include "ipu3_awb.h"
+
+#include <cmath>
+#include <numeric>
+#include <unordered_map>
+
+#include <libcamera/base/log.h>
+
+namespace libcamera {
+
+namespace ipa::ipu3 {
+
+LOG_DEFINE_CATEGORY(IPU3Awb)
+
+static constexpr uint32_t kMinZonesCounted = 16;
+static constexpr uint32_t kMinGreenLevelInZone = 32;
+
+/**
+ * \struct IspStatsRegion
+ * \brief RGB statistics for a given region
+ *
+ * The IspStatsRegion structure is intended to abstract the ISP specific
+ * statistics and use an agnostic algorithm to compute AWB.
+ *
+ * \var IspStatsRegion::counted
+ * \brief Number of pixels used to calculate the sums
+ *
+ * \var IspStatsRegion::uncounted
+ * \brief Remaining number of pixels in the region
+ *
+ * \var IspStatsRegion::rSum
+ * \brief Sum of the red values in the region
+ *
+ * \var IspStatsRegion::gSum
+ * \brief Sum of the green values in the region
+ *
+ * \var IspStatsRegion::bSum
+ * \brief Sum of the blue values in the region
+ */
+
+/**
+ * \struct AwbStatus
+ * \brief AWB parameters calculated
+ *
+ * The AwbStatus structure is intended to store the AWB
+ * parameters calculated by the algorithm
+ *
+ * \var AwbStatus::temperatureK
+ * \brief Color temperature calculated
+ *
+ * \var AwbStatus::redGain
+ * \brief Gain calculated for the red channel
+ *
+ * \var AwbStatus::greenGain
+ * \brief Gain calculated for the green channel
+ *
+ * \var AwbStatus::blueGain
+ * \brief Gain calculated for the blue channel
+ */
+
+/**
+ * \struct Ipu3AwbCell
+ * \brief Memory layout for each cell in AWB metadata
+ *
+ * The Ipu3AwbCell structure is used to get individual values
+ * such as red average or saturation ratio in a particular cell.
+ *
+ * \var Ipu3AwbCell::greenRedAvg
+ * \brief Green average for red lines in the cell
+ *
+ * \var Ipu3AwbCell::redAvg
+ * \brief Red average in the cell
+ *
+ * \var Ipu3AwbCell::blueAvg
+ * \brief blue average in the cell
+ *
+ * \var Ipu3AwbCell::greenBlueAvg
+ * \brief Green average for blue lines
+ *
+ * \var Ipu3AwbCell::satRatio
+ * \brief Saturation ratio in the cell
+ *
+ * \var Ipu3AwbCell::padding
+ * \brief array of unused bytes for padding
+ */
+
+/* Default settings for Bayer noise reduction replicated from the Kernel */
+static const struct ipu3_uapi_bnr_static_config imguCssBnrDefaults = {
+ .wb_gains = { 16, 16, 16, 16 },
+ .wb_gains_thr = { 255, 255, 255, 255 },
+ .thr_coeffs = { 1700, 0, 31, 31, 0, 16 },
+ .thr_ctrl_shd = { 26, 26, 26, 26 },
+ .opt_center = { -648, 0, -366, 0 },
+ .lut = {
+ { 17, 23, 28, 32, 36, 39, 42, 45,
+ 48, 51, 53, 55, 58, 60, 62, 64,
+ 66, 68, 70, 72, 73, 75, 77, 78,
+ 80, 82, 83, 85, 86, 88, 89, 90 } },
+ .bp_ctrl = { 20, 0, 1, 40, 0, 6, 0, 6, 0 },
+ .dn_detect_ctrl = { 9, 3, 4, 0, 8, 0, 1, 1, 1, 1, 0 },
+ .column_size = 1296,
+ .opt_center_sqr = { 419904, 133956 },
+};
+
+/* Default settings for Auto White Balance replicated from the Kernel*/
+static const struct ipu3_uapi_awb_config_s imguCssAwbDefaults = {
+ .rgbs_thr_gr = 8191,
+ .rgbs_thr_r = 8191,
+ .rgbs_thr_gb = 8191,
+ .rgbs_thr_b = 8191 | IPU3_UAPI_AWB_RGBS_THR_B_EN | IPU3_UAPI_AWB_RGBS_THR_B_INCL_SAT,
+ .grid = {
+ .width = 160,
+ .height = 36,
+ .block_width_log2 = 3,
+ .block_height_log2 = 4,
+ .height_per_slice = 1, /* Overridden by kernel. */
+ .x_start = 0,
+ .y_start = 0,
+ .x_end = 0,
+ .y_end = 0,
+ },
+};
+
+/* Default color correction matrix defined as an identity matrix */
+static const struct ipu3_uapi_ccm_mat_config imguCssCcmDefault = {
+ 8191, 0, 0, 0,
+ 0, 8191, 0, 0,
+ 0, 0, 8191, 0
+};
+
+/* Default settings for Gamma correction */
+const struct ipu3_uapi_gamma_corr_lut imguCssGammaLut = { {
+ 63, 79, 95, 111, 127, 143, 159, 175, 191, 207, 223, 239, 255, 271, 287,
+ 303, 319, 335, 351, 367, 383, 399, 415, 431, 447, 463, 479, 495, 511,
+ 527, 543, 559, 575, 591, 607, 623, 639, 655, 671, 687, 703, 719, 735,
+ 751, 767, 783, 799, 815, 831, 847, 863, 879, 895, 911, 927, 943, 959,
+ 975, 991, 1007, 1023, 1039, 1055, 1071, 1087, 1103, 1119, 1135, 1151,
+ 1167, 1183, 1199, 1215, 1231, 1247, 1263, 1279, 1295, 1311, 1327, 1343,
+ 1359, 1375, 1391, 1407, 1423, 1439, 1455, 1471, 1487, 1503, 1519, 1535,
+ 1551, 1567, 1583, 1599, 1615, 1631, 1647, 1663, 1679, 1695, 1711, 1727,
+ 1743, 1759, 1775, 1791, 1807, 1823, 1839, 1855, 1871, 1887, 1903, 1919,
+ 1935, 1951, 1967, 1983, 1999, 2015, 2031, 2047, 2063, 2079, 2095, 2111,
+ 2143, 2175, 2207, 2239, 2271, 2303, 2335, 2367, 2399, 2431, 2463, 2495,
+ 2527, 2559, 2591, 2623, 2655, 2687, 2719, 2751, 2783, 2815, 2847, 2879,
+ 2911, 2943, 2975, 3007, 3039, 3071, 3103, 3135, 3167, 3199, 3231, 3263,
+ 3295, 3327, 3359, 3391, 3423, 3455, 3487, 3519, 3551, 3583, 3615, 3647,
+ 3679, 3711, 3743, 3775, 3807, 3839, 3871, 3903, 3935, 3967, 3999, 4031,
+ 4063, 4095, 4127, 4159, 4223, 4287, 4351, 4415, 4479, 4543, 4607, 4671,
+ 4735, 4799, 4863, 4927, 4991, 5055, 5119, 5183, 5247, 5311, 5375, 5439,
+ 5503, 5567, 5631, 5695, 5759, 5823, 5887, 5951, 6015, 6079, 6143, 6207,
+ 6271, 6335, 6399, 6463, 6527, 6591, 6655, 6719, 6783, 6847, 6911, 6975,
+ 7039, 7103, 7167, 7231, 7295, 7359, 7423, 7487, 7551, 7615, 7679, 7743,
+ 7807, 7871, 7935, 7999, 8063, 8127, 8191
+} };
+
+IPU3Awb::IPU3Awb()
+ : Algorithm()
+{
+ asyncResults_.blueGain = 1.0;
+ asyncResults_.greenGain = 1.0;
+ asyncResults_.redGain = 1.0;
+ asyncResults_.temperatureK = 4500;
+}
+
+IPU3Awb::~IPU3Awb()
+{
+}
+
+void IPU3Awb::initialise(ipu3_uapi_params &params, const Size &bdsOutputSize, struct ipu3_uapi_grid_config &bdsGrid)
+{
+ params.use.acc_awb = 1;
+ params.acc_param.awb.config = imguCssAwbDefaults;
+
+ awbGrid_ = bdsGrid;
+ params.acc_param.awb.config.grid = awbGrid_;
+
+ params.use.acc_bnr = 1;
+ params.acc_param.bnr = imguCssBnrDefaults;
+ /**
+ * Optical center is column (respectively row) startminus X (respectively Y) center.
+ * For the moment use BDS as a first approximation, but it should
+ * be calculated based on Shading (SHD) parameters.
+ */
+ params.acc_param.bnr.column_size = bdsOutputSize.width;
+ params.acc_param.bnr.opt_center.x_reset = awbGrid_.x_start - (bdsOutputSize.width / 2);
+ params.acc_param.bnr.opt_center.y_reset = awbGrid_.y_start - (bdsOutputSize.height / 2);
+ params.acc_param.bnr.opt_center_sqr.x_sqr_reset = params.acc_param.bnr.opt_center.x_reset
+ * params.acc_param.bnr.opt_center.x_reset;
+ params.acc_param.bnr.opt_center_sqr.y_sqr_reset = params.acc_param.bnr.opt_center.y_reset
+ * params.acc_param.bnr.opt_center.y_reset;
+
+ params.use.acc_ccm = 1;
+ params.acc_param.ccm = imguCssCcmDefault;
+
+ params.use.acc_gamma = 1;
+ params.acc_param.gamma.gc_lut = imguCssGammaLut;
+ params.acc_param.gamma.gc_ctrl.enable = 1;
+
+ zones_.reserve(kAwbStatsSizeX * kAwbStatsSizeY);
+}
+
+/**
+ * The function estimates the correlated color temperature using
+ * from RGB color space input.
+ * In physics and color science, the Planckian locus or black body locus is
+ * the path or locus that the color of an incandescent black body would take
+ * in a particular chromaticity space as the blackbody temperature changes.
+ *
+ * If a narrow range of color temperatures is considered (those encapsulating
+ * daylight being the most practical case) one can approximate the Planckian
+ * locus in order to calculate the CCT in terms of chromaticity coordinates.
+ *
+ * More detailed information can be found in:
+ * https://en.wikipedia.org/wiki/Color_temperature#Approximation
+ */
+uint32_t IPU3Awb::estimateCCT(double red, double green, double blue)
+{
+ /* Convert the RGB values to CIE tristimulus values (XYZ) */
+ double X = (-0.14282) * (red) + (1.54924) * (green) + (-0.95641) * (blue);
+ double Y = (-0.32466) * (red) + (1.57837) * (green) + (-0.73191) * (blue);
+ double Z = (-0.68202) * (red) + (0.77073) * (green) + (0.56332) * (blue);
+
+ /* Calculate the normalized chromaticity values */
+ double x = X / (X + Y + Z);
+ double y = Y / (X + Y + Z);
+
+ /* Calculate CCT */
+ double n = (x - 0.3320) / (0.1858 - y);
+ return 449 * n * n * n + 3525 * n * n + 6823.3 * n + 5520.33;
+}
+
+/* Generate an RGB vector with the average values for each region */
+void IPU3Awb::generateZones(std::vector<RGB> &zones)
+{
+ for (unsigned int i = 0; i < kAwbStatsSizeX * kAwbStatsSizeY; i++) {
+ RGB zone;
+ double counted = awbStats_[i].counted;
+ if (counted >= kMinZonesCounted) {
+ zone.G = awbStats_[i].gSum / counted;
+ if (zone.G >= kMinGreenLevelInZone) {
+ zone.R = awbStats_[i].rSum / counted;
+ zone.B = awbStats_[i].bSum / counted;
+ zones.push_back(zone);
+ }
+ }
+ }
+}
+
+/* Translate the IPU3 statistics into the default statistics region array */
+void IPU3Awb::generateAwbStats(const ipu3_uapi_stats_3a *stats)
+{
+ uint32_t regionWidth = round(awbGrid_.width / static_cast<double>(kAwbStatsSizeX));
+ uint32_t regionHeight = round(awbGrid_.height / static_cast<double>(kAwbStatsSizeY));
+
+ /*
+ * Generate a (kAwbStatsSizeX x kAwbStatsSizeY) array from the IPU3 grid which is
+ * (awbGrid_.width x awbGrid_.height).
+ */
+ for (unsigned int j = 0; j < kAwbStatsSizeY * regionHeight; j++) {
+ for (unsigned int i = 0; i < kAwbStatsSizeX * regionWidth; i++) {
+ uint32_t cellPosition = j * awbGrid_.width + i;
+ uint32_t cellX = (cellPosition / regionWidth) % kAwbStatsSizeX;
+ uint32_t cellY = ((cellPosition / awbGrid_.width) / regionHeight) % kAwbStatsSizeY;
+
+ uint32_t awbRegionPosition = cellY * kAwbStatsSizeX + cellX;
+ cellPosition *= 8;
+
+ /* Cast the initial IPU3 structure to simplify the reading */
+ Ipu3AwbCell *currentCell = reinterpret_cast<Ipu3AwbCell *>(const_cast<uint8_t *>(&stats->awb_raw_buffer.meta_data[cellPosition]));
+ if (currentCell->satRatio == 0) {
+ /* The cell is not saturated, use the current cell */
+ awbStats_[awbRegionPosition].counted++;
+ uint32_t greenValue = currentCell->greenRedAvg + currentCell->greenBlueAvg;
+ awbStats_[awbRegionPosition].gSum += greenValue / 2;
+ awbStats_[awbRegionPosition].rSum += currentCell->redAvg;
+ awbStats_[awbRegionPosition].bSum += currentCell->blueAvg;
+ }
+ }
+ }
+}
+
+void IPU3Awb::clearAwbStats()
+{
+ for (unsigned int i = 0; i < kAwbStatsSizeX * kAwbStatsSizeY; i++) {
+ awbStats_[i].bSum = 0;
+ awbStats_[i].rSum = 0;
+ awbStats_[i].gSum = 0;
+ awbStats_[i].counted = 0;
+ awbStats_[i].uncounted = 0;
+ }
+}
+
+void IPU3Awb::awbGreyWorld()
+{
+ LOG(IPU3Awb, Debug) << "Grey world AWB";
+ /*
+ * Make a separate list of the derivatives for each of red and blue, so
+ * that we can sort them to exclude the extreme gains. We could
+ * consider some variations, such as normalising all the zones first, or
+ * doing an L2 average etc.
+ */
+ std::vector<RGB> &redDerivative(zones_);
+ std::vector<RGB> blueDerivative(redDerivative);
+ std::sort(redDerivative.begin(), redDerivative.end(),
+ [](RGB const &a, RGB const &b) {
+ return a.G * b.R < b.G * a.R;
+ });
+ std::sort(blueDerivative.begin(), blueDerivative.end(),
+ [](RGB const &a, RGB const &b) {
+ return a.G * b.B < b.G * a.B;
+ });
+
+ /* Average the middle half of the values. */
+ int discard = redDerivative.size() / 4;
+
+ RGB sumRed(0, 0, 0);
+ RGB sumBlue(0, 0, 0);
+ for (auto ri = redDerivative.begin() + discard,
+ bi = blueDerivative.begin() + discard;
+ ri != redDerivative.end() - discard; ri++, bi++)
+ sumRed += *ri, sumBlue += *bi;
+
+ double redGain = sumRed.G / (sumRed.R + 1),
+ blueGain = sumBlue.G / (sumBlue.B + 1);
+
+ /* Color temperature is not relevant in Grey world but still useful to estimate it :-) */
+ asyncResults_.temperatureK = estimateCCT(sumRed.R, sumRed.G, sumBlue.B);
+ asyncResults_.redGain = redGain;
+ asyncResults_.greenGain = 1.0;
+ asyncResults_.blueGain = blueGain;
+}
+
+void IPU3Awb::calculateWBGains(const ipu3_uapi_stats_3a *stats)
+{
+ ASSERT(stats->stats_3a_status.awb_en);
+ zones_.clear();
+ clearAwbStats();
+ generateAwbStats(stats);
+ generateZones(zones_);
+ LOG(IPU3Awb, Debug) << "Valid zones: " << zones_.size();
+ if (zones_.size() > 10) {
+ awbGreyWorld();
+ LOG(IPU3Awb, Debug) << "Gain found for red: " << asyncResults_.redGain
+ << " and for blue: " << asyncResults_.blueGain;
+ }
+}
+
+void IPU3Awb::updateWbParameters(ipu3_uapi_params &params, double agcGamma)
+{
+ /*
+ * Green gains should not be touched and considered 1.
+ * Default is 16, so do not change it at all.
+ * 4096 is the value for a gain of 1.0
+ */
+ params.acc_param.bnr.wb_gains.gr = 16;
+ params.acc_param.bnr.wb_gains.r = 4096 * asyncResults_.redGain;
+ params.acc_param.bnr.wb_gains.b = 4096 * asyncResults_.blueGain;
+ params.acc_param.bnr.wb_gains.gb = 16;
+
+ LOG(IPU3Awb, Debug) << "Color temperature estimated: " << asyncResults_.temperatureK
+ << " and gamma calculated: " << agcGamma;
+
+ /* The CCM matrix may change when color temperature will be used */
+ params.acc_param.ccm = imguCssCcmDefault;
+
+ for (uint32_t i = 0; i < 256; i++) {
+ double j = i / 255.0;
+ double gamma = std::pow(j, 1.0 / agcGamma);
+ /* The maximum value 255 is represented on 13 bits in the IPU3 */
+ params.acc_param.gamma.gc_lut.lut[i] = gamma * 8191;
+ }
+}
+
+} /* namespace ipa::ipu3 */
+
+} /* namespace libcamera */
diff --git a/src/ipa/ipu3/ipu3_awb.h b/src/ipa/ipu3/ipu3_awb.h
new file mode 100644
index 00000000..122cf68c
--- /dev/null
+++ b/src/ipa/ipu3/ipu3_awb.h
@@ -0,0 +1,91 @@
+/* SPDX-License-Identifier: LGPL-2.1-or-later */
+/*
+ * Copyright (C) 2021, Ideas On Board
+ *
+ * ipu3_awb.h - IPU3 AWB control algorithm
+ */
+#ifndef __LIBCAMERA_IPU3_AWB_H__
+#define __LIBCAMERA_IPU3_AWB_H__
+
+#include <vector>
+
+#include <linux/intel-ipu3.h>
+
+#include <libcamera/geometry.h>
+
+#include "libipa/algorithm.h"
+
+namespace libcamera {
+
+namespace ipa::ipu3 {
+
+/* Region size for the statistics generation algorithm */
+static constexpr uint32_t kAwbStatsSizeX = 16;
+static constexpr uint32_t kAwbStatsSizeY = 12;
+
+class IPU3Awb : public Algorithm
+{
+public:
+ IPU3Awb();
+ ~IPU3Awb();
+
+ void initialise(ipu3_uapi_params &params, const Size &bdsOutputSize, struct ipu3_uapi_grid_config &bdsGrid);
+ void calculateWBGains(const ipu3_uapi_stats_3a *stats);
+ void updateWbParameters(ipu3_uapi_params &params, double agcGamma);
+
+ struct Ipu3AwbCell {
+ unsigned char greenRedAvg;
+ unsigned char redAvg;
+ unsigned char blueAvg;
+ unsigned char greenBlueAvg;
+ unsigned char satRatio;
+ unsigned char padding[3];
+ } __attribute__((packed));
+
+ /* \todo Make these three structs available to all the ISPs ? */
+ struct RGB {
+ RGB(double _R = 0, double _G = 0, double _B = 0)
+ : R(_R), G(_G), B(_B)
+ {
+ }
+ double R, G, B;
+ RGB &operator+=(RGB const &other)
+ {
+ R += other.R, G += other.G, B += other.B;
+ return *this;
+ }
+ };
+
+ struct IspStatsRegion {
+ unsigned int counted;
+ unsigned int uncounted;
+ unsigned long long rSum;
+ unsigned long long gSum;
+ unsigned long long bSum;
+ };
+
+ struct AwbStatus {
+ double temperatureK;
+ double redGain;
+ double greenGain;
+ double blueGain;
+ };
+
+private:
+ void generateZones(std::vector<RGB> &zones);
+ void generateAwbStats(const ipu3_uapi_stats_3a *stats);
+ void clearAwbStats();
+ void awbGreyWorld();
+ uint32_t estimateCCT(double red, double green, double blue);
+
+ struct ipu3_uapi_grid_config awbGrid_;
+
+ std::vector<RGB> zones_;
+ IspStatsRegion awbStats_[kAwbStatsSizeX * kAwbStatsSizeY];
+ AwbStatus asyncResults_;
+};
+
+} /* namespace ipa::ipu3 */
+
+} /* namespace libcamera*/
+#endif /* __LIBCAMERA_IPU3_AWB_H__ */
diff --git a/src/ipa/ipu3/meson.build b/src/ipa/ipu3/meson.build
new file mode 100644
index 00000000..b6364190
--- /dev/null
+++ b/src/ipa/ipu3/meson.build
@@ -0,0 +1,27 @@
+# SPDX-License-Identifier: CC0-1.0
+
+ipa_name = 'ipa_ipu3'
+
+ipu3_ipa_sources = files([
+ 'ipu3.cpp',
+ 'ipu3_agc.cpp',
+ 'ipu3_awb.cpp',
+])
+
+mod = shared_module(ipa_name,
+ [ipu3_ipa_sources, libcamera_generated_ipa_headers],
+ name_prefix : '',
+ include_directories : [ipa_includes, libipa_includes],
+ dependencies : libcamera_private,
+ link_with : libipa,
+ install : true,
+ install_dir : ipa_install_dir)
+
+if ipa_sign_module
+ custom_target(ipa_name + '.so.sign',
+ input : mod,
+ output : ipa_name + '.so.sign',
+ command : [ipa_sign, ipa_priv_key, '@INPUT@', '@OUTPUT@'],
+ install : false,
+ build_by_default : true)
+endif