dynamic_params.h 3.1 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273
  1. // Copyright 2023 RealSense, Inc. All Rights Reserved.
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. #pragma once
  15. #include <ros_utils.h>
  16. #include "constants.h"
  17. #include <deque>
  18. #include "ros_param_backend.h"
  19. namespace realsense2_camera
  20. {
  21. class Parameters
  22. {
  23. public:
  24. Parameters(RosNodeBase& node);
  25. ~Parameters();
  26. template <class T>
  27. T setParam(std::string param_name, const T& initial_value,
  28. std::function<void(const rclcpp::Parameter&)> func = std::function<void(const rclcpp::Parameter&)>(),
  29. rcl_interfaces::msg::ParameterDescriptor descriptor=rcl_interfaces::msg::ParameterDescriptor());
  30. template <class T>
  31. T readAndDeleteParam(std::string param_name, const T& initial_value);
  32. template <class T>
  33. void setParamT(std::string param_name, T& param,
  34. std::function<void(const rclcpp::Parameter&)> func = std::function<void(const rclcpp::Parameter&)>(),
  35. rcl_interfaces::msg::ParameterDescriptor descriptor=rcl_interfaces::msg::ParameterDescriptor());
  36. template <class T>
  37. void setParamValue(T& param, const T& value); // function updates the parameter value both locally and in the parameters server
  38. void setRosParamValue(const std::string param_name, void const* const value); // function updates the parameters server
  39. void removeParam(std::string param_name);
  40. void pushUpdateFunctions(std::vector<std::function<void()> > funcs);
  41. template <class T>
  42. void queueSetRosValue(const std::string& param_name, const T value);
  43. template<typename T>
  44. T getOrDeclareParameter(const std::string param_name, const T& initial_value);
  45. template <class T>
  46. T getParam(std::string param_name);
  47. private:
  48. void monitor_update_functions();
  49. private:
  50. RosNodeBase& _node;
  51. rclcpp::Logger _logger;
  52. std::map<std::string, std::function<void(const rclcpp::Parameter&)> > _param_functions;
  53. std::map<void*, std::string> _param_names;
  54. ParametersBackend _params_backend;
  55. std::condition_variable _update_functions_cv;
  56. bool _is_running;
  57. std::shared_ptr<std::thread> _update_functions_t;
  58. std::deque<std::function<void()> > _update_functions_v;
  59. std::list<std::string> self_set_parameters;
  60. std::mutex _mu;
  61. };
  62. }