mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
dynparam_mgr.hpp
Go to the documentation of this file.
1// clang: MatousFormat
6#pragma once
7
9#include <any>
10
11namespace mrs_lib
12{
13
14 /* register_param() method //{ */
15 template <typename MemT>
16 bool DynparamMgr::register_param(const std::string& name, MemT* param_var, const update_cbk_t<MemT>& update_cbk)
17 {
18 return register_param_impl<MemT>(name, param_var, std::nullopt, std::nullopt, update_cbk);
19 }
20
21 template <typename MemT>
22 bool DynparamMgr::register_param(const std::string& name, MemT* param_var, const MemT& default_value, const update_cbk_t<MemT>& update_cbk)
23 {
24 return register_param_impl<MemT>(name, param_var, default_value, std::nullopt, update_cbk);
25 }
26
27 template <typename MemT>
28 bool DynparamMgr::register_param(const std::string& name, MemT* param_var, const range_t<MemT>& valid_range, const update_cbk_t<MemT>& update_cbk)
29 requires(numeric<MemT>)
30 {
31 return register_param_impl<MemT>(name, param_var, std::nullopt, valid_range, update_cbk);
32 }
33
34 template <typename MemT>
35 bool DynparamMgr::register_param(const std::string& name, MemT* param_var, const MemT& default_value, const range_t<MemT>& valid_range,
36 const update_cbk_t<MemT>& update_cbk)
37 requires(numeric<MemT>)
38 {
39 return register_param_impl<MemT>(name, param_var, default_value, valid_range, update_cbk);
40 }
41
42 template <typename MemT>
43 bool DynparamMgr::register_param_impl(const std::string& name, MemT* param_var, const std::optional<MemT>& default_value,
44 const std::optional<range_t<MemT>>& valid_range, const update_cbk_t<MemT>& update_cbk)
45 {
46 const auto resolved_name = m_pp.resolveName(name);
47
49 opts.always_declare = true;
50 opts.declare_options.reconfigurable = true;
51 opts.declare_options.default_value = default_value;
52 opts.declare_options.range = valid_range;
53
54 // load the current value of the parameter
55 MemT current_value;
56 const bool get_success = m_pp.getParam(resolved_name, current_value, opts);
57 if (!get_success)
58 {
59 m_load_successful = false;
60 RCLCPP_ERROR_STREAM(m_node->get_logger(), "[" << m_node->get_name() << "]: Could not register dynamic parameter '" << name << "'");
61 return false;
62 }
63
64 // only assign the default value if everything is OK, otherwise leave param_var untouched
65 *param_var = current_value;
66
67 // remember the registered parameter, the corresponding variable, etc.
68 RCLCPP_INFO_STREAM(m_node->get_logger(), "[" << m_node->get_name() << "]: Dynamic parameter '" << name << "':\t" << *param_var);
69
70 m_registered_params.emplace_back(*m_node, resolved_name, to_param_type<MemT>(), param_var, update_cbk);
71 return true;
72 }
73 //}
74
75 /* registered_param_t struct //{ */
76
78 {
79 // | --------------------- Metaprogramming -------------------- |
80 // some metaprogramming tooling to generate a variant of pointers from a tuple of types
81 template <typename... Types>
82 using variant_of_pointers_t = std::variant<std::add_pointer_t<Types>...>;
83
84 template <typename Type>
86
87 template <typename... Types>
88 struct pointer_variant_from_list_t<std::tuple<Types...>>
89 {
90 using type = variant_of_pointers_t<Types...>;
91 };
92
93 // the same tooling for creating a variant of functions with the types as const-ref arguments
94 template <typename Type>
95 using add_function_cref_t = std::function<void(const Type&)>;
96
97 template <typename... Types>
98 using variant_of_functions_t = std::variant<add_function_cref_t<Types>...>;
99
100 template <typename Type>
102
103 template <typename... Types>
104 struct function_variant_from_list_t<std::tuple<Types...>>
105 {
106 using type = variant_of_functions_t<Types...>;
107 };
108
109 // define the std::variant of pointers-to the types from valid_types_t
110 using param_ptr_variant_t = pointer_variant_from_list_t<valid_types_t>::type;
111
112 // define the std::variant of std::functions taking a const-ref of the types from valid_types_t
113 using update_cbk_variant_t = function_variant_from_list_t<valid_types_t>::type;
114
115 // | ------------------------- Members ------------------------ |
116 rclcpp::Node& node; // non-owning reference (the memory is share-owned by the DynparamMgr)
117 ParamProvider::resolved_name_t resolved_name;
118 rclcpp::ParameterType type;
119 param_ptr_variant_t param_ptr;
120 update_cbk_variant_t update_cbk;
121
122 // | ------------------------- Methods ------------------------ |
123 template <typename T>
124 bool try_cast(T& out)
125 {
126 try
127 {
128 out = std::get<T>(param_ptr);
129 return true;
130 }
131 catch (const std::bad_any_cast& e)
132 {
133 return false;
134 }
135 }
136
137 template <typename NewValueT>
138 bool update_value(const NewValueT& new_value)
139 {
140 // if there is an update callback registered, try to call it
141 std::visit(
142 [&new_value, this](auto arg) {
143 using CbkT = decltype(arg);
144 if constexpr (std::is_invocable_v<CbkT, NewValueT>)
145 {
146 if (arg)
147 // actually call the callback
148 arg(new_value);
149 } else
150 {
151 RCLCPP_ERROR_STREAM_THROTTLE(node.get_logger(), *node.get_clock(), 1000,
152 "Cannot call update callback for parameter \"" << resolved_name.str << "\" - incompatible callback type!");
153 }
154 },
155 update_cbk);
156
157 return std::visit(
158 [&new_value](auto arg) {
159 using ParamT = std::remove_pointer_t<decltype(arg)>;
160 if constexpr (std::is_convertible_v<NewValueT, ParamT>)
161 {
162 *arg = static_cast<ParamT>(new_value);
163 return true;
164 } else
165 return false;
166 },
167 param_ptr);
168 }
169
170 rclcpp::ParameterValue to_param_val() const;
171 };
172
173 //}
174
175}; // namespace mrs_lib
std::function< void(const T &)> update_cbk_t
A convenience alias defining the update callback function type.
Definition dynparam_mgr.h:41
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
resolved_name_t resolveName(const std::string &param_name) const
Returns the parameter name with prefixes and subnode namespaces.
Definition param_provider.cpp:160
bool getParam(const std::string &param_name, T &value_out) const
Gets the value of a parameter.
Definition param_provider.hpp:83
Convenience concept of a numeric value (i.e. either integral or floating point, and not bool).
Definition param_provider.h:58
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
Definition dynparam_mgr.hpp:78
Struct of options when getting a parameter from ROS.
Definition param_provider.h:118
declare_options_t< T > declare_options
Options when declaring a parameter to ROS (see the declare_options_t<T> documentation).
Definition param_provider.h:128
bool always_declare
Iff true, the parameter will be declared to ROS even if it's value was loaded from a YAML.
Definition param_provider.h:120
Helper struct for a numeric range with named members to make the code a bit more readable.
Definition param_provider.h:87
Definition param_provider.hpp:43