mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
mrs_lib::DynparamMgr Class Reference

Convenience class for managing dynamic ROS parameters. More...

#include <dynparam_mgr.h>

Classes

struct  registered_param_t
 

Public Types

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 >, std::vector< bool >, std::vector< std::string > >
 A convenience alias defining the valid C++ types to be registered.
 
template<typename T >
using update_cbk_t = std::function< void(const T &)>
 A convenience alias defining the update callback function type.
 
template<typename T >
using range_t = ParamProvider::range_t< T >
 A helper alias for ParamProvider's range struct for specifying ranges of numeric values.
 

Public Member Functions

 DynparamMgr (const std::shared_ptr< rclcpp::Node > &node, std::mutex &mtx)
 The main constructor.
 
template<typename MemT >
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.
 
template<typename MemT >
bool register_param (const std::string &name, MemT *param_var, const MemT &default_value, const update_cbk_t< MemT > &update_cbk={})
 An overoad for specifying a default value of the parameter.
 
template<typename MemT >
requires (numeric<MemT>)
bool register_param (const std::string &name, MemT *param_var, const range_t< MemT > &valid_range, const update_cbk_t< MemT > &update_cbk={})
 An overload of for specifying the minimum and maximum of a numeric value.
 
template<typename MemT >
requires (numeric<MemT>)
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={})
 An overload of for specifying the default, minimum and maximum of a numeric value.
 
bool loaded_successfully () const
 Indicates whether all parameters were successfully declared and loaded.
 
rcl_interfaces::msg::SetParametersResult update_to_ros ()
 Pushes the current values of the pointed-to variables to ROS.
 
mrs_lib::ParamProviderget_param_provider ()
 Returns the underlying ParamProvider object.
 

Detailed Description

Convenience class for managing dynamic ROS parameters.

In the typical use-case, you give DynparamMgr a mutex and register a number of ROS parameters together with pointers to variables that you want to keep up-to-date with the values of the respective parameters. When a parameter is changed, the mutex is locked and the value of the corresponding variable is updated accordingly.

Default values of the parameters can be loaded from ROS or from YAML.

Constructor & Destructor Documentation

◆ DynparamMgr()

mrs_lib::DynparamMgr::DynparamMgr ( const std::shared_ptr< rclcpp::Node > &  node,
std::mutex &  mtx 
)

The main constructor.

Constructs the DynparamMgr object, initialies an internal ParamProvider object, and registers the on_set_parameters ROS callback.

Parameters
nodeA pointer to the ROS node handle used for registering, getting, setting, etc. of the parameters.
mtxThe mutex to be locked whenever the pointed-to variables passed in register_param() are touched.

Member Function Documentation

◆ get_param_provider()

mrs_lib::ParamProvider & mrs_lib::DynparamMgr::get_param_provider ( )
inline

Returns the underlying ParamProvider object.

Useful e.g. for manually setting values of some parameters while making sure the correct subnode namespacing is used etc.

Returns
a reference to the underlying ParamProvider object.

◆ loaded_successfully()

bool mrs_lib::DynparamMgr::loaded_successfully ( ) const

Indicates whether all parameters were successfully declared and loaded.

Returns
false if any compulsory parameter was not declared or loaded. Otherwise returns true.

◆ register_param() [1/4]

template<typename MemT >
requires (numeric<MemT>)
bool mrs_lib::DynparamMgr::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 = {} 
)

An overload of for specifying the default, minimum and maximum of a numeric value.

Parameters
nameName of the parameter (this will be used for the declaration etc.).
param_varPointer to a variable whose value will be changed when the parameter is updated. It is the user's responsibility to ensure that the lifetime of the pointed-to variable is valid while it is being used by the DynparamMgr.
default_valueDefault value to be set if no value could be loaded from ParamProvider.
valid_rangeRange of valid values (inclusive) of the parameter.
update_cbkOptional function to be called when the parameter is changed.
Returns
true iff the parameter was successfully declared and its default value loaded.

◆ register_param() [2/4]

template<typename MemT >
bool mrs_lib::DynparamMgr::register_param ( const std::string &  name,
MemT *  param_var,
const MemT &  default_value,
const update_cbk_t< MemT > &  update_cbk = {} 
)

An overoad for specifying a default value of the parameter.

Parameters
nameName of the parameter (this will be used for the ROS declaration etc.).
param_varPointer to the variable whose value will be changed when the parameter is updated. It is the user's responsibility to ensure that the lifetime of the pointed-to variable is valid while it is being used by the DynparamMgr.
default_valueOptional default value to be set if no value could be loaded from ParamProvider.
update_cbkOptional function to be called when the parameter is changed.
Returns
true iff the parameter was successfully declared and its default value loaded.
Note
The C++ type passed to this function will be mapped to one of the valid values of rclcpp::ParameterType. Not all C++ types are supported (see valid_types_t).

◆ register_param() [3/4]

template<typename MemT >
requires (numeric<MemT>)
bool mrs_lib::DynparamMgr::register_param ( const std::string &  name,
MemT *  param_var,
const range_t< MemT > &  valid_range,
const update_cbk_t< MemT > &  update_cbk = {} 
)

An overload of for specifying the minimum and maximum of a numeric value.

Parameters
nameName of the parameter (this will be used for the declaration etc.).
param_varPointer to a variable whose value will be changed when the parameter is updated. It is the user's responsibility to ensure that the lifetime of the pointed-to variable is valid while it is being used by the DynparamMgr.
valid_rangeRange of valid values (inclusive) of the parameter.
update_cbkOptional function to be called when the parameter is changed.
Returns
true iff the parameter was successfully declared and its default value loaded.

◆ register_param() [4/4]

template<typename MemT >
bool mrs_lib::DynparamMgr::register_param ( const std::string &  name,
MemT *  param_var,
const update_cbk_t< MemT > &  update_cbk = {} 
)

Registers a ROS parameter and a corresponding variable.

This method registers the provided pointer to a variable and a name of a ROS parameter to keep the pointed-to variable up-to-date with the value of the ROS parameter.

It will:

  1. Declare the parameter in ROS as a dynamic parameter with the corresponding type, or return false if the declaration fails.
  2. Load its default value using ParamProvider - this means the default value can be loaded from ROS or from a provided YAML file, if available, or return false if the loading fails.
  3. Set the value of the pointed-to variable to this default value.
  4. Save the name of the parameter and the pointer so that the variable can be updated when the parameter value changes.
Parameters
nameName of the parameter (this will be used for the ROS declaration etc.).
param_varPointer to the variable whose value will be changed when the parameter is updated. It is the user's responsibility to ensure that the lifetime of the pointed-to variable is valid while it is being used by the DynparamMgr.
update_cbkOptional function to be called when the parameter is changed.
Returns
true iff the parameter was successfully declared and its default value loaded.
Note
The C++ type passed to this function will be mapped to one of the valid values of rclcpp::ParameterType. Not all C++ types are supported (see valid_types_t).

◆ update_to_ros()

rcl_interfaces::msg::SetParametersResult mrs_lib::DynparamMgr::update_to_ros ( )

Pushes the current values of the pointed-to variables to ROS.

This method serves to update changes to the registered pointed-to variables made in your code to their ROS counterparts.

Returns
the result of setting the parameters returned by the internally called rclcpp::Node::set_parameters_atomically().

The documentation for this class was generated from the following files: