15 template <
typename MemT>
18 return register_param_impl<MemT>(name, param_var, std::nullopt, std::nullopt, update_cbk);
21 template <
typename MemT>
24 return register_param_impl<MemT>(name, param_var, default_value, std::nullopt, update_cbk);
27 template <
typename MemT>
31 return register_param_impl<MemT>(name, param_var, std::nullopt, valid_range, update_cbk);
34 template <
typename MemT>
39 return register_param_impl<MemT>(name, param_var, default_value, valid_range, update_cbk);
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)
56 const bool get_success = m_pp.
getParam(resolved_name, current_value, opts);
59 m_load_successful =
false;
60 RCLCPP_ERROR_STREAM(m_node->get_logger(),
"[" << m_node->get_name() <<
"]: Could not register dynamic parameter '" << name <<
"'");
65 *param_var = current_value;
68 RCLCPP_INFO_STREAM(m_node->get_logger(),
"[" << m_node->get_name() <<
"]: Dynamic parameter '" << name <<
"':\t" << *param_var);
70 m_registered_params.emplace_back(*m_node, resolved_name, to_param_type<MemT>(), param_var, update_cbk);
81 template <
typename... Types>
82 using variant_of_pointers_t = std::variant<std::add_pointer_t<Types>...>;
84 template <
typename Type>
87 template <
typename... Types>
90 using type = variant_of_pointers_t<Types...>;
94 template <
typename Type>
95 using add_function_cref_t = std::function<void(
const Type&)>;
97 template <
typename... Types>
98 using variant_of_functions_t = std::variant<add_function_cref_t<Types>...>;
100 template <
typename Type>
103 template <
typename... Types>
106 using type = variant_of_functions_t<Types...>;
118 rclcpp::ParameterType type;
119 param_ptr_variant_t param_ptr;
120 update_cbk_variant_t update_cbk;
123 template <
typename T>
124 bool try_cast(T& out)
128 out = std::get<T>(param_ptr);
131 catch (
const std::bad_any_cast& e)
137 template <
typename NewValueT>
138 bool update_value(
const NewValueT& new_value)
142 [&new_value,
this](
auto arg) {
143 using CbkT =
decltype(arg);
144 if constexpr (std::is_invocable_v<CbkT, NewValueT>)
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!");
158 [&new_value](
auto arg) {
159 using ParamT = std::remove_pointer_t<
decltype(arg)>;
160 if constexpr (std::is_convertible_v<NewValueT, ParamT>)
162 *arg =
static_cast<ParamT
>(new_value);
170 rclcpp::ParameterValue to_param_val()
const;
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 ¶m_name) const
Returns the parameter name with prefixes and subnode namespaces.
Definition param_provider.cpp:160
bool getParam(const std::string ¶m_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:101
Definition dynparam_mgr.hpp:85
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