.. _program_listing_file_src_ParameterHandler.hpp: Program Listing for File ParameterHandler.hpp ============================================= |exhale_lsh| :ref:`Return to documentation for file ` (``src/ParameterHandler.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #pragma once #include "ParameterConflictHandler.hpp" #include #include #include #include #include #include #include #include namespace rclcpp { class Node; } // namespace rclcpp class ParameterHandler { public: explicit ParameterHandler(rclcpp::Node *const node); void declare(const libcamera::ControlInfoMap &controls); const libcamera::ControlList & get_control_values(); void move_control_values(libcamera::ControlList &controls); void redeclare(); private: struct control_info_t { const libcamera::ControlId *id; libcamera::ControlInfo info; }; rclcpp::Node *const node; ParameterConflictHandler parameter_conflict_handler; rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_cb_on; #ifdef RCLCPP_HAS_PARAM_EXT_CB rclcpp::node_interfaces::PreSetParametersCallbackHandle::SharedPtr param_cb_pre; rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr param_cb_post; #endif std::unordered_map camera_controls; libcamera::ControlList control_values; std::mutex control_values_lock; std::unordered_map parameter_descriptors; void PreSetResolve(std::vector ¶meters); rcl_interfaces::msg::SetParametersResult OnSetValidate(const std::vector ¶meters); void PostSetApply(const std::vector ¶meters); std::vector validate_new_parameters(const std::vector ¶meters); };