Refresh them with the patches from https://patchwork.libcamera.org/cover/19663/. This is still based off v0.2.0. Change-Id: I875fd64e3bb71a95c92af1108a23d27c0f3494e0 Reviewed-on: https://cl.tvl.fyi/c/depot/+/11179 Tested-by: BuildkiteCI Reviewed-by: flokli <flokli@flokli.de> Autosubmit: flokli <flokli@flokli.de>
		
			
				
	
	
		
			203 lines
		
	
	
	
		
			5.6 KiB
		
	
	
	
		
			Diff
		
	
	
	
	
	
			
		
		
	
	
			203 lines
		
	
	
	
		
			5.6 KiB
		
	
	
	
		
			Diff
		
	
	
	
	
	
| From aabc53453d542495d9da25411f57308c01f2bc28 Mon Sep 17 00:00:00 2001
 | |
| From: Hans de Goede <hdegoede@redhat.com>
 | |
| Date: Mon, 11 Mar 2024 15:15:17 +0100
 | |
| Subject: [PATCH 13/21] libcamera: swstats_cpu: Add support for 8, 10 and 12
 | |
|  bpp unpacked bayer input
 | |
| 
 | |
| Add support for 8, 10 and 12 bpp unpacked bayer input for all 4 standard
 | |
| bayer orders.
 | |
| 
 | |
| Tested-by: Bryan O'Donoghue <bryan.odonoghue@linaro.org> # sc8280xp Lenovo x13s
 | |
| Tested-by: Pavel Machek <pavel@ucw.cz>
 | |
| Reviewed-by: Pavel Machek <pavel@ucw.cz>
 | |
| Reviewed-by: Milan Zamazal <mzamazal@redhat.com>
 | |
| Signed-off-by: Kieran Bingham <kieran.bingham@ideasonboard.com>
 | |
| Signed-off-by: Hans de Goede <hdegoede@redhat.com>
 | |
| ---
 | |
|  src/libcamera/software_isp/swstats_cpu.cpp | 128 +++++++++++++++++++++
 | |
|  src/libcamera/software_isp/swstats_cpu.h   |   9 ++
 | |
|  2 files changed, 137 insertions(+)
 | |
| 
 | |
| diff --git a/src/libcamera/software_isp/swstats_cpu.cpp b/src/libcamera/software_isp/swstats_cpu.cpp
 | |
| index 448d0e4c..be310f56 100644
 | |
| --- a/src/libcamera/software_isp/swstats_cpu.cpp
 | |
| +++ b/src/libcamera/software_isp/swstats_cpu.cpp
 | |
| @@ -71,6 +71,83 @@ static const unsigned int kBlueYMul = 29; /* 0.114 * 256 */
 | |
|  	stats_.sumG_ += sumG;       \
 | |
|  	stats_.sumB_ += sumB;
 | |
|  
 | |
| +void SwStatsCpu::statsBGGR8Line0(const uint8_t *src[])
 | |
| +{
 | |
| +	const uint8_t *src0 = src[1] + window_.x;
 | |
| +	const uint8_t *src1 = src[2] + window_.x;
 | |
| +
 | |
| +	SWSTATS_START_LINE_STATS(uint8_t)
 | |
| +
 | |
| +	if (swapLines_)
 | |
| +		std::swap(src0, src1);
 | |
| +
 | |
| +	/* x += 4 sample every other 2x2 block */
 | |
| +	for (int x = 0; x < (int)window_.width; x += 4) {
 | |
| +		b = src0[x];
 | |
| +		g = src0[x + 1];
 | |
| +		g2 = src1[x];
 | |
| +		r = src1[x + 1];
 | |
| +
 | |
| +		g = (g + g2) / 2;
 | |
| +
 | |
| +		SWSTATS_ACCUMULATE_LINE_STATS(1)
 | |
| +	}
 | |
| +
 | |
| +	SWSTATS_FINISH_LINE_STATS()
 | |
| +}
 | |
| +
 | |
| +void SwStatsCpu::statsBGGR10Line0(const uint8_t *src[])
 | |
| +{
 | |
| +	const uint16_t *src0 = (const uint16_t *)src[1] + window_.x;
 | |
| +	const uint16_t *src1 = (const uint16_t *)src[2] + window_.x;
 | |
| +
 | |
| +	SWSTATS_START_LINE_STATS(uint16_t)
 | |
| +
 | |
| +	if (swapLines_)
 | |
| +		std::swap(src0, src1);
 | |
| +
 | |
| +	/* x += 4 sample every other 2x2 block */
 | |
| +	for (int x = 0; x < (int)window_.width; x += 4) {
 | |
| +		b = src0[x];
 | |
| +		g = src0[x + 1];
 | |
| +		g2 = src1[x];
 | |
| +		r = src1[x + 1];
 | |
| +
 | |
| +		g = (g + g2) / 2;
 | |
| +
 | |
| +		/* divide Y by 4 for 10 -> 8 bpp value */
 | |
| +		SWSTATS_ACCUMULATE_LINE_STATS(4)
 | |
| +	}
 | |
| +
 | |
| +	SWSTATS_FINISH_LINE_STATS()
 | |
| +}
 | |
| +
 | |
| +void SwStatsCpu::statsBGGR12Line0(const uint8_t *src[])
 | |
| +{
 | |
| +	const uint16_t *src0 = (const uint16_t *)src[1] + window_.x;
 | |
| +	const uint16_t *src1 = (const uint16_t *)src[2] + window_.x;
 | |
| +
 | |
| +	SWSTATS_START_LINE_STATS(uint16_t)
 | |
| +
 | |
| +	if (swapLines_)
 | |
| +		std::swap(src0, src1);
 | |
| +
 | |
| +	/* x += 4 sample every other 2x2 block */
 | |
| +	for (int x = 0; x < (int)window_.width; x += 4) {
 | |
| +		b = src0[x];
 | |
| +		g = src0[x + 1];
 | |
| +		g2 = src1[x];
 | |
| +		r = src1[x + 1];
 | |
| +
 | |
| +		g = (g + g2) / 2;
 | |
| +
 | |
| +		/* divide Y by 16 for 12 -> 8 bpp value */
 | |
| +		SWSTATS_ACCUMULATE_LINE_STATS(16)
 | |
| +	}
 | |
| +
 | |
| +	SWSTATS_FINISH_LINE_STATS()
 | |
| +}
 | |
| +
 | |
|  void SwStatsCpu::statsBGGR10PLine0(const uint8_t *src[])
 | |
|  {
 | |
|  	const uint8_t *src0 = src[1] + window_.x * 5 / 4;
 | |
| @@ -147,6 +224,42 @@ void SwStatsCpu::finishFrame(void)
 | |
|  	statsReady.emit(0);
 | |
|  }
 | |
|  
 | |
| +/**
 | |
| + * \brief Setup SwStatsCpu object for standard Bayer orders
 | |
| + * \param[in] order The Bayer order
 | |
| + *
 | |
| + * Check if order is a standard Bayer order and setup xShift_ and swapLines_
 | |
| + * so that a single BGGR stats function can be used for all 4 standard orders.
 | |
| + */
 | |
| +int SwStatsCpu::setupStandardBayerOrder(BayerFormat::Order order)
 | |
| +{
 | |
| +	switch (order) {
 | |
| +	case BayerFormat::BGGR:
 | |
| +		xShift_ = 0;
 | |
| +		swapLines_ = false;
 | |
| +		break;
 | |
| +	case BayerFormat::GBRG:
 | |
| +		xShift_ = 1; /* BGGR -> GBRG */
 | |
| +		swapLines_ = false;
 | |
| +		break;
 | |
| +	case BayerFormat::GRBG:
 | |
| +		xShift_ = 0;
 | |
| +		swapLines_ = true; /* BGGR -> GRBG */
 | |
| +		break;
 | |
| +	case BayerFormat::RGGB:
 | |
| +		xShift_ = 1; /* BGGR -> GBRG */
 | |
| +		swapLines_ = true; /* GBRG -> RGGB */
 | |
| +		break;
 | |
| +	default:
 | |
| +		return -EINVAL;
 | |
| +	}
 | |
| +
 | |
| +	patternSize_.height = 2;
 | |
| +	patternSize_.width = 2;
 | |
| +	ySkipMask_ = 0x02; /* Skip every 3th and 4th line */
 | |
| +	return 0;
 | |
| +}
 | |
| +
 | |
|  /**
 | |
|   * \brief Configure the statistics object for the passed in input format.
 | |
|   * \param[in] inputCfg The input format
 | |
| @@ -158,6 +271,21 @@ int SwStatsCpu::configure(const StreamConfiguration &inputCfg)
 | |
|  	BayerFormat bayerFormat =
 | |
|  		BayerFormat::fromPixelFormat(inputCfg.pixelFormat);
 | |
|  
 | |
| +	if (bayerFormat.packing == BayerFormat::Packing::None &&
 | |
| +	    setupStandardBayerOrder(bayerFormat.order) == 0) {
 | |
| +		switch (bayerFormat.bitDepth) {
 | |
| +		case 8:
 | |
| +			stats0_ = &SwStatsCpu::statsBGGR8Line0;
 | |
| +			return 0;
 | |
| +		case 10:
 | |
| +			stats0_ = &SwStatsCpu::statsBGGR10Line0;
 | |
| +			return 0;
 | |
| +		case 12:
 | |
| +			stats0_ = &SwStatsCpu::statsBGGR12Line0;
 | |
| +			return 0;
 | |
| +		}
 | |
| +	}
 | |
| +
 | |
|  	if (bayerFormat.bitDepth == 10 &&
 | |
|  	    bayerFormat.packing == BayerFormat::Packing::CSI2) {
 | |
|  		patternSize_.height = 2;
 | |
| diff --git a/src/libcamera/software_isp/swstats_cpu.h b/src/libcamera/software_isp/swstats_cpu.h
 | |
| index 0ac9ae71..bbbcf69b 100644
 | |
| --- a/src/libcamera/software_isp/swstats_cpu.h
 | |
| +++ b/src/libcamera/software_isp/swstats_cpu.h
 | |
| @@ -17,6 +17,7 @@
 | |
|  
 | |
|  #include <libcamera/geometry.h>
 | |
|  
 | |
| +#include "libcamera/internal/bayer_format.h"
 | |
|  #include "libcamera/internal/shared_mem_object.h"
 | |
|  #include "libcamera/internal/software_isp/swisp_stats.h"
 | |
|  
 | |
| @@ -120,6 +121,14 @@ private:
 | |
|  	 */
 | |
|  	using statsProcessFn = void (SwStatsCpu::*)(const uint8_t *src[]);
 | |
|  
 | |
| +	int setupStandardBayerOrder(BayerFormat::Order order);
 | |
| +	/* Bayer 8 bpp unpacked */
 | |
| +	void statsBGGR8Line0(const uint8_t *src[]);
 | |
| +	/* Bayer 10 bpp unpacked */
 | |
| +	void statsBGGR10Line0(const uint8_t *src[]);
 | |
| +	/* Bayer 12 bpp unpacked */
 | |
| +	void statsBGGR12Line0(const uint8_t *src[]);
 | |
| +	/* Bayer 10 bpp packed */
 | |
|  	void statsBGGR10PLine0(const uint8_t *src[]);
 | |
|  	void statsGBRG10PLine0(const uint8_t *src[]);
 | |
|  
 | |
| -- 
 | |
| 2.43.2
 | |
| 
 |