Skip to content

Commit

Permalink
cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
christianrauch committed Nov 19, 2024
1 parent ed00b3f commit cde65d2
Showing 1 changed file with 3 additions and 45 deletions.
48 changes: 3 additions & 45 deletions src/CameraNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@
#include <libcamera/request.h>
#include <libcamera/stream.h>
#include <memory>
// #include <mutex>
#include <opencv2/core/mat.hpp>
#include <opencv2/imgcodecs.hpp>
#include <optional>
Expand Down Expand Up @@ -109,9 +108,6 @@ class CameraNode : public rclcpp::Node

// map parameter names to libcamera control id
std::unordered_map<std::string, const libcamera::ControlId *> parameter_ids;
// parameters that are to be set for every request
// ParameterHandler::ControlValueMap parameters;
// std::mutex parameters_lock;
// compression quality parameter
std::atomic_uint8_t jpeg_quality;

Expand Down Expand Up @@ -191,10 +187,6 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options)
param_cb_change(add_post_set_parameters_callback(
std::bind(&CameraNode::onParameterChange, this, std::placeholders::_1)))
{
// register callback to handle parameter updates
// callback_parameter_change = add_post_set_parameters_callback(
// std::bind(&CameraNode::onParameterChange, this, std::placeholders::_1));

// pixel format
rcl_interfaces::msg::ParameterDescriptor param_descr_format;
param_descr_format.description = "pixel format of streaming buffer";
Expand Down Expand Up @@ -436,8 +428,7 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options)
camera->requestCompleted.connect(this, &CameraNode::requestComplete);

libcamera::ControlList controls_ = camera->controls();
auto parameters = parameter_handler.get();
for (const auto &[id, value] : parameters)
for (const auto &[id, value] : parameter_handler.get())
controls_.set(id, value);

// start camera and queue all requests
Expand Down Expand Up @@ -559,19 +550,16 @@ CameraNode::process(libcamera::Request *const request)
request->reuse(libcamera::Request::ReuseBuffers);

// update parameters
// parameters_lock.lock();
auto parameters = parameter_handler.get();
const ParameterHandler::ControlValueMap parameters = parameter_handler.get();
if (!parameters.empty()) {
RCLCPP_DEBUG_STREAM(get_logger(), request->toString() << " setting " << parameters.size() << " controls");
for (const auto &[id, value] : parameters) {
const std::string &name = libcamera::controls::controls.at(id)->name();
RCLCPP_DEBUG_STREAM(get_logger(), "apply " << name << ": " << value.toString());
request->controls().set(id, value);
}
// parameters.clear();
parameter_handler.clear();
}
// parameters_lock.unlock();

camera->queueRequest(request);
}
Expand All @@ -580,46 +568,16 @@ CameraNode::process(libcamera::Request *const request)
rcl_interfaces::msg::SetParametersResult
CameraNode::onParameterChange(const std::vector<rclcpp::Parameter> &parameters)
{
for (const rclcpp::Parameter &param : parameters) {
std::cout << "CameraNode post: " << param.get_name() << std::endl;
}

// check non-controls parameters
for (const rclcpp::Parameter &parameter : parameters) {
if (!parameter.get_name().compare("jpeg_quality")) {
if (parameter.get_name() == "jpeg_quality") {
jpeg_quality = parameter.get_parameter_value().get<uint8_t>();
}
}

// DBG:
// TODO: this should go into the 'add_post_set_parameters_callback'
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
return result;

// ParameterHandler::ControlValueMap controls;
// std::vector<std::string> msgs;

// std::tie(controls, msgs) = parameter_handler.parameterCheckAndConvert(parameters);

// parameters_lock.lock();
// this->parameters = controls;
// parameters_lock.unlock();

// rcl_interfaces::msg::SetParametersResult result;
// result.successful = msgs.empty();
// if (!msgs.empty()) {
// result.successful = false;
// for (size_t i = 0; i < msgs.size(); i++) {
// if (msgs.size() > 1)
// result.reason += "(" + std::to_string(i) + ") ";
// result.reason += msgs[i];
// if (i < msgs.size() - 1)
// result.reason += "; ";
// }
// }

// return result;
}

} // namespace camera

0 comments on commit cde65d2

Please sign in to comment.