[libcamera-devel] [PATCH v7.1 13/14] ipa: raspberrypi: Use YamlParser to replace dependency on boost

Laurent Pinchart laurent.pinchart at ideasonboard.com
Wed Jul 27 19:43:52 CEST 2022


The Raspberry Pi IPA module depends on boost only to parse the JSON
tuning data files. As libcamera depends on libyaml, use the YamlParser
class to parse those files and drop the dependency on boost.

Signed-off-by: Laurent Pinchart <laurent.pinchart at ideasonboard.com>
Tested-by: Naushir Patuck <naush at raspberrypi.com>
---
Changes since v7:

- Guard against invalid number of entries or invalid entries in
  Pwl::read()
- Don't use default value for reference_Y and reference_lux in lux.cpp

Changes since v6:

- Propagate tuning data read errors
---
 README.rst                                    |   6 -
 src/ipa/raspberrypi/controller/algorithm.cpp  |   2 +-
 src/ipa/raspberrypi/controller/algorithm.h    |   6 +-
 src/ipa/raspberrypi/controller/controller.cpp |  27 ++--
 src/ipa/raspberrypi/controller/pwl.cpp        |  27 ++--
 src/ipa/raspberrypi/controller/pwl.h          |   4 +-
 src/ipa/raspberrypi/controller/rpi/agc.cpp    | 136 ++++++++++--------
 src/ipa/raspberrypi/controller/rpi/agc.h      |  10 +-
 src/ipa/raspberrypi/controller/rpi/alsc.cpp   | 105 +++++++-------
 src/ipa/raspberrypi/controller/rpi/alsc.h     |   2 +-
 src/ipa/raspberrypi/controller/rpi/awb.cpp    | 134 ++++++++++-------
 src/ipa/raspberrypi/controller/rpi/awb.h      |   8 +-
 .../controller/rpi/black_level.cpp            |  12 +-
 .../raspberrypi/controller/rpi/black_level.h  |   2 +-
 src/ipa/raspberrypi/controller/rpi/ccm.cpp    |  47 +++---
 src/ipa/raspberrypi/controller/rpi/ccm.h      |   4 +-
 .../raspberrypi/controller/rpi/contrast.cpp   |  28 ++--
 src/ipa/raspberrypi/controller/rpi/contrast.h |   2 +-
 src/ipa/raspberrypi/controller/rpi/dpc.cpp    |   7 +-
 src/ipa/raspberrypi/controller/rpi/dpc.h      |   2 +-
 src/ipa/raspberrypi/controller/rpi/geq.cpp    |  10 +-
 src/ipa/raspberrypi/controller/rpi/geq.h      |   2 +-
 src/ipa/raspberrypi/controller/rpi/lux.cpp    |  30 +++-
 src/ipa/raspberrypi/controller/rpi/lux.h      |   2 +-
 src/ipa/raspberrypi/controller/rpi/noise.cpp  |  14 +-
 src/ipa/raspberrypi/controller/rpi/noise.h    |   2 +-
 src/ipa/raspberrypi/controller/rpi/sdn.cpp    |   6 +-
 src/ipa/raspberrypi/controller/rpi/sdn.h      |   2 +-
 .../raspberrypi/controller/rpi/sharpen.cpp    |   8 +-
 src/ipa/raspberrypi/controller/rpi/sharpen.h  |   2 +-
 src/ipa/raspberrypi/meson.build               |   1 -
 src/ipa/raspberrypi/raspberrypi.cpp           |   1 +
 32 files changed, 374 insertions(+), 277 deletions(-)

diff --git a/README.rst b/README.rst
index b9e72d81b90c..3d4e48ddc8f6 100644
--- a/README.rst
+++ b/README.rst
@@ -71,12 +71,6 @@ for improved debugging: [optional]
         information, and libunwind is not needed if both libdw and the glibc
         backtrace() function are available.
 
-for the Raspberry Pi IPA: [optional]
-        libboost-dev
-
-        Support for Raspberry Pi can be disabled through the meson
-         'pipelines' option to avoid this dependency.
-
 for device hotplug enumeration: [optional]
         libudev-dev
 
diff --git a/src/ipa/raspberrypi/controller/algorithm.cpp b/src/ipa/raspberrypi/controller/algorithm.cpp
index d73cb36fe2d6..6d91ee292bd1 100644
--- a/src/ipa/raspberrypi/controller/algorithm.cpp
+++ b/src/ipa/raspberrypi/controller/algorithm.cpp
@@ -9,7 +9,7 @@
 
 using namespace RPiController;
 
-int Algorithm::read([[maybe_unused]] boost::property_tree::ptree const &params)
+int Algorithm::read([[maybe_unused]] const libcamera::YamlObject &params)
 {
 	return 0;
 }
diff --git a/src/ipa/raspberrypi/controller/algorithm.h b/src/ipa/raspberrypi/controller/algorithm.h
index 0c5566fda874..cbbb13ba07a3 100644
--- a/src/ipa/raspberrypi/controller/algorithm.h
+++ b/src/ipa/raspberrypi/controller/algorithm.h
@@ -15,10 +15,10 @@
 #include <memory>
 #include <map>
 
+#include "libcamera/internal/yaml_parser.h"
+
 #include "controller.h"
 
-#include <boost/property_tree/ptree.hpp>
-
 namespace RPiController {
 
 /* This defines the basic interface for all control algorithms. */
@@ -35,7 +35,7 @@ public:
 	virtual bool isPaused() const { return paused_; }
 	virtual void pause() { paused_ = true; }
 	virtual void resume() { paused_ = false; }
-	virtual int read(boost::property_tree::ptree const &params);
+	virtual int read(const libcamera::YamlObject &params);
 	virtual void initialise();
 	virtual void switchMode(CameraMode const &cameraMode, Metadata *metadata);
 	virtual void prepare(Metadata *imageMetadata);
diff --git a/src/ipa/raspberrypi/controller/controller.cpp b/src/ipa/raspberrypi/controller/controller.cpp
index d91ac90704cb..bceb62540dbd 100644
--- a/src/ipa/raspberrypi/controller/controller.cpp
+++ b/src/ipa/raspberrypi/controller/controller.cpp
@@ -5,14 +5,16 @@
  * controller.cpp - ISP controller
  */
 
+#include <assert.h>
+
+#include <libcamera/base/file.h>
 #include <libcamera/base/log.h>
 
+#include "libcamera/internal/yaml_parser.h"
+
 #include "algorithm.h"
 #include "controller.h"
 
-#include <boost/property_tree/json_parser.hpp>
-#include <boost/property_tree/ptree.hpp>
-
 using namespace RPiController;
 using namespace libcamera;
 
@@ -34,18 +36,25 @@ Controller::~Controller() {}
 
 int Controller::read(char const *filename)
 {
-	boost::property_tree::ptree root;
-	boost::property_tree::read_json(filename, root);
-	for (auto const &keyAndValue : root) {
-		Algorithm *algo = createAlgorithm(keyAndValue.first.c_str());
+	File file(filename);
+	if (!file.open(File::OpenModeFlag::ReadOnly)) {
+		LOG(RPiController, Warning)
+			<< "Failed to open tuning file '" << filename << "'";
+		return -EINVAL;
+	}
+
+	std::unique_ptr<YamlObject> root = YamlParser::parse(file);
+
+	for (auto const &[key, value] : root->asDict()) {
+		Algorithm *algo = createAlgorithm(key.c_str());
 		if (algo) {
-			int ret = algo->read(keyAndValue.second);
+			int ret = algo->read(value);
 			if (ret)
 				return ret;
 			algorithms_.push_back(AlgorithmPtr(algo));
 		} else
 			LOG(RPiController, Warning)
-				<< "No algorithm found for \"" << keyAndValue.first << "\"";
+				<< "No algorithm found for \"" << key << "\"";
 	}
 
 	return 0;
diff --git a/src/ipa/raspberrypi/controller/pwl.cpp b/src/ipa/raspberrypi/controller/pwl.cpp
index fde0b298c6ce..c59f5fa131e3 100644
--- a/src/ipa/raspberrypi/controller/pwl.cpp
+++ b/src/ipa/raspberrypi/controller/pwl.cpp
@@ -12,16 +12,27 @@
 
 using namespace RPiController;
 
-int Pwl::read(boost::property_tree::ptree const &params)
+int Pwl::read(const libcamera::YamlObject &params)
 {
-	for (auto it = params.begin(); it != params.end(); it++) {
-		double x = it->second.get_value<double>();
-		assert(it == params.begin() || x > points_.back().x);
-		it++;
-		double y = it->second.get_value<double>();
-		points_.push_back(Point(x, y));
+	if (!params.size() || params.size() % 2)
+		return -EINVAL;
+
+	const auto &list = params.asList();
+
+	for (auto it = list.begin(); it != list.end(); it++) {
+		auto x = it->get<double>();
+		if (!x)
+			return -EINVAL;
+		if (it != list.begin() && *x <= points_.back().x)
+			return -EINVAL;
+
+		auto y = (++it)->get<double>();
+		if (!y)
+			return -EINVAL;
+
+		points_.push_back(Point(*x, *y));
 	}
-	assert(points_.size() >= 2);
+
 	return 0;
 }
 
diff --git a/src/ipa/raspberrypi/controller/pwl.h b/src/ipa/raspberrypi/controller/pwl.h
index ef1cc2ed113a..546482cd04d7 100644
--- a/src/ipa/raspberrypi/controller/pwl.h
+++ b/src/ipa/raspberrypi/controller/pwl.h
@@ -9,7 +9,7 @@
 #include <math.h>
 #include <vector>
 
-#include <boost/property_tree/ptree.hpp>
+#include "libcamera/internal/yaml_parser.h"
 
 namespace RPiController {
 
@@ -57,7 +57,7 @@ public:
 	};
 	Pwl() {}
 	Pwl(std::vector<Point> const &points) : points_(points) {}
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 	void append(double x, double y, const double eps = 1e-6);
 	void prepend(double x, double y, const double eps = 1e-6);
 	Interval domain() const;
diff --git a/src/ipa/raspberrypi/controller/rpi/agc.cpp b/src/ipa/raspberrypi/controller/rpi/agc.cpp
index 7fd5d18b9a22..5037f9008117 100644
--- a/src/ipa/raspberrypi/controller/rpi/agc.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/agc.cpp
@@ -31,67 +31,76 @@ LOG_DEFINE_CATEGORY(RPiAgc)
 
 static constexpr unsigned int PipelineBits = 13; /* seems to be a 13-bit pipeline */
 
-int AgcMeteringMode::read(boost::property_tree::ptree const &params)
+int AgcMeteringMode::read(const libcamera::YamlObject &params)
 {
-	int num = 0;
-
-	for (auto &p : params.get_child("weights")) {
-		if (num == AgcStatsSize) {
-			LOG(RPiAgc, Error) << "AgcMeteringMode: too many weights";
-			return -EINVAL;
-		}
-		weights[num++] = p.second.get_value<double>();
-	}
-
-	if (num != AgcStatsSize) {
-		LOG(RPiAgc, Error) << "AgcMeteringMode: insufficient weights";
+	const YamlObject &yamlWeights = params["weights"];
+	if (yamlWeights.size() != AgcStatsSize) {
+		LOG(RPiAgc, Error) << "AgcMeteringMode: Incorrect number of weights";
 		return -EINVAL;
 	}
 
+	unsigned int num = 0;
+	for (const auto &p : yamlWeights.asList()) {
+		auto value = p.get<double>();
+		if (!value)
+			return -EINVAL;
+		weights[num++] = *value;
+	}
+
 	return 0;
 }
 
 static std::tuple<int, std::string>
-readMeteringModes(std::map<std::string, AgcMeteringMode> &meteringModes,
-		  boost::property_tree::ptree const &params)
+readMeteringModes(std::map<std::string, AgcMeteringMode> &metering_modes,
+		  const libcamera::YamlObject &params)
 {
 	std::string first;
 	int ret;
 
-	for (auto &p : params) {
+	for (const auto &[key, value] : params.asDict()) {
 		AgcMeteringMode meteringMode;
-		ret = meteringMode.read(p.second);
+		ret = meteringMode.read(value);
 		if (ret)
 			return { ret, {} };
 
-		meteringModes[p.first] = std::move(meteringMode);
+		metering_modes[key] = std::move(meteringMode);
 		if (first.empty())
-			first = p.first;
+			first = key;
 	}
 
 	return { 0, first };
 }
 
 static int readList(std::vector<double> &list,
-		    boost::property_tree::ptree const &params)
+		    const libcamera::YamlObject &params)
 {
-	for (auto &p : params)
-		list.push_back(p.second.get_value<double>());
+	for (const auto &p : params.asList()) {
+		auto value = p.get<double>();
+		if (!value)
+			return -EINVAL;
+		list.push_back(*value);
+	}
+
 	return list.size();
 }
 
 static int readList(std::vector<Duration> &list,
-		    boost::property_tree::ptree const &params)
+		    const libcamera::YamlObject &params)
 {
-	for (auto &p : params)
-		list.push_back(p.second.get_value<double>() * 1us);
+	for (const auto &p : params.asList()) {
+		auto value = p.get<double>();
+		if (!value)
+			return -EINVAL;
+		list.push_back(*value * 1us);
+	}
+
 	return list.size();
 }
 
-int AgcExposureMode::read(boost::property_tree::ptree const &params)
+int AgcExposureMode::read(const libcamera::YamlObject &params)
 {
-	int numShutters = readList(shutter, params.get_child("shutter"));
-	int numAgs = readList(gain, params.get_child("gain"));
+	int numShutters = readList(shutter, params["shutter"]);
+	int numAgs = readList(gain, params["gain"]);
 
 	if (numShutters < 2 || numAgs < 2) {
 		LOG(RPiAgc, Error)
@@ -110,28 +119,28 @@ int AgcExposureMode::read(boost::property_tree::ptree const &params)
 
 static std::tuple<int, std::string>
 readExposureModes(std::map<std::string, AgcExposureMode> &exposureModes,
-		  boost::property_tree::ptree const &params)
+		  const libcamera::YamlObject &params)
 {
 	std::string first;
 	int ret;
 
-	for (auto &p : params) {
+	for (const auto &[key, value] : params.asDict()) {
 		AgcExposureMode exposureMode;
-		ret = exposureMode.read(p.second);
+		ret = exposureMode.read(value);
 		if (ret)
 			return { ret, {} };
 
-		exposureModes[p.first] = std::move(exposureMode);
+		exposureModes[key] = std::move(exposureMode);
 		if (first.empty())
-			first = p.first;
+			first = key;
 	}
 
 	return { 0, first };
 }
 
-int AgcConstraint::read(boost::property_tree::ptree const &params)
+int AgcConstraint::read(const libcamera::YamlObject &params)
 {
-	std::string boundString = params.get<std::string>("bound", "");
+	std::string boundString = params["bound"].get<std::string>("");
 	transform(boundString.begin(), boundString.end(),
 		  boundString.begin(), ::toupper);
 	if (boundString != "UPPER" && boundString != "LOWER") {
@@ -139,20 +148,29 @@ int AgcConstraint::read(boost::property_tree::ptree const &params)
 		return -EINVAL;
 	}
 	bound = boundString == "UPPER" ? Bound::UPPER : Bound::LOWER;
-	qLo = params.get<double>("q_lo");
-	qHi = params.get<double>("q_hi");
-	return yTarget.read(params.get_child("y_target"));
+
+	auto value = params["q_lo"].get<double>();
+	if (!value)
+		return -EINVAL;
+	qLo = *value;
+
+	value = params["q_hi"].get<double>();
+	if (!value)
+		return -EINVAL;
+	qHi = *value;
+
+	return yTarget.read(params["y_target"]);
 }
 
 static std::tuple<int, AgcConstraintMode>
-readConstraintMode(boost::property_tree::ptree const &params)
+readConstraintMode(const libcamera::YamlObject &params)
 {
 	AgcConstraintMode mode;
 	int ret;
 
-	for (auto &p : params) {
+	for (const auto &p : params.asList()) {
 		AgcConstraint constraint;
-		ret = constraint.read(p.second);
+		ret = constraint.read(p);
 		if (ret)
 			return { ret, {} };
 
@@ -164,53 +182,55 @@ readConstraintMode(boost::property_tree::ptree const &params)
 
 static std::tuple<int, std::string>
 readConstraintModes(std::map<std::string, AgcConstraintMode> &constraintModes,
-		    boost::property_tree::ptree const &params)
+		    const libcamera::YamlObject &params)
 {
 	std::string first;
 	int ret;
 
-	for (auto &p : params) {
-		std::tie(ret, constraintModes[p.first]) = readConstraintMode(p.second);
+	for (const auto &[key, value] : params.asDict()) {
+		std::tie(ret, constraintModes[key]) = readConstraintMode(value);
 		if (ret)
 			return { ret, {} };
 
 		if (first.empty())
-			first = p.first;
+			first = key;
 	}
 
 	return { 0, first };
 }
 
-int AgcConfig::read(boost::property_tree::ptree const &params)
+int AgcConfig::read(const libcamera::YamlObject &params)
 {
 	LOG(RPiAgc, Debug) << "AgcConfig";
 	int ret;
 
 	std::tie(ret, defaultMeteringMode) =
-		readMeteringModes(meteringModes, params.get_child("metering_modes"));
+		readMeteringModes(meteringModes, params["metering_modes"]);
 	if (ret)
 		return ret;
 	std::tie(ret, defaultExposureMode) =
-		readExposureModes(exposureModes, params.get_child("exposure_modes"));
+		readExposureModes(exposureModes, params["exposure_modes"]);
 	if (ret)
 		return ret;
 	std::tie(ret, defaultConstraintMode) =
-		readConstraintModes(constraintModes, params.get_child("constraint_modes"));
+		readConstraintModes(constraintModes, params["constraint_modes"]);
 	if (ret)
 		return ret;
 
-	ret = yTarget.read(params.get_child("y_target"));
+	ret = yTarget.read(params["y_target"]);
 	if (ret)
 		return ret;
 
-	speed = params.get<double>("speed", 0.2);
-	startupFrames = params.get<uint16_t>("startup_frames", 10);
-	convergenceFrames = params.get<unsigned int>("convergence_frames", 6);
-	fastReduceThreshold = params.get<double>("fast_reduce_threshold", 0.4);
-	baseEv = params.get<double>("base_ev", 1.0);
+	speed = params["speed"].get<double>(0.2);
+	startupFrames = params["startup_frames"].get<uint16_t>(10);
+	convergenceFrames = params["convergence_frames"].get<unsigned int>(6);
+	fastReduceThreshold = params["fast_reduce_threshold"].get<double>(0.4);
+	baseEv = params["base_ev"].get<double>(1.0);
+
 	/* Start with quite a low value as ramping up is easier than ramping down. */
-	defaultExposureTime = params.get<double>("default_exposure_time", 1000) * 1us;
-	defaultAnalogueGain = params.get<double>("default_analogueGain", 1.0);
+	defaultExposureTime = params["default_exposure_time"].get<double>(1000) * 1us;
+	defaultAnalogueGain = params["default_analogue_gain"].get<double>(1.0);
+
 	return 0;
 }
 
@@ -242,7 +262,7 @@ char const *Agc::name() const
 	return NAME;
 }
 
-int Agc::read(boost::property_tree::ptree const &params)
+int Agc::read(const libcamera::YamlObject &params)
 {
 	LOG(RPiAgc, Debug) << "Agc";
 
diff --git a/src/ipa/raspberrypi/controller/rpi/agc.h b/src/ipa/raspberrypi/controller/rpi/agc.h
index 1351b0ee079c..6d6b0e5ad857 100644
--- a/src/ipa/raspberrypi/controller/rpi/agc.h
+++ b/src/ipa/raspberrypi/controller/rpi/agc.h
@@ -28,13 +28,13 @@ namespace RPiController {
 
 struct AgcMeteringMode {
 	double weights[AgcStatsSize];
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 };
 
 struct AgcExposureMode {
 	std::vector<libcamera::utils::Duration> shutter;
 	std::vector<double> gain;
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 };
 
 struct AgcConstraint {
@@ -43,13 +43,13 @@ struct AgcConstraint {
 	double qLo;
 	double qHi;
 	Pwl yTarget;
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 };
 
 typedef std::vector<AgcConstraint> AgcConstraintMode;
 
 struct AgcConfig {
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 	std::map<std::string, AgcMeteringMode> meteringModes;
 	std::map<std::string, AgcExposureMode> exposureModes;
 	std::map<std::string, AgcConstraintMode> constraintModes;
@@ -74,7 +74,7 @@ class Agc : public AgcAlgorithm
 public:
 	Agc(Controller *controller);
 	char const *name() const override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	/* AGC handles "pausing" for itself. */
 	bool isPaused() const override;
 	void pause() override;
diff --git a/src/ipa/raspberrypi/controller/rpi/alsc.cpp b/src/ipa/raspberrypi/controller/rpi/alsc.cpp
index 49aaf6b74603..a4afaf841c41 100644
--- a/src/ipa/raspberrypi/controller/rpi/alsc.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/alsc.cpp
@@ -5,6 +5,7 @@
  * alsc.cpp - ALSC (auto lens shading correction) control algorithm
  */
 
+#include <functional>
 #include <math.h>
 #include <numeric>
 
@@ -50,15 +51,15 @@ char const *Alsc::name() const
 	return NAME;
 }
 
-static int generateLut(double *lut, boost::property_tree::ptree const &params)
+static int generateLut(double *lut, const libcamera::YamlObject &params)
 {
-	double cstrength = params.get<double>("corner_strength", 2.0);
+	double cstrength = params["corner_strength"].get<double>(2.0);
 	if (cstrength <= 1.0) {
 		LOG(RPiAlsc, Error) << "corner_strength must be > 1.0";
 		return -EINVAL;
 	}
 
-	double asymmetry = params.get<double>("asymmetry", 1.0);
+	double asymmetry = params["asymmetry"].get<double>(1.0);
 	if (asymmetry < 0) {
 		LOG(RPiAlsc, Error) << "asymmetry must be >= 0";
 		return -EINVAL;
@@ -80,34 +81,35 @@ static int generateLut(double *lut, boost::property_tree::ptree const &params)
 	return 0;
 }
 
-static int readLut(double *lut, boost::property_tree::ptree const &params)
+static int readLut(double *lut, const libcamera::YamlObject &params)
 {
-	int num = 0;
-	const int maxNum = XY;
+	if (params.size() != XY) {
+		LOG(RPiAlsc, Error) << "Invalid number of entries in LSC table";
+		return -EINVAL;
+	}
 
-	for (auto &p : params) {
-		if (num == maxNum) {
-			LOG(RPiAlsc, Error) << "Too many entries in LSC table";
+	int num = 0;
+	for (const auto &p : params.asList()) {
+		auto value = p.get<double>();
+		if (!value)
 			return -EINVAL;
-		}
-		lut[num++] = p.second.get_value<double>();
+		lut[num++] = *value;
 	}
 
-	if (num < maxNum) {
-		LOG(RPiAlsc, Error) << "Too few entries in LSC table";
-		return -EINVAL;
-	}
 	return 0;
 }
 
 static int readCalibrations(std::vector<AlscCalibration> &calibrations,
-			    boost::property_tree::ptree const &params,
+			    const libcamera::YamlObject &params,
 			    std::string const &name)
 {
-	if (params.get_child_optional(name)) {
+	if (params.contains(name)) {
 		double lastCt = 0;
-		for (auto &p : params.get_child(name)) {
-			double ct = p.second.get<double>("ct");
+		for (const auto &p : params[name].asList()) {
+			auto value = p["ct"].get<double>();
+			if (!value)
+				return -EINVAL;
+			double ct = *value;
 			if (ct <= lastCt) {
 				LOG(RPiAlsc, Error)
 					<< "Entries in " << name << " must be in increasing ct order";
@@ -115,23 +117,23 @@ static int readCalibrations(std::vector<AlscCalibration> &calibrations,
 			}
 			AlscCalibration calibration;
 			calibration.ct = lastCt = ct;
-			boost::property_tree::ptree const &table =
-				p.second.get_child("table");
+
+			const libcamera::YamlObject &table = p["table"];
+			if (table.size() != XY) {
+				LOG(RPiAlsc, Error)
+					<< "Incorrect number of values for ct "
+					<< ct << " in " << name;
+				return -EINVAL;
+			}
+
 			int num = 0;
-			for (auto it = table.begin(); it != table.end(); it++) {
-				if (num == XY) {
-					LOG(RPiAlsc, Error)
-						<< "Too many values for ct " << ct << " in " << name;
+			for (const auto &elem : table.asList()) {
+				value = elem.get<double>();
+				if (!value)
 					return -EINVAL;
-				}
-				calibration.table[num++] =
-					it->second.get_value<double>();
-			}
-			if (num != XY) {
-				LOG(RPiAlsc, Error)
-					<< "Too few values for ct " << ct << " in " << name;
-				return -EINVAL;
+				calibration.table[num++] = *value;
 			}
+
 			calibrations.push_back(calibration);
 			LOG(RPiAlsc, Debug)
 				<< "Read " << name << " calibration for ct " << ct;
@@ -140,30 +142,29 @@ static int readCalibrations(std::vector<AlscCalibration> &calibrations,
 	return 0;
 }
 
-int Alsc::read(boost::property_tree::ptree const &params)
+int Alsc::read(const libcamera::YamlObject &params)
 {
-	config_.framePeriod = params.get<uint16_t>("frame_period", 12);
-	config_.startupFrames = params.get<uint16_t>("startup_frames", 10);
-	config_.speed = params.get<double>("speed", 0.05);
-	double sigma = params.get<double>("sigma", 0.01);
-	config_.sigmaCr = params.get<double>("sigma_Cr", sigma);
-	config_.sigmaCb = params.get<double>("sigma_Cb", sigma);
-	config_.minCount = params.get<double>("min_count", 10.0);
-	config_.minG = params.get<uint16_t>("min_G", 50);
-	config_.omega = params.get<double>("omega", 1.3);
-	config_.nIter = params.get<uint32_t>("n_iter", X + Y);
+	config_.framePeriod = params["frame_period"].get<uint16_t>(12);
+	config_.startupFrames = params["startup_frames"].get<uint16_t>(10);
+	config_.speed = params["speed"].get<double>(0.05);
+	double sigma = params["sigma"].get<double>(0.01);
+	config_.sigmaCr = params["sigma_Cr"].get<double>(sigma);
+	config_.sigmaCb = params["sigma_Cb"].get<double>(sigma);
+	config_.minCount = params["min_count"].get<double>(10.0);
+	config_.minG = params["min_G"].get<uint16_t>(50);
+	config_.omega = params["omega"].get<double>(1.3);
+	config_.nIter = params["n_iter"].get<uint32_t>(X + Y);
 	config_.luminanceStrength =
-		params.get<double>("luminance_strength", 1.0);
+		params["luminance_strength"].get<double>(1.0);
 	for (int i = 0; i < XY; i++)
 		config_.luminanceLut[i] = 1.0;
 
 	int ret = 0;
 
-	if (params.get_child_optional("corner_strength"))
+	if (params.contains("corner_strength"))
 		ret = generateLut(config_.luminanceLut, params);
-	else if (params.get_child_optional("luminance_lut"))
-		ret = readLut(config_.luminanceLut,
-			      params.get_child("luminance_lut"));
+	else if (params.contains("luminance_lut"))
+		ret = readLut(config_.luminanceLut, params["luminance_lut"]);
 	else
 		LOG(RPiAlsc, Warning)
 			<< "no luminance table - assume unity everywhere";
@@ -177,9 +178,9 @@ int Alsc::read(boost::property_tree::ptree const &params)
 	if (ret)
 		return ret;
 
-	config_.defaultCt = params.get<double>("default_ct", 4500.0);
-	config_.threshold = params.get<double>("threshold", 1e-3);
-	config_.lambdaBound = params.get<double>("lambda_bound", 0.05);
+	config_.defaultCt = params["default_ct"].get<double>(4500.0);
+	config_.threshold = params["threshold"].get<double>(1e-3);
+	config_.lambdaBound = params["lambda_bound"].get<double>(0.05);
 
 	return 0;
 }
diff --git a/src/ipa/raspberrypi/controller/rpi/alsc.h b/src/ipa/raspberrypi/controller/rpi/alsc.h
index 773fd338ea8e..a858ef5a6551 100644
--- a/src/ipa/raspberrypi/controller/rpi/alsc.h
+++ b/src/ipa/raspberrypi/controller/rpi/alsc.h
@@ -52,7 +52,7 @@ public:
 	char const *name() const override;
 	void initialise() override;
 	void switchMode(CameraMode const &cameraMode, Metadata *metadata) override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void prepare(Metadata *imageMetadata) override;
 	void process(StatisticsPtr &stats, Metadata *imageMetadata) override;
 
diff --git a/src/ipa/raspberrypi/controller/rpi/awb.cpp b/src/ipa/raspberrypi/controller/rpi/awb.cpp
index d8c9665445f9..a16e04a07ff8 100644
--- a/src/ipa/raspberrypi/controller/rpi/awb.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/awb.cpp
@@ -5,6 +5,8 @@
  * awb.cpp - AWB control algorithm
  */
 
+#include <assert.h>
+
 #include <libcamera/base/log.h>
 
 #include "../lux_status.h"
@@ -26,62 +28,87 @@ static constexpr unsigned int AwbStatsSizeY = DEFAULT_AWB_REGIONS_Y;
  * elsewhere (ALSC and AGC).
  */
 
-int AwbMode::read(boost::property_tree::ptree const &params)
+int AwbMode::read(const libcamera::YamlObject &params)
 {
-	ctLo = params.get<double>("lo");
-	ctHi = params.get<double>("hi");
+	auto value = params["lo"].get<double>();
+	if (!value)
+		return -EINVAL;
+	ctLo = *value;
+
+	value = params["hi"].get<double>();
+	if (!value)
+		return -EINVAL;
+	ctHi = *value;
+
 	return 0;
 }
 
-int AwbPrior::read(boost::property_tree::ptree const &params)
+int AwbPrior::read(const libcamera::YamlObject &params)
 {
-	lux = params.get<double>("lux");
-	return prior.read(params.get_child("prior"));
+	auto value = params["lux"].get<double>();
+	if (!value)
+		return -EINVAL;
+	lux = *value;
+
+	return prior.read(params["prior"]);
 }
 
-static int readCtCurve(Pwl &ctR, Pwl &ctB,
-		       boost::property_tree::ptree const &params)
+static int readCtCurve(Pwl &ctR, Pwl &ctB, const libcamera::YamlObject &params)
 {
-	int num = 0;
-	for (auto it = params.begin(); it != params.end(); it++) {
-		double ct = it->second.get_value<double>();
-		assert(it == params.begin() || ct != ctR.domain().end);
-		if (++it == params.end()) {
-			LOG(RPiAwb, Error) << "AwbConfig: incomplete CT curve entry";
-			return -EINVAL;
-		}
-		ctR.append(ct, it->second.get_value<double>());
-		if (++it == params.end()) {
-			LOG(RPiAwb, Error) << "AwbConfig: incomplete CT curve entry";
-			return -EINVAL;
-		}
-		ctB.append(ct, it->second.get_value<double>());
-		num++;
+	if (params.size() % 3) {
+		LOG(RPiAwb, Error) << "AwbConfig: incomplete CT curve entry";
+		return -EINVAL;
 	}
-	if (num < 2) {
+
+	if (params.size() < 6) {
 		LOG(RPiAwb, Error) << "AwbConfig: insufficient points in CT curve";
 		return -EINVAL;
 	}
+
+	const auto &list = params.asList();
+
+	for (auto it = list.begin(); it != list.end(); it++) {
+		auto value = it->get<double>();
+		if (!value)
+			return -EINVAL;
+		double ct = *value;
+
+		assert(it == list.begin() || ct != ctR.domain().end);
+
+		value = (++it)->get<double>();
+		if (!value)
+			return -EINVAL;
+		ctR.append(ct, *value);
+
+		value = (++it)->get<double>();
+		if (!value)
+			return -EINVAL;
+		ctB.append(ct, *value);
+	}
+
 	return 0;
 }
 
-int AwbConfig::read(boost::property_tree::ptree const &params)
+int AwbConfig::read(const libcamera::YamlObject &params)
 {
 	int ret;
-	bayes = params.get<int>("bayes", 1);
-	framePeriod = params.get<uint16_t>("framePeriod", 10);
-	startupFrames = params.get<uint16_t>("startupFrames", 10);
-	convergenceFrames = params.get<unsigned int>("convergence_frames", 3);
-	speed = params.get<double>("speed", 0.05);
-	if (params.get_child_optional("ct_curve")) {
-		ret = readCtCurve(ctR, ctB, params.get_child("ct_curve"));
+
+	bayes = params["bayes"].get<int>(1);
+	framePeriod = params["frame_period"].get<uint16_t>(10);
+	startupFrames = params["startup_frames"].get<uint16_t>(10);
+	convergenceFrames = params["convergence_frames"].get<unsigned int>(3);
+	speed = params["speed"].get<double>(0.05);
+
+	if (params.contains("ct_curve")) {
+		ret = readCtCurve(ctR, ctB, params["ct_curve"]);
 		if (ret)
 			return ret;
 	}
-	if (params.get_child_optional("priors")) {
-		for (auto &p : params.get_child("priors")) {
+
+	if (params.contains("priors")) {
+		for (const auto &p : params["priors"].asList()) {
 			AwbPrior prior;
-			ret = prior.read(p.second);
+			ret = prior.read(p);
 			if (ret)
 				return ret;
 			if (!priors.empty() && prior.lux <= priors.back().lux) {
@@ -95,32 +122,35 @@ int AwbConfig::read(boost::property_tree::ptree const &params)
 			return ret;
 		}
 	}
-	if (params.get_child_optional("modes")) {
-		for (auto &p : params.get_child("modes")) {
-			ret = modes[p.first].read(p.second);
+	if (params.contains("modes")) {
+		for (const auto &[key, value] : params["modes"].asDict()) {
+			ret = modes[key].read(value);
 			if (ret)
 				return ret;
 			if (defaultMode == nullptr)
-				defaultMode = &modes[p.first];
+				defaultMode = &modes[key];
 		}
 		if (defaultMode == nullptr) {
 			LOG(RPiAwb, Error) << "AwbConfig: no AWB modes configured";
 			return -EINVAL;
 		}
 	}
-	minPixels = params.get<double>("min_pixels", 16.0);
-	minG = params.get<uint16_t>("min_G", 32);
-	minRegions = params.get<uint32_t>("min_regions", 10);
-	deltaLimit = params.get<double>("delta_limit", 0.2);
-	coarseStep = params.get<double>("coarse_step", 0.2);
-	transversePos = params.get<double>("transverse_pos", 0.01);
-	transverseNeg = params.get<double>("transverse_neg", 0.01);
+
+	minPixels = params["min_pixels"].get<double>(16.0);
+	minG = params["min_G"].get<uint16_t>(32);
+	minRegions = params["min_regions"].get<uint32_t>(10);
+	deltaLimit = params["delta_limit"].get<double>(0.2);
+	coarseStep = params["coarse_step"].get<double>(0.2);
+	transversePos = params["transverse_pos"].get<double>(0.01);
+	transverseNeg = params["transverse_neg"].get<double>(0.01);
 	if (transversePos <= 0 || transverseNeg <= 0) {
 		LOG(RPiAwb, Error) << "AwbConfig: transverse_pos/neg must be > 0";
 		return -EINVAL;
 	}
-	sensitivityR = params.get<double>("sensitivity_r", 1.0);
-	sensitivityB = params.get<double>("sensitivity_b", 1.0);
+
+	sensitivityR = params["sensitivity_r"].get<double>(1.0);
+	sensitivityB = params["sensitivity_b"].get<double>(1.0);
+
 	if (bayes) {
 		if (ctR.empty() || ctB.empty() || priors.empty() ||
 		    defaultMode == nullptr) {
@@ -129,9 +159,9 @@ int AwbConfig::read(boost::property_tree::ptree const &params)
 			bayes = false;
 		}
 	}
-	fast = params.get<int>("fast", bayes); /* default to fast for Bayesian, otherwise slow */
-	whitepointR = params.get<double>("whitepoint_r", 0.0);
-	whitepointB = params.get<double>("whitepoint_b", 0.0);
+	fast = params[fast].get<int>(bayes); /* default to fast for Bayesian, otherwise slow */
+	whitepointR = params["whitepoint_r"].get<double>(0.0);
+	whitepointB = params["whitepoint_b"].get<double>(0.0);
 	if (bayes == false)
 		sensitivityR = sensitivityB = 1.0; /* nor do sensitivities make any sense */
 	return 0;
@@ -162,7 +192,7 @@ char const *Awb::name() const
 	return NAME;
 }
 
-int Awb::read(boost::property_tree::ptree const &params)
+int Awb::read(const libcamera::YamlObject &params)
 {
 	return config_.read(params);
 }
diff --git a/src/ipa/raspberrypi/controller/rpi/awb.h b/src/ipa/raspberrypi/controller/rpi/awb.h
index 9c5cf4eaaaaf..cb4cfd1be2e8 100644
--- a/src/ipa/raspberrypi/controller/rpi/awb.h
+++ b/src/ipa/raspberrypi/controller/rpi/awb.h
@@ -19,20 +19,20 @@ namespace RPiController {
 /* Control algorithm to perform AWB calculations. */
 
 struct AwbMode {
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 	double ctLo; /* low CT value for search */
 	double ctHi; /* high CT value for search */
 };
 
 struct AwbPrior {
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 	double lux; /* lux level */
 	Pwl prior; /* maps CT to prior log likelihood for this lux level */
 };
 
 struct AwbConfig {
 	AwbConfig() : defaultMode(nullptr) {}
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 	/* Only repeat the AWB calculation every "this many" frames */
 	uint16_t framePeriod;
 	/* number of initial frames for which speed taken as 1.0 (maximum) */
@@ -90,7 +90,7 @@ public:
 	~Awb();
 	char const *name() const override;
 	void initialise() override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	/* AWB handles "pausing" for itself. */
 	bool isPaused() const override;
 	void pause() override;
diff --git a/src/ipa/raspberrypi/controller/rpi/black_level.cpp b/src/ipa/raspberrypi/controller/rpi/black_level.cpp
index 749fcd7cdf8c..85baec3fcbdd 100644
--- a/src/ipa/raspberrypi/controller/rpi/black_level.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/black_level.cpp
@@ -31,13 +31,13 @@ char const *BlackLevel::name() const
 	return NAME;
 }
 
-int BlackLevel::read(boost::property_tree::ptree const &params)
+int BlackLevel::read(const libcamera::YamlObject &params)
 {
-	uint16_t blackLevel = params.get<uint16_t>(
-		"black_level", 4096); /* 64 in 10 bits scaled to 16 bits */
-	blackLevelR_ = params.get<uint16_t>("black_level_r", blackLevel);
-	blackLevelG_ = params.get<uint16_t>("black_level_g", blackLevel);
-	blackLevelB_ = params.get<uint16_t>("black_level_b", blackLevel);
+	/* 64 in 10 bits scaled to 16 bits */
+	uint16_t blackLevel = params["black_level"].get<uint16_t>(4096);
+	blackLevelR_ = params["black_level_r"].get<uint16_t>(blackLevel);
+	blackLevelG_ = params["black_level_g"].get<uint16_t>(blackLevel);
+	blackLevelB_ = params["black_level_b"].get<uint16_t>(blackLevel);
 	LOG(RPiBlackLevel, Debug)
 		<< " Read black levels red " << blackLevelR_
 		<< " green " << blackLevelG_
diff --git a/src/ipa/raspberrypi/controller/rpi/black_level.h b/src/ipa/raspberrypi/controller/rpi/black_level.h
index 6ec8c4f9ba8f..2403f7f77625 100644
--- a/src/ipa/raspberrypi/controller/rpi/black_level.h
+++ b/src/ipa/raspberrypi/controller/rpi/black_level.h
@@ -18,7 +18,7 @@ class BlackLevel : public Algorithm
 public:
 	BlackLevel(Controller *controller);
 	char const *name() const override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void prepare(Metadata *imageMetadata) override;
 
 private:
diff --git a/src/ipa/raspberrypi/controller/rpi/ccm.cpp b/src/ipa/raspberrypi/controller/rpi/ccm.cpp
index 9588e94adeb1..2e2e66647e86 100644
--- a/src/ipa/raspberrypi/controller/rpi/ccm.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/ccm.cpp
@@ -39,21 +39,22 @@ Matrix::Matrix(double m0, double m1, double m2, double m3, double m4, double m5,
 	m[0][0] = m0, m[0][1] = m1, m[0][2] = m2, m[1][0] = m3, m[1][1] = m4,
 	m[1][2] = m5, m[2][0] = m6, m[2][1] = m7, m[2][2] = m8;
 }
-int Matrix::read(boost::property_tree::ptree const &params)
+int Matrix::read(const libcamera::YamlObject &params)
 {
 	double *ptr = (double *)m;
-	int n = 0;
-	for (auto it = params.begin(); it != params.end(); it++) {
-		if (n++ == 9) {
-			LOG(RPiCcm, Error) << "Too many values in CCM";
-			return -EINVAL;
-		}
-		*ptr++ = it->second.get_value<double>();
-	}
-	if (n < 9) {
-		LOG(RPiCcm, Error) << "Too few values in CCM";
+
+	if (params.size() != 9) {
+		LOG(RPiCcm, Error) << "Wrong number of values in CCM";
 		return -EINVAL;
 	}
+
+	for (const auto &param : params.asList()) {
+		auto value = param.get<double>();
+		if (!value)
+			return -EINVAL;
+		*ptr++ = *value;
+	}
+
 	return 0;
 }
 
@@ -65,27 +66,33 @@ char const *Ccm::name() const
 	return NAME;
 }
 
-int Ccm::read(boost::property_tree::ptree const &params)
+int Ccm::read(const libcamera::YamlObject &params)
 {
 	int ret;
 
-	if (params.get_child_optional("saturation")) {
-		ret = config_.saturation.read(params.get_child("saturation"));
+	if (params.contains("saturation")) {
+		ret = config_.saturation.read(params["saturation"]);
 		if (ret)
 			return ret;
 	}
 
-	for (auto &p : params.get_child("ccms")) {
+	for (auto &p : params["ccms"].asList()) {
+		auto value = p["ct"].get<double>();
+		if (!value)
+			return -EINVAL;
+
 		CtCcm ctCcm;
-		ctCcm.ct = p.second.get<double>("ct");
-		ret = ctCcm.ccm.read(p.second.get_child("ccm"));
+		ctCcm.ct = *value;
+		ret = ctCcm.ccm.read(p["ccm"]);
 		if (ret)
 			return ret;
-		if (!config_.ccms.empty() &&
-		    ctCcm.ct <= config_.ccms.back().ct) {
-			LOG(RPiCcm, Error) << "CCM not in increasing colour temperature order";
+
+		if (!config_.ccms.empty() && ctCcm.ct <= config_.ccms.back().ct) {
+			LOG(RPiCcm, Error)
+				<< "CCM not in increasing colour temperature order";
 			return -EINVAL;
 		}
+
 		config_.ccms.push_back(std::move(ctCcm));
 	}
 
diff --git a/src/ipa/raspberrypi/controller/rpi/ccm.h b/src/ipa/raspberrypi/controller/rpi/ccm.h
index 6b65c7aea8a6..286d0b33e72f 100644
--- a/src/ipa/raspberrypi/controller/rpi/ccm.h
+++ b/src/ipa/raspberrypi/controller/rpi/ccm.h
@@ -20,7 +20,7 @@ struct Matrix {
 	       double m6, double m7, double m8);
 	Matrix();
 	double m[3][3];
-	int read(boost::property_tree::ptree const &params);
+	int read(const libcamera::YamlObject &params);
 };
 static inline Matrix operator*(double d, Matrix const &m)
 {
@@ -62,7 +62,7 @@ class Ccm : public CcmAlgorithm
 public:
 	Ccm(Controller *controller = NULL);
 	char const *name() const override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void setSaturation(double saturation) override;
 	void initialise() override;
 	void prepare(Metadata *imageMetadata) override;
diff --git a/src/ipa/raspberrypi/controller/rpi/contrast.cpp b/src/ipa/raspberrypi/controller/rpi/contrast.cpp
index d76dc43b837f..5b37edcbd46a 100644
--- a/src/ipa/raspberrypi/controller/rpi/contrast.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/contrast.cpp
@@ -38,21 +38,21 @@ char const *Contrast::name() const
 	return NAME;
 }
 
-int Contrast::read(boost::property_tree::ptree const &params)
+int Contrast::read(const libcamera::YamlObject &params)
 {
-	/* enable adaptive enhancement by default */
-	config_.ceEnable = params.get<int>("ce_enable", 1);
-	/* the point near the bottom of the histogram to move */
-	config_.loHistogram = params.get<double>("lo_histogram", 0.01);
-	/* where in the range to try and move it to */
-	config_.loLevel = params.get<double>("lo_level", 0.015);
-	/* but don't move by more than this */
-	config_.loMax = params.get<double>("lo_max", 500);
-	/* equivalent values for the top of the histogram... */
-	config_.hiHistogram = params.get<double>("hi_histogram", 0.95);
-	config_.hiLevel = params.get<double>("hi_level", 0.95);
-	config_.hiMax = params.get<double>("hi_max", 2000);
-	return config_.gammaCurve.read(params.get_child("gamma_curve"));
+	// enable adaptive enhancement by default
+	config_.ceEnable = params["ce_enable"].get<int>(1);
+	// the point near the bottom of the histogram to move
+	config_.loHistogram = params["lo_histogram"].get<double>(0.01);
+	// where in the range to try and move it to
+	config_.loLevel = params["lo_level"].get<double>(0.015);
+	// but don't move by more than this
+	config_.loMax = params["lo_max"].get<double>(500);
+	// equivalent values for the top of the histogram...
+	config_.hiHistogram = params["hi_histogram"].get<double>(0.95);
+	config_.hiLevel = params["hi_level"].get<double>(0.95);
+	config_.hiMax = params["hi_max"].get<double>(2000);
+	return config_.gammaCurve.read(params["gamma_curve"]);
 }
 
 void Contrast::setBrightness(double brightness)
diff --git a/src/ipa/raspberrypi/controller/rpi/contrast.h b/src/ipa/raspberrypi/controller/rpi/contrast.h
index 5c3d2f56b310..c68adbc9e463 100644
--- a/src/ipa/raspberrypi/controller/rpi/contrast.h
+++ b/src/ipa/raspberrypi/controller/rpi/contrast.h
@@ -34,7 +34,7 @@ class Contrast : public ContrastAlgorithm
 public:
 	Contrast(Controller *controller = NULL);
 	char const *name() const override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void setBrightness(double brightness) override;
 	void setContrast(double contrast) override;
 	void initialise() override;
diff --git a/src/ipa/raspberrypi/controller/rpi/dpc.cpp b/src/ipa/raspberrypi/controller/rpi/dpc.cpp
index def39bb7416a..be3871dffe28 100644
--- a/src/ipa/raspberrypi/controller/rpi/dpc.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/dpc.cpp
@@ -31,13 +31,14 @@ char const *Dpc::name() const
 	return NAME;
 }
 
-int Dpc::read(boost::property_tree::ptree const &params)
+int Dpc::read(const libcamera::YamlObject &params)
 {
-	config_.strength = params.get<int>("strength", 1);
+	config_.strength = params["strength"].get<int>(1);
 	if (config_.strength < 0 || config_.strength > 2) {
-		LOG(RPiDpc, Error) << "bad strength value";
+		LOG(RPiDpc, Error) << "Bad strength value";
 		return -EINVAL;
 	}
+
 	return 0;
 }
 
diff --git a/src/ipa/raspberrypi/controller/rpi/dpc.h b/src/ipa/raspberrypi/controller/rpi/dpc.h
index 2bb6cef565a7..84a05604394d 100644
--- a/src/ipa/raspberrypi/controller/rpi/dpc.h
+++ b/src/ipa/raspberrypi/controller/rpi/dpc.h
@@ -22,7 +22,7 @@ class Dpc : public Algorithm
 public:
 	Dpc(Controller *controller);
 	char const *name() const override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void prepare(Metadata *imageMetadata) override;
 
 private:
diff --git a/src/ipa/raspberrypi/controller/rpi/geq.cpp b/src/ipa/raspberrypi/controller/rpi/geq.cpp
index 106f0a40dfc1..510870e9edbf 100644
--- a/src/ipa/raspberrypi/controller/rpi/geq.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/geq.cpp
@@ -35,17 +35,17 @@ char const *Geq::name() const
 	return NAME;
 }
 
-int Geq::read(boost::property_tree::ptree const &params)
+int Geq::read(const libcamera::YamlObject &params)
 {
-	config_.offset = params.get<uint16_t>("offset", 0);
-	config_.slope = params.get<double>("slope", 0.0);
+	config_.offset = params["offset"].get<uint16_t>(0);
+	config_.slope = params["slope"].get<double>(0.0);
 	if (config_.slope < 0.0 || config_.slope >= 1.0) {
 		LOG(RPiGeq, Error) << "Bad slope value";
 		return -EINVAL;
 	}
 
-	if (params.get_child_optional("strength")) {
-		int ret = config_.strength.read(params.get_child("strength"));
+	if (params.contains("strength")) {
+		int ret = config_.strength.read(params["strength"]);
 		if (ret)
 			return ret;
 	}
diff --git a/src/ipa/raspberrypi/controller/rpi/geq.h b/src/ipa/raspberrypi/controller/rpi/geq.h
index 677a0510c6ac..ee3a52ff50f5 100644
--- a/src/ipa/raspberrypi/controller/rpi/geq.h
+++ b/src/ipa/raspberrypi/controller/rpi/geq.h
@@ -24,7 +24,7 @@ class Geq : public Algorithm
 public:
 	Geq(Controller *controller);
 	char const *name() const override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void prepare(Metadata *imageMetadata) override;
 
 private:
diff --git a/src/ipa/raspberrypi/controller/rpi/lux.cpp b/src/ipa/raspberrypi/controller/rpi/lux.cpp
index ca1e827191fd..9759186afacf 100644
--- a/src/ipa/raspberrypi/controller/rpi/lux.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/lux.cpp
@@ -38,14 +38,30 @@ char const *Lux::name() const
 	return NAME;
 }
 
-int Lux::read(boost::property_tree::ptree const &params)
+int Lux::read(const libcamera::YamlObject &params)
 {
-	referenceShutterSpeed_ =
-		params.get<double>("reference_shutter_speed") * 1.0us;
-	referenceGain_ = params.get<double>("reference_gain");
-	referenceAperture_ = params.get<double>("reference_aperture", 1.0);
-	referenceY_ = params.get<double>("reference_Y");
-	referenceLux_ = params.get<double>("reference_lux");
+	auto value = params["reference_shutter_speed"].get<double>();
+	if (!value)
+		return -EINVAL;
+	referenceShutterSpeed_ = *value * 1.0us;
+
+	value = params["reference_gain"].get<double>();
+	if (!value)
+		return -EINVAL;
+	referenceGain_ = *value;
+
+	referenceAperture_ = params["reference_aperture"].get<double>(1.0);
+
+	value = params["reference_Y"].get<double>();
+	if (!value)
+		return -EINVAL;
+	referenceY_ = *value;
+
+	value = params["reference_lux"].get<double>();
+	if (!value)
+		return -EINVAL;
+	referenceLux_ = *value;
+
 	currentAperture_ = referenceAperture_;
 	return 0;
 }
diff --git a/src/ipa/raspberrypi/controller/rpi/lux.h b/src/ipa/raspberrypi/controller/rpi/lux.h
index 6416dfb52553..89411a5432b4 100644
--- a/src/ipa/raspberrypi/controller/rpi/lux.h
+++ b/src/ipa/raspberrypi/controller/rpi/lux.h
@@ -22,7 +22,7 @@ class Lux : public Algorithm
 public:
 	Lux(Controller *controller);
 	char const *name() const override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void prepare(Metadata *imageMetadata) override;
 	void process(StatisticsPtr &stats, Metadata *imageMetadata) override;
 	void setCurrentAperture(double aperture);
diff --git a/src/ipa/raspberrypi/controller/rpi/noise.cpp b/src/ipa/raspberrypi/controller/rpi/noise.cpp
index 74fa99bafe48..bcd8b9edaebe 100644
--- a/src/ipa/raspberrypi/controller/rpi/noise.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/noise.cpp
@@ -41,10 +41,18 @@ void Noise::switchMode(CameraMode const &cameraMode,
 	modeFactor_ = std::max(1.0, cameraMode.noiseFactor);
 }
 
-int Noise::read(boost::property_tree::ptree const &params)
+int Noise::read(const libcamera::YamlObject &params)
 {
-	referenceConstant_ = params.get<double>("reference_constant");
-	referenceSlope_ = params.get<double>("reference_slope");
+	auto value = params["reference_constant"].get<double>();
+	if (!value)
+		return -EINVAL;
+	referenceConstant_ = *value;
+
+	value = params["reference_slope"].get<double>();
+	if (!value)
+		return -EINVAL;
+	referenceSlope_ = *value;
+
 	return 0;
 }
 
diff --git a/src/ipa/raspberrypi/controller/rpi/noise.h b/src/ipa/raspberrypi/controller/rpi/noise.h
index b33a5fc75ec7..74c31e640c3f 100644
--- a/src/ipa/raspberrypi/controller/rpi/noise.h
+++ b/src/ipa/raspberrypi/controller/rpi/noise.h
@@ -19,7 +19,7 @@ public:
 	Noise(Controller *controller);
 	char const *name() const override;
 	void switchMode(CameraMode const &cameraMode, Metadata *metadata) override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void prepare(Metadata *imageMetadata) override;
 
 private:
diff --git a/src/ipa/raspberrypi/controller/rpi/sdn.cpp b/src/ipa/raspberrypi/controller/rpi/sdn.cpp
index 03d9f119a338..b6b662518f2c 100644
--- a/src/ipa/raspberrypi/controller/rpi/sdn.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/sdn.cpp
@@ -34,10 +34,10 @@ char const *Sdn::name() const
 	return NAME;
 }
 
-int Sdn::read(boost::property_tree::ptree const &params)
+int Sdn::read(const libcamera::YamlObject &params)
 {
-	deviation_ = params.get<double>("deviation", 3.2);
-	strength_ = params.get<double>("strength", 0.75);
+	deviation_ = params["deviation"].get<double>(3.2);
+	strength_ = params["strength"].get<double>(0.75);
 	return 0;
 }
 
diff --git a/src/ipa/raspberrypi/controller/rpi/sdn.h b/src/ipa/raspberrypi/controller/rpi/sdn.h
index 4287ef08a79f..9dd73c388edb 100644
--- a/src/ipa/raspberrypi/controller/rpi/sdn.h
+++ b/src/ipa/raspberrypi/controller/rpi/sdn.h
@@ -18,7 +18,7 @@ class Sdn : public DenoiseAlgorithm
 public:
 	Sdn(Controller *controller = NULL);
 	char const *name() const override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void initialise() override;
 	void prepare(Metadata *imageMetadata) override;
 	void setMode(DenoiseMode mode) override;
diff --git a/src/ipa/raspberrypi/controller/rpi/sharpen.cpp b/src/ipa/raspberrypi/controller/rpi/sharpen.cpp
index 9c4cffa4128c..4f6f020a417b 100644
--- a/src/ipa/raspberrypi/controller/rpi/sharpen.cpp
+++ b/src/ipa/raspberrypi/controller/rpi/sharpen.cpp
@@ -37,11 +37,11 @@ void Sharpen::switchMode(CameraMode const &cameraMode,
 	modeFactor_ = std::max(1.0, cameraMode.noiseFactor);
 }
 
-int Sharpen::read(boost::property_tree::ptree const &params)
+int Sharpen::read(const libcamera::YamlObject &params)
 {
-	threshold_ = params.get<double>("threshold", 1.0);
-	strength_ = params.get<double>("strength", 1.0);
-	limit_ = params.get<double>("limit", 1.0);
+	threshold_ = params["threshold"].get<double>(1.0);
+	strength_ = params["strength"].get<double>(1.0);
+	limit_ = params["limit"].get<double>(1.0);
 	LOG(RPiSharpen, Debug)
 		<< "Read threshold " << threshold_
 		<< " strength " << strength_
diff --git a/src/ipa/raspberrypi/controller/rpi/sharpen.h b/src/ipa/raspberrypi/controller/rpi/sharpen.h
index 0cd8b92f2224..8bb7631e916b 100644
--- a/src/ipa/raspberrypi/controller/rpi/sharpen.h
+++ b/src/ipa/raspberrypi/controller/rpi/sharpen.h
@@ -19,7 +19,7 @@ public:
 	Sharpen(Controller *controller);
 	char const *name() const override;
 	void switchMode(CameraMode const &cameraMode, Metadata *metadata) override;
-	int read(boost::property_tree::ptree const &params) override;
+	int read(const libcamera::YamlObject &params) override;
 	void setStrength(double strength) override;
 	void prepare(Metadata *imageMetadata) override;
 
diff --git a/src/ipa/raspberrypi/meson.build b/src/ipa/raspberrypi/meson.build
index 32897e07dad9..517d815bb98c 100644
--- a/src/ipa/raspberrypi/meson.build
+++ b/src/ipa/raspberrypi/meson.build
@@ -4,7 +4,6 @@ ipa_name = 'ipa_rpi'
 
 rpi_ipa_deps = [
     libcamera_private,
-    dependency('boost'),
     libatomic,
 ]
 
diff --git a/src/ipa/raspberrypi/raspberrypi.cpp b/src/ipa/raspberrypi/raspberrypi.cpp
index b9e9b814e886..6befdd71433d 100644
--- a/src/ipa/raspberrypi/raspberrypi.cpp
+++ b/src/ipa/raspberrypi/raspberrypi.cpp
@@ -7,6 +7,7 @@
 
 #include <algorithm>
 #include <array>
+#include <cstring>
 #include <fcntl.h>
 #include <math.h>
 #include <stdint.h>
-- 
Regards,

Laurent Pinchart



More information about the libcamera-devel mailing list