8#include <rclcpp/rclcpp.hpp>
33 using valid_types_t = std::tuple<int, int64_t, float, double, bool, std::string, std::vector<uint8_t>, std::vector<int64_t>, std::vector<double>,
34 std::vector<bool>, std::vector<std::string>>;
58 DynparamMgr(
const std::shared_ptr<rclcpp::Node>& node, std::mutex& mtx);
81 template <
typename MemT>
96 template <
typename MemT>
97 bool register_param(
const std::string& name, MemT* param_var,
const MemT& default_value,
const update_cbk_t<MemT>& update_cbk = {});
108 template <
typename MemT>
109 bool register_param(
const std::string& name, MemT* param_var,
const range_t<MemT>& valid_range,
const update_cbk_t<MemT>& update_cbk = {})
110 requires(numeric<MemT>);
121 template <
typename MemT>
123 const update_cbk_t<MemT>& update_cbk = {})
124 requires(numeric<MemT>);
154 std::shared_ptr<rclcpp::Node> m_node;
156 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr m_param_cbk;
158 rcl_interfaces::msg::SetParametersResult cbk_param_update(
const std::vector<rclcpp::Parameter>&
parameters);
160 template <
typename MemT>
161 bool register_param_impl(
const std::string& name, MemT* param_var,
const std::optional<MemT>& default_value,
162 const std::optional<
range_t<MemT>>& valid_range,
const update_cbk_t<MemT>& update_cbk);
164 bool m_load_successful;
166 struct registered_param_t;
168 std::vector<registered_param_t> m_registered_params;
Convenience class for managing dynamic ROS parameters.
Definition dynparam_mgr.h:26
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:34
bool loaded_successfully() const
Indicates whether all parameters were successfully declared and loaded.
Definition dynparam_mgr.cpp:19
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
rcl_interfaces::msg::SetParametersResult update_to_ros()
Pushes the current values of the pointed-to variables to ROS.
Definition dynparam_mgr.cpp:25
mrs_lib::ParamProvider & get_param_provider()
Returns the underlying ParamProvider object.
Definition dynparam_mgr.h:148
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