Class ParamHandler

Class Documentation

class ParamHandler

The param handler is a convenience class for managing static and dynamic ROS parameters. It will handle receiving and sending parameter updates.

When registering a new parameter the param handler will return a parameter object which can be used to access the parameter value in a thread safe way if the application is using multiple threads.

All parameters require a name, default value, and description.

Optionally, a pointer to an existing variable can be passed in when registering a parameter. In this case that variable is used to store the parameter value, but access to it is not protected, so should only be used in single threaded applications.

When registering a parameter it is possible to chain additional configuration items to the parameter, such as:

  • .dynamic() - allow the parameter to by modified with dynamic reconfig

  • .callback(func) - provide a callback function when the parameter changes, implies .dynamic()

  • .min(val) - specify a minimun value for numeric parameters

  • .max(val) - specify a maximum value for numeric parameters

  • .step(val) - specify step size for numeric parameters

  • .enum(list) - specify an enumeration for integer parameters

Once the parameter has been configured, it’s necessary to call the .declare() method.

The parameter objects values can be accessed in a thread safe way with the .value() method and updated with the .update(val) method.

Assigning parameter objects results in a shallow copy.

Public Functions

inline ParamHandler(rclcpp::Node::SharedPtr node)
~ParamHandler() = default
inline void register_verbose_logging_param()

Register a boolean ‘verbose’ dynamic parameter to enable or disable debug level logging.

inline BoolParameter &param(const std::string &name, bool default_val, const std::string &description)

Register a bool parameter and return its value.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline BoolParameter &param(bool *param, const std::string &name, bool default_val, const std::string &description)

Register a bool parameter and return its value.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline BoolArrayParameter &param(const std::string &name, const std::vector<bool> &default_val, const std::string &description)

Register a bool array parameter and return its value.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline BoolArrayParameter &param(std::vector<bool> *param, const std::string &name, const std::vector<bool> &default_val, const std::string &description)

Register a bool array parameter and return its value.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline SystemIntParameter &param(const std::string &name, int default_val, const std::string &description)

Register a system integer parameter and return its value.

NOTE: Since ROS2 internally only uses int64_t for params, this version casts int64_t to int. It does check if the value is within the int range, and will fail to update the parameter internally if it’s not.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline SystemIntParameter &param(int *param, const std::string &name, int default_val, const std::string &description)

Register a system integer parameter and return its value.

NOTE: Since ROS2 internally only uses int64_t for params, this version casts int64_t to int. It does check if the value is within the int range, and will fail to update the parameter internally if it’s not.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline IntParameter &param(const std::string &name, int64_t default_val, const std::string &description)

Register an integer parameter and return its value.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline IntParameter &param(int64_t *param, const std::string &name, int64_t default_val, const std::string &description)

Register an integer parameter and return its value.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline IntArrayParameter &param(const std::string &name, const std::vector<int64_t> &default_val, const std::string &description)

Register an integer array parameter and return its value.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline IntArrayParameter &param(std::vector<int64_t> *param, const std::string &name, const std::vector<int64_t> &default_val, const std::string &description)

Register an integer array parameter and return its value.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline DoubleParameter &param(const std::string &name, double default_val, const std::string &description)

Register a double parameter and return its value.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline DoubleParameter &param(double *param, const std::string &name, double default_val, const std::string &description)

Register a double parameter and return its value.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline DoubleArrayParameter &param(const std::string &name, const std::vector<double> &default_val, const std::string &description)

Register a double array parameter and return its value.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline DoubleArrayParameter &param(std::vector<double> *param, const std::string &name, const std::vector<double> &default_val, const std::string &description)

Register a double array parameter and return its value.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline StringParameter &param(const std::string &name, const std::string &default_val, const std::string &description)

Register a string parameter and return its value.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline StringParameter &param(std::string *param, const std::string &name, const std::string &default_val, const std::string &description)

Register a string parameter and return its value.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline StringArrayParameter &param(const std::string &name, const std::vector<std::string> &default_val, const std::string &description)

Register a string parameter and return its value.

Parameters:
  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline StringArrayParameter &param(std::vector<std::string> *param, const std::string &name, const std::vector<std::string> &default_val, const std::string &description)

Register a string parameter and return its value.

NOTE: This version is only recommended for single threaded applications since the user provided parameter pointer won’t be fully guarded from concurrent usage.

The point should also remain valid for the life of the handler.

Parameters:
  • param[out] Reference to parameter variable

  • name[in] Parameter name

  • default_val[in] Default parameter value

  • description[in] Parameter description

Returns:

the value of the parameter.

inline void setCallback(std::function<void()> callback)