mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
dynparam_mgr.h
Go to the documentation of this file.
1// clang: MatousFormat
6#pragma once
7
8#include <rclcpp/rclcpp.hpp>
10
11namespace mrs_lib
12{
13
26 {
27
28 public:
33 using valid_types_t = std::tuple<
34 int,
35 int64_t,
36 float,
37 double,
38 bool,
39 std::string,
40 std::vector<uint8_t>,
41 std::vector<int64_t>,
42 std::vector<double>,
43 std::vector<bool>,
44 std::vector<std::string>
45 >;
46
51 template <typename T>
52 using update_cbk_t = std::function<void(const T&)>;
53
58 template <typename T>
60
69 DynparamMgr(const std::shared_ptr<rclcpp::Node>& node, std::mutex& mtx);
70
89 template <typename MemT>
90 bool register_param(const std::string& name, MemT* param_var, const update_cbk_t<MemT>& update_cbk = {});
91
103 template <typename MemT>
104 bool register_param(const std::string& name, MemT* param_var, const MemT& default_value, const update_cbk_t<MemT>& update_cbk = {});
105
115 template <typename MemT>
116 bool register_param(const std::string& name, MemT* param_var, const range_t<MemT>& valid_range, const update_cbk_t<MemT>& update_cbk = {})
117 requires(numeric<MemT>);
118
129 template <typename MemT>
130 bool register_param(const std::string& name, MemT* param_var, const MemT& default_value, const range_t<MemT>& valid_range, const update_cbk_t<MemT>& update_cbk = {})
131 requires(numeric<MemT>);
132
138 bool loaded_successfully() const;
139
146 rcl_interfaces::msg::SetParametersResult update_to_ros();
147
156 {
157 return m_pp;
158 };
159
160 private:
161 std::shared_ptr<rclcpp::Node> m_node;
163 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr m_param_cbk;
164
165 rcl_interfaces::msg::SetParametersResult cbk_param_update(const std::vector<rclcpp::Parameter>& parameters);
166
167 template <typename MemT>
168 bool register_param_impl(const std::string& name, MemT* param_var, const std::optional<MemT>& default_value, const std::optional<range_t<MemT>>& valid_range, const update_cbk_t<MemT>& update_cbk);
169
170 bool m_load_successful;
171
172 struct registered_param_t;
173 std::mutex& m_mtx;
174 std::vector<registered_param_t> m_registered_params;
175 };
176
177} // namespace mrs_lib
178
Convenience class for managing dynamic ROS parameters.
Definition dynparam_mgr.h:26
bool loaded_successfully() const
Indicates whether all parameters were successfully declared and loaded.
Definition dynparam_mgr.cpp:21
std::function< void(const T &)> update_cbk_t
A convenience alias defining the update callback function type.
Definition dynparam_mgr.h:52
bool register_param(const std::string &name, MemT *param_var, const update_cbk_t< MemT > &update_cbk={})
Registers a ROS parameter and a corresponding variable.
Definition dynparam_mgr.hpp:16
rcl_interfaces::msg::SetParametersResult update_to_ros()
Pushes the current values of the pointed-to variables to ROS.
Definition dynparam_mgr.cpp:27
std::tuple< int, int64_t, float, double, bool, std::string, std::vector< uint8_t >, std::vector< int64_t >, std::vector< double >, std::vector< bool >, std::vector< std::string > > valid_types_t
A convenience alias defining the valid C++ types to be registered.
Definition dynparam_mgr.h:45
mrs_lib::ParamProvider & get_param_provider()
Returns the underlying ParamProvider object.
Definition dynparam_mgr.h:155
Helper class for ParamLoader and DynparamMgr.
Definition param_provider.h:73
Defines DynparamMgr - a convenience class for managing dynamic ROS parameters.
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Defines ParamProvider - a convenience class for seamlessly loading parameters from YAML or ROS.
Helper struct for a numeric range with named members to make the code a bit more readable.
Definition param_provider.h:87
Definition test.cpp:15