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>
		
			
				
	
	
		
			350 lines
		
	
	
	
		
			9.3 KiB
		
	
	
	
		
			Diff
		
	
	
	
	
	
			
		
		
	
	
			350 lines
		
	
	
	
		
			9.3 KiB
		
	
	
	
		
			Diff
		
	
	
	
	
	
| From 96e50c6a43352a9cb81d558fea27e580f2b26585 Mon Sep 17 00:00:00 2001
 | |
| From: Andrey Konovalov <andrey.konovalov@linaro.org>
 | |
| Date: Mon, 11 Mar 2024 15:15:06 +0100
 | |
| Subject: [PATCH 02/21] libcamera: internal: Move dma_heaps.[h, cpp] to common
 | |
|  directories
 | |
| 
 | |
| DmaHeap class is useful outside the RPi pipeline handler too.
 | |
| 
 | |
| Move dma_heaps.h and dma_heaps.cpp to common directories. Update
 | |
| the build files and RPi vc4 pipeline handler accordingly.
 | |
| 
 | |
| Tested-by: Bryan O'Donoghue <bryan.odonoghue@linaro.org> # sc8280xp Lenovo x13s
 | |
| Tested-by: Pavel Machek <pavel@ucw.cz>
 | |
| Reviewed-by: Kieran Bingham <kieran.bingham@ideasonboard.com>
 | |
| Reviewed-by: Naushir Patuck <naush@raspberrypi.com>
 | |
| Reviewed-by: Pavel Machek <pavel@ucw.cz>
 | |
| Signed-off-by: Andrey Konovalov <andrey.konovalov@linaro.org>
 | |
| Signed-off-by: Hans de Goede <hdegoede@redhat.com>
 | |
| Reviewed-by: Milan Zamazal <mzamazal@redhat.com>
 | |
| ---
 | |
|  .../libcamera/internal}/dma_heaps.h           |   4 -
 | |
|  include/libcamera/internal/meson.build        |   1 +
 | |
|  src/libcamera/dma_heaps.cpp                   | 127 ++++++++++++++++++
 | |
|  src/libcamera/meson.build                     |   1 +
 | |
|  src/libcamera/pipeline/rpi/vc4/dma_heaps.cpp  |  90 -------------
 | |
|  src/libcamera/pipeline/rpi/vc4/meson.build    |   1 -
 | |
|  src/libcamera/pipeline/rpi/vc4/vc4.cpp        |   5 +-
 | |
|  7 files changed, 131 insertions(+), 98 deletions(-)
 | |
|  rename {src/libcamera/pipeline/rpi/vc4 => include/libcamera/internal}/dma_heaps.h (92%)
 | |
|  create mode 100644 src/libcamera/dma_heaps.cpp
 | |
|  delete mode 100644 src/libcamera/pipeline/rpi/vc4/dma_heaps.cpp
 | |
| 
 | |
| diff --git a/src/libcamera/pipeline/rpi/vc4/dma_heaps.h b/include/libcamera/internal/dma_heaps.h
 | |
| similarity index 92%
 | |
| rename from src/libcamera/pipeline/rpi/vc4/dma_heaps.h
 | |
| rename to include/libcamera/internal/dma_heaps.h
 | |
| index 0a4a8d86..cff8f140 100644
 | |
| --- a/src/libcamera/pipeline/rpi/vc4/dma_heaps.h
 | |
| +++ b/include/libcamera/internal/dma_heaps.h
 | |
| @@ -13,8 +13,6 @@
 | |
|  
 | |
|  namespace libcamera {
 | |
|  
 | |
| -namespace RPi {
 | |
| -
 | |
|  class DmaHeap
 | |
|  {
 | |
|  public:
 | |
| @@ -27,6 +25,4 @@ private:
 | |
|  	UniqueFD dmaHeapHandle_;
 | |
|  };
 | |
|  
 | |
| -} /* namespace RPi */
 | |
| -
 | |
|  } /* namespace libcamera */
 | |
| diff --git a/include/libcamera/internal/meson.build b/include/libcamera/internal/meson.build
 | |
| index 7f1f3440..33eb0fb3 100644
 | |
| --- a/include/libcamera/internal/meson.build
 | |
| +++ b/include/libcamera/internal/meson.build
 | |
| @@ -25,6 +25,7 @@ libcamera_internal_headers = files([
 | |
|      'device_enumerator.h',
 | |
|      'device_enumerator_sysfs.h',
 | |
|      'device_enumerator_udev.h',
 | |
| +    'dma_heaps.h',
 | |
|      'formats.h',
 | |
|      'framebuffer.h',
 | |
|      'ipa_manager.h',
 | |
| diff --git a/src/libcamera/dma_heaps.cpp b/src/libcamera/dma_heaps.cpp
 | |
| new file mode 100644
 | |
| index 00000000..38ef175a
 | |
| --- /dev/null
 | |
| +++ b/src/libcamera/dma_heaps.cpp
 | |
| @@ -0,0 +1,127 @@
 | |
| +/* SPDX-License-Identifier: LGPL-2.1-or-later */
 | |
| +/*
 | |
| + * Copyright (C) 2020, Raspberry Pi Ltd
 | |
| + *
 | |
| + * dma_heaps.h - Helper class for dma-heap allocations.
 | |
| + */
 | |
| +
 | |
| +#include "libcamera/internal/dma_heaps.h"
 | |
| +
 | |
| +#include <array>
 | |
| +#include <fcntl.h>
 | |
| +#include <sys/ioctl.h>
 | |
| +#include <unistd.h>
 | |
| +
 | |
| +#include <linux/dma-buf.h>
 | |
| +#include <linux/dma-heap.h>
 | |
| +
 | |
| +#include <libcamera/base/log.h>
 | |
| +
 | |
| +/**
 | |
| + * \file dma_heaps.cpp
 | |
| + * \brief CMA dma-heap allocator
 | |
| + */
 | |
| +
 | |
| +/*
 | |
| + * /dev/dma_heap/linux,cma is the dma-heap allocator, which allows dmaheap-cma
 | |
| + * to only have to worry about importing.
 | |
| + *
 | |
| + * Annoyingly, should the cma heap size be specified on the kernel command line
 | |
| + * instead of DT, the heap gets named "reserved" instead.
 | |
| + */
 | |
| +static constexpr std::array<const char *, 2> heapNames = {
 | |
| +	"/dev/dma_heap/linux,cma",
 | |
| +	"/dev/dma_heap/reserved"
 | |
| +};
 | |
| +
 | |
| +namespace libcamera {
 | |
| +
 | |
| +LOG_DEFINE_CATEGORY(DmaHeap)
 | |
| +
 | |
| +/**
 | |
| + * \class DmaHeap
 | |
| + * \brief Helper class for CMA dma-heap allocations
 | |
| + */
 | |
| +
 | |
| +/**
 | |
| + * \brief Construct a DmaHeap that owns a CMA dma-heap file descriptor
 | |
| + *
 | |
| + * Goes through the internal list of possible names of the CMA dma-heap devices
 | |
| + * until a CMA dma-heap device is successfully opened. If it fails to open any
 | |
| + * dma-heap device, an invalid DmaHeap object is constructed. A valid DmaHeap
 | |
| + * object owns a wrapped dma-heap file descriptor.
 | |
| + *
 | |
| + * Please check the new DmaHeap object with \ref DmaHeap::isValid before using it.
 | |
| + */
 | |
| +DmaHeap::DmaHeap()
 | |
| +{
 | |
| +	for (const char *name : heapNames) {
 | |
| +		int ret = ::open(name, O_RDWR | O_CLOEXEC, 0);
 | |
| +		if (ret < 0) {
 | |
| +			ret = errno;
 | |
| +			LOG(DmaHeap, Debug)
 | |
| +				<< "Failed to open " << name << ": "
 | |
| +				<< strerror(ret);
 | |
| +			continue;
 | |
| +		}
 | |
| +
 | |
| +		dmaHeapHandle_ = UniqueFD(ret);
 | |
| +		break;
 | |
| +	}
 | |
| +
 | |
| +	if (!dmaHeapHandle_.isValid())
 | |
| +		LOG(DmaHeap, Error) << "Could not open any dmaHeap device";
 | |
| +}
 | |
| +
 | |
| +/**
 | |
| + * \brief Destroy the DmaHeap instance
 | |
| + *
 | |
| + * Destroying a DmaHeap instance which owns a wrapped dma-heap file descriptor
 | |
| + * closes the descriptor automatically.
 | |
| + */
 | |
| +DmaHeap::~DmaHeap() = default;
 | |
| +
 | |
| +/**
 | |
| + * \fn DmaHeap::isValid()
 | |
| + * \brief Check if the DmaHeap instance is valid
 | |
| + * \return True if the DmaHeap is valid, false otherwise
 | |
| + */
 | |
| +
 | |
| +/**
 | |
| + * \brief Allocate a dma-buf from the DmaHeap
 | |
| + * \param [in] name The name to set for the allocated buffer
 | |
| + * \param [in] size The size of the buffer to allocate
 | |
| + * \return The \ref UniqueFD of the allocated buffer
 | |
| + *
 | |
| + * Allocates a dma-buf with read/write access.
 | |
| + * If the allocation fails returns invalid UniqueFD.
 | |
| + */
 | |
| +UniqueFD DmaHeap::alloc(const char *name, std::size_t size)
 | |
| +{
 | |
| +	int ret;
 | |
| +
 | |
| +	if (!name)
 | |
| +		return {};
 | |
| +
 | |
| +	struct dma_heap_allocation_data alloc = {};
 | |
| +
 | |
| +	alloc.len = size;
 | |
| +	alloc.fd_flags = O_CLOEXEC | O_RDWR;
 | |
| +
 | |
| +	ret = ::ioctl(dmaHeapHandle_.get(), DMA_HEAP_IOCTL_ALLOC, &alloc);
 | |
| +	if (ret < 0) {
 | |
| +		LOG(DmaHeap, Error) << "dmaHeap allocation failure for " << name;
 | |
| +		return {};
 | |
| +	}
 | |
| +
 | |
| +	UniqueFD allocFd(alloc.fd);
 | |
| +	ret = ::ioctl(allocFd.get(), DMA_BUF_SET_NAME, name);
 | |
| +	if (ret < 0) {
 | |
| +		LOG(DmaHeap, Error) << "dmaHeap naming failure for " << name;
 | |
| +		return {};
 | |
| +	}
 | |
| +
 | |
| +	return allocFd;
 | |
| +}
 | |
| +
 | |
| +} /* namespace libcamera */
 | |
| diff --git a/src/libcamera/meson.build b/src/libcamera/meson.build
 | |
| index 45f63e93..3c5e43df 100644
 | |
| --- a/src/libcamera/meson.build
 | |
| +++ b/src/libcamera/meson.build
 | |
| @@ -17,6 +17,7 @@ libcamera_sources = files([
 | |
|      'delayed_controls.cpp',
 | |
|      'device_enumerator.cpp',
 | |
|      'device_enumerator_sysfs.cpp',
 | |
| +    'dma_heaps.cpp',
 | |
|      'fence.cpp',
 | |
|      'formats.cpp',
 | |
|      'framebuffer.cpp',
 | |
| diff --git a/src/libcamera/pipeline/rpi/vc4/dma_heaps.cpp b/src/libcamera/pipeline/rpi/vc4/dma_heaps.cpp
 | |
| deleted file mode 100644
 | |
| index 317b1fc1..00000000
 | |
| --- a/src/libcamera/pipeline/rpi/vc4/dma_heaps.cpp
 | |
| +++ /dev/null
 | |
| @@ -1,90 +0,0 @@
 | |
| -/* SPDX-License-Identifier: LGPL-2.1-or-later */
 | |
| -/*
 | |
| - * Copyright (C) 2020, Raspberry Pi Ltd
 | |
| - *
 | |
| - * dma_heaps.h - Helper class for dma-heap allocations.
 | |
| - */
 | |
| -
 | |
| -#include "dma_heaps.h"
 | |
| -
 | |
| -#include <array>
 | |
| -#include <fcntl.h>
 | |
| -#include <linux/dma-buf.h>
 | |
| -#include <linux/dma-heap.h>
 | |
| -#include <sys/ioctl.h>
 | |
| -#include <unistd.h>
 | |
| -
 | |
| -#include <libcamera/base/log.h>
 | |
| -
 | |
| -/*
 | |
| - * /dev/dma-heap/linux,cma is the dma-heap allocator, which allows dmaheap-cma
 | |
| - * to only have to worry about importing.
 | |
| - *
 | |
| - * Annoyingly, should the cma heap size be specified on the kernel command line
 | |
| - * instead of DT, the heap gets named "reserved" instead.
 | |
| - */
 | |
| -static constexpr std::array<const char *, 2> heapNames = {
 | |
| -	"/dev/dma_heap/linux,cma",
 | |
| -	"/dev/dma_heap/reserved"
 | |
| -};
 | |
| -
 | |
| -namespace libcamera {
 | |
| -
 | |
| -LOG_DECLARE_CATEGORY(RPI)
 | |
| -
 | |
| -namespace RPi {
 | |
| -
 | |
| -DmaHeap::DmaHeap()
 | |
| -{
 | |
| -	for (const char *name : heapNames) {
 | |
| -		int ret = ::open(name, O_RDWR | O_CLOEXEC, 0);
 | |
| -		if (ret < 0) {
 | |
| -			ret = errno;
 | |
| -			LOG(RPI, Debug) << "Failed to open " << name << ": "
 | |
| -					<< strerror(ret);
 | |
| -			continue;
 | |
| -		}
 | |
| -
 | |
| -		dmaHeapHandle_ = UniqueFD(ret);
 | |
| -		break;
 | |
| -	}
 | |
| -
 | |
| -	if (!dmaHeapHandle_.isValid())
 | |
| -		LOG(RPI, Error) << "Could not open any dmaHeap device";
 | |
| -}
 | |
| -
 | |
| -DmaHeap::~DmaHeap() = default;
 | |
| -
 | |
| -UniqueFD DmaHeap::alloc(const char *name, std::size_t size)
 | |
| -{
 | |
| -	int ret;
 | |
| -
 | |
| -	if (!name)
 | |
| -		return {};
 | |
| -
 | |
| -	struct dma_heap_allocation_data alloc = {};
 | |
| -
 | |
| -	alloc.len = size;
 | |
| -	alloc.fd_flags = O_CLOEXEC | O_RDWR;
 | |
| -
 | |
| -	ret = ::ioctl(dmaHeapHandle_.get(), DMA_HEAP_IOCTL_ALLOC, &alloc);
 | |
| -	if (ret < 0) {
 | |
| -		LOG(RPI, Error) << "dmaHeap allocation failure for "
 | |
| -				<< name;
 | |
| -		return {};
 | |
| -	}
 | |
| -
 | |
| -	UniqueFD allocFd(alloc.fd);
 | |
| -	ret = ::ioctl(allocFd.get(), DMA_BUF_SET_NAME, name);
 | |
| -	if (ret < 0) {
 | |
| -		LOG(RPI, Error) << "dmaHeap naming failure for "
 | |
| -				<< name;
 | |
| -		return {};
 | |
| -	}
 | |
| -
 | |
| -	return allocFd;
 | |
| -}
 | |
| -
 | |
| -} /* namespace RPi */
 | |
| -
 | |
| -} /* namespace libcamera */
 | |
| diff --git a/src/libcamera/pipeline/rpi/vc4/meson.build b/src/libcamera/pipeline/rpi/vc4/meson.build
 | |
| index cdb049c5..386e2296 100644
 | |
| --- a/src/libcamera/pipeline/rpi/vc4/meson.build
 | |
| +++ b/src/libcamera/pipeline/rpi/vc4/meson.build
 | |
| @@ -1,7 +1,6 @@
 | |
|  # SPDX-License-Identifier: CC0-1.0
 | |
|  
 | |
|  libcamera_sources += files([
 | |
| -    'dma_heaps.cpp',
 | |
|      'vc4.cpp',
 | |
|  ])
 | |
|  
 | |
| diff --git a/src/libcamera/pipeline/rpi/vc4/vc4.cpp b/src/libcamera/pipeline/rpi/vc4/vc4.cpp
 | |
| index 26102ea7..3a42e75e 100644
 | |
| --- a/src/libcamera/pipeline/rpi/vc4/vc4.cpp
 | |
| +++ b/src/libcamera/pipeline/rpi/vc4/vc4.cpp
 | |
| @@ -12,12 +12,11 @@
 | |
|  #include <libcamera/formats.h>
 | |
|  
 | |
|  #include "libcamera/internal/device_enumerator.h"
 | |
| +#include "libcamera/internal/dma_heaps.h"
 | |
|  
 | |
|  #include "../common/pipeline_base.h"
 | |
|  #include "../common/rpi_stream.h"
 | |
|  
 | |
| -#include "dma_heaps.h"
 | |
| -
 | |
|  using namespace std::chrono_literals;
 | |
|  
 | |
|  namespace libcamera {
 | |
| @@ -87,7 +86,7 @@ public:
 | |
|  	RPi::Device<Isp, 4> isp_;
 | |
|  
 | |
|  	/* DMAHEAP allocation helper. */
 | |
| -	RPi::DmaHeap dmaHeap_;
 | |
| +	DmaHeap dmaHeap_;
 | |
|  	SharedFD lsTable_;
 | |
|  
 | |
|  	struct Config {
 | |
| -- 
 | |
| 2.43.2
 | |
| 
 |