snix/users/flokli/ipu6-softisp/libcamera/0005-libcamera-shared_mem_object-reorganize-the-code-and-.patch
Florian Klink 9948eb64d1 chore(users/flokli/ipu6-softisp): refresh libcamera patches
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>
2024-03-19 06:59:57 +00:00

403 lines
10 KiB
Diff

From f94af21adc1889706127d07c5425f44c9cec9a95 Mon Sep 17 00:00:00 2001
From: Andrei Konovalov <andrey.konovalov.ynk@gmail.com>
Date: Mon, 11 Mar 2024 15:15:09 +0100
Subject: [PATCH 05/21] libcamera: shared_mem_object: reorganize the code and
document the SharedMemObject class
Split the parts which doesn't otherwise depend on the type T or
arguments Args out of the SharedMemObject class into a new
SharedMem class.
Doxygen documentation by Dennis Bonke and Andrei Konovalov.
Reviewed-by: Pavel Machek <pavel@ucw.cz>
Co-developed-by: Dennis Bonke <admin@dennisbonke.com>
Signed-off-by: Dennis Bonke <admin@dennisbonke.com>
Signed-off-by: Andrei Konovalov <andrey.konovalov.ynk@gmail.com>
Signed-off-by: Hans de Goede <hdegoede@redhat.com>
Reviewed-by: Milan Zamazal <mzamazal@redhat.com>
---
.../libcamera/internal/shared_mem_object.h | 101 ++++++----
src/libcamera/meson.build | 1 +
src/libcamera/shared_mem_object.cpp | 190 ++++++++++++++++++
3 files changed, 253 insertions(+), 39 deletions(-)
create mode 100644 src/libcamera/shared_mem_object.cpp
diff --git a/include/libcamera/internal/shared_mem_object.h b/include/libcamera/internal/shared_mem_object.h
index 98636b44..43b07c9d 100644
--- a/include/libcamera/internal/shared_mem_object.h
+++ b/include/libcamera/internal/shared_mem_object.h
@@ -6,12 +6,9 @@
*/
#pragma once
-#include <fcntl.h>
#include <stddef.h>
#include <string>
#include <sys/mman.h>
-#include <sys/stat.h>
-#include <unistd.h>
#include <utility>
#include <libcamera/base/class.h>
@@ -19,58 +16,92 @@
namespace libcamera {
+class SharedMem
+{
+public:
+ SharedMem()
+ : mem_(nullptr)
+ {
+ }
+
+ SharedMem(const std::string &name, std::size_t size);
+
+ SharedMem(SharedMem &&rhs)
+ {
+ this->name_ = std::move(rhs.name_);
+ this->fd_ = std::move(rhs.fd_);
+ this->mem_ = rhs.mem_;
+ rhs.mem_ = nullptr;
+ }
+
+ virtual ~SharedMem()
+ {
+ if (mem_)
+ munmap(mem_, size_);
+ }
+
+ /* Make SharedMem non-copyable for now. */
+ LIBCAMERA_DISABLE_COPY(SharedMem)
+
+ SharedMem &operator=(SharedMem &&rhs)
+ {
+ this->name_ = std::move(rhs.name_);
+ this->fd_ = std::move(rhs.fd_);
+ this->mem_ = rhs.mem_;
+ rhs.mem_ = nullptr;
+ return *this;
+ }
+
+ const SharedFD &fd() const
+ {
+ return fd_;
+ }
+
+ void *mem() const
+ {
+ return mem_;
+ }
+
+private:
+ std::string name_;
+ SharedFD fd_;
+ size_t size_;
+protected:
+ void *mem_;
+};
+
template<class T>
-class SharedMemObject
+class SharedMemObject : public SharedMem
{
public:
static constexpr std::size_t SIZE = sizeof(T);
SharedMemObject()
- : obj_(nullptr)
+ : SharedMem(), obj_(nullptr)
{
}
template<class... Args>
SharedMemObject(const std::string &name, Args &&...args)
- : name_(name), obj_(nullptr)
+ : SharedMem(name, SIZE), obj_(nullptr)
{
- void *mem;
- int ret;
-
- ret = memfd_create(name_.c_str(), MFD_CLOEXEC);
- if (ret < 0)
- return;
-
- fd_ = SharedFD(std::move(ret));
- if (!fd_.isValid())
- return;
-
- ret = ftruncate(fd_.get(), SIZE);
- if (ret < 0)
+ if (mem_ == nullptr)
return;
- mem = mmap(nullptr, SIZE, PROT_READ | PROT_WRITE, MAP_SHARED,
- fd_.get(), 0);
- if (mem == MAP_FAILED)
- return;
-
- obj_ = new (mem) T(std::forward<Args>(args)...);
+ obj_ = new (mem_) T(std::forward<Args>(args)...);
}
SharedMemObject(SharedMemObject<T> &&rhs)
+ : SharedMem(std::move(rhs))
{
- this->name_ = std::move(rhs.name_);
- this->fd_ = std::move(rhs.fd_);
this->obj_ = rhs.obj_;
rhs.obj_ = nullptr;
}
~SharedMemObject()
{
- if (obj_) {
+ if (obj_)
obj_->~T();
- munmap(obj_, SIZE);
- }
}
/* Make SharedMemObject non-copyable for now. */
@@ -78,8 +109,7 @@ public:
SharedMemObject<T> &operator=(SharedMemObject<T> &&rhs)
{
- this->name_ = std::move(rhs.name_);
- this->fd_ = std::move(rhs.fd_);
+ SharedMem::operator=(std::move(rhs));
this->obj_ = rhs.obj_;
rhs.obj_ = nullptr;
return *this;
@@ -105,19 +135,12 @@ public:
return *obj_;
}
- const SharedFD &fd() const
- {
- return fd_;
- }
-
explicit operator bool() const
{
return !!obj_;
}
private:
- std::string name_;
- SharedFD fd_;
T *obj_;
};
diff --git a/src/libcamera/meson.build b/src/libcamera/meson.build
index 3c5e43df..94a95ae3 100644
--- a/src/libcamera/meson.build
+++ b/src/libcamera/meson.build
@@ -41,6 +41,7 @@ libcamera_sources = files([
'process.cpp',
'pub_key.cpp',
'request.cpp',
+ 'shared_mem_object.cpp',
'source_paths.cpp',
'stream.cpp',
'sysfs.cpp',
diff --git a/src/libcamera/shared_mem_object.cpp b/src/libcamera/shared_mem_object.cpp
new file mode 100644
index 00000000..44fe74c2
--- /dev/null
+++ b/src/libcamera/shared_mem_object.cpp
@@ -0,0 +1,190 @@
+/* SPDX-License-Identifier: LGPL-2.1-or-later */
+/*
+ * Copyright (C) 2023, Raspberry Pi Ltd
+ *
+ * shared_mem_object.cpp - Helper class for shared memory allocations
+ */
+
+#include "libcamera/internal/shared_mem_object.h"
+
+#include <sys/types.h>
+#include <unistd.h>
+
+/**
+ * \file shared_mem_object.cpp
+ * \brief Helper class for shared memory allocations
+ */
+
+namespace libcamera {
+
+/**
+ * \class SharedMem
+ * \brief Helper class for allocating shared memory
+ *
+ * Memory is allocated and exposed as a SharedFD for use across IPC boundaries.
+ *
+ * SharedMem allocates the shared memory of the given size and maps it.
+ * To check that the shared memory was allocated and mapped successfully, one
+ * needs to verify that the pointer to the shared memory returned by SharedMem::mem()
+ * is not nullptr.
+ *
+ * To access the shared memory from another process the SharedFD should be passed
+ * to that process, and then the shared memory should be mapped into that process
+ * address space by calling mmap().
+ *
+ * A single memfd is created for every SharedMem. If there is a need to allocate
+ * a large number of objects in shared memory, these objects should be grouped
+ * together and use the shared memory allocated by a single SharedMem object if
+ * possible. This will help to minimize the number of created memfd's.
+ */
+
+/**
+ * \fn SharedMem::SharedMem(const std::string &name, std::size_t size)
+ * \brief Constructor for the SharedMem
+ * \param[in] name Name of the SharedMem
+ * \param[in] size Size of the shared memory to allocate and map
+ */
+
+/**
+ * \fn SharedMem::SharedMem(SharedMem &&rhs)
+ * \brief Move constructor for SharedMem
+ * \param[in] rhs The object to move
+ */
+
+/**
+ * \fn SharedMem::~SharedMem()
+ * \brief SharedMem destructor
+ *
+ * Unmaps the allocated shared memory. Decrements the shared memory descriptor use
+ * count.
+ */
+
+/**
+ * \fn SharedMem &SharedMem::operator=(SharedMem &&rhs)
+ * \brief Move constructor for SharedMem
+ * \param[in] rhs The object to move
+ */
+
+/**
+ * \fn const SharedFD &SharedMem::fd() const
+ * \brief Gets the file descriptor for the underlying shared memory
+ * \return The file descriptor
+ */
+
+/**
+ * \fn void *SharedMem::mem() const
+ * \brief Gets the pointer to the underlying shared memory
+ * \return The pointer to the shared memory
+ */
+
+SharedMem::SharedMem(const std::string &name, std::size_t size)
+ : name_(name), size_(size), mem_(nullptr)
+{
+ int fd = memfd_create(name_.c_str(), MFD_CLOEXEC);
+ if (fd < 0)
+ return;
+
+ fd_ = SharedFD(std::move(fd));
+ if (!fd_.isValid())
+ return;
+
+ if (ftruncate(fd_.get(), size_) < 0)
+ return;
+
+ mem_ = mmap(nullptr, size, PROT_READ | PROT_WRITE, MAP_SHARED,
+ fd_.get(), 0);
+ if (mem_ == MAP_FAILED)
+ mem_ = nullptr;
+}
+
+/**
+ * \var SharedMem::mem_
+ * \brief Pointer to the shared memory allocated
+ */
+
+/**
+ * \class SharedMemObject
+ * \brief Helper class for allocating objects in shared memory
+ *
+ * Memory is allocated and exposed as a SharedFD for use across IPC boundaries.
+ *
+ * Given the type of the object to be created in shared memory and the arguments
+ * to pass to this object's constructor, SharedMemObject allocates the shared memory
+ * of the size of the object and constructs the object in this memory. To ensure
+ * that the SharedMemObject was created successfully, one needs to verify that the
+ * overloaded bool() operator returns true. The object created in the shared memory
+ * can be accessed using the SharedMemObject::operator*() indirection operator. Its
+ * members can be accessed with the SharedMemObject::operator->() member of pointer
+ * operator.
+ *
+ * To access the object from another process the SharedFD should be passed to that
+ * process, and the shared memory should be mapped by calling mmap().
+ *
+ * A single memfd is created for every SharedMemObject. If there is a need to allocate
+ * a large number of objects in shared memory, these objects should be grouped into a
+ * single large object to keep the number of created memfd's reasonably small.
+ */
+
+/**
+ * \var SharedMemObject::SIZE
+ * \brief The size of the object that is going to be stored here
+ */
+
+/**
+ * \fn SharedMemObject< T >::SharedMemObject(const std::string &name, Args &&...args)
+ * \brief Constructor for the SharedMemObject
+ * \param[in] name Name of the SharedMemObject
+ * \param[in] args Args to pass to the constructor of the object in shared memory
+ */
+
+/**
+ * \fn SharedMemObject::SharedMemObject(SharedMemObject<T> &&rhs)
+ * \brief Move constructor for SharedMemObject
+ * \param[in] rhs The object to move
+ */
+
+/**
+ * \fn SharedMemObject::~SharedMemObject()
+ * \brief SharedMemObject destructor
+ *
+ * Destroys the object created in the shared memory and then unmaps the shared memory.
+ * Decrements the shared memory descriptor use count.
+ */
+
+/**
+ * \fn SharedMemObject::operator=(SharedMemObject<T> &&rhs)
+ * \brief Operator= for SharedMemObject
+ * \param[in] rhs The SharedMemObject object to take the data from
+ */
+
+/**
+ * \fn SharedMemObject::operator->()
+ * \brief Operator-> for SharedMemObject
+ * \return The pointer to the object
+ */
+
+/**
+ * \fn const T *SharedMemObject::operator->() const
+ * \brief Operator-> for SharedMemObject
+ * \return The pointer to the const object
+ */
+
+/**
+ * \fn SharedMemObject::operator*()
+ * \brief Operator* for SharedMemObject
+ * \return The reference to the object
+ */
+
+/**
+ * \fn const T &SharedMemObject::operator*() const
+ * \brief Operator* for SharedMemObject
+ * \return Const reference to the object
+ */
+
+/**
+ * \fn SharedMemObject::operator bool()
+ * \brief Operator bool() for SharedMemObject
+ * \return True if the object was created OK in the shared memory, false otherwise
+ */
+
+} // namespace libcamera
--
2.43.2