[libcamera-devel,09/13] ipa: raspberrypi: Introduce IpaBase class
diff mbox series

Message ID 20230503122035.32026-10-naush@raspberrypi.com
State Accepted
Headers show
Series
  • Raspberry Pi: Code refactoring
Related show

Commit Message

Naushir Patuck May 3, 2023, 12:20 p.m. UTC
Create a new IpaBase class that handles general purpose housekeeping
duties for the Raspberry Pi IPA. The implementation of the new class
is essentially pulled from the existing ipa/rpi/vc4/raspberrypi.cpp file
with a minimal amount of refactoring.

Create a derived IpaVc4 class from IpaBase that handles the VC4 pipeline
specific tasks of the IPA. Again, code for this class implementation is
taken from the existing ipa/rpi/vc4/raspberrypi.cpp with a
minimal amount of refactoring.

The goal of this change is to allow third parties to implement their own
IPA running on the Raspberry Pi without duplicating all of the IPA
housekeeping tasks.

Signed-off-by: Naushir Patuck <naush@raspberrypi.com>
Reviewed-by: Jacopo Mondi <jacopo.mondi@ideasonboard.com>
---
 .../raspberrypi.cpp => common/ipa_base.cpp}   | 1305 +++++------------
 src/ipa/rpi/common/ipa_base.h                 |  122 ++
 src/ipa/rpi/common/meson.build                |   17 +
 src/ipa/rpi/meson.build                       |    1 +
 src/ipa/rpi/vc4/meson.build                   |    4 +-
 src/ipa/rpi/vc4/vc4.cpp                       |  540 +++++++
 6 files changed, 1056 insertions(+), 933 deletions(-)
 rename src/ipa/rpi/{vc4/raspberrypi.cpp => common/ipa_base.cpp} (65%)
 create mode 100644 src/ipa/rpi/common/ipa_base.h
 create mode 100644 src/ipa/rpi/common/meson.build
 create mode 100644 src/ipa/rpi/vc4/vc4.cpp

Patch
diff mbox series

diff --git a/src/ipa/rpi/vc4/raspberrypi.cpp b/src/ipa/rpi/common/ipa_base.cpp
similarity index 65%
rename from src/ipa/rpi/vc4/raspberrypi.cpp
rename to src/ipa/rpi/common/ipa_base.cpp
index 17ea5c046f4f..db7a0eb3a1ca 100644
--- a/src/ipa/rpi/vc4/raspberrypi.cpp
+++ b/src/ipa/rpi/common/ipa_base.cpp
@@ -1,60 +1,30 @@ 
 /* SPDX-License-Identifier: BSD-2-Clause */
 /*
- * Copyright (C) 2019-2021, Raspberry Pi Ltd
+ * Copyright (C) 2019-2023, Raspberry Pi Ltd
  *
- * rpi.cpp - Raspberry Pi Image Processing Algorithms
+ * ipa_base.cpp - Raspberry Pi IPA base class
  */
 
-#include <algorithm>
-#include <array>
-#include <cstring>
-#include <deque>
-#include <fcntl.h>
-#include <math.h>
-#include <stdint.h>
-#include <string.h>
-#include <sys/mman.h>
-#include <vector>
+#include "ipa_base.h"
 
-#include <linux/bcm2835-isp.h>
+#include <cmath>
 
 #include <libcamera/base/log.h>
-#include <libcamera/base/shared_fd.h>
 #include <libcamera/base/span.h>
-
 #include <libcamera/control_ids.h>
-#include <libcamera/controls.h>
-#include <libcamera/framebuffer.h>
-#include <libcamera/request.h>
-
-#include <libcamera/ipa/ipa_interface.h>
-#include <libcamera/ipa/ipa_module_info.h>
-#include <libcamera/ipa/raspberrypi_ipa_interface.h>
 
-#include "libcamera/internal/mapped_framebuffer.h"
-
-#include "cam_helper/cam_helper.h"
 #include "controller/af_algorithm.h"
 #include "controller/af_status.h"
 #include "controller/agc_algorithm.h"
-#include "controller/agc_status.h"
-#include "controller/alsc_status.h"
 #include "controller/awb_algorithm.h"
 #include "controller/awb_status.h"
 #include "controller/black_level_status.h"
 #include "controller/ccm_algorithm.h"
 #include "controller/ccm_status.h"
 #include "controller/contrast_algorithm.h"
-#include "controller/contrast_status.h"
-#include "controller/controller.h"
 #include "controller/denoise_algorithm.h"
-#include "controller/denoise_status.h"
-#include "controller/dpc_status.h"
-#include "controller/geq_status.h"
 #include "controller/lux_status.h"
-#include "controller/metadata.h"
 #include "controller/sharpen_algorithm.h"
-#include "controller/sharpen_status.h"
 #include "controller/statistics.h"
 
 namespace libcamera {
@@ -62,8 +32,7 @@  namespace libcamera {
 using namespace std::literals::chrono_literals;
 using utils::Duration;
 
-/* Number of metadata objects available in the context list. */
-constexpr unsigned int numMetadataContexts = 16;
+namespace {
 
 /* Number of frame length times to hold in the queue. */
 constexpr unsigned int FrameLengthsQueueSize = 10;
@@ -83,7 +52,7 @@  constexpr Duration defaultMaxFrameDuration = 250.0s;
 constexpr Duration controllerMinFrameDuration = 1.0s / 30.0;
 
 /* List of controls handled by the Raspberry Pi IPA */
-static const ControlInfoMap::Map ipaControls{
+const ControlInfoMap::Map ipaControls{
 	{ &controls::AeEnable, ControlInfo(false, true) },
 	{ &controls::ExposureTime, ControlInfo(0, 66666) },
 	{ &controls::AnalogueGain, ControlInfo(1.0f, 16.0f) },
@@ -105,7 +74,7 @@  static const ControlInfoMap::Map ipaControls{
 };
 
 /* IPA controls handled conditionally, if the lens has a focus control */
-static const ControlInfoMap::Map ipaAfControls{
+const ControlInfoMap::Map ipaAfControls{
 	{ &controls::AfMode, ControlInfo(controls::AfModeValues) },
 	{ &controls::AfRange, ControlInfo(controls::AfRangeValues) },
 	{ &controls::AfSpeed, ControlInfo(controls::AfSpeedValues) },
@@ -116,118 +85,23 @@  static const ControlInfoMap::Map ipaAfControls{
 	{ &controls::LensPosition, ControlInfo(0.0f, 32.0f, 1.0f) }
 };
 
+} /* namespace */
+
 LOG_DEFINE_CATEGORY(IPARPI)
 
 namespace ipa::RPi {
 
-class IPARPi : public IPARPiInterface
+IpaBase::IpaBase()
+	: controller_(), frameCount_(0), mistrustCount_(0), lastRunTimestamp_(0),
+	  firstStart_(true)
 {
-public:
-	IPARPi()
-		: controller_(), frameCount_(0), checkCount_(0), mistrustCount_(0),
-		  lastRunTimestamp_(0), lsTable_(nullptr), firstStart_(true),
-		  lastTimeout_(0s)
-	{
-	}
-
-	~IPARPi()
-	{
-		if (lsTable_)
-			munmap(lsTable_, MaxLsGridSize);
-	}
-
-	int init(const IPASettings &settings, const InitParams &params, InitResult *result) override;
-	void start(const ControlList &controls, StartResult *result) override;
-	void stop() override {}
-
-	int configure(const IPACameraSensorInfo &sensorInfo, const ConfigParams &params,
-		      ConfigResult *result) override;
-	void mapBuffers(const std::vector<IPABuffer> &buffers) override;
-	void unmapBuffers(const std::vector<unsigned int> &ids) override;
-	void prepareIsp(const PrepareParams &params) override;
-	void processStats(const ProcessParams &params) override;
-
-private:
-	void setMode(const IPACameraSensorInfo &sensorInfo);
-	bool validateSensorControls();
-	bool validateIspControls();
-	bool validateLensControls();
-	void applyControls(const ControlList &controls);
-	void prepare(const PrepareParams &params);
-	void reportMetadata(unsigned int ipaContext);
-	void fillDeviceStatus(const ControlList &sensorControls, unsigned int ipaContext);
-	RPiController::StatisticsPtr fillStatistics(bcm2835_isp_stats *stats) const;
-	void process(unsigned int bufferId, unsigned int ipaContext);
-	void setCameraTimeoutValue();
-	void applyFrameDurations(Duration minFrameDuration, Duration maxFrameDuration);
-	void applyAGC(const struct AgcStatus *agcStatus, ControlList &ctrls);
-	void applyAWB(const struct AwbStatus *awbStatus, ControlList &ctrls);
-	void applyDG(const struct AgcStatus *dgStatus, ControlList &ctrls);
-	void applyCCM(const struct CcmStatus *ccmStatus, ControlList &ctrls);
-	void applyBlackLevel(const struct BlackLevelStatus *blackLevelStatus, ControlList &ctrls);
-	void applyGamma(const struct ContrastStatus *contrastStatus, ControlList &ctrls);
-	void applyGEQ(const struct GeqStatus *geqStatus, ControlList &ctrls);
-	void applyDenoise(const struct DenoiseStatus *denoiseStatus, ControlList &ctrls);
-	void applySharpen(const struct SharpenStatus *sharpenStatus, ControlList &ctrls);
-	void applyDPC(const struct DpcStatus *dpcStatus, ControlList &ctrls);
-	void applyLS(const struct AlscStatus *lsStatus, ControlList &ctrls);
-	void applyAF(const struct AfStatus *afStatus, ControlList &lensCtrls);
-	void resampleTable(uint16_t dest[], const std::vector<double> &src, int destW, int destH);
-
-	std::map<unsigned int, MappedFrameBuffer> buffers_;
-
-	ControlInfoMap sensorCtrls_;
-	ControlInfoMap ispCtrls_;
-	ControlInfoMap lensCtrls_;
-	bool lensPresent_;
-	ControlList libcameraMetadata_;
-
-	/* Camera sensor params. */
-	CameraMode mode_;
-
-	/* Raspberry Pi controller specific defines. */
-	std::unique_ptr<RPiController::CamHelper> helper_;
-	RPiController::Controller controller_;
-	std::array<RPiController::Metadata, numMetadataContexts> rpiMetadata_;
-
-	/*
-	 * We count frames to decide if the frame must be hidden (e.g. from
-	 * display) or mistrusted (i.e. not given to the control algos).
-	 */
-	uint64_t frameCount_;
-
-	/* For checking the sequencing of Prepare/Process calls. */
-	uint64_t checkCount_;
-
-	/* How many frames we should avoid running control algos on. */
-	unsigned int mistrustCount_;
-
-	/* Number of frames that need to be dropped on startup. */
-	unsigned int dropFrameCount_;
-
-	/* Frame timestamp for the last run of the controller. */
-	uint64_t lastRunTimestamp_;
-
-	/* Do we run a Controller::process() for this frame? */
-	bool processPending_;
-
-	/* LS table allocation passed in from the pipeline handler. */
-	SharedFD lsTableHandle_;
-	void *lsTable_;
-
-	/* Distinguish the first camera start from others. */
-	bool firstStart_;
-
-	/* Frame duration (1/fps) limits. */
-	Duration minFrameDuration_;
-	Duration maxFrameDuration_;
+}
 
-	/* Track the frame length times over FrameLengthsQueueSize frames. */
-	std::deque<Duration> frameLengths_;
-	Duration lastTimeout_;
-};
+IpaBase::~IpaBase()
+{
+}
 
-int IPARPi::init(const IPASettings &settings, const InitParams &params, InitResult *result)
+int32_t IpaBase::init(const IPASettings &settings, const InitParams &params, InitResult *result)
 {
 	/*
 	 * Load the "helper" for this sensor. This tells us all the device specific stuff
@@ -264,14 +138,6 @@  int IPARPi::init(const IPASettings &settings, const InitParams &params, InitResu
 		return ret;
 	}
 
-	const std::string &target = controller_.getTarget();
-	if (target != "bcm2835") {
-		LOG(IPARPI, Error)
-			<< "Tuning data file target returned \"" << target << "\""
-			<< ", expected \"bcm2835\"";
-		return -EINVAL;
-	}
-
 	lensPresent_ = params.lensPresent;
 
 	controller_.initialise();
@@ -282,10 +148,88 @@  int IPARPi::init(const IPASettings &settings, const InitParams &params, InitResu
 		ctrlMap.merge(ControlInfoMap::Map(ipaAfControls));
 	result->controlInfo = ControlInfoMap(std::move(ctrlMap), controls::controls);
 
-	return 0;
+	return platformInit(params, result);
+}
+
+int32_t IpaBase::configure(const IPACameraSensorInfo &sensorInfo, const ConfigParams &params,
+			   ConfigResult *result)
+{
+	sensorCtrls_ = params.sensorControls;
+
+	if (!validateSensorControls()) {
+		LOG(IPARPI, Error) << "Sensor control validation failed.";
+		return -1;
+	}
+
+	if (lensPresent_) {
+		lensCtrls_ = params.lensControls;
+		if (!validateLensControls()) {
+			LOG(IPARPI, Warning) << "Lens validation failed, "
+					     << "no lens control will be available.";
+			lensPresent_ = false;
+		}
+	}
+
+	/* Setup a metadata ControlList to output metadata. */
+	libcameraMetadata_ = ControlList(controls::controls);
+
+	/* Re-assemble camera mode using the sensor info. */
+	setMode(sensorInfo);
+
+	mode_.transform = static_cast<libcamera::Transform>(params.transform);
+
+	/* Pass the camera mode to the CamHelper to setup algorithms. */
+	helper_->setCameraMode(mode_);
+
+	/*
+	 * Initialise this ControlList correctly, even if empty, in case the IPA is
+	 * running is isolation mode (passing the ControlList through the IPC layer).
+	 */
+	ControlList ctrls(sensorCtrls_);
+
+	/* The pipeline handler passes out the mode's sensitivity. */
+	result->modeSensitivity = mode_.sensitivity;
+
+	if (firstStart_) {
+		/* Supply initial values for frame durations. */
+		applyFrameDurations(defaultMinFrameDuration, defaultMaxFrameDuration);
+
+		/* Supply initial values for gain and exposure. */
+		AgcStatus agcStatus;
+		agcStatus.shutterTime = defaultExposureTime;
+		agcStatus.analogueGain = defaultAnalogueGain;
+		applyAGC(&agcStatus, ctrls);
+	}
+
+	result->controls = std::move(ctrls);
+
+	/*
+	 * Apply the correct limits to the exposure, gain and frame duration controls
+	 * based on the current sensor mode.
+	 */
+	ControlInfoMap::Map ctrlMap = ipaControls;
+	ctrlMap[&controls::FrameDurationLimits] =
+		ControlInfo(static_cast<int64_t>(mode_.minFrameDuration.get<std::micro>()),
+			    static_cast<int64_t>(mode_.maxFrameDuration.get<std::micro>()));
+
+	ctrlMap[&controls::AnalogueGain] =
+		ControlInfo(static_cast<float>(mode_.minAnalogueGain),
+			    static_cast<float>(mode_.maxAnalogueGain));
+
+	ctrlMap[&controls::ExposureTime] =
+		ControlInfo(static_cast<int32_t>(mode_.minShutter.get<std::micro>()),
+			    static_cast<int32_t>(mode_.maxShutter.get<std::micro>()));
+
+	/* Declare Autofocus controls, only if we have a controllable lens */
+	if (lensPresent_)
+		ctrlMap.merge(ControlInfoMap::Map(ipaAfControls));
+
+	result->controlInfo = ControlInfoMap(std::move(ctrlMap), controls::controls);
+
+	return platformConfigure(params, result);
 }
 
-void IPARPi::start(const ControlList &controls, StartResult *result)
+void IpaBase::start(const ControlList &controls, StartResult *result)
 {
 	RPiController::Metadata metadata;
 
@@ -320,7 +264,6 @@  void IPARPi::start(const ControlList &controls, StartResult *result)
 	 * or merely a mode switch in a running system.
 	 */
 	frameCount_ = 0;
-	checkCount_ = 0;
 	if (firstStart_) {
 		dropFrameCount_ = helper_->hideFramesStartup();
 		mistrustCount_ = helper_->mistrustFramesStartup();
@@ -363,7 +306,142 @@  void IPARPi::start(const ControlList &controls, StartResult *result)
 	lastRunTimestamp_ = 0;
 }
 
-void IPARPi::setMode(const IPACameraSensorInfo &sensorInfo)
+void IpaBase::mapBuffers(const std::vector<IPABuffer> &buffers)
+{
+	for (const IPABuffer &buffer : buffers) {
+		const FrameBuffer fb(buffer.planes);
+		buffers_.emplace(buffer.id,
+				 MappedFrameBuffer(&fb, MappedFrameBuffer::MapFlag::ReadWrite));
+	}
+}
+
+void IpaBase::unmapBuffers(const std::vector<unsigned int> &ids)
+{
+	for (unsigned int id : ids) {
+		auto it = buffers_.find(id);
+		if (it == buffers_.end())
+			continue;
+
+		buffers_.erase(id);
+	}
+}
+
+void IpaBase::prepareIsp(const PrepareParams &params)
+{
+	applyControls(params.requestControls);
+
+	/*
+	 * At start-up, or after a mode-switch, we may want to
+	 * avoid running the control algos for a few frames in case
+	 * they are "unreliable".
+	 */
+	int64_t frameTimestamp = params.sensorControls.get(controls::SensorTimestamp).value_or(0);
+	unsigned int ipaContext = params.ipaContext % rpiMetadata_.size();
+	RPiController::Metadata &rpiMetadata = rpiMetadata_[ipaContext];
+	Span<uint8_t> embeddedBuffer;
+
+	rpiMetadata.clear();
+	fillDeviceStatus(params.sensorControls, ipaContext);
+
+	if (params.buffers.embedded) {
+		/*
+		 * Pipeline handler has supplied us with an embedded data buffer,
+		 * we must pass it to the CamHelper for parsing.
+		 */
+		auto it = buffers_.find(params.buffers.embedded);
+		ASSERT(it != buffers_.end());
+		embeddedBuffer = it->second.planes()[0];
+	}
+
+	/*
+	 * AGC wants to know the algorithm status from the time it actioned the
+	 * sensor exposure/gain changes. So fetch it from the metadata list
+	 * indexed by the IPA cookie returned, and put it in the current frame
+	 * metadata.
+	 */
+	AgcStatus agcStatus;
+	RPiController::Metadata &delayedMetadata = rpiMetadata_[params.delayContext];
+	if (!delayedMetadata.get<AgcStatus>("agc.status", agcStatus))
+		rpiMetadata.set("agc.delayed_status", agcStatus);
+
+	/*
+	 * This may overwrite the DeviceStatus using values from the sensor
+	 * metadata, and may also do additional custom processing.
+	 */
+	helper_->prepare(embeddedBuffer, rpiMetadata);
+
+	/* Allow a 10% margin on the comparison below. */
+	Duration delta = (frameTimestamp - lastRunTimestamp_) * 1.0ns;
+	if (lastRunTimestamp_ && frameCount_ > dropFrameCount_ &&
+	    delta < controllerMinFrameDuration * 0.9) {
+		/*
+		 * Ensure we merge the previous frame's metadata with the current
+		 * frame. This will not overwrite exposure/gain values for the
+		 * current frame, or any other bits of metadata that were added
+		 * in helper_->Prepare().
+		 */
+		RPiController::Metadata &lastMetadata =
+			rpiMetadata_[(ipaContext ? ipaContext : rpiMetadata_.size()) - 1];
+		rpiMetadata.mergeCopy(lastMetadata);
+		processPending_ = false;
+	} else {
+		processPending_ = true;
+		lastRunTimestamp_ = frameTimestamp;
+	}
+
+	/*
+	 * If a statistics buffer has been passed in, call processStats
+	 * directly now before prepare() since the statistics are available in-line
+	 * with the Bayer frame.
+	 */
+	if (params.buffers.stats)
+		processStats({ params.buffers, params.ipaContext });
+
+	/* Do we need/want to call prepare? */
+	if (processPending_) {
+		controller_.prepare(&rpiMetadata);
+		/* Actually prepare the ISP parameters for the frame. */
+		platformPrepareIsp(params, rpiMetadata);
+	}
+
+	frameCount_++;
+
+	/* Ready to push the input buffer into the ISP. */
+	prepareIspComplete.emit(params.buffers);
+}
+
+void IpaBase::processStats(const ProcessParams &params)
+{
+	unsigned int ipaContext = params.ipaContext % rpiMetadata_.size();
+
+	if (processPending_ && frameCount_ > mistrustCount_) {
+		RPiController::Metadata &rpiMetadata = rpiMetadata_[ipaContext];
+
+		auto it = buffers_.find(params.buffers.stats);
+		if (it == buffers_.end()) {
+			LOG(IPARPI, Error) << "Could not find stats buffer!";
+			return;
+		}
+
+		RPiController::StatisticsPtr statistics = platformProcessStats(it->second.planes()[0]);
+
+		helper_->process(statistics, rpiMetadata);
+		controller_.process(statistics, &rpiMetadata);
+
+		struct AgcStatus agcStatus;
+		if (rpiMetadata.get("agc.status", agcStatus) == 0) {
+			ControlList ctrls(sensorCtrls_);
+			applyAGC(&agcStatus, ctrls);
+			setDelayedControls.emit(ctrls, ipaContext);
+			setCameraTimeoutValue();
+		}
+	}
+
+	reportMetadata(ipaContext);
+	processStatsComplete.emit(params.buffers);
+}
+
+void IpaBase::setMode(const IPACameraSensorInfo &sensorInfo)
 {
 	mode_.bitdepth = sensorInfo.bitsPerPixel;
 	mode_.width = sensorInfo.outputSize.width;
@@ -393,7 +471,7 @@  void IPARPi::setMode(const IPACameraSensorInfo &sensorInfo)
 	mode_.binY = std::min(2, static_cast<int>(mode_.scaleY));
 
 	/* The noise factor is the square root of the total binning factor. */
-	mode_.noiseFactor = sqrt(mode_.binX * mode_.binY);
+	mode_.noiseFactor = std::sqrt(mode_.binX * mode_.binY);
 
 	/*
 	 * Calculate the line length as the ratio between the line length in
@@ -432,327 +510,46 @@  void IPARPi::setMode(const IPACameraSensorInfo &sensorInfo)
 			     mode_.minFrameDuration, mode_.maxFrameDuration);
 }
 
-int IPARPi::configure(const IPACameraSensorInfo &sensorInfo, const ConfigParams &params,
-		      ConfigResult *result)
+void IpaBase::setCameraTimeoutValue()
 {
-	sensorCtrls_ = params.sensorControls;
-	ispCtrls_ = params.ispControls;
+	/*
+	 * Take the maximum value of the exposure queue as the camera timeout
+	 * value to pass back to the pipeline handler. Only signal if it has changed
+	 * from the last set value.
+	 */
+	auto max = std::max_element(frameLengths_.begin(), frameLengths_.end());
 
-	if (!validateSensorControls()) {
-		LOG(IPARPI, Error) << "Sensor control validation failed.";
-		return -1;
+	if (*max != lastTimeout_) {
+		setCameraTimeout.emit(max->get<std::milli>());
+		lastTimeout_ = *max;
 	}
+}
 
-	if (!validateIspControls()) {
-		LOG(IPARPI, Error) << "ISP control validation failed.";
-		return -1;
-	}
+bool IpaBase::validateSensorControls()
+{
+	static const uint32_t ctrls[] = {
+		V4L2_CID_ANALOGUE_GAIN,
+		V4L2_CID_EXPOSURE,
+		V4L2_CID_VBLANK,
+		V4L2_CID_HBLANK,
+	};
 
-	if (lensPresent_) {
-		lensCtrls_ = params.lensControls;
-		if (!validateLensControls()) {
-			LOG(IPARPI, Warning) << "Lens validation failed, "
-					     << "no lens control will be available.";
-			lensPresent_ = false;
+	for (auto c : ctrls) {
+		if (sensorCtrls_.find(c) == sensorCtrls_.end()) {
+			LOG(IPARPI, Error) << "Unable to find sensor control "
+					   << utils::hex(c);
+			return false;
 		}
 	}
 
-	/* Setup a metadata ControlList to output metadata. */
-	libcameraMetadata_ = ControlList(controls::controls);
-
-	/* Re-assemble camera mode using the sensor info. */
-	setMode(sensorInfo);
-
-	mode_.transform = static_cast<libcamera::Transform>(params.transform);
-
-	/* Store the lens shading table pointer and handle if available. */
-	if (params.lsTableHandle.isValid()) {
-		/* Remove any previous table, if there was one. */
-		if (lsTable_) {
-			munmap(lsTable_, MaxLsGridSize);
-			lsTable_ = nullptr;
-		}
-
-		/* Map the LS table buffer into user space. */
-		lsTableHandle_ = std::move(params.lsTableHandle);
-		if (lsTableHandle_.isValid()) {
-			lsTable_ = mmap(nullptr, MaxLsGridSize, PROT_READ | PROT_WRITE,
-					MAP_SHARED, lsTableHandle_.get(), 0);
+	return true;
+}
 
-			if (lsTable_ == MAP_FAILED) {
-				LOG(IPARPI, Error) << "dmaHeap mmap failure for LS table.";
-				lsTable_ = nullptr;
-			}
-		}
-	}
-
-	/* Pass the camera mode to the CamHelper to setup algorithms. */
-	helper_->setCameraMode(mode_);
-
-	/*
-	 * Initialise this ControlList correctly, even if empty, in case the IPA is
-	 * running is isolation mode (passing the ControlList through the IPC layer).
-	 */
-	ControlList ctrls(sensorCtrls_);
-
-	/* The pipeline handler passes out the mode's sensitivity. */
-	result->modeSensitivity = mode_.sensitivity;
-
-	if (firstStart_) {
-		/* Supply initial values for frame durations. */
-		applyFrameDurations(defaultMinFrameDuration, defaultMaxFrameDuration);
-
-		/* Supply initial values for gain and exposure. */
-		AgcStatus agcStatus;
-		agcStatus.shutterTime = defaultExposureTime;
-		agcStatus.analogueGain = defaultAnalogueGain;
-		applyAGC(&agcStatus, ctrls);
-	}
-
-	result->controls = std::move(ctrls);
-
-	/*
-	 * Apply the correct limits to the exposure, gain and frame duration controls
-	 * based on the current sensor mode.
-	 */
-	ControlInfoMap::Map ctrlMap = ipaControls;
-	ctrlMap[&controls::FrameDurationLimits] =
-		ControlInfo(static_cast<int64_t>(mode_.minFrameDuration.get<std::micro>()),
-			    static_cast<int64_t>(mode_.maxFrameDuration.get<std::micro>()));
-
-	ctrlMap[&controls::AnalogueGain] =
-		ControlInfo(static_cast<float>(mode_.minAnalogueGain),
-			    static_cast<float>(mode_.maxAnalogueGain));
-
-	ctrlMap[&controls::ExposureTime] =
-		ControlInfo(static_cast<int32_t>(mode_.minShutter.get<std::micro>()),
-			    static_cast<int32_t>(mode_.maxShutter.get<std::micro>()));
-
-	/* Declare Autofocus controls, only if we have a controllable lens */
-	if (lensPresent_)
-		ctrlMap.merge(ControlInfoMap::Map(ipaAfControls));
-
-	result->controlInfo = ControlInfoMap(std::move(ctrlMap), controls::controls);
-	return 0;
-}
-
-void IPARPi::mapBuffers(const std::vector<IPABuffer> &buffers)
-{
-	for (const IPABuffer &buffer : buffers) {
-		const FrameBuffer fb(buffer.planes);
-		buffers_.emplace(buffer.id,
-				 MappedFrameBuffer(&fb, MappedFrameBuffer::MapFlag::ReadWrite));
-	}
-}
-
-void IPARPi::unmapBuffers(const std::vector<unsigned int> &ids)
-{
-	for (unsigned int id : ids) {
-		auto it = buffers_.find(id);
-		if (it == buffers_.end())
-			continue;
-
-		buffers_.erase(id);
-	}
-}
-
-void IPARPi::processStats(const ProcessParams &params)
-{
-	unsigned int context = params.ipaContext % rpiMetadata_.size();
-
-	if (++checkCount_ != frameCount_) /* assert here? */
-		LOG(IPARPI, Error) << "WARNING: Prepare/Process mismatch!!!";
-	if (processPending_ && frameCount_ > mistrustCount_)
-		process(params.buffers.stats, context);
-
-	reportMetadata(context);
-	processStatsComplete.emit(params.buffers);
-}
-
-
-void IPARPi::prepareIsp(const PrepareParams &params)
-{
-	applyControls(params.requestControls);
-
-	/*
-	 * At start-up, or after a mode-switch, we may want to
-	 * avoid running the control algos for a few frames in case
-	 * they are "unreliable".
-	 */
-	prepare(params);
-	frameCount_++;
-
-	/* Ready to push the input buffer into the ISP. */
-	prepareIspComplete.emit(params.buffers);
-}
-
-void IPARPi::reportMetadata(unsigned int ipaContext)
-{
-	RPiController::Metadata &rpiMetadata = rpiMetadata_[ipaContext];
-	std::unique_lock<RPiController::Metadata> lock(rpiMetadata);
-
-	/*
-	 * Certain information about the current frame and how it will be
-	 * processed can be extracted and placed into the libcamera metadata
-	 * buffer, where an application could query it.
-	 */
-	DeviceStatus *deviceStatus = rpiMetadata.getLocked<DeviceStatus>("device.status");
-	if (deviceStatus) {
-		libcameraMetadata_.set(controls::ExposureTime,
-				       deviceStatus->shutterSpeed.get<std::micro>());
-		libcameraMetadata_.set(controls::AnalogueGain, deviceStatus->analogueGain);
-		libcameraMetadata_.set(controls::FrameDuration,
-				       helper_->exposure(deviceStatus->frameLength, deviceStatus->lineLength).get<std::micro>());
-		if (deviceStatus->sensorTemperature)
-			libcameraMetadata_.set(controls::SensorTemperature, *deviceStatus->sensorTemperature);
-		if (deviceStatus->lensPosition)
-			libcameraMetadata_.set(controls::LensPosition, *deviceStatus->lensPosition);
-	}
-
-	AgcStatus *agcStatus = rpiMetadata.getLocked<AgcStatus>("agc.status");
-	if (agcStatus) {
-		libcameraMetadata_.set(controls::AeLocked, agcStatus->locked);
-		libcameraMetadata_.set(controls::DigitalGain, agcStatus->digitalGain);
-	}
-
-	LuxStatus *luxStatus = rpiMetadata.getLocked<LuxStatus>("lux.status");
-	if (luxStatus)
-		libcameraMetadata_.set(controls::Lux, luxStatus->lux);
-
-	AwbStatus *awbStatus = rpiMetadata.getLocked<AwbStatus>("awb.status");
-	if (awbStatus) {
-		libcameraMetadata_.set(controls::ColourGains, { static_cast<float>(awbStatus->gainR),
-								static_cast<float>(awbStatus->gainB) });
-		libcameraMetadata_.set(controls::ColourTemperature, awbStatus->temperatureK);
-	}
-
-	BlackLevelStatus *blackLevelStatus = rpiMetadata.getLocked<BlackLevelStatus>("black_level.status");
-	if (blackLevelStatus)
-		libcameraMetadata_.set(controls::SensorBlackLevels,
-				       { static_cast<int32_t>(blackLevelStatus->blackLevelR),
-					 static_cast<int32_t>(blackLevelStatus->blackLevelG),
-					 static_cast<int32_t>(blackLevelStatus->blackLevelG),
-					 static_cast<int32_t>(blackLevelStatus->blackLevelB) });
-
-	RPiController::FocusRegions *focusStatus =
-		rpiMetadata.getLocked<RPiController::FocusRegions>("focus.status");
-	if (focusStatus) {
-		/*
-		 * Calculate the average FoM over the central (symmetric) positions
-		 * to give an overall scene FoM. This can change later if it is
-		 * not deemed suitable.
-		 */
-		libcamera::Size size = focusStatus->size();
-		unsigned rows = size.height;
-		unsigned cols = size.width;
-
-		uint64_t sum = 0;
-		unsigned int numRegions = 0;
-		for (unsigned r = rows / 3; r < rows - rows / 3; ++r) {
-			for (unsigned c = cols / 4; c < cols - cols / 4; ++c) {
-				sum += focusStatus->get({ (int)c, (int)r }).val;
-				numRegions++;
-			}
-		}
-
-		uint32_t focusFoM = (sum / numRegions) >> 16;
-		libcameraMetadata_.set(controls::FocusFoM, focusFoM);
-	}
-
-	CcmStatus *ccmStatus = rpiMetadata.getLocked<CcmStatus>("ccm.status");
-	if (ccmStatus) {
-		float m[9];
-		for (unsigned int i = 0; i < 9; i++)
-			m[i] = ccmStatus->matrix[i];
-		libcameraMetadata_.set(controls::ColourCorrectionMatrix, m);
-	}
-
-	const AfStatus *afStatus = rpiMetadata.getLocked<AfStatus>("af.status");
-	if (afStatus) {
-		int32_t s, p;
-		switch (afStatus->state) {
-		case AfState::Scanning:
-			s = controls::AfStateScanning;
-			break;
-		case AfState::Focused:
-			s = controls::AfStateFocused;
-			break;
-		case AfState::Failed:
-			s = controls::AfStateFailed;
-			break;
-		default:
-			s = controls::AfStateIdle;
-		}
-		switch (afStatus->pauseState) {
-		case AfPauseState::Pausing:
-			p = controls::AfPauseStatePausing;
-			break;
-		case AfPauseState::Paused:
-			p = controls::AfPauseStatePaused;
-			break;
-		default:
-			p = controls::AfPauseStateRunning;
-		}
-		libcameraMetadata_.set(controls::AfState, s);
-		libcameraMetadata_.set(controls::AfPauseState, p);
-	}
-
-	metadataReady.emit(libcameraMetadata_);
-}
-
-bool IPARPi::validateSensorControls()
-{
-	static const uint32_t ctrls[] = {
-		V4L2_CID_ANALOGUE_GAIN,
-		V4L2_CID_EXPOSURE,
-		V4L2_CID_VBLANK,
-		V4L2_CID_HBLANK,
-	};
-
-	for (auto c : ctrls) {
-		if (sensorCtrls_.find(c) == sensorCtrls_.end()) {
-			LOG(IPARPI, Error) << "Unable to find sensor control "
-					   << utils::hex(c);
-			return false;
-		}
-	}
-
-	return true;
-}
-
-bool IPARPi::validateIspControls()
-{
-	static const uint32_t ctrls[] = {
-		V4L2_CID_RED_BALANCE,
-		V4L2_CID_BLUE_BALANCE,
-		V4L2_CID_DIGITAL_GAIN,
-		V4L2_CID_USER_BCM2835_ISP_CC_MATRIX,
-		V4L2_CID_USER_BCM2835_ISP_GAMMA,
-		V4L2_CID_USER_BCM2835_ISP_BLACK_LEVEL,
-		V4L2_CID_USER_BCM2835_ISP_GEQ,
-		V4L2_CID_USER_BCM2835_ISP_DENOISE,
-		V4L2_CID_USER_BCM2835_ISP_SHARPEN,
-		V4L2_CID_USER_BCM2835_ISP_DPC,
-		V4L2_CID_USER_BCM2835_ISP_LENS_SHADING,
-		V4L2_CID_USER_BCM2835_ISP_CDN,
-	};
-
-	for (auto c : ctrls) {
-		if (ispCtrls_.find(c) == ispCtrls_.end()) {
-			LOG(IPARPI, Error) << "Unable to find ISP control "
-					   << utils::hex(c);
-			return false;
-		}
-	}
-
-	return true;
-}
-
-bool IPARPi::validateLensControls()
-{
-	if (lensCtrls_.find(V4L2_CID_FOCUS_ABSOLUTE) == lensCtrls_.end()) {
-		LOG(IPARPI, Error) << "Unable to find Lens control V4L2_CID_FOCUS_ABSOLUTE";
-		return false;
+bool IpaBase::validateLensControls()
+{
+	if (lensCtrls_.find(V4L2_CID_FOCUS_ABSOLUTE) == lensCtrls_.end()) {
+		LOG(IPARPI, Error) << "Unable to find Lens control V4L2_CID_FOCUS_ABSOLUTE";
+		return false;
 	}
 
 	return true;
@@ -821,7 +618,7 @@  static const std::map<int32_t, RPiController::AfAlgorithm::AfPause> AfPauseTable
 	{ controls::AfPauseResume, RPiController::AfAlgorithm::AfPauseResume },
 };
 
-void IPARPi::applyControls(const ControlList &controls)
+void IpaBase::applyControls(const ControlList &controls)
 {
 	using RPiController::AfAlgorithm;
 
@@ -841,7 +638,7 @@  void IPARPi::applyControls(const ControlList &controls)
 		if (mode == AfModeTable.end()) {
 			LOG(IPARPI, Error) << "AF mode " << idx
 					   << " not recognised";
-		} else
+		} else if (af)
 			af->setMode(mode->second);
 	}
 
@@ -1113,6 +910,10 @@  void IPARPi::applyControls(const ControlList &controls)
 		case controls::NOISE_REDUCTION_MODE: {
 			RPiController::DenoiseAlgorithm *sdn = dynamic_cast<RPiController::DenoiseAlgorithm *>(
 				controller_.getAlgorithm("SDN"));
+			/* Some platforms may have a combined "denoise" algorithm instead. */
+			if (!sdn)
+				sdn = dynamic_cast<RPiController::DenoiseAlgorithm *>(
+				controller_.getAlgorithm("denoise"));
 			if (!sdn) {
 				LOG(IPARPI, Warning)
 					<< "Could not set NOISE_REDUCTION_MODE - no SDN algorithm";
@@ -1249,125 +1050,12 @@  void IPARPi::applyControls(const ControlList &controls)
 			break;
 		}
 	}
-}
-
-void IPARPi::prepare(const PrepareParams &params)
-{
-	int64_t frameTimestamp = params.sensorControls.get(controls::SensorTimestamp).value_or(0);
-	unsigned int ipaContext = params.ipaContext % rpiMetadata_.size();
-	RPiController::Metadata &rpiMetadata = rpiMetadata_[ipaContext];
-	Span<uint8_t> embeddedBuffer;
-
-	rpiMetadata.clear();
-	fillDeviceStatus(params.sensorControls, ipaContext);
-
-	if (params.buffers.embedded) {
-		/*
-		 * Pipeline handler has supplied us with an embedded data buffer,
-		 * we must pass it to the CamHelper for parsing.
-		 */
-		auto it = buffers_.find(params.buffers.embedded);
-		ASSERT(it != buffers_.end());
-		embeddedBuffer = it->second.planes()[0];
-	}
-
-	/*
-	 * AGC wants to know the algorithm status from the time it actioned the
-	 * sensor exposure/gain changes. So fetch it from the metadata list
-	 * indexed by the IPA cookie returned, and put it in the current frame
-	 * metadata.
-	 */
-	AgcStatus agcStatus;
-	RPiController::Metadata &delayedMetadata = rpiMetadata_[params.delayContext];
-	if (!delayedMetadata.get<AgcStatus>("agc.status", agcStatus))
-		rpiMetadata.set("agc.delayed_status", agcStatus);
-
-	/*
-	 * This may overwrite the DeviceStatus using values from the sensor
-	 * metadata, and may also do additional custom processing.
-	 */
-	helper_->prepare(embeddedBuffer, rpiMetadata);
-
-	/* Allow a 10% margin on the comparison below. */
-	Duration delta = (frameTimestamp - lastRunTimestamp_) * 1.0ns;
-	if (lastRunTimestamp_ && frameCount_ > dropFrameCount_ &&
-	    delta < controllerMinFrameDuration * 0.9) {
-		/*
-		 * Ensure we merge the previous frame's metadata with the current
-		 * frame. This will not overwrite exposure/gain values for the
-		 * current frame, or any other bits of metadata that were added
-		 * in helper_->Prepare().
-		 */
-		RPiController::Metadata &lastMetadata =
-			rpiMetadata_[(ipaContext ? ipaContext : rpiMetadata_.size()) - 1];
-		rpiMetadata.mergeCopy(lastMetadata);
-		processPending_ = false;
-		return;
-	}
-
-	lastRunTimestamp_ = frameTimestamp;
-	processPending_ = true;
-
-	ControlList ctrls(ispCtrls_);
-
-	controller_.prepare(&rpiMetadata);
-
-	/* Lock the metadata buffer to avoid constant locks/unlocks. */
-	std::unique_lock<RPiController::Metadata> lock(rpiMetadata);
-
-	AwbStatus *awbStatus = rpiMetadata.getLocked<AwbStatus>("awb.status");
-	if (awbStatus)
-		applyAWB(awbStatus, ctrls);
-
-	CcmStatus *ccmStatus = rpiMetadata.getLocked<CcmStatus>("ccm.status");
-	if (ccmStatus)
-		applyCCM(ccmStatus, ctrls);
-
-	AgcStatus *dgStatus = rpiMetadata.getLocked<AgcStatus>("agc.status");
-	if (dgStatus)
-		applyDG(dgStatus, ctrls);
-
-	AlscStatus *lsStatus = rpiMetadata.getLocked<AlscStatus>("alsc.status");
-	if (lsStatus)
-		applyLS(lsStatus, ctrls);
-
-	ContrastStatus *contrastStatus = rpiMetadata.getLocked<ContrastStatus>("contrast.status");
-	if (contrastStatus)
-		applyGamma(contrastStatus, ctrls);
-
-	BlackLevelStatus *blackLevelStatus = rpiMetadata.getLocked<BlackLevelStatus>("black_level.status");
-	if (blackLevelStatus)
-		applyBlackLevel(blackLevelStatus, ctrls);
-
-	GeqStatus *geqStatus = rpiMetadata.getLocked<GeqStatus>("geq.status");
-	if (geqStatus)
-		applyGEQ(geqStatus, ctrls);
-
-	DenoiseStatus *denoiseStatus = rpiMetadata.getLocked<DenoiseStatus>("denoise.status");
-	if (denoiseStatus)
-		applyDenoise(denoiseStatus, ctrls);
-
-	SharpenStatus *sharpenStatus = rpiMetadata.getLocked<SharpenStatus>("sharpen.status");
-	if (sharpenStatus)
-		applySharpen(sharpenStatus, ctrls);
-
-	DpcStatus *dpcStatus = rpiMetadata.getLocked<DpcStatus>("dpc.status");
-	if (dpcStatus)
-		applyDPC(dpcStatus, ctrls);
-
-	const AfStatus *afStatus = rpiMetadata.getLocked<AfStatus>("af.status");
-	if (afStatus) {
-		ControlList lensctrls(lensCtrls_);
-		applyAF(afStatus, lensctrls);
-		if (!lensctrls.empty())
-			setLensControls.emit(lensctrls);
-	}
 
-	if (!ctrls.empty())
-		setIspControls.emit(ctrls);
+	/* Give derived classes a chance to examine the new controls. */
+	handleControls(controls);
 }
 
-void IPARPi::fillDeviceStatus(const ControlList &sensorControls, unsigned int ipaContext)
+void IpaBase::fillDeviceStatus(const ControlList &sensorControls, unsigned int ipaContext)
 {
 	DeviceStatus deviceStatus = {};
 
@@ -1391,103 +1079,121 @@  void IPARPi::fillDeviceStatus(const ControlList &sensorControls, unsigned int ip
 	rpiMetadata_[ipaContext].set("device.status", deviceStatus);
 }
 
-RPiController::StatisticsPtr IPARPi::fillStatistics(bcm2835_isp_stats *stats) const
-{
-	using namespace RPiController;
-
-	const Controller::HardwareConfig &hw = controller_.getHardwareConfig();
-	unsigned int i;
-	StatisticsPtr statistics =
-		std::make_unique<Statistics>(Statistics::AgcStatsPos::PreWb, Statistics::ColourStatsPos::PostLsc);
-
-	/* RGB histograms are not used, so do not populate them. */
-	statistics->yHist = RPiController::Histogram(stats->hist[0].g_hist,
-						     hw.numHistogramBins);
-
-	/* All region sums are based on a 16-bit normalised pipeline bit-depth. */
-	unsigned int scale = Statistics::NormalisationFactorPow2 - hw.pipelineWidth;
-
-	statistics->awbRegions.init(hw.awbRegions);
-	for (i = 0; i < statistics->awbRegions.numRegions(); i++)
-		statistics->awbRegions.set(i, { { stats->awb_stats[i].r_sum << scale,
-						  stats->awb_stats[i].g_sum << scale,
-						  stats->awb_stats[i].b_sum << scale },
-						stats->awb_stats[i].counted,
-						stats->awb_stats[i].notcounted });
-
-	statistics->agcRegions.init(hw.agcRegions);
-	for (i = 0; i < statistics->agcRegions.numRegions(); i++)
-		statistics->agcRegions.set(i, { { stats->agc_stats[i].r_sum << scale,
-						  stats->agc_stats[i].g_sum << scale,
-						  stats->agc_stats[i].b_sum << scale },
-						stats->agc_stats[i].counted,
-						stats->awb_stats[i].notcounted });
-
-	statistics->focusRegions.init(hw.focusRegions);
-	for (i = 0; i < statistics->focusRegions.numRegions(); i++)
-		statistics->focusRegions.set(i, { stats->focus_stats[i].contrast_val[1][1] / 1000,
-						  stats->focus_stats[i].contrast_val_num[1][1],
-						  stats->focus_stats[i].contrast_val_num[1][0] });
-	return statistics;
-}
-
-void IPARPi::process(unsigned int bufferId, unsigned int ipaContext)
+void IpaBase::reportMetadata(unsigned int ipaContext)
 {
 	RPiController::Metadata &rpiMetadata = rpiMetadata_[ipaContext];
+	std::unique_lock<RPiController::Metadata> lock(rpiMetadata);
 
-	auto it = buffers_.find(bufferId);
-	if (it == buffers_.end()) {
-		LOG(IPARPI, Error) << "Could not find stats buffer!";
-		return;
+	/*
+	 * Certain information about the current frame and how it will be
+	 * processed can be extracted and placed into the libcamera metadata
+	 * buffer, where an application could query it.
+	 */
+	DeviceStatus *deviceStatus = rpiMetadata.getLocked<DeviceStatus>("device.status");
+	if (deviceStatus) {
+		libcameraMetadata_.set(controls::ExposureTime,
+				       deviceStatus->shutterSpeed.get<std::micro>());
+		libcameraMetadata_.set(controls::AnalogueGain, deviceStatus->analogueGain);
+		libcameraMetadata_.set(controls::FrameDuration,
+				       helper_->exposure(deviceStatus->frameLength, deviceStatus->lineLength).get<std::micro>());
+		if (deviceStatus->sensorTemperature)
+			libcameraMetadata_.set(controls::SensorTemperature, *deviceStatus->sensorTemperature);
+		if (deviceStatus->lensPosition)
+			libcameraMetadata_.set(controls::LensPosition, *deviceStatus->lensPosition);
 	}
 
-	Span<uint8_t> mem = it->second.planes()[0];
-	bcm2835_isp_stats *stats = reinterpret_cast<bcm2835_isp_stats *>(mem.data());
-	RPiController::StatisticsPtr statistics = fillStatistics(stats);
+	AgcStatus *agcStatus = rpiMetadata.getLocked<AgcStatus>("agc.status");
+	if (agcStatus) {
+		libcameraMetadata_.set(controls::AeLocked, agcStatus->locked);
+		libcameraMetadata_.set(controls::DigitalGain, agcStatus->digitalGain);
+	}
 
-	/* Save the focus stats in the metadata structure to report out later. */
-	rpiMetadata_[ipaContext].set("focus.status", statistics->focusRegions);
+	LuxStatus *luxStatus = rpiMetadata.getLocked<LuxStatus>("lux.status");
+	if (luxStatus)
+		libcameraMetadata_.set(controls::Lux, luxStatus->lux);
 
-	helper_->process(statistics, rpiMetadata);
-	controller_.process(statistics, &rpiMetadata);
+	AwbStatus *awbStatus = rpiMetadata.getLocked<AwbStatus>("awb.status");
+	if (awbStatus) {
+		libcameraMetadata_.set(controls::ColourGains, { static_cast<float>(awbStatus->gainR),
+								static_cast<float>(awbStatus->gainB) });
+		libcameraMetadata_.set(controls::ColourTemperature, awbStatus->temperatureK);
+	}
 
-	struct AgcStatus agcStatus;
-	if (rpiMetadata.get("agc.status", agcStatus) == 0) {
-		ControlList ctrls(sensorCtrls_);
-		applyAGC(&agcStatus, ctrls);
+	BlackLevelStatus *blackLevelStatus = rpiMetadata.getLocked<BlackLevelStatus>("black_level.status");
+	if (blackLevelStatus)
+		libcameraMetadata_.set(controls::SensorBlackLevels,
+				       { static_cast<int32_t>(blackLevelStatus->blackLevelR),
+					 static_cast<int32_t>(blackLevelStatus->blackLevelG),
+					 static_cast<int32_t>(blackLevelStatus->blackLevelG),
+					 static_cast<int32_t>(blackLevelStatus->blackLevelB) });
 
-		setDelayedControls.emit(ctrls, ipaContext);
-		setCameraTimeoutValue();
-	}
-}
+	RPiController::FocusRegions *focusStatus =
+		rpiMetadata.getLocked<RPiController::FocusRegions>("focus.status");
+	if (focusStatus) {
+		/*
+		 * Calculate the average FoM over the central (symmetric) positions
+		 * to give an overall scene FoM. This can change later if it is
+		 * not deemed suitable.
+		 */
+		libcamera::Size size = focusStatus->size();
+		unsigned rows = size.height;
+		unsigned cols = size.width;
 
-void IPARPi::setCameraTimeoutValue()
-{
-	/*
-	 * Take the maximum value of the exposure queue as the camera timeout
-	 * value to pass back to the pipeline handler. Only signal if it has changed
-	 * from the last set value.
-	 */
-	auto max = std::max_element(frameLengths_.begin(), frameLengths_.end());
+		uint64_t sum = 0;
+		unsigned int numRegions = 0;
+		for (unsigned r = rows / 3; r < rows - rows / 3; ++r) {
+			for (unsigned c = cols / 4; c < cols - cols / 4; ++c) {
+				sum += focusStatus->get({ (int)c, (int)r }).val;
+				numRegions++;
+			}
+		}
 
-	if (*max != lastTimeout_) {
-		setCameraTimeout.emit(max->get<std::milli>());
-		lastTimeout_ = *max;
+		uint32_t focusFoM = (sum / numRegions) >> 16;
+		libcameraMetadata_.set(controls::FocusFoM, focusFoM);
 	}
-}
 
-void IPARPi::applyAWB(const struct AwbStatus *awbStatus, ControlList &ctrls)
-{
-	LOG(IPARPI, Debug) << "Applying WB R: " << awbStatus->gainR << " B: "
-			   << awbStatus->gainB;
+	CcmStatus *ccmStatus = rpiMetadata.getLocked<CcmStatus>("ccm.status");
+	if (ccmStatus) {
+		float m[9];
+		for (unsigned int i = 0; i < 9; i++)
+			m[i] = ccmStatus->matrix[i];
+		libcameraMetadata_.set(controls::ColourCorrectionMatrix, m);
+	}
+
+	const AfStatus *afStatus = rpiMetadata.getLocked<AfStatus>("af.status");
+	if (afStatus) {
+		int32_t s, p;
+		switch (afStatus->state) {
+		case AfState::Scanning:
+			s = controls::AfStateScanning;
+			break;
+		case AfState::Focused:
+			s = controls::AfStateFocused;
+			break;
+		case AfState::Failed:
+			s = controls::AfStateFailed;
+			break;
+		default:
+			s = controls::AfStateIdle;
+		}
+		switch (afStatus->pauseState) {
+		case AfPauseState::Pausing:
+			p = controls::AfPauseStatePausing;
+			break;
+		case AfPauseState::Paused:
+			p = controls::AfPauseStatePaused;
+			break;
+		default:
+			p = controls::AfPauseStateRunning;
+		}
+		libcameraMetadata_.set(controls::AfState, s);
+		libcameraMetadata_.set(controls::AfPauseState, p);
+	}
 
-	ctrls.set(V4L2_CID_RED_BALANCE,
-		  static_cast<int32_t>(awbStatus->gainR * 1000));
-	ctrls.set(V4L2_CID_BLUE_BALANCE,
-		  static_cast<int32_t>(awbStatus->gainB * 1000));
+	metadataReady.emit(libcameraMetadata_);
 }
 
-void IPARPi::applyFrameDurations(Duration minFrameDuration, Duration maxFrameDuration)
+void IpaBase::applyFrameDurations(Duration minFrameDuration, Duration maxFrameDuration)
 {
 	/*
 	 * This will only be applied once AGC recalculations occur.
@@ -1519,7 +1225,7 @@  void IPARPi::applyFrameDurations(Duration minFrameDuration, Duration maxFrameDur
 	agc->setMaxShutter(maxShutter);
 }
 
-void IPARPi::applyAGC(const struct AgcStatus *agcStatus, ControlList &ctrls)
+void IpaBase::applyAGC(const struct AgcStatus *agcStatus, ControlList &ctrls)
 {
 	const int32_t minGainCode = helper_->gainCode(mode_.minAnalogueGain);
 	const int32_t maxGainCode = helper_->gainCode(mode_.maxAnalogueGain);
@@ -1571,269 +1277,6 @@  void IPARPi::applyAGC(const struct AgcStatus *agcStatus, ControlList &ctrls)
 						  helper_->hblankToLineLength(hblank)));
 }
 
-void IPARPi::applyDG(const struct AgcStatus *dgStatus, ControlList &ctrls)
-{
-	ctrls.set(V4L2_CID_DIGITAL_GAIN,
-		  static_cast<int32_t>(dgStatus->digitalGain * 1000));
-}
-
-void IPARPi::applyCCM(const struct CcmStatus *ccmStatus, ControlList &ctrls)
-{
-	bcm2835_isp_custom_ccm ccm;
-
-	for (int i = 0; i < 9; i++) {
-		ccm.ccm.ccm[i / 3][i % 3].den = 1000;
-		ccm.ccm.ccm[i / 3][i % 3].num = 1000 * ccmStatus->matrix[i];
-	}
-
-	ccm.enabled = 1;
-	ccm.ccm.offsets[0] = ccm.ccm.offsets[1] = ccm.ccm.offsets[2] = 0;
-
-	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&ccm),
-					    sizeof(ccm) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_CC_MATRIX, c);
-}
-
-void IPARPi::applyGamma(const struct ContrastStatus *contrastStatus, ControlList &ctrls)
-{
-	const unsigned int numGammaPoints = controller_.getHardwareConfig().numGammaPoints;
-	struct bcm2835_isp_gamma gamma;
-
-	for (unsigned int i = 0; i < numGammaPoints - 1; i++) {
-		int x = i < 16 ? i * 1024
-			       : (i < 24 ? (i - 16) * 2048 + 16384
-					 : (i - 24) * 4096 + 32768);
-		gamma.x[i] = x;
-		gamma.y[i] = std::min<uint16_t>(65535, contrastStatus->gammaCurve.eval(x));
-	}
-
-	gamma.x[numGammaPoints - 1] = 65535;
-	gamma.y[numGammaPoints - 1] = 65535;
-	gamma.enabled = 1;
-
-	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&gamma),
-					    sizeof(gamma) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_GAMMA, c);
-}
-
-void IPARPi::applyBlackLevel(const struct BlackLevelStatus *blackLevelStatus, ControlList &ctrls)
-{
-	bcm2835_isp_black_level blackLevel;
-
-	blackLevel.enabled = 1;
-	blackLevel.black_level_r = blackLevelStatus->blackLevelR;
-	blackLevel.black_level_g = blackLevelStatus->blackLevelG;
-	blackLevel.black_level_b = blackLevelStatus->blackLevelB;
-
-	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&blackLevel),
-					    sizeof(blackLevel) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_BLACK_LEVEL, c);
-}
-
-void IPARPi::applyGEQ(const struct GeqStatus *geqStatus, ControlList &ctrls)
-{
-	bcm2835_isp_geq geq;
-
-	geq.enabled = 1;
-	geq.offset = geqStatus->offset;
-	geq.slope.den = 1000;
-	geq.slope.num = 1000 * geqStatus->slope;
-
-	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&geq),
-					    sizeof(geq) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_GEQ, c);
-}
-
-void IPARPi::applyDenoise(const struct DenoiseStatus *denoiseStatus, ControlList &ctrls)
-{
-	using RPiController::DenoiseMode;
-
-	bcm2835_isp_denoise denoise;
-	DenoiseMode mode = static_cast<DenoiseMode>(denoiseStatus->mode);
-
-	denoise.enabled = mode != DenoiseMode::Off;
-	denoise.constant = denoiseStatus->noiseConstant;
-	denoise.slope.num = 1000 * denoiseStatus->noiseSlope;
-	denoise.slope.den = 1000;
-	denoise.strength.num = 1000 * denoiseStatus->strength;
-	denoise.strength.den = 1000;
-
-	/* Set the CDN mode to match the SDN operating mode. */
-	bcm2835_isp_cdn cdn;
-	switch (mode) {
-	case DenoiseMode::ColourFast:
-		cdn.enabled = 1;
-		cdn.mode = CDN_MODE_FAST;
-		break;
-	case DenoiseMode::ColourHighQuality:
-		cdn.enabled = 1;
-		cdn.mode = CDN_MODE_HIGH_QUALITY;
-		break;
-	default:
-		cdn.enabled = 0;
-	}
-
-	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&denoise),
-					    sizeof(denoise) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_DENOISE, c);
-
-	c = ControlValue(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&cdn),
-					      sizeof(cdn) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_CDN, c);
-}
-
-void IPARPi::applySharpen(const struct SharpenStatus *sharpenStatus, ControlList &ctrls)
-{
-	bcm2835_isp_sharpen sharpen;
-
-	sharpen.enabled = 1;
-	sharpen.threshold.num = 1000 * sharpenStatus->threshold;
-	sharpen.threshold.den = 1000;
-	sharpen.strength.num = 1000 * sharpenStatus->strength;
-	sharpen.strength.den = 1000;
-	sharpen.limit.num = 1000 * sharpenStatus->limit;
-	sharpen.limit.den = 1000;
-
-	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&sharpen),
-					    sizeof(sharpen) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_SHARPEN, c);
-}
-
-void IPARPi::applyDPC(const struct DpcStatus *dpcStatus, ControlList &ctrls)
-{
-	bcm2835_isp_dpc dpc;
-
-	dpc.enabled = 1;
-	dpc.strength = dpcStatus->strength;
-
-	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&dpc),
-					    sizeof(dpc) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_DPC, c);
-}
-
-void IPARPi::applyLS(const struct AlscStatus *lsStatus, ControlList &ctrls)
-{
-	/*
-	 * Program lens shading tables into pipeline.
-	 * Choose smallest cell size that won't exceed 63x48 cells.
-	 */
-	const int cellSizes[] = { 16, 32, 64, 128, 256 };
-	unsigned int numCells = std::size(cellSizes);
-	unsigned int i, w, h, cellSize;
-	for (i = 0; i < numCells; i++) {
-		cellSize = cellSizes[i];
-		w = (mode_.width + cellSize - 1) / cellSize;
-		h = (mode_.height + cellSize - 1) / cellSize;
-		if (w < 64 && h <= 48)
-			break;
-	}
-
-	if (i == numCells) {
-		LOG(IPARPI, Error) << "Cannot find cell size";
-		return;
-	}
-
-	/* We're going to supply corner sampled tables, 16 bit samples. */
-	w++, h++;
-	bcm2835_isp_lens_shading ls = {
-		.enabled = 1,
-		.grid_cell_size = cellSize,
-		.grid_width = w,
-		.grid_stride = w,
-		.grid_height = h,
-		/* .dmabuf will be filled in by pipeline handler. */
-		.dmabuf = 0,
-		.ref_transform = 0,
-		.corner_sampled = 1,
-		.gain_format = GAIN_FORMAT_U4P10
-	};
-
-	if (!lsTable_ || w * h * 4 * sizeof(uint16_t) > MaxLsGridSize) {
-		LOG(IPARPI, Error) << "Do not have a correctly allocate lens shading table!";
-		return;
-	}
-
-	if (lsStatus) {
-		/* Format will be u4.10 */
-		uint16_t *grid = static_cast<uint16_t *>(lsTable_);
-
-		resampleTable(grid, lsStatus->r, w, h);
-		resampleTable(grid + w * h, lsStatus->g, w, h);
-		std::memcpy(grid + 2 * w * h, grid + w * h, w * h * sizeof(uint16_t));
-		resampleTable(grid + 3 * w * h, lsStatus->b, w, h);
-	}
-
-	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&ls),
-					    sizeof(ls) });
-	ctrls.set(V4L2_CID_USER_BCM2835_ISP_LENS_SHADING, c);
-}
-
-void IPARPi::applyAF(const struct AfStatus *afStatus, ControlList &lensCtrls)
-{
-	if (afStatus->lensSetting) {
-		ControlValue v(afStatus->lensSetting.value());
-		lensCtrls.set(V4L2_CID_FOCUS_ABSOLUTE, v);
-	}
-}
-
-/*
- * Resamples a 16x12 table with central sampling to destW x destH with corner
- * sampling.
- */
-void IPARPi::resampleTable(uint16_t dest[], const std::vector<double> &src,
-			   int destW, int destH)
-{
-	/*
-	 * Precalculate and cache the x sampling locations and phases to
-	 * save recomputing them on every row.
-	 */
-	assert(destW > 1 && destH > 1 && destW <= 64);
-	int xLo[64], xHi[64];
-	double xf[64];
-	double x = -0.5, xInc = 16.0 / (destW - 1);
-	for (int i = 0; i < destW; i++, x += xInc) {
-		xLo[i] = floor(x);
-		xf[i] = x - xLo[i];
-		xHi[i] = xLo[i] < 15 ? xLo[i] + 1 : 15;
-		xLo[i] = xLo[i] > 0 ? xLo[i] : 0;
-	}
-
-	/* Now march over the output table generating the new values. */
-	double y = -0.5, yInc = 12.0 / (destH - 1);
-	for (int j = 0; j < destH; j++, y += yInc) {
-		int yLo = floor(y);
-		double yf = y - yLo;
-		int yHi = yLo < 11 ? yLo + 1 : 11;
-		yLo = yLo > 0 ? yLo : 0;
-		double const *rowAbove = src.data() + yLo * 16;
-		double const *rowBelow = src.data() + yHi * 16;
-		for (int i = 0; i < destW; i++) {
-			double above = rowAbove[xLo[i]] * (1 - xf[i]) + rowAbove[xHi[i]] * xf[i];
-			double below = rowBelow[xLo[i]] * (1 - xf[i]) + rowBelow[xHi[i]] * xf[i];
-			int result = floor(1024 * (above * (1 - yf) + below * yf) + .5);
-			*(dest++) = result > 16383 ? 16383 : result; /* want u4.10 */
-		}
-	}
-}
-
 } /* namespace ipa::RPi */
 
-/*
- * External IPA module interface
- */
-extern "C" {
-const struct IPAModuleInfo ipaModuleInfo = {
-	IPA_MODULE_API_VERSION,
-	1,
-	"PipelineHandlerRPi",
-	"rpi/vc4",
-};
-
-IPAInterface *ipaCreate()
-{
-	return new ipa::RPi::IPARPi();
-}
-
-} /* extern "C" */
-
 } /* namespace libcamera */
diff --git a/src/ipa/rpi/common/ipa_base.h b/src/ipa/rpi/common/ipa_base.h
new file mode 100644
index 000000000000..6f9c46bb16b1
--- /dev/null
+++ b/src/ipa/rpi/common/ipa_base.h
@@ -0,0 +1,122 @@ 
+/* SPDX-License-Identifier: BSD-2-Clause */
+/*
+ * Copyright (C) 2023, Raspberry Pi Ltd
+ *
+ * ipa_base.h - Raspberry Pi IPA base class
+ */
+#pragma once
+
+#include <array>
+#include <deque>
+#include <map>
+#include <stdint.h>
+
+#include <libcamera/base/utils.h>
+#include <libcamera/controls.h>
+
+#include <libcamera/ipa/raspberrypi_ipa_interface.h>
+
+#include "libcamera/internal/mapped_framebuffer.h"
+
+#include "cam_helper/cam_helper.h"
+#include "controller/agc_status.h"
+#include "controller/camera_mode.h"
+#include "controller/controller.h"
+#include "controller/metadata.h"
+
+namespace libcamera {
+
+namespace ipa::RPi {
+
+class IpaBase : public IPARPiInterface
+{
+public:
+	IpaBase();
+	~IpaBase();
+
+	int32_t init(const IPASettings &settings, const InitParams &params, InitResult *result) override;
+	int32_t configure(const IPACameraSensorInfo &sensorInfo, const ConfigParams &params,
+			  ConfigResult *result) override;
+
+	void start(const ControlList &controls, StartResult *result) override;
+	void stop() override {}
+
+	void mapBuffers(const std::vector<IPABuffer> &buffers) override;
+	void unmapBuffers(const std::vector<unsigned int> &ids) override;
+
+	void prepareIsp(const PrepareParams &params) override;
+	void processStats(const ProcessParams &params) override;
+
+protected:
+	/* Raspberry Pi controller specific defines. */
+	std::unique_ptr<RPiController::CamHelper> helper_;
+	RPiController::Controller controller_;
+
+	ControlInfoMap sensorCtrls_;
+	ControlInfoMap lensCtrls_;
+
+	/* Camera sensor params. */
+	CameraMode mode_;
+
+	/* Track the frame length times over FrameLengthsQueueSize frames. */
+	std::deque<utils::Duration> frameLengths_;
+	utils::Duration lastTimeout_;
+
+private:
+	/* Number of metadata objects available in the context list. */
+	static constexpr unsigned int numMetadataContexts = 16;
+
+	virtual int32_t platformInit(const InitParams &params, InitResult *result) = 0;
+	virtual int32_t platformConfigure(const ConfigParams &params, ConfigResult *result) = 0;
+
+	virtual void platformPrepareIsp(const PrepareParams &params,
+					RPiController::Metadata &rpiMetadata) = 0;
+	virtual RPiController::StatisticsPtr platformProcessStats(Span<uint8_t> mem) = 0;
+
+	void setMode(const IPACameraSensorInfo &sensorInfo);
+	void setCameraTimeoutValue();
+	bool validateSensorControls();
+	bool validateLensControls();
+	void applyControls(const ControlList &controls);
+	virtual void handleControls(const ControlList &controls) = 0;
+	void fillDeviceStatus(const ControlList &sensorControls, unsigned int ipaContext);
+	void reportMetadata(unsigned int ipaContext);
+	void applyFrameDurations(utils::Duration minFrameDuration, utils::Duration maxFrameDuration);
+	void applyAGC(const struct AgcStatus *agcStatus, ControlList &ctrls);
+
+	std::map<unsigned int, MappedFrameBuffer> buffers_;
+
+	bool lensPresent_;
+	ControlList libcameraMetadata_;
+
+	std::array<RPiController::Metadata, numMetadataContexts> rpiMetadata_;
+
+	/*
+	 * We count frames to decide if the frame must be hidden (e.g. from
+	 * display) or mistrusted (i.e. not given to the control algos).
+	 */
+	uint64_t frameCount_;
+
+	/* How many frames we should avoid running control algos on. */
+	unsigned int mistrustCount_;
+
+	/* Number of frames that need to be dropped on startup. */
+	unsigned int dropFrameCount_;
+
+	/* Frame timestamp for the last run of the controller. */
+	uint64_t lastRunTimestamp_;
+
+	/* Do we run a Controller::process() for this frame? */
+	bool processPending_;
+
+	/* Distinguish the first camera start from others. */
+	bool firstStart_;
+
+	/* Frame duration (1/fps) limits. */
+	utils::Duration minFrameDuration_;
+	utils::Duration maxFrameDuration_;
+};
+
+} /* namespace ipa::RPi */
+
+} /* namespace libcamera */
diff --git a/src/ipa/rpi/common/meson.build b/src/ipa/rpi/common/meson.build
new file mode 100644
index 000000000000..73d2ee732339
--- /dev/null
+++ b/src/ipa/rpi/common/meson.build
@@ -0,0 +1,17 @@ 
+# SPDX-License-Identifier: CC0-1.0
+
+rpi_ipa_common_sources = files([
+    'ipa_base.cpp',
+])
+
+rpi_ipa_common_includes = [
+    include_directories('..'),
+]
+
+rpi_ipa_common_deps = [
+    libcamera_private,
+]
+
+rpi_ipa_common_lib = static_library('rpi_ipa_common', rpi_ipa_common_sources,
+                                    include_directories : rpi_ipa_common_includes,
+                                    dependencies : rpi_ipa_common_deps)
diff --git a/src/ipa/rpi/meson.build b/src/ipa/rpi/meson.build
index 7d7a61f7cea7..4811c76f3f9e 100644
--- a/src/ipa/rpi/meson.build
+++ b/src/ipa/rpi/meson.build
@@ -1,6 +1,7 @@ 
 # SPDX-License-Identifier: CC0-1.0
 
 subdir('cam_helper')
+subdir('common')
 subdir('controller')
 
 foreach pipeline : pipelines
diff --git a/src/ipa/rpi/vc4/meson.build b/src/ipa/rpi/vc4/meson.build
index cbd4dec62659..590e9197756d 100644
--- a/src/ipa/rpi/vc4/meson.build
+++ b/src/ipa/rpi/vc4/meson.build
@@ -9,6 +9,7 @@  vc4_ipa_deps = [
 
 vc4_ipa_libs = [
     rpi_ipa_cam_helper_lib,
+    rpi_ipa_common_lib,
     rpi_ipa_controller_lib
 ]
 
@@ -18,7 +19,7 @@  vc4_ipa_includes = [
 ]
 
 vc4_ipa_sources = files([
-    'raspberrypi.cpp',
+    'vc4.cpp',
 ])
 
 vc4_ipa_includes += include_directories('..')
@@ -45,4 +46,3 @@  endif
 subdir('data')
 
 ipa_names += ipa_name
-
diff --git a/src/ipa/rpi/vc4/vc4.cpp b/src/ipa/rpi/vc4/vc4.cpp
new file mode 100644
index 000000000000..a32db9bcaf9a
--- /dev/null
+++ b/src/ipa/rpi/vc4/vc4.cpp
@@ -0,0 +1,540 @@ 
+/* SPDX-License-Identifier: BSD-2-Clause */
+/*
+ * Copyright (C) 2019-2021, Raspberry Pi Ltd
+ *
+ * rpi.cpp - Raspberry Pi VC4/BCM2835 ISP IPA.
+ */
+
+#include <string.h>
+#include <sys/mman.h>
+
+#include <linux/bcm2835-isp.h>
+
+#include <libcamera/base/log.h>
+#include <libcamera/ipa/ipa_module_info.h>
+
+#include "common/ipa_base.h"
+#include "controller/af_status.h"
+#include "controller/agc_algorithm.h"
+#include "controller/alsc_status.h"
+#include "controller/awb_status.h"
+#include "controller/black_level_status.h"
+#include "controller/ccm_status.h"
+#include "controller/contrast_status.h"
+#include "controller/denoise_algorithm.h"
+#include "controller/denoise_status.h"
+#include "controller/dpc_status.h"
+#include "controller/geq_status.h"
+#include "controller/lux_status.h"
+#include "controller/noise_status.h"
+#include "controller/sharpen_status.h"
+
+namespace libcamera {
+
+LOG_DECLARE_CATEGORY(IPARPI)
+
+namespace ipa::RPi {
+
+class IpaVc4 final : public IpaBase
+{
+public:
+	IpaVc4()
+		: IpaBase(), lsTable_(nullptr)
+	{
+	}
+
+	~IpaVc4()
+	{
+		if (lsTable_)
+			munmap(lsTable_, MaxLsGridSize);
+	}
+
+private:
+	int32_t platformInit(const InitParams &params, InitResult *result) override;
+	int32_t platformConfigure(const ConfigParams &params, ConfigResult *result) override;
+
+	void platformPrepareIsp(const PrepareParams &params, RPiController::Metadata &rpiMetadata) override;
+	RPiController::StatisticsPtr platformProcessStats(Span<uint8_t> mem) override;
+
+	void handleControls(const ControlList &controls) override;
+	bool validateIspControls();
+
+	void applyAWB(const struct AwbStatus *awbStatus, ControlList &ctrls);
+	void applyDG(const struct AgcStatus *dgStatus, ControlList &ctrls);
+	void applyCCM(const struct CcmStatus *ccmStatus, ControlList &ctrls);
+	void applyBlackLevel(const struct BlackLevelStatus *blackLevelStatus, ControlList &ctrls);
+	void applyGamma(const struct ContrastStatus *contrastStatus, ControlList &ctrls);
+	void applyGEQ(const struct GeqStatus *geqStatus, ControlList &ctrls);
+	void applyDenoise(const struct DenoiseStatus *denoiseStatus, ControlList &ctrls);
+	void applySharpen(const struct SharpenStatus *sharpenStatus, ControlList &ctrls);
+	void applyDPC(const struct DpcStatus *dpcStatus, ControlList &ctrls);
+	void applyLS(const struct AlscStatus *lsStatus, ControlList &ctrls);
+	void applyAF(const struct AfStatus *afStatus, ControlList &lensCtrls);
+	void resampleTable(uint16_t dest[], const std::vector<double> &src, int destW, int destH);
+
+	/* VC4 ISP controls. */
+	ControlInfoMap ispCtrls_;
+
+	/* LS table allocation passed in from the pipeline handler. */
+	SharedFD lsTableHandle_;
+	void *lsTable_;
+};
+
+int32_t IpaVc4::platformInit([[maybe_unused]] const InitParams &params, [[maybe_unused]] InitResult *result)
+{
+	const std::string &target = controller_.getTarget();
+
+	if (target != "bcm2835") {
+		LOG(IPARPI, Error)
+			<< "Tuning data file target returned \"" << target << "\""
+			<< ", expected \"bcm2835\"";
+		return -EINVAL;
+	}
+
+	return 0;
+}
+
+int32_t IpaVc4::platformConfigure(const ConfigParams &params, [[maybe_unused]] ConfigResult *result)
+{
+	ispCtrls_ = params.ispControls;
+	if (!validateIspControls()) {
+		LOG(IPARPI, Error) << "ISP control validation failed.";
+		return -1;
+	}
+
+	/* Store the lens shading table pointer and handle if available. */
+	if (params.lsTableHandle.isValid()) {
+		/* Remove any previous table, if there was one. */
+		if (lsTable_) {
+			munmap(lsTable_, MaxLsGridSize);
+			lsTable_ = nullptr;
+		}
+
+		/* Map the LS table buffer into user space. */
+		lsTableHandle_ = std::move(params.lsTableHandle);
+		if (lsTableHandle_.isValid()) {
+			lsTable_ = mmap(nullptr, MaxLsGridSize, PROT_READ | PROT_WRITE,
+					MAP_SHARED, lsTableHandle_.get(), 0);
+
+			if (lsTable_ == MAP_FAILED) {
+				LOG(IPARPI, Error) << "dmaHeap mmap failure for LS table.";
+				lsTable_ = nullptr;
+			}
+		}
+	}
+
+	return 0;
+}
+
+void IpaVc4::platformPrepareIsp([[maybe_unused]] const PrepareParams &params,
+				RPiController::Metadata &rpiMetadata)
+{
+	ControlList ctrls(ispCtrls_);
+
+	/* Lock the metadata buffer to avoid constant locks/unlocks. */
+	std::unique_lock<RPiController::Metadata> lock(rpiMetadata);
+
+	AwbStatus *awbStatus = rpiMetadata.getLocked<AwbStatus>("awb.status");
+	if (awbStatus)
+		applyAWB(awbStatus, ctrls);
+
+	CcmStatus *ccmStatus = rpiMetadata.getLocked<CcmStatus>("ccm.status");
+	if (ccmStatus)
+		applyCCM(ccmStatus, ctrls);
+
+	AgcStatus *dgStatus = rpiMetadata.getLocked<AgcStatus>("agc.status");
+	if (dgStatus)
+		applyDG(dgStatus, ctrls);
+
+	AlscStatus *lsStatus = rpiMetadata.getLocked<AlscStatus>("alsc.status");
+	if (lsStatus)
+		applyLS(lsStatus, ctrls);
+
+	ContrastStatus *contrastStatus = rpiMetadata.getLocked<ContrastStatus>("contrast.status");
+	if (contrastStatus)
+		applyGamma(contrastStatus, ctrls);
+
+	BlackLevelStatus *blackLevelStatus = rpiMetadata.getLocked<BlackLevelStatus>("black_level.status");
+	if (blackLevelStatus)
+		applyBlackLevel(blackLevelStatus, ctrls);
+
+	GeqStatus *geqStatus = rpiMetadata.getLocked<GeqStatus>("geq.status");
+	if (geqStatus)
+		applyGEQ(geqStatus, ctrls);
+
+	DenoiseStatus *denoiseStatus = rpiMetadata.getLocked<DenoiseStatus>("denoise.status");
+	if (denoiseStatus)
+		applyDenoise(denoiseStatus, ctrls);
+
+	SharpenStatus *sharpenStatus = rpiMetadata.getLocked<SharpenStatus>("sharpen.status");
+	if (sharpenStatus)
+		applySharpen(sharpenStatus, ctrls);
+
+	DpcStatus *dpcStatus = rpiMetadata.getLocked<DpcStatus>("dpc.status");
+	if (dpcStatus)
+		applyDPC(dpcStatus, ctrls);
+
+	const AfStatus *afStatus = rpiMetadata.getLocked<AfStatus>("af.status");
+	if (afStatus) {
+		ControlList lensctrls(lensCtrls_);
+		applyAF(afStatus, lensctrls);
+		if (!lensctrls.empty())
+			setLensControls.emit(lensctrls);
+	}
+
+	if (!ctrls.empty())
+		setIspControls.emit(ctrls);
+}
+
+RPiController::StatisticsPtr IpaVc4::platformProcessStats(Span<uint8_t> mem)
+{
+	using namespace RPiController;
+
+	const bcm2835_isp_stats *stats = reinterpret_cast<bcm2835_isp_stats *>(mem.data());
+	StatisticsPtr statistics = std::make_unique<Statistics>(Statistics::AgcStatsPos::PreWb,
+								Statistics::ColourStatsPos::PostLsc);
+	const Controller::HardwareConfig &hw = controller_.getHardwareConfig();
+	unsigned int i;
+
+	/* RGB histograms are not used, so do not populate them. */
+	statistics->yHist = RPiController::Histogram(stats->hist[0].g_hist,
+						     hw.numHistogramBins);
+
+	/* All region sums are based on a 16-bit normalised pipeline bit-depth. */
+	unsigned int scale = Statistics::NormalisationFactorPow2 - hw.pipelineWidth;
+
+	statistics->awbRegions.init(hw.awbRegions);
+	for (i = 0; i < statistics->awbRegions.numRegions(); i++)
+		statistics->awbRegions.set(i, { { stats->awb_stats[i].r_sum << scale,
+						  stats->awb_stats[i].g_sum << scale,
+						  stats->awb_stats[i].b_sum << scale },
+						stats->awb_stats[i].counted,
+						stats->awb_stats[i].notcounted });
+
+	statistics->agcRegions.init(hw.agcRegions);
+	for (i = 0; i < statistics->agcRegions.numRegions(); i++)
+		statistics->agcRegions.set(i, { { stats->agc_stats[i].r_sum << scale,
+						  stats->agc_stats[i].g_sum << scale,
+						  stats->agc_stats[i].b_sum << scale },
+						stats->agc_stats[i].counted,
+						stats->awb_stats[i].notcounted });
+
+	statistics->focusRegions.init(hw.focusRegions);
+	for (i = 0; i < statistics->focusRegions.numRegions(); i++)
+		statistics->focusRegions.set(i, { stats->focus_stats[i].contrast_val[1][1] / 1000,
+						  stats->focus_stats[i].contrast_val_num[1][1],
+						  stats->focus_stats[i].contrast_val_num[1][0] });
+
+	return statistics;
+}
+
+void IpaVc4::handleControls([[maybe_unused]] const ControlList &controls)
+{
+	/* No controls require any special updates to the hardware configuration. */
+}
+
+bool IpaVc4::validateIspControls()
+{
+	static const uint32_t ctrls[] = {
+		V4L2_CID_RED_BALANCE,
+		V4L2_CID_BLUE_BALANCE,
+		V4L2_CID_DIGITAL_GAIN,
+		V4L2_CID_USER_BCM2835_ISP_CC_MATRIX,
+		V4L2_CID_USER_BCM2835_ISP_GAMMA,
+		V4L2_CID_USER_BCM2835_ISP_BLACK_LEVEL,
+		V4L2_CID_USER_BCM2835_ISP_GEQ,
+		V4L2_CID_USER_BCM2835_ISP_DENOISE,
+		V4L2_CID_USER_BCM2835_ISP_SHARPEN,
+		V4L2_CID_USER_BCM2835_ISP_DPC,
+		V4L2_CID_USER_BCM2835_ISP_LENS_SHADING,
+		V4L2_CID_USER_BCM2835_ISP_CDN,
+	};
+
+	for (auto c : ctrls) {
+		if (ispCtrls_.find(c) == ispCtrls_.end()) {
+			LOG(IPARPI, Error) << "Unable to find ISP control "
+					   << utils::hex(c);
+			return false;
+		}
+	}
+
+	return true;
+}
+
+void IpaVc4::applyAWB(const struct AwbStatus *awbStatus, ControlList &ctrls)
+{
+	LOG(IPARPI, Debug) << "Applying WB R: " << awbStatus->gainR << " B: "
+			   << awbStatus->gainB;
+
+	ctrls.set(V4L2_CID_RED_BALANCE,
+		  static_cast<int32_t>(awbStatus->gainR * 1000));
+	ctrls.set(V4L2_CID_BLUE_BALANCE,
+		  static_cast<int32_t>(awbStatus->gainB * 1000));
+}
+
+void IpaVc4::applyDG(const struct AgcStatus *dgStatus, ControlList &ctrls)
+{
+	ctrls.set(V4L2_CID_DIGITAL_GAIN,
+		  static_cast<int32_t>(dgStatus->digitalGain * 1000));
+}
+
+void IpaVc4::applyCCM(const struct CcmStatus *ccmStatus, ControlList &ctrls)
+{
+	bcm2835_isp_custom_ccm ccm;
+
+	for (int i = 0; i < 9; i++) {
+		ccm.ccm.ccm[i / 3][i % 3].den = 1000;
+		ccm.ccm.ccm[i / 3][i % 3].num = 1000 * ccmStatus->matrix[i];
+	}
+
+	ccm.enabled = 1;
+	ccm.ccm.offsets[0] = ccm.ccm.offsets[1] = ccm.ccm.offsets[2] = 0;
+
+	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&ccm),
+					    sizeof(ccm) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_CC_MATRIX, c);
+}
+
+void IpaVc4::applyBlackLevel(const struct BlackLevelStatus *blackLevelStatus, ControlList &ctrls)
+{
+	bcm2835_isp_black_level blackLevel;
+
+	blackLevel.enabled = 1;
+	blackLevel.black_level_r = blackLevelStatus->blackLevelR;
+	blackLevel.black_level_g = blackLevelStatus->blackLevelG;
+	blackLevel.black_level_b = blackLevelStatus->blackLevelB;
+
+	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&blackLevel),
+					    sizeof(blackLevel) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_BLACK_LEVEL, c);
+}
+
+void IpaVc4::applyGamma(const struct ContrastStatus *contrastStatus, ControlList &ctrls)
+{
+	const unsigned int numGammaPoints = controller_.getHardwareConfig().numGammaPoints;
+	struct bcm2835_isp_gamma gamma;
+
+	for (unsigned int i = 0; i < numGammaPoints - 1; i++) {
+		int x = i < 16 ? i * 1024
+			       : (i < 24 ? (i - 16) * 2048 + 16384
+					 : (i - 24) * 4096 + 32768);
+		gamma.x[i] = x;
+		gamma.y[i] = std::min<uint16_t>(65535, contrastStatus->gammaCurve.eval(x));
+	}
+
+	gamma.x[numGammaPoints - 1] = 65535;
+	gamma.y[numGammaPoints - 1] = 65535;
+	gamma.enabled = 1;
+
+	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&gamma),
+					    sizeof(gamma) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_GAMMA, c);
+}
+
+void IpaVc4::applyGEQ(const struct GeqStatus *geqStatus, ControlList &ctrls)
+{
+	bcm2835_isp_geq geq;
+
+	geq.enabled = 1;
+	geq.offset = geqStatus->offset;
+	geq.slope.den = 1000;
+	geq.slope.num = 1000 * geqStatus->slope;
+
+	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&geq),
+					    sizeof(geq) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_GEQ, c);
+}
+
+void IpaVc4::applyDenoise(const struct DenoiseStatus *denoiseStatus, ControlList &ctrls)
+{
+	using RPiController::DenoiseMode;
+
+	bcm2835_isp_denoise denoise;
+	DenoiseMode mode = static_cast<DenoiseMode>(denoiseStatus->mode);
+
+	denoise.enabled = mode != DenoiseMode::Off;
+	denoise.constant = denoiseStatus->noiseConstant;
+	denoise.slope.num = 1000 * denoiseStatus->noiseSlope;
+	denoise.slope.den = 1000;
+	denoise.strength.num = 1000 * denoiseStatus->strength;
+	denoise.strength.den = 1000;
+
+	/* Set the CDN mode to match the SDN operating mode. */
+	bcm2835_isp_cdn cdn;
+	switch (mode) {
+	case DenoiseMode::ColourFast:
+		cdn.enabled = 1;
+		cdn.mode = CDN_MODE_FAST;
+		break;
+	case DenoiseMode::ColourHighQuality:
+		cdn.enabled = 1;
+		cdn.mode = CDN_MODE_HIGH_QUALITY;
+		break;
+	default:
+		cdn.enabled = 0;
+	}
+
+	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&denoise),
+					    sizeof(denoise) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_DENOISE, c);
+
+	c = ControlValue(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&cdn),
+					      sizeof(cdn) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_CDN, c);
+}
+
+void IpaVc4::applySharpen(const struct SharpenStatus *sharpenStatus, ControlList &ctrls)
+{
+	bcm2835_isp_sharpen sharpen;
+
+	sharpen.enabled = 1;
+	sharpen.threshold.num = 1000 * sharpenStatus->threshold;
+	sharpen.threshold.den = 1000;
+	sharpen.strength.num = 1000 * sharpenStatus->strength;
+	sharpen.strength.den = 1000;
+	sharpen.limit.num = 1000 * sharpenStatus->limit;
+	sharpen.limit.den = 1000;
+
+	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&sharpen),
+					    sizeof(sharpen) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_SHARPEN, c);
+}
+
+void IpaVc4::applyDPC(const struct DpcStatus *dpcStatus, ControlList &ctrls)
+{
+	bcm2835_isp_dpc dpc;
+
+	dpc.enabled = 1;
+	dpc.strength = dpcStatus->strength;
+
+	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&dpc),
+					    sizeof(dpc) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_DPC, c);
+}
+
+void IpaVc4::applyLS(const struct AlscStatus *lsStatus, ControlList &ctrls)
+{
+	/*
+	 * Program lens shading tables into pipeline.
+	 * Choose smallest cell size that won't exceed 63x48 cells.
+	 */
+	const int cellSizes[] = { 16, 32, 64, 128, 256 };
+	unsigned int numCells = std::size(cellSizes);
+	unsigned int i, w, h, cellSize;
+	for (i = 0; i < numCells; i++) {
+		cellSize = cellSizes[i];
+		w = (mode_.width + cellSize - 1) / cellSize;
+		h = (mode_.height + cellSize - 1) / cellSize;
+		if (w < 64 && h <= 48)
+			break;
+	}
+
+	if (i == numCells) {
+		LOG(IPARPI, Error) << "Cannot find cell size";
+		return;
+	}
+
+	/* We're going to supply corner sampled tables, 16 bit samples. */
+	w++, h++;
+	bcm2835_isp_lens_shading ls = {
+		.enabled = 1,
+		.grid_cell_size = cellSize,
+		.grid_width = w,
+		.grid_stride = w,
+		.grid_height = h,
+		/* .dmabuf will be filled in by pipeline handler. */
+		.dmabuf = 0,
+		.ref_transform = 0,
+		.corner_sampled = 1,
+		.gain_format = GAIN_FORMAT_U4P10
+	};
+
+	if (!lsTable_ || w * h * 4 * sizeof(uint16_t) > MaxLsGridSize) {
+		LOG(IPARPI, Error) << "Do not have a correctly allocate lens shading table!";
+		return;
+	}
+
+	if (lsStatus) {
+		/* Format will be u4.10 */
+		uint16_t *grid = static_cast<uint16_t *>(lsTable_);
+
+		resampleTable(grid, lsStatus->r, w, h);
+		resampleTable(grid + w * h, lsStatus->g, w, h);
+		memcpy(grid + 2 * w * h, grid + w * h, w * h * sizeof(uint16_t));
+		resampleTable(grid + 3 * w * h, lsStatus->b, w, h);
+	}
+
+	ControlValue c(Span<const uint8_t>{ reinterpret_cast<uint8_t *>(&ls),
+					    sizeof(ls) });
+	ctrls.set(V4L2_CID_USER_BCM2835_ISP_LENS_SHADING, c);
+}
+
+void IpaVc4::applyAF(const struct AfStatus *afStatus, ControlList &lensCtrls)
+{
+	if (afStatus->lensSetting) {
+		ControlValue v(afStatus->lensSetting.value());
+		lensCtrls.set(V4L2_CID_FOCUS_ABSOLUTE, v);
+	}
+}
+
+/*
+ * Resamples a 16x12 table with central sampling to destW x destH with corner
+ * sampling.
+ */
+void IpaVc4::resampleTable(uint16_t dest[], const std::vector<double> &src,
+			   int destW, int destH)
+{
+	/*
+	 * Precalculate and cache the x sampling locations and phases to
+	 * save recomputing them on every row.
+	 */
+	assert(destW > 1 && destH > 1 && destW <= 64);
+	int xLo[64], xHi[64];
+	double xf[64];
+	double x = -0.5, xInc = 16.0 / (destW - 1);
+	for (int i = 0; i < destW; i++, x += xInc) {
+		xLo[i] = floor(x);
+		xf[i] = x - xLo[i];
+		xHi[i] = xLo[i] < 15 ? xLo[i] + 1 : 15;
+		xLo[i] = xLo[i] > 0 ? xLo[i] : 0;
+	}
+
+	/* Now march over the output table generating the new values. */
+	double y = -0.5, yInc = 12.0 / (destH - 1);
+	for (int j = 0; j < destH; j++, y += yInc) {
+		int yLo = floor(y);
+		double yf = y - yLo;
+		int yHi = yLo < 11 ? yLo + 1 : 11;
+		yLo = yLo > 0 ? yLo : 0;
+		double const *rowAbove = src.data() + yLo * 16;
+		double const *rowBelow = src.data() + yHi * 16;
+		for (int i = 0; i < destW; i++) {
+			double above = rowAbove[xLo[i]] * (1 - xf[i]) + rowAbove[xHi[i]] * xf[i];
+			double below = rowBelow[xLo[i]] * (1 - xf[i]) + rowBelow[xHi[i]] * xf[i];
+			int result = floor(1024 * (above * (1 - yf) + below * yf) + .5);
+			*(dest++) = result > 16383 ? 16383 : result; /* want u4.10 */
+		}
+	}
+}
+
+} /* namespace ipa::RPi */
+
+/*
+ * External IPA module interface
+ */
+extern "C" {
+const struct IPAModuleInfo ipaModuleInfo = {
+	IPA_MODULE_API_VERSION,
+	1,
+	"PipelineHandlerRPi",
+	"rpi/vc4",
+};
+
+IPAInterface *ipaCreate()
+{
+	return new ipa::RPi::IpaVc4();
+}
+
+} /* extern "C" */
+
+} /* namespace libcamera */