Class Parameter

Class Documentation

class Parameter

Structure to store an arbitrary parameter with templated get/set methods.

Public Functions

Parameter()

Construct with an empty name and a parameter value of type rclcpp::PARAMETER_NOT_SET.

explicit Parameter(const std::string &name)

Construct with given name and a parameter value of type rclcpp::PARAMETER_NOT_SET.

Parameter(const std::string &name, const ParameterValue &value)

Construct with given name and given parameter value.

template<typename ValueTypeT>
inline Parameter(const std::string &name, ValueTypeT value)

Construct with given name and given parameter value.

explicit Parameter(const rclcpp::node_interfaces::ParameterInfo &parameter_info)
bool operator==(const Parameter &rhs) const

Equal operator.

bool operator!=(const Parameter &rhs) const

Not equal operator.

ParameterType get_type() const

Get the type of the parameter.

std::string get_type_name() const

Get the type name of the parameter.

const std::string &get_name() const

Get the name of the parameter.

rcl_interfaces::msg::ParameterValue get_value_message() const

Get value of parameter as a parameter message.

const rclcpp::ParameterValue &get_parameter_value() const

Get the internal storage for the parameter value.

template<ParameterType ParamT>
inline decltype(auto) get_value() const

Get value of parameter using rclcpp::ParameterType as template argument.

Throws:

rclcpp::exceptions::InvalidParameterTypeException – if the type doesn’t match

template<typename T>
decltype(auto) get_value() const

Get value of parameter using c++ types as template argument.

bool as_bool() const

Get value of parameter as boolean.

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

int64_t as_int() const

Get value of parameter as integer.

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

double as_double() const

Get value of parameter as double.

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

const std::string &as_string() const

Get value of parameter as string.

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

const std::vector<uint8_t> &as_byte_array() const

Get value of parameter as byte array (vector<uint8_t>).

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

const std::vector<bool> &as_bool_array() const

Get value of parameter as bool array (vector<bool>).

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

const std::vector<int64_t> &as_integer_array() const

Get value of parameter as integer array (vector<int64_t>).

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

const std::vector<double> &as_double_array() const

Get value of parameter as double array (vector<double>).

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

const std::vector<std::string> &as_string_array() const

Get value of parameter as string array (vector<std::string>).

Throws:

rclcpp::ParameterTypeException – if the type doesn’t match

rcl_interfaces::msg::Parameter to_parameter_msg() const

Convert the class in a parameter message.

std::string value_to_string() const

Get value of parameter as a string.

Public Static Functions

static Parameter from_parameter_msg(const rcl_interfaces::msg::Parameter &parameter)

Convert a parameter message in a Parameter class object.