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

Store the type and value of a parameter. More...

#include <rclcpp/parameter_value.hpp>

Public Member Functions

RCLCPP_PUBLIC ParameterValue ()
 Construct a parameter value with type PARAMETER_NOT_SET.
 
RCLCPP_PUBLIC ParameterValue (const rcl_interfaces::msg::ParameterValue &value)
 Construct a parameter value from a message.
 
RCLCPP_PUBLIC ParameterValue (const bool bool_value)
 Construct a parameter value with type PARAMETER_BOOL.
 
RCLCPP_PUBLIC ParameterValue (const int int_value)
 Construct a parameter value with type PARAMETER_INTEGER.
 
RCLCPP_PUBLIC ParameterValue (const int64_t int_value)
 Construct a parameter value with type PARAMETER_INTEGER.
 
RCLCPP_PUBLIC ParameterValue (const float double_value)
 Construct a parameter value with type PARAMETER_DOUBLE.
 
RCLCPP_PUBLIC ParameterValue (const double double_value)
 Construct a parameter value with type PARAMETER_DOUBLE.
 
RCLCPP_PUBLIC ParameterValue (const std::string &string_value)
 Construct a parameter value with type PARAMETER_STRING.
 
RCLCPP_PUBLIC ParameterValue (const char *string_value)
 Construct a parameter value with type PARAMETER_STRING.
 
RCLCPP_PUBLIC ParameterValue (const std::vector< uint8_t > &byte_array_value)
 Construct a parameter value with type PARAMETER_BYTE_ARRAY.
 
RCLCPP_PUBLIC ParameterValue (const std::vector< bool > &bool_array_value)
 Construct a parameter value with type PARAMETER_BOOL_ARRAY.
 
RCLCPP_PUBLIC ParameterValue (const std::vector< int > &int_array_value)
 Construct a parameter value with type PARAMETER_INTEGER_ARRAY.
 
RCLCPP_PUBLIC ParameterValue (const std::vector< int64_t > &int_array_value)
 Construct a parameter value with type PARAMETER_INTEGER_ARRAY.
 
RCLCPP_PUBLIC ParameterValue (const std::vector< float > &double_array_value)
 Construct a parameter value with type PARAMETER_DOUBLE_ARRAY.
 
RCLCPP_PUBLIC ParameterValue (const std::vector< double > &double_array_value)
 Construct a parameter value with type PARAMETER_DOUBLE_ARRAY.
 
RCLCPP_PUBLIC ParameterValue (const std::vector< std::string > &string_array_value)
 Construct a parameter value with type PARAMETER_STRING_ARRAY.
 
RCLCPP_PUBLIC ParameterType get_type () const
 Return an enum indicating the type of the set value.
 
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue to_value_msg () const
 Return a message populated with the parameter value.
 
RCLCPP_PUBLIC bool operator== (const ParameterValue &rhs) const
 Equal operator.
 
RCLCPP_PUBLIC bool operator!= (const ParameterValue &rhs) const
 Not equal operator.
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get () const
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_INTEGER, const int64_t & >::type get () const
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_DOUBLE, const double & >::type get () const
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_STRING, const std::string & >::type get () const
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_BYTE_ARRAY, const std::vector< uint8_t > & >::type get () const
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL_ARRAY, const std::vector< bool > & >::type get () const
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector< int64_t > & >::type get () const
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector< double > & >::type get () const
 
template<ParameterType type>
constexpr std::enable_if< type==ParameterType::PARAMETER_STRING_ARRAY, const std::vector< std::string > & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_same< type, bool >::value, const bool & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_integral< type >::value &&!std::is_same< type, bool >::value, const int64_t & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_floating_point< type >::value, const double & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_convertible< type, std::string >::value, const std::string & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_convertible< type, const std::vector< uint8_t > & >::value, const std::vector< uint8_t > & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_convertible< type, const std::vector< bool > & >::value, const std::vector< bool > & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_convertible< type, const std::vector< int > & >::value, const std::vector< int64_t > & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_convertible< type, const std::vector< int64_t > & >::value, const std::vector< int64_t > & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_convertible< type, const std::vector< float > & >::value, const std::vector< double > & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_convertible< type, const std::vector< double > & >::value, const std::vector< double > & >::type get () const
 
template<typename type >
constexpr std::enable_if< std::is_convertible< type, const std::vector< std::string > & >::value, const std::vector< std::string > & >::type get () const
 

Detailed Description

Store the type and value of a parameter.

Definition at line 72 of file parameter_value.hpp.


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