summaryrefslogtreecommitdiff
path: root/src/ipa/raspberrypi/raspberrypi.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/ipa/raspberrypi/raspberrypi.cpp')
-rw-r--r--src/ipa/raspberrypi/raspberrypi.cpp986
1 files changed, 601 insertions, 385 deletions
diff --git a/src/ipa/raspberrypi/raspberrypi.cpp b/src/ipa/raspberrypi/raspberrypi.cpp
index b0c7d1c1..5cd33304 100644
--- a/src/ipa/raspberrypi/raspberrypi.cpp
+++ b/src/ipa/raspberrypi/raspberrypi.cpp
@@ -1,34 +1,34 @@
/* SPDX-License-Identifier: BSD-2-Clause */
/*
- * Copyright (C) 2019-2020, Raspberry Pi (Trading) Ltd.
+ * Copyright (C) 2019-2021, Raspberry Pi (Trading) Ltd.
*
* rpi.cpp - Raspberry Pi Image Processing Algorithms
*/
#include <algorithm>
+#include <array>
#include <fcntl.h>
#include <math.h>
#include <stdint.h>
#include <string.h>
#include <sys/mman.h>
-#include <libcamera/buffer.h>
+#include <linux/bcm2835-isp.h>
+
+#include <libcamera/base/log.h>
+#include <libcamera/base/span.h>
+
#include <libcamera/control_ids.h>
#include <libcamera/controls.h>
#include <libcamera/file_descriptor.h>
+#include <libcamera/framebuffer.h>
#include <libcamera/ipa/ipa_interface.h>
#include <libcamera/ipa/ipa_module_info.h>
#include <libcamera/ipa/raspberrypi.h>
+#include <libcamera/ipa/raspberrypi_ipa_interface.h>
#include <libcamera/request.h>
-#include <libcamera/span.h>
-#include <libipa/ipa_interface_wrapper.h>
-
-#include "libcamera/internal/camera_sensor.h"
-#include "libcamera/internal/log.h"
-#include "libcamera/internal/utils.h"
-
-#include <linux/bcm2835-isp.h>
+#include "libcamera/internal/framebuffer.h"
#include "agc_algorithm.hpp"
#include "agc_status.h"
@@ -42,61 +42,79 @@
#include "contrast_algorithm.hpp"
#include "contrast_status.h"
#include "controller.hpp"
+#include "denoise_algorithm.hpp"
+#include "denoise_status.h"
#include "dpc_status.h"
#include "focus_status.h"
#include "geq_status.h"
#include "lux_status.h"
#include "metadata.hpp"
#include "noise_status.h"
-#include "sdn_status.h"
#include "sharpen_algorithm.hpp"
#include "sharpen_status.h"
namespace libcamera {
+using namespace std::literals::chrono_literals;
+using utils::Duration;
+
/* Configure the sensor with these values initially. */
-constexpr double DefaultAnalogueGain = 1.0;
-constexpr unsigned int DefaultExposureTime = 20000;
+constexpr double defaultAnalogueGain = 1.0;
+constexpr Duration defaultExposureTime = 20.0ms;
+constexpr Duration defaultMinFrameDuration = 1.0s / 30.0;
+constexpr Duration defaultMaxFrameDuration = 250.0s;
+
+/*
+ * Determine the minimum allowable inter-frame duration to run the controller
+ * algorithms. If the pipeline handler provider frames at a rate higher than this,
+ * we rate-limit the controller Prepare() and Process() calls to lower than or
+ * equal to this rate.
+ */
+constexpr Duration controllerMinFrameDuration = 1.0s / 60.0;
LOG_DEFINE_CATEGORY(IPARPI)
-class IPARPi : public IPAInterface
+class IPARPi : public ipa::RPi::IPARPiInterface
{
public:
IPARPi()
- : lastMode_({}), controller_(), controllerInit_(false),
- frameCount_(0), checkCount_(0), mistrustCount_(0),
- lsTable_(nullptr)
+ : controller_(), frameCount_(0), checkCount_(0), mistrustCount_(0),
+ lastRunTimestamp_(0), lsTable_(nullptr), firstStart_(true)
{
}
~IPARPi()
{
if (lsTable_)
- munmap(lsTable_, RPi::MaxLsGridSize);
+ munmap(lsTable_, ipa::RPi::MaxLsGridSize);
}
- int init(const IPASettings &settings) override;
- int start() override { return 0; }
+ int init(const IPASettings &settings, ipa::RPi::SensorConfig *sensorConfig) override;
+ void start(const ControlList &controls, ipa::RPi::StartConfig *startConfig) override;
void stop() override {}
- void configure(const CameraSensorInfo &sensorInfo,
- const std::map<unsigned int, IPAStream> &streamConfig,
- const std::map<unsigned int, const ControlInfoMap &> &entityControls,
- const IPAOperationData &data,
- IPAOperationData *response) override;
+ int configure(const IPACameraSensorInfo &sensorInfo,
+ const std::map<unsigned int, IPAStream> &streamConfig,
+ const std::map<unsigned int, ControlInfoMap> &entityControls,
+ const ipa::RPi::IPAConfig &data,
+ ControlList *controls) override;
void mapBuffers(const std::vector<IPABuffer> &buffers) override;
void unmapBuffers(const std::vector<unsigned int> &ids) override;
- void processEvent(const IPAOperationData &event) override;
+ void signalStatReady(const uint32_t bufferId) override;
+ void signalQueueRequest(const ControlList &controls) override;
+ void signalIspPrepare(const ipa::RPi::ISPConfig &data) override;
private:
- void setMode(const CameraSensorInfo &sensorInfo);
+ void setMode(const IPACameraSensorInfo &sensorInfo);
+ bool validateSensorControls();
+ bool validateIspControls();
void queueRequest(const ControlList &controls);
void returnEmbeddedBuffer(unsigned int bufferId);
- void prepareISP(unsigned int bufferId);
+ void prepareISP(const ipa::RPi::ISPConfig &data);
void reportMetadata();
- bool parseEmbeddedData(unsigned int bufferId, struct DeviceStatus &deviceStatus);
+ void fillDeviceStatus(const ControlList &sensorControls);
void processStats(unsigned int bufferId);
+ 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);
@@ -104,30 +122,24 @@ private:
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 SdnStatus *denoiseStatus, 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 resampleTable(uint16_t dest[], double const src[12][16], int destW, int destH);
- std::map<unsigned int, FrameBuffer> buffers_;
- std::map<unsigned int, void *> buffersMemory_;
+ std::map<unsigned int, MappedFrameBuffer> buffers_;
- ControlInfoMap unicamCtrls_;
+ ControlInfoMap sensorCtrls_;
ControlInfoMap ispCtrls_;
ControlList libcameraMetadata_;
- /* IPA configuration. */
- std::string tuningFile_;
-
/* Camera sensor params. */
CameraMode mode_;
- CameraMode lastMode_;
/* Raspberry Pi controller specific defines. */
std::unique_ptr<RPiController::CamHelper> helper_;
RPiController::Controller controller_;
- bool controllerInit_;
RPiController::Metadata rpiMetadata_;
/*
@@ -142,18 +154,135 @@ private:
/* 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. */
FileDescriptor lsTableHandle_;
void *lsTable_;
+
+ /* Distinguish the first camera start from others. */
+ bool firstStart_;
+
+ /* Frame duration (1/fps) limits. */
+ Duration minFrameDuration_;
+ Duration maxFrameDuration_;
};
-int IPARPi::init(const IPASettings &settings)
+int IPARPi::init(const IPASettings &settings, ipa::RPi::SensorConfig *sensorConfig)
{
- tuningFile_ = settings.configurationFile;
+ /*
+ * Load the "helper" for this sensor. This tells us all the device specific stuff
+ * that the kernel driver doesn't. We only do this the first time; we don't need
+ * to re-parse the metadata after a simple mode-switch for no reason.
+ */
+ helper_ = std::unique_ptr<RPiController::CamHelper>(RPiController::CamHelper::Create(settings.sensorModel));
+ if (!helper_) {
+ LOG(IPARPI, Error) << "Could not create camera helper for "
+ << settings.sensorModel;
+ return -EINVAL;
+ }
+
+ /*
+ * Pass out the sensor config to the pipeline handler in order
+ * to setup the staggered writer class.
+ */
+ int gainDelay, exposureDelay, vblankDelay, sensorMetadata;
+ helper_->GetDelays(exposureDelay, gainDelay, vblankDelay);
+ sensorMetadata = helper_->SensorEmbeddedDataPresent();
+
+ sensorConfig->gainDelay = gainDelay;
+ sensorConfig->exposureDelay = exposureDelay;
+ sensorConfig->vblankDelay = vblankDelay;
+ sensorConfig->sensorMetadata = sensorMetadata;
+
+ /* Load the tuning file for this sensor. */
+ controller_.Read(settings.configurationFile.c_str());
+ controller_.Initialise();
+
return 0;
}
-void IPARPi::setMode(const CameraSensorInfo &sensorInfo)
+void IPARPi::start(const ControlList &controls, ipa::RPi::StartConfig *startConfig)
+{
+ RPiController::Metadata metadata;
+
+ ASSERT(startConfig);
+ if (!controls.empty()) {
+ /* We have been given some controls to action before start. */
+ queueRequest(controls);
+ }
+
+ controller_.SwitchMode(mode_, &metadata);
+
+ /* SwitchMode may supply updated exposure/gain values to use. */
+ AgcStatus agcStatus;
+ agcStatus.shutter_time = 0.0s;
+ agcStatus.analogue_gain = 0.0;
+
+ metadata.Get("agc.status", agcStatus);
+ if (agcStatus.shutter_time && agcStatus.analogue_gain) {
+ ControlList ctrls(sensorCtrls_);
+ applyAGC(&agcStatus, ctrls);
+ startConfig->controls = std::move(ctrls);
+ }
+
+ /*
+ * Initialise frame counts, and decide how many frames must be hidden or
+ * "mistrusted", which depends on whether this is a startup from cold,
+ * or merely a mode switch in a running system.
+ */
+ frameCount_ = 0;
+ checkCount_ = 0;
+ if (firstStart_) {
+ dropFrameCount_ = helper_->HideFramesStartup();
+ mistrustCount_ = helper_->MistrustFramesStartup();
+
+ /*
+ * Query the AGC/AWB for how many frames they may take to
+ * converge sufficiently. Where these numbers are non-zero
+ * we must allow for the frames with bad statistics
+ * (mistrustCount_) that they won't see. But if zero (i.e.
+ * no convergence necessary), no frames need to be dropped.
+ */
+ unsigned int agcConvergenceFrames = 0;
+ RPiController::AgcAlgorithm *agc = dynamic_cast<RPiController::AgcAlgorithm *>(
+ controller_.GetAlgorithm("agc"));
+ if (agc) {
+ agcConvergenceFrames = agc->GetConvergenceFrames();
+ if (agcConvergenceFrames)
+ agcConvergenceFrames += mistrustCount_;
+ }
+
+ unsigned int awbConvergenceFrames = 0;
+ RPiController::AwbAlgorithm *awb = dynamic_cast<RPiController::AwbAlgorithm *>(
+ controller_.GetAlgorithm("awb"));
+ if (awb) {
+ awbConvergenceFrames = awb->GetConvergenceFrames();
+ if (awbConvergenceFrames)
+ awbConvergenceFrames += mistrustCount_;
+ }
+
+ dropFrameCount_ = std::max({ dropFrameCount_, agcConvergenceFrames, awbConvergenceFrames });
+ LOG(IPARPI, Debug) << "Drop " << dropFrameCount_ << " frames on startup";
+ } else {
+ dropFrameCount_ = helper_->HideFramesModeSwitch();
+ mistrustCount_ = helper_->MistrustFramesModeSwitch();
+ }
+
+ startConfig->dropFrameCount = dropFrameCount_;
+
+ firstStart_ = false;
+ lastRunTimestamp_ = 0;
+}
+
+void IPARPi::setMode(const IPACameraSensorInfo &sensorInfo)
{
mode_.bitdepth = sensorInfo.bitsPerPixel;
mode_.width = sensorInfo.outputSize.width;
@@ -178,81 +307,70 @@ void IPARPi::setMode(const CameraSensorInfo &sensorInfo)
*
* \todo Get the pipeline handle to provide the full data
*/
- mode_.bin_y = std::min(2, static_cast<int>(mode_.scale_x));
+ mode_.bin_x = std::min(2, static_cast<int>(mode_.scale_x));
mode_.bin_y = std::min(2, static_cast<int>(mode_.scale_y));
/* The noise factor is the square root of the total binning factor. */
mode_.noise_factor = sqrt(mode_.bin_x * mode_.bin_y);
/*
- * Calculate the line length in nanoseconds as the ratio between
- * the line length in pixels and the pixel rate.
+ * Calculate the line length as the ratio between the line length in
+ * pixels and the pixel rate.
+ */
+ mode_.line_length = sensorInfo.lineLength * (1.0s / sensorInfo.pixelRate);
+
+ /*
+ * Set the frame length limits for the mode to ensure exposure and
+ * framerate calculations are clipped appropriately.
*/
- mode_.line_length = 1e9 * sensorInfo.lineLength / sensorInfo.pixelRate;
+ mode_.min_frame_length = sensorInfo.minFrameLength;
+ mode_.max_frame_length = sensorInfo.maxFrameLength;
}
-void IPARPi::configure(const CameraSensorInfo &sensorInfo,
- [[maybe_unused]] const std::map<unsigned int, IPAStream> &streamConfig,
- const std::map<unsigned int, const ControlInfoMap &> &entityControls,
- const IPAOperationData &ipaConfig,
- IPAOperationData *result)
+int IPARPi::configure(const IPACameraSensorInfo &sensorInfo,
+ [[maybe_unused]] const std::map<unsigned int, IPAStream> &streamConfig,
+ const std::map<unsigned int, ControlInfoMap> &entityControls,
+ const ipa::RPi::IPAConfig &ipaConfig,
+ ControlList *controls)
{
- if (entityControls.empty())
- return;
-
- result->operation = 0;
+ if (entityControls.size() != 2) {
+ LOG(IPARPI, Error) << "No ISP or sensor controls found.";
+ return -1;
+ }
- unicamCtrls_ = entityControls.at(0);
+ sensorCtrls_ = entityControls.at(0);
ispCtrls_ = entityControls.at(1);
- /* Setup a metadata ControlList to output metadata. */
- libcameraMetadata_ = ControlList(controls::controls);
-
- /*
- * Load the "helper" for this sensor. This tells us all the device specific stuff
- * that the kernel driver doesn't. We only do this the first time; we don't need
- * to re-parse the metadata after a simple mode-switch for no reason.
- */
- std::string cameraName(sensorInfo.model);
- if (!helper_) {
- helper_ = std::unique_ptr<RPiController::CamHelper>(RPiController::CamHelper::Create(cameraName));
-
- /*
- * Pass out the sensor config to the pipeline handler in order
- * to setup the staggered writer class.
- */
- int gainDelay, exposureDelay, sensorMetadata;
- helper_->GetDelays(exposureDelay, gainDelay);
- sensorMetadata = helper_->SensorEmbeddedDataPresent();
-
- result->data.push_back(gainDelay);
- result->data.push_back(exposureDelay);
- result->data.push_back(sensorMetadata);
+ if (!validateSensorControls()) {
+ LOG(IPARPI, Error) << "Sensor control validation failed.";
+ return -1;
+ }
- result->operation |= RPi::IPA_CONFIG_STAGGERED_WRITE;
+ if (!validateIspControls()) {
+ LOG(IPARPI, Error) << "ISP control validation failed.";
+ return -1;
}
+ /* Setup a metadata ControlList to output metadata. */
+ libcameraMetadata_ = ControlList(controls::controls);
+
/* Re-assemble camera mode using the sensor info. */
setMode(sensorInfo);
- /*
- * The ipaConfig.data always gives us the user transform first. Note that
- * this will always make the LS table pointer (if present) element 1.
- */
- mode_.transform = static_cast<libcamera::Transform>(ipaConfig.data[0]);
+ mode_.transform = static_cast<libcamera::Transform>(ipaConfig.transform);
/* Store the lens shading table pointer and handle if available. */
- if (ipaConfig.operation & RPi::IPA_CONFIG_LS_TABLE) {
+ if (ipaConfig.lsTableHandle.isValid()) {
/* Remove any previous table, if there was one. */
if (lsTable_) {
- munmap(lsTable_, RPi::MaxLsGridSize);
+ munmap(lsTable_, ipa::RPi::MaxLsGridSize);
lsTable_ = nullptr;
}
- /* Map the LS table buffer into user space (now element 1). */
- lsTableHandle_ = FileDescriptor(ipaConfig.data[1]);
+ /* Map the LS table buffer into user space. */
+ lsTableHandle_ = std::move(ipaConfig.lsTableHandle);
if (lsTableHandle_.isValid()) {
- lsTable_ = mmap(nullptr, RPi::MaxLsGridSize, PROT_READ | PROT_WRITE,
+ lsTable_ = mmap(nullptr, ipa::RPi::MaxLsGridSize, PROT_READ | PROT_WRITE,
MAP_SHARED, lsTableHandle_.fd(), 0);
if (lsTable_ == MAP_FAILED) {
@@ -265,139 +383,72 @@ void IPARPi::configure(const CameraSensorInfo &sensorInfo,
/* Pass the camera mode to the CamHelper to setup algorithms. */
helper_->SetCameraMode(mode_);
- /*
- * Initialise frame counts, and decide how many frames must be hidden or
- *"mistrusted", which depends on whether this is a startup from cold,
- * or merely a mode switch in a running system.
- */
- frameCount_ = 0;
- checkCount_ = 0;
- unsigned int dropFrame = 0;
- if (controllerInit_) {
- dropFrame = helper_->HideFramesModeSwitch();
- mistrustCount_ = helper_->MistrustFramesModeSwitch();
- } else {
- dropFrame = helper_->HideFramesStartup();
- mistrustCount_ = helper_->MistrustFramesStartup();
- }
-
- result->data.push_back(dropFrame);
- result->operation |= RPi::IPA_CONFIG_DROP_FRAMES;
-
- /* These zero values mean not program anything (unless overwritten). */
- struct AgcStatus agcStatus;
- agcStatus.shutter_time = 0.0;
- agcStatus.analogue_gain = 0.0;
-
- if (!controllerInit_) {
- /* Load the tuning file for this sensor. */
- controller_.Read(tuningFile_.c_str());
- controller_.Initialise();
- controllerInit_ = true;
+ if (firstStart_) {
+ /* Supply initial values for frame durations. */
+ applyFrameDurations(defaultMinFrameDuration, defaultMaxFrameDuration);
/* Supply initial values for gain and exposure. */
- agcStatus.shutter_time = DefaultExposureTime;
- agcStatus.analogue_gain = DefaultAnalogueGain;
- }
-
- RPiController::Metadata metadata;
- controller_.SwitchMode(mode_, &metadata);
-
- /* SwitchMode may supply updated exposure/gain values to use. */
- metadata.Get("agc.status", agcStatus);
- if (agcStatus.shutter_time != 0.0 && agcStatus.analogue_gain != 0.0) {
- ControlList ctrls(unicamCtrls_);
+ ControlList ctrls(sensorCtrls_);
+ AgcStatus agcStatus;
+ agcStatus.shutter_time = defaultExposureTime;
+ agcStatus.analogue_gain = defaultAnalogueGain;
applyAGC(&agcStatus, ctrls);
- result->controls.push_back(ctrls);
- result->operation |= RPi::IPA_CONFIG_SENSOR;
+ ASSERT(controls);
+ *controls = std::move(ctrls);
}
- lastMode_ = mode_;
+ return 0;
}
void IPARPi::mapBuffers(const std::vector<IPABuffer> &buffers)
{
for (const IPABuffer &buffer : buffers) {
- auto elem = buffers_.emplace(std::piecewise_construct,
- std::forward_as_tuple(buffer.id),
- std::forward_as_tuple(buffer.planes));
- const FrameBuffer &fb = elem.first->second;
-
- buffersMemory_[buffer.id] = mmap(nullptr, fb.planes()[0].length,
- PROT_READ | PROT_WRITE, MAP_SHARED,
- fb.planes()[0].fd.fd(), 0);
-
- if (buffersMemory_[buffer.id] == MAP_FAILED) {
- int ret = -errno;
- LOG(IPARPI, Fatal) << "Failed to mmap buffer: " << strerror(-ret);
- }
+ const FrameBuffer fb(buffer.planes);
+ buffers_.emplace(buffer.id, MappedFrameBuffer(&fb, PROT_READ | PROT_WRITE));
}
}
void IPARPi::unmapBuffers(const std::vector<unsigned int> &ids)
{
for (unsigned int id : ids) {
- const auto fb = buffers_.find(id);
- if (fb == buffers_.end())
+ auto it = buffers_.find(id);
+ if (it == buffers_.end())
continue;
- munmap(buffersMemory_[id], fb->second.planes()[0].length);
- buffersMemory_.erase(id);
buffers_.erase(id);
}
}
-void IPARPi::processEvent(const IPAOperationData &event)
+void IPARPi::signalStatReady(uint32_t bufferId)
{
- switch (event.operation) {
- case RPi::IPA_EVENT_SIGNAL_STAT_READY: {
- unsigned int bufferId = event.data[0];
-
- if (++checkCount_ != frameCount_) /* assert here? */
- LOG(IPARPI, Error) << "WARNING: Prepare/Process mismatch!!!";
- if (frameCount_ > mistrustCount_)
- processStats(bufferId);
-
- reportMetadata();
-
- IPAOperationData op;
- op.operation = RPi::IPA_ACTION_STATS_METADATA_COMPLETE;
- op.data = { bufferId & RPi::BufferMask::ID };
- op.controls = { libcameraMetadata_ };
- queueFrameAction.emit(0, op);
- break;
- }
+ if (++checkCount_ != frameCount_) /* assert here? */
+ LOG(IPARPI, Error) << "WARNING: Prepare/Process mismatch!!!";
+ if (processPending_ && frameCount_ > mistrustCount_)
+ processStats(bufferId);
- case RPi::IPA_EVENT_SIGNAL_ISP_PREPARE: {
- unsigned int embeddedbufferId = event.data[0];
- unsigned int bayerbufferId = event.data[1];
+ reportMetadata();
- /*
- * 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".
- */
- prepareISP(embeddedbufferId);
- frameCount_++;
-
- /* Ready to push the input buffer into the ISP. */
- IPAOperationData op;
- op.operation = RPi::IPA_ACTION_RUN_ISP;
- op.data = { bayerbufferId & RPi::BufferMask::ID };
- queueFrameAction.emit(0, op);
- break;
- }
+ statsMetadataComplete.emit(bufferId & ipa::RPi::MaskID, libcameraMetadata_);
+}
- case RPi::IPA_EVENT_QUEUE_REQUEST: {
- queueRequest(event.controls[0]);
- break;
- }
+void IPARPi::signalQueueRequest(const ControlList &controls)
+{
+ queueRequest(controls);
+}
- default:
- LOG(IPARPI, Error) << "Unknown event " << event.operation;
- break;
- }
+void IPARPi::signalIspPrepare(const ipa::RPi::ISPConfig &data)
+{
+ /*
+ * 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".
+ */
+ prepareISP(data);
+ frameCount_++;
+
+ /* Ready to push the input buffer into the ISP. */
+ runIsp.emit(data.bayerBufferId & ipa::RPi::MaskID);
}
void IPARPi::reportMetadata()
@@ -411,13 +462,16 @@ void IPARPi::reportMetadata()
*/
DeviceStatus *deviceStatus = rpiMetadata_.GetLocked<DeviceStatus>("device.status");
if (deviceStatus) {
- libcameraMetadata_.set(controls::ExposureTime, deviceStatus->shutter_speed);
+ libcameraMetadata_.set(controls::ExposureTime,
+ deviceStatus->shutter_speed.get<std::micro>());
libcameraMetadata_.set(controls::AnalogueGain, deviceStatus->analogue_gain);
}
AgcStatus *agcStatus = rpiMetadata_.GetLocked<AgcStatus>("agc.status");
- if (agcStatus)
+ if (agcStatus) {
libcameraMetadata_.set(controls::AeLocked, agcStatus->locked);
+ libcameraMetadata_.set(controls::DigitalGain, agcStatus->digital_gain);
+ }
LuxStatus *luxStatus = rpiMetadata_.GetLocked<LuxStatus>("lux.status");
if (luxStatus)
@@ -458,6 +512,53 @@ void IPARPi::reportMetadata()
}
}
+bool IPARPi::validateSensorControls()
+{
+ static const uint32_t ctrls[] = {
+ V4L2_CID_ANALOGUE_GAIN,
+ V4L2_CID_EXPOSURE,
+ V4L2_CID_VBLANK,
+ };
+
+ 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;
+}
+
/*
* Converting between enums (used in the libcamera API) and the names that
* we use to identify different modes. Unfortunately, the conversion tables
@@ -490,9 +591,18 @@ static const std::map<int32_t, std::string> AwbModeTable = {
{ controls::AwbFluorescent, "fluorescent" },
{ controls::AwbIndoor, "indoor" },
{ controls::AwbDaylight, "daylight" },
+ { controls::AwbCloudy, "cloudy" },
{ controls::AwbCustom, "custom" },
};
+static const std::map<int32_t, RPiController::DenoiseMode> DenoiseModeTable = {
+ { controls::draft::NoiseReductionModeOff, RPiController::DenoiseMode::Off },
+ { controls::draft::NoiseReductionModeFast, RPiController::DenoiseMode::ColourFast },
+ { controls::draft::NoiseReductionModeHighQuality, RPiController::DenoiseMode::ColourHighQuality },
+ { controls::draft::NoiseReductionModeMinimal, RPiController::DenoiseMode::ColourOff },
+ { controls::draft::NoiseReductionModeZSL, RPiController::DenoiseMode::ColourHighQuality },
+};
+
void IPARPi::queueRequest(const ControlList &controls)
{
/* Clear the return metadata buffer. */
@@ -506,7 +616,12 @@ void IPARPi::queueRequest(const ControlList &controls)
switch (ctrl.first) {
case controls::AE_ENABLE: {
RPiController::Algorithm *agc = controller_.GetAlgorithm("agc");
- ASSERT(agc);
+ if (!agc) {
+ LOG(IPARPI, Warning)
+ << "Could not set AE_ENABLE - no AGC algorithm";
+ break;
+ }
+
if (ctrl.second.get<bool>() == false)
agc->Pause();
else
@@ -519,14 +634,14 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::EXPOSURE_TIME: {
RPiController::AgcAlgorithm *agc = dynamic_cast<RPiController::AgcAlgorithm *>(
controller_.GetAlgorithm("agc"));
- ASSERT(agc);
-
- /* This expects units of micro-seconds. */
- agc->SetFixedShutter(ctrl.second.get<int32_t>());
+ if (!agc) {
+ LOG(IPARPI, Warning)
+ << "Could not set EXPOSURE_TIME - no AGC algorithm";
+ break;
+ }
- /* For the manual values to take effect, AGC must be unpaused. */
- if (agc->IsPaused())
- agc->Resume();
+ /* The control provides units of microseconds. */
+ agc->SetFixedShutter(ctrl.second.get<int32_t>() * 1.0us);
libcameraMetadata_.set(controls::ExposureTime, ctrl.second.get<int32_t>());
break;
@@ -535,12 +650,13 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::ANALOGUE_GAIN: {
RPiController::AgcAlgorithm *agc = dynamic_cast<RPiController::AgcAlgorithm *>(
controller_.GetAlgorithm("agc"));
- ASSERT(agc);
- agc->SetFixedAnalogueGain(ctrl.second.get<float>());
+ if (!agc) {
+ LOG(IPARPI, Warning)
+ << "Could not set ANALOGUE_GAIN - no AGC algorithm";
+ break;
+ }
- /* For the manual values to take effect, AGC must be unpaused. */
- if (agc->IsPaused())
- agc->Resume();
+ agc->SetFixedAnalogueGain(ctrl.second.get<float>());
libcameraMetadata_.set(controls::AnalogueGain,
ctrl.second.get<float>());
@@ -550,7 +666,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::AE_METERING_MODE: {
RPiController::AgcAlgorithm *agc = dynamic_cast<RPiController::AgcAlgorithm *>(
controller_.GetAlgorithm("agc"));
- ASSERT(agc);
+ if (!agc) {
+ LOG(IPARPI, Warning)
+ << "Could not set AE_METERING_MODE - no AGC algorithm";
+ break;
+ }
int32_t idx = ctrl.second.get<int32_t>();
if (MeteringModeTable.count(idx)) {
@@ -566,7 +686,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::AE_CONSTRAINT_MODE: {
RPiController::AgcAlgorithm *agc = dynamic_cast<RPiController::AgcAlgorithm *>(
controller_.GetAlgorithm("agc"));
- ASSERT(agc);
+ if (!agc) {
+ LOG(IPARPI, Warning)
+ << "Could not set AE_CONSTRAINT_MODE - no AGC algorithm";
+ break;
+ }
int32_t idx = ctrl.second.get<int32_t>();
if (ConstraintModeTable.count(idx)) {
@@ -582,7 +706,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::AE_EXPOSURE_MODE: {
RPiController::AgcAlgorithm *agc = dynamic_cast<RPiController::AgcAlgorithm *>(
controller_.GetAlgorithm("agc"));
- ASSERT(agc);
+ if (!agc) {
+ LOG(IPARPI, Warning)
+ << "Could not set AE_EXPOSURE_MODE - no AGC algorithm";
+ break;
+ }
int32_t idx = ctrl.second.get<int32_t>();
if (ExposureModeTable.count(idx)) {
@@ -598,7 +726,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::EXPOSURE_VALUE: {
RPiController::AgcAlgorithm *agc = dynamic_cast<RPiController::AgcAlgorithm *>(
controller_.GetAlgorithm("agc"));
- ASSERT(agc);
+ if (!agc) {
+ LOG(IPARPI, Warning)
+ << "Could not set EXPOSURE_VALUE - no AGC algorithm";
+ break;
+ }
/*
* The SetEv() method takes in a direct exposure multiplier.
@@ -613,7 +745,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::AWB_ENABLE: {
RPiController::Algorithm *awb = controller_.GetAlgorithm("awb");
- ASSERT(awb);
+ if (!awb) {
+ LOG(IPARPI, Warning)
+ << "Could not set AWB_ENABLE - no AWB algorithm";
+ break;
+ }
if (ctrl.second.get<bool>() == false)
awb->Pause();
@@ -628,7 +764,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::AWB_MODE: {
RPiController::AwbAlgorithm *awb = dynamic_cast<RPiController::AwbAlgorithm *>(
controller_.GetAlgorithm("awb"));
- ASSERT(awb);
+ if (!awb) {
+ LOG(IPARPI, Warning)
+ << "Could not set AWB_MODE - no AWB algorithm";
+ break;
+ }
int32_t idx = ctrl.second.get<int32_t>();
if (AwbModeTable.count(idx)) {
@@ -645,7 +785,11 @@ void IPARPi::queueRequest(const ControlList &controls)
auto gains = ctrl.second.get<Span<const float>>();
RPiController::AwbAlgorithm *awb = dynamic_cast<RPiController::AwbAlgorithm *>(
controller_.GetAlgorithm("awb"));
- ASSERT(awb);
+ if (!awb) {
+ LOG(IPARPI, Warning)
+ << "Could not set COLOUR_GAINS - no AWB algorithm";
+ break;
+ }
awb->SetManualGains(gains[0], gains[1]);
if (gains[0] != 0.0f && gains[1] != 0.0f)
@@ -658,7 +802,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::BRIGHTNESS: {
RPiController::ContrastAlgorithm *contrast = dynamic_cast<RPiController::ContrastAlgorithm *>(
controller_.GetAlgorithm("contrast"));
- ASSERT(contrast);
+ if (!contrast) {
+ LOG(IPARPI, Warning)
+ << "Could not set BRIGHTNESS - no contrast algorithm";
+ break;
+ }
contrast->SetBrightness(ctrl.second.get<float>() * 65536);
libcameraMetadata_.set(controls::Brightness,
@@ -669,7 +817,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::CONTRAST: {
RPiController::ContrastAlgorithm *contrast = dynamic_cast<RPiController::ContrastAlgorithm *>(
controller_.GetAlgorithm("contrast"));
- ASSERT(contrast);
+ if (!contrast) {
+ LOG(IPARPI, Warning)
+ << "Could not set CONTRAST - no contrast algorithm";
+ break;
+ }
contrast->SetContrast(ctrl.second.get<float>());
libcameraMetadata_.set(controls::Contrast,
@@ -680,7 +832,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::SATURATION: {
RPiController::CcmAlgorithm *ccm = dynamic_cast<RPiController::CcmAlgorithm *>(
controller_.GetAlgorithm("ccm"));
- ASSERT(ccm);
+ if (!ccm) {
+ LOG(IPARPI, Warning)
+ << "Could not set SATURATION - no ccm algorithm";
+ break;
+ }
ccm->SetSaturation(ctrl.second.get<float>());
libcameraMetadata_.set(controls::Saturation,
@@ -691,7 +847,11 @@ void IPARPi::queueRequest(const ControlList &controls)
case controls::SHARPNESS: {
RPiController::SharpenAlgorithm *sharpen = dynamic_cast<RPiController::SharpenAlgorithm *>(
controller_.GetAlgorithm("sharpen"));
- ASSERT(sharpen);
+ if (!sharpen) {
+ LOG(IPARPI, Warning)
+ << "Could not set SHARPNESS - no sharpen algorithm";
+ break;
+ }
sharpen->SetStrength(ctrl.second.get<float>());
libcameraMetadata_.set(controls::Sharpness,
@@ -699,6 +859,44 @@ void IPARPi::queueRequest(const ControlList &controls)
break;
}
+ case controls::SCALER_CROP: {
+ /* We do nothing with this, but should avoid the warning below. */
+ break;
+ }
+
+ case controls::FRAME_DURATION_LIMITS: {
+ auto frameDurations = ctrl.second.get<Span<const int64_t>>();
+ applyFrameDurations(frameDurations[0] * 1.0us, frameDurations[1] * 1.0us);
+ break;
+ }
+
+ case controls::NOISE_REDUCTION_MODE: {
+ RPiController::DenoiseAlgorithm *sdn = dynamic_cast<RPiController::DenoiseAlgorithm *>(
+ controller_.GetAlgorithm("SDN"));
+ if (!sdn) {
+ LOG(IPARPI, Warning)
+ << "Could not set NOISE_REDUCTION_MODE - no SDN algorithm";
+ break;
+ }
+
+ int32_t idx = ctrl.second.get<int32_t>();
+ auto mode = DenoiseModeTable.find(idx);
+ if (mode != DenoiseModeTable.end()) {
+ sdn->SetMode(mode->second);
+
+ /*
+ * \todo If the colour denoise is not going to run due to an
+ * analysis image resolution or format mismatch, we should
+ * report the status correctly in the metadata.
+ */
+ libcameraMetadata_.set(controls::draft::NoiseReductionMode, idx);
+ } else {
+ LOG(IPARPI, Error) << "Noise reduction mode " << idx
+ << " not recognised";
+ }
+ break;
+ }
+
default:
LOG(IPARPI, Warning)
<< "Ctrl " << controls::controls.at(ctrl.first)->name()
@@ -710,152 +908,149 @@ void IPARPi::queueRequest(const ControlList &controls)
void IPARPi::returnEmbeddedBuffer(unsigned int bufferId)
{
- IPAOperationData op;
- op.operation = RPi::IPA_ACTION_EMBEDDED_COMPLETE;
- op.data = { bufferId & RPi::BufferMask::ID };
- queueFrameAction.emit(0, op);
+ embeddedComplete.emit(bufferId & ipa::RPi::MaskID);
}
-void IPARPi::prepareISP(unsigned int bufferId)
+void IPARPi::prepareISP(const ipa::RPi::ISPConfig &data)
{
- struct DeviceStatus deviceStatus = {};
- bool success = parseEmbeddedData(bufferId, deviceStatus);
+ int64_t frameTimestamp = data.controls.get(controls::SensorTimestamp);
+ RPiController::Metadata lastMetadata;
+ Span<uint8_t> embeddedBuffer;
+
+ lastMetadata = std::move(rpiMetadata_);
+ fillDeviceStatus(data.controls);
+
+ if (data.embeddedBufferPresent) {
+ /*
+ * Pipeline handler has supplied us with an embedded data buffer,
+ * we must pass it to the CamHelper for parsing.
+ */
+ auto it = buffers_.find(data.embeddedBufferId);
+ ASSERT(it != buffers_.end());
+ embeddedBuffer = it->second.maps()[0];
+ }
+
+ /*
+ * This may overwrite the DeviceStatus using values from the sensor
+ * metadata, and may also do additional custom processing.
+ */
+ helper_->Prepare(embeddedBuffer, rpiMetadata_);
/* Done with embedded data now, return to pipeline handler asap. */
- returnEmbeddedBuffer(bufferId);
+ if (data.embeddedBufferPresent)
+ returnEmbeddedBuffer(data.embeddedBufferId);
- if (success) {
- ControlList ctrls(ispCtrls_);
+ /* 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().
+ */
+ rpiMetadata_.Merge(lastMetadata);
+ processPending_ = false;
+ return;
+ }
- rpiMetadata_.Clear();
- rpiMetadata_.Set("device.status", deviceStatus);
- controller_.Prepare(&rpiMetadata_);
+ lastRunTimestamp_ = frameTimestamp;
+ processPending_ = true;
- /* Lock the metadata buffer to avoid constant locks/unlocks. */
- std::unique_lock<RPiController::Metadata> lock(rpiMetadata_);
+ ControlList ctrls(ispCtrls_);
- AwbStatus *awbStatus = rpiMetadata_.GetLocked<AwbStatus>("awb.status");
- if (awbStatus)
- applyAWB(awbStatus, ctrls);
+ controller_.Prepare(&rpiMetadata_);
- CcmStatus *ccmStatus = rpiMetadata_.GetLocked<CcmStatus>("ccm.status");
- if (ccmStatus)
- applyCCM(ccmStatus, ctrls);
+ /* Lock the metadata buffer to avoid constant locks/unlocks. */
+ std::unique_lock<RPiController::Metadata> lock(rpiMetadata_);
- AgcStatus *dgStatus = rpiMetadata_.GetLocked<AgcStatus>("agc.status");
- if (dgStatus)
- applyDG(dgStatus, ctrls);
+ AwbStatus *awbStatus = rpiMetadata_.GetLocked<AwbStatus>("awb.status");
+ if (awbStatus)
+ applyAWB(awbStatus, ctrls);
- AlscStatus *lsStatus = rpiMetadata_.GetLocked<AlscStatus>("alsc.status");
- if (lsStatus)
- applyLS(lsStatus, ctrls);
+ CcmStatus *ccmStatus = rpiMetadata_.GetLocked<CcmStatus>("ccm.status");
+ if (ccmStatus)
+ applyCCM(ccmStatus, ctrls);
- ContrastStatus *contrastStatus = rpiMetadata_.GetLocked<ContrastStatus>("contrast.status");
- if (contrastStatus)
- applyGamma(contrastStatus, ctrls);
+ AgcStatus *dgStatus = rpiMetadata_.GetLocked<AgcStatus>("agc.status");
+ if (dgStatus)
+ applyDG(dgStatus, ctrls);
- BlackLevelStatus *blackLevelStatus = rpiMetadata_.GetLocked<BlackLevelStatus>("black_level.status");
- if (blackLevelStatus)
- applyBlackLevel(blackLevelStatus, ctrls);
+ AlscStatus *lsStatus = rpiMetadata_.GetLocked<AlscStatus>("alsc.status");
+ if (lsStatus)
+ applyLS(lsStatus, ctrls);
- GeqStatus *geqStatus = rpiMetadata_.GetLocked<GeqStatus>("geq.status");
- if (geqStatus)
- applyGEQ(geqStatus, ctrls);
+ ContrastStatus *contrastStatus = rpiMetadata_.GetLocked<ContrastStatus>("contrast.status");
+ if (contrastStatus)
+ applyGamma(contrastStatus, ctrls);
- SdnStatus *denoiseStatus = rpiMetadata_.GetLocked<SdnStatus>("sdn.status");
- if (denoiseStatus)
- applyDenoise(denoiseStatus, ctrls);
+ BlackLevelStatus *blackLevelStatus = rpiMetadata_.GetLocked<BlackLevelStatus>("black_level.status");
+ if (blackLevelStatus)
+ applyBlackLevel(blackLevelStatus, ctrls);
- SharpenStatus *sharpenStatus = rpiMetadata_.GetLocked<SharpenStatus>("sharpen.status");
- if (sharpenStatus)
- applySharpen(sharpenStatus, ctrls);
+ GeqStatus *geqStatus = rpiMetadata_.GetLocked<GeqStatus>("geq.status");
+ if (geqStatus)
+ applyGEQ(geqStatus, ctrls);
- DpcStatus *dpcStatus = rpiMetadata_.GetLocked<DpcStatus>("dpc.status");
- if (dpcStatus)
- applyDPC(dpcStatus, ctrls);
+ DenoiseStatus *denoiseStatus = rpiMetadata_.GetLocked<DenoiseStatus>("denoise.status");
+ if (denoiseStatus)
+ applyDenoise(denoiseStatus, ctrls);
- if (!ctrls.empty()) {
- IPAOperationData op;
- op.operation = RPi::IPA_ACTION_V4L2_SET_ISP;
- op.controls.push_back(ctrls);
- queueFrameAction.emit(0, op);
- }
- }
+ SharpenStatus *sharpenStatus = rpiMetadata_.GetLocked<SharpenStatus>("sharpen.status");
+ if (sharpenStatus)
+ applySharpen(sharpenStatus, ctrls);
+
+ DpcStatus *dpcStatus = rpiMetadata_.GetLocked<DpcStatus>("dpc.status");
+ if (dpcStatus)
+ applyDPC(dpcStatus, ctrls);
+
+ if (!ctrls.empty())
+ setIspControls.emit(ctrls);
}
-bool IPARPi::parseEmbeddedData(unsigned int bufferId, struct DeviceStatus &deviceStatus)
+void IPARPi::fillDeviceStatus(const ControlList &sensorControls)
{
- auto it = buffersMemory_.find(bufferId);
- if (it == buffersMemory_.end()) {
- LOG(IPARPI, Error) << "Could not find embedded buffer!";
- return false;
- }
+ DeviceStatus deviceStatus = {};
- int size = buffers_.find(bufferId)->second.planes()[0].length;
- helper_->Parser().SetBufferSize(size);
- RPiController::MdParser::Status status = helper_->Parser().Parse(it->second);
- if (status != RPiController::MdParser::Status::OK) {
- LOG(IPARPI, Error) << "Embedded Buffer parsing failed, error " << status;
- } else {
- uint32_t exposureLines, gainCode;
- if (helper_->Parser().GetExposureLines(exposureLines) != RPiController::MdParser::Status::OK) {
- LOG(IPARPI, Error) << "Exposure time failed";
- return false;
- }
+ int32_t exposureLines = sensorControls.get(V4L2_CID_EXPOSURE).get<int32_t>();
+ int32_t gainCode = sensorControls.get(V4L2_CID_ANALOGUE_GAIN).get<int32_t>();
+ int32_t vblank = sensorControls.get(V4L2_CID_VBLANK).get<int32_t>();
- deviceStatus.shutter_speed = helper_->Exposure(exposureLines);
- if (helper_->Parser().GetGainCode(gainCode) != RPiController::MdParser::Status::OK) {
- LOG(IPARPI, Error) << "Gain failed";
- return false;
- }
+ deviceStatus.shutter_speed = helper_->Exposure(exposureLines);
+ deviceStatus.analogue_gain = helper_->Gain(gainCode);
+ deviceStatus.frame_length = mode_.height + vblank;
- deviceStatus.analogue_gain = helper_->Gain(gainCode);
- LOG(IPARPI, Debug) << "Metadata - Exposure : "
- << deviceStatus.shutter_speed << " Gain : "
- << deviceStatus.analogue_gain;
- }
+ LOG(IPARPI, Debug) << "Metadata - " << deviceStatus;
- return true;
+ rpiMetadata_.Set("device.status", deviceStatus);
}
void IPARPi::processStats(unsigned int bufferId)
{
- auto it = buffersMemory_.find(bufferId);
- if (it == buffersMemory_.end()) {
+ auto it = buffers_.find(bufferId);
+ if (it == buffers_.end()) {
LOG(IPARPI, Error) << "Could not find stats buffer!";
return;
}
- bcm2835_isp_stats *stats = static_cast<bcm2835_isp_stats *>(it->second);
+ Span<uint8_t> mem = it->second.maps()[0];
+ bcm2835_isp_stats *stats = reinterpret_cast<bcm2835_isp_stats *>(mem.data());
RPiController::StatisticsPtr statistics = std::make_shared<bcm2835_isp_stats>(*stats);
+ helper_->Process(statistics, rpiMetadata_);
controller_.Process(statistics, &rpiMetadata_);
struct AgcStatus agcStatus;
if (rpiMetadata_.Get("agc.status", agcStatus) == 0) {
- ControlList ctrls(unicamCtrls_);
+ ControlList ctrls(sensorCtrls_);
applyAGC(&agcStatus, ctrls);
- IPAOperationData op;
- op.operation = RPi::IPA_ACTION_V4L2_SET_STAGGERED;
- op.controls.push_back(ctrls);
- queueFrameAction.emit(0, op);
+ setDelayedControls.emit(ctrls);
}
}
void IPARPi::applyAWB(const struct AwbStatus *awbStatus, ControlList &ctrls)
{
- const auto gainR = ispCtrls_.find(V4L2_CID_RED_BALANCE);
- if (gainR == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find red gain control";
- return;
- }
-
- const auto gainB = ispCtrls_.find(V4L2_CID_BLUE_BALANCE);
- if (gainB == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find blue gain control";
- return;
- }
-
LOG(IPARPI, Debug) << "Applying WB R: " << awbStatus->gain_r << " B: "
<< awbStatus->gain_b;
@@ -865,49 +1060,76 @@ void IPARPi::applyAWB(const struct AwbStatus *awbStatus, ControlList &ctrls)
static_cast<int32_t>(awbStatus->gain_b * 1000));
}
+void IPARPi::applyFrameDurations(Duration minFrameDuration, Duration maxFrameDuration)
+{
+ const Duration minSensorFrameDuration = mode_.min_frame_length * mode_.line_length;
+ const Duration maxSensorFrameDuration = mode_.max_frame_length * mode_.line_length;
+
+ /*
+ * This will only be applied once AGC recalculations occur.
+ * The values may be clamped based on the sensor mode capabilities as well.
+ */
+ minFrameDuration_ = minFrameDuration ? minFrameDuration : defaultMaxFrameDuration;
+ maxFrameDuration_ = maxFrameDuration ? maxFrameDuration : defaultMinFrameDuration;
+ minFrameDuration_ = std::clamp(minFrameDuration_,
+ minSensorFrameDuration, maxSensorFrameDuration);
+ maxFrameDuration_ = std::clamp(maxFrameDuration_,
+ minSensorFrameDuration, maxSensorFrameDuration);
+ maxFrameDuration_ = std::max(maxFrameDuration_, minFrameDuration_);
+
+ /* Return the validated limits via metadata. */
+ libcameraMetadata_.set(controls::FrameDurationLimits,
+ { static_cast<int64_t>(minFrameDuration_.get<std::micro>()),
+ static_cast<int64_t>(maxFrameDuration_.get<std::micro>()) });
+
+ /*
+ * Calculate the maximum exposure time possible for the AGC to use.
+ * GetVBlanking() will update maxShutter with the largest exposure
+ * value possible.
+ */
+ Duration maxShutter = Duration::max();
+ helper_->GetVBlanking(maxShutter, minFrameDuration_, maxFrameDuration_);
+
+ RPiController::AgcAlgorithm *agc = dynamic_cast<RPiController::AgcAlgorithm *>(
+ controller_.GetAlgorithm("agc"));
+ agc->SetMaxShutter(maxShutter);
+}
+
void IPARPi::applyAGC(const struct AgcStatus *agcStatus, ControlList &ctrls)
{
int32_t gainCode = helper_->GainCode(agcStatus->analogue_gain);
- int32_t exposureLines = helper_->ExposureLines(agcStatus->shutter_time);
- if (unicamCtrls_.find(V4L2_CID_ANALOGUE_GAIN) == unicamCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find analogue gain control";
- return;
- }
-
- if (unicamCtrls_.find(V4L2_CID_EXPOSURE) == unicamCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find exposure control";
- return;
- }
+ /* GetVBlanking might clip exposure time to the fps limits. */
+ Duration exposure = agcStatus->shutter_time;
+ int32_t vblanking = helper_->GetVBlanking(exposure, minFrameDuration_, maxFrameDuration_);
+ int32_t exposureLines = helper_->ExposureLines(exposure);
- LOG(IPARPI, Debug) << "Applying AGC Exposure: " << agcStatus->shutter_time
- << " (Shutter lines: " << exposureLines << ") Gain: "
+ LOG(IPARPI, Debug) << "Applying AGC Exposure: " << exposure
+ << " (Shutter lines: " << exposureLines << ", AGC requested "
+ << agcStatus->shutter_time << ") Gain: "
<< agcStatus->analogue_gain << " (Gain Code: "
<< gainCode << ")";
- ctrls.set(V4L2_CID_ANALOGUE_GAIN, gainCode);
+ /*
+ * Due to the behavior of V4L2, the current value of VBLANK could clip the
+ * exposure time without us knowing. The next time though this function should
+ * clip exposure correctly.
+ */
+ ctrls.set(V4L2_CID_VBLANK, vblanking);
ctrls.set(V4L2_CID_EXPOSURE, exposureLines);
+ ctrls.set(V4L2_CID_ANALOGUE_GAIN, gainCode);
}
void IPARPi::applyDG(const struct AgcStatus *dgStatus, ControlList &ctrls)
{
- if (ispCtrls_.find(V4L2_CID_DIGITAL_GAIN) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find digital gain control";
- return;
- }
-
ctrls.set(V4L2_CID_DIGITAL_GAIN,
static_cast<int32_t>(dgStatus->digital_gain * 1000));
}
void IPARPi::applyCCM(const struct CcmStatus *ccmStatus, ControlList &ctrls)
{
- if (ispCtrls_.find(V4L2_CID_USER_BCM2835_ISP_CC_MATRIX) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find CCM control";
- return;
- }
-
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];
@@ -923,12 +1145,8 @@ void IPARPi::applyCCM(const struct CcmStatus *ccmStatus, ControlList &ctrls)
void IPARPi::applyGamma(const struct ContrastStatus *contrastStatus, ControlList &ctrls)
{
- if (ispCtrls_.find(V4L2_CID_USER_BCM2835_ISP_GAMMA) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find Gamma control";
- return;
- }
-
struct bcm2835_isp_gamma gamma;
+
gamma.enabled = 1;
for (int i = 0; i < CONTRAST_NUM_POINTS; i++) {
gamma.x[i] = contrastStatus->points[i].x;
@@ -942,12 +1160,8 @@ void IPARPi::applyGamma(const struct ContrastStatus *contrastStatus, ControlList
void IPARPi::applyBlackLevel(const struct BlackLevelStatus *blackLevelStatus, ControlList &ctrls)
{
- if (ispCtrls_.find(V4L2_CID_USER_BCM2835_ISP_BLACK_LEVEL) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find black level control";
- return;
- }
-
bcm2835_isp_black_level blackLevel;
+
blackLevel.enabled = 1;
blackLevel.black_level_r = blackLevelStatus->black_level_r;
blackLevel.black_level_g = blackLevelStatus->black_level_g;
@@ -960,12 +1174,8 @@ void IPARPi::applyBlackLevel(const struct BlackLevelStatus *blackLevelStatus, Co
void IPARPi::applyGEQ(const struct GeqStatus *geqStatus, ControlList &ctrls)
{
- if (ispCtrls_.find(V4L2_CID_USER_BCM2835_ISP_GEQ) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find geq control";
- return;
- }
-
bcm2835_isp_geq geq;
+
geq.enabled = 1;
geq.offset = geqStatus->offset;
geq.slope.den = 1000;
@@ -976,34 +1186,48 @@ void IPARPi::applyGEQ(const struct GeqStatus *geqStatus, ControlList &ctrls)
ctrls.set(V4L2_CID_USER_BCM2835_ISP_GEQ, c);
}
-void IPARPi::applyDenoise(const struct SdnStatus *denoiseStatus, ControlList &ctrls)
+void IPARPi::applyDenoise(const struct DenoiseStatus *denoiseStatus, ControlList &ctrls)
{
- if (ispCtrls_.find(V4L2_CID_USER_BCM2835_ISP_DENOISE) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find denoise control";
- return;
- }
+ using RPiController::DenoiseMode;
bcm2835_isp_denoise denoise;
- denoise.enabled = 1;
+ DenoiseMode mode = static_cast<DenoiseMode>(denoiseStatus->mode);
+
+ denoise.enabled = mode != DenoiseMode::Off;
denoise.constant = denoiseStatus->noise_constant;
denoise.slope.num = 1000 * denoiseStatus->noise_slope;
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)
{
- if (ispCtrls_.find(V4L2_CID_USER_BCM2835_ISP_SHARPEN) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find sharpen control";
- return;
- }
-
bcm2835_isp_sharpen sharpen;
+
sharpen.enabled = 1;
sharpen.threshold.num = 1000 * sharpenStatus->threshold;
sharpen.threshold.den = 1000;
@@ -1019,12 +1243,8 @@ void IPARPi::applySharpen(const struct SharpenStatus *sharpenStatus, ControlList
void IPARPi::applyDPC(const struct DpcStatus *dpcStatus, ControlList &ctrls)
{
- if (ispCtrls_.find(V4L2_CID_USER_BCM2835_ISP_DPC) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find DPC control";
- return;
- }
-
bcm2835_isp_dpc dpc;
+
dpc.enabled = 1;
dpc.strength = dpcStatus->strength;
@@ -1035,17 +1255,12 @@ void IPARPi::applyDPC(const struct DpcStatus *dpcStatus, ControlList &ctrls)
void IPARPi::applyLS(const struct AlscStatus *lsStatus, ControlList &ctrls)
{
- if (ispCtrls_.find(V4L2_CID_USER_BCM2835_ISP_LENS_SHADING) == ispCtrls_.end()) {
- LOG(IPARPI, Error) << "Can't find LS control";
- return;
- }
-
/*
* 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 = ARRAY_SIZE(cellSizes);
+ unsigned int numCells = std::size(cellSizes);
unsigned int i, w, h, cellSize;
for (i = 0; i < numCells; i++) {
cellSize = cellSizes[i];
@@ -1068,13 +1283,14 @@ void IPARPi::applyLS(const struct AlscStatus *lsStatus, ControlList &ctrls)
.grid_width = w,
.grid_stride = w,
.grid_height = h,
- .dmabuf = lsTableHandle_.fd(),
+ /* .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) > RPi::MaxLsGridSize) {
+ if (!lsTable_ || w * h * 4 * sizeof(uint16_t) > ipa::RPi::MaxLsGridSize) {
LOG(IPARPI, Error) << "Do not have a correctly allocate lens shading table!";
return;
}
@@ -1145,11 +1361,11 @@ const struct IPAModuleInfo ipaModuleInfo = {
"raspberrypi",
};
-struct ipa_context *ipaCreate()
+IPAInterface *ipaCreate()
{
- return new IPAInterfaceWrapper(std::make_unique<IPARPi>());
+ return new IPARPi();
}
-}; /* extern "C" */
+} /* extern "C" */
} /* namespace libcamera */