ROS 2 rclcpp + rcl - kilted  kilted
ROS 2 C++ Client Library with ROS Client Library
Public Member Functions | Static Public Member Functions | List of all members
rclcpp::Parameter Class Reference

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

#include <rclcpp/parameter.hpp>

Public Member Functions

RCLCPP_PUBLIC Parameter ()
 Construct with an empty name and a parameter value of type rclcpp::PARAMETER_NOT_SET.
 
RCLCPP_PUBLIC Parameter (const std::string &name)
 Construct with given name and a parameter value of type rclcpp::PARAMETER_NOT_SET.
 
RCLCPP_PUBLIC Parameter (const std::string &name, const ParameterValue &value)
 Construct with given name and given parameter value.
 
template<typename ValueTypeT >
 Parameter (const std::string &name, ValueTypeT value)
 Construct with given name and given parameter value.
 
RCLCPP_PUBLIC Parameter (const rclcpp::node_interfaces::ParameterInfo &parameter_info)
 
RCLCPP_PUBLIC bool operator== (const Parameter &rhs) const
 Equal operator.
 
RCLCPP_PUBLIC bool operator!= (const Parameter &rhs) const
 Not equal operator.
 
RCLCPP_PUBLIC ParameterType get_type () const
 Get the type of the parameter.
 
RCLCPP_PUBLIC std::string get_type_name () const
 Get the type name of the parameter.
 
RCLCPP_PUBLIC const std::string & get_name () const
 Get the name of the parameter.
 
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue get_value_message () const
 Get value of parameter as a parameter message.
 
RCLCPP_PUBLIC const rclcpp::ParameterValueget_parameter_value () const
 Get the internal storage for the parameter value.
 
template<ParameterType ParamT>
decltype(auto) get_value () const
 Get value of parameter using rclcpp::ParameterType as template argument. More...
 
template<typename T >
decltype(auto) get_value () const
 Get value of parameter using c++ types as template argument.
 
RCLCPP_PUBLIC bool as_bool () const
 Get value of parameter as boolean. More...
 
RCLCPP_PUBLIC int64_t as_int () const
 Get value of parameter as integer. More...
 
RCLCPP_PUBLIC double as_double () const
 Get value of parameter as double. More...
 
RCLCPP_PUBLIC const std::string & as_string () const
 Get value of parameter as string. More...
 
RCLCPP_PUBLIC const std::vector< uint8_t > & as_byte_array () const
 Get value of parameter as byte array (vector<uint8_t>). More...
 
RCLCPP_PUBLIC const std::vector< bool > & as_bool_array () const
 Get value of parameter as bool array (vector<bool>). More...
 
RCLCPP_PUBLIC const std::vector< int64_t > & as_integer_array () const
 Get value of parameter as integer array (vector<int64_t>). More...
 
RCLCPP_PUBLIC const std::vector< double > & as_double_array () const
 Get value of parameter as double array (vector<double>). More...
 
RCLCPP_PUBLIC const std::vector< std::string > & as_string_array () const
 Get value of parameter as string array (vector<std::string>). More...
 
RCLCPP_PUBLIC rcl_interfaces::msg::Parameter to_parameter_msg () const
 Convert the class in a parameter message.
 
RCLCPP_PUBLIC std::string value_to_string () const
 Get value of parameter as a string.
 

Static Public Member Functions

static RCLCPP_PUBLIC Parameter from_parameter_msg (const rcl_interfaces::msg::Parameter &parameter)
 Convert a parameter message in a Parameter class object.
 

Detailed Description

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

Definition at line 52 of file parameter.hpp.

Member Function Documentation

◆ as_bool()

bool Parameter::as_bool ( ) const

Get value of parameter as boolean.

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 91 of file parameter.cpp.

◆ as_bool_array()

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

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

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 121 of file parameter.cpp.

◆ as_byte_array()

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

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

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 115 of file parameter.cpp.

◆ as_double()

double Parameter::as_double ( ) const

Get value of parameter as double.

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 103 of file parameter.cpp.

◆ as_double_array()

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

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

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 133 of file parameter.cpp.

◆ as_int()

int64_t Parameter::as_int ( ) const

Get value of parameter as integer.

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 97 of file parameter.cpp.

◆ as_integer_array()

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

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

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 127 of file parameter.cpp.

◆ as_string()

const std::string & Parameter::as_string ( ) const

Get value of parameter as string.

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 109 of file parameter.cpp.

◆ as_string_array()

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

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

Exceptions
rclcpp::ParameterTypeExceptionif the type doesn't match

Definition at line 139 of file parameter.cpp.

◆ get_value()

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

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

Exceptions
rclcpp::exceptions::InvalidParameterTypeExceptionif the type doesn't match

Definition at line 117 of file parameter.hpp.

Referenced by rclcpp::Node::get_parameter().

Here is the caller graph for this function:

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