Struct Parameter

Inheritance Relationships

Base Type

  • public tuw_std_msgs::msg::Parameter

Struct Documentation

struct Parameter : public tuw_std_msgs::msg::Parameter

Public Functions

inline Parameter()
inline explicit Parameter(const std::string &name)
inline Parameter(const std::string &name, const double &value)
inline const std::string &set(const std::string &name, const double &value)

set the name and the value entry and retuns the created string

Parameters:
  • name – name to set

  • value – value to set

Returns:

string crated

inline const std::string &set(const double &value)

set a value entry and retuns the created string

Parameters:

values – value to set

Returns:

string crated

template<typename T>
inline T get() const
inline double &get(double &data) const
inline Parameter(const std::string &name, const int &value)
inline const std::string &set(const std::string &name, const int &value)

set the name and the value entry and retuns the created string

Parameters:
  • name – name to set

  • value – value to set

Returns:

string crated

inline const std::string &set(int &value)

set a value entry and retuns the created string

Parameters:

values – value to set

Returns:

string crated

inline int &get(int &data) const
inline Parameter(const std::string &name, const std::string &value)
inline const std::string &set(const std::string &name, const std::string &value)

set the name and the value entry and retuns the created string

Parameters:
  • name – name to set

  • value – value to set

Returns:

string crated

inline const std::string &set(const std::string &value)

set a value entry and retuns the created string

Parameters:

values – value to set

Returns:

string crated

inline std::string &get(std::string &data) const
inline Parameter(const std::string &name, const std::vector<double> &values, int precision = 10)
inline const std::string &set(const std::string &name, const std::vector<double> &values, int precision = 10)

set the name and the value entry and retuns the created string

Parameters:
  • name – values to set

  • values – values to set

Returns:

string crated

inline const std::string &set(const std::vector<double> &values, int precision = 10)

set a value entry and retuns the created string

Parameters:

values – values to set

Returns:

string crated

inline std::vector<double> &get(std::vector<double> &data) const
inline Parameter(const std::string &name, const std::vector<int> &values)
inline const std::string &set(const std::string &name, const std::vector<int> &values)

set the name and the value entry and retuns the created string

Parameters:
  • name – values to set

  • values – values to set

Returns:

string crated

inline const std::string &set(const std::vector<int> &values)

set a value entry and retuns the created string

Parameters:

values – values to set

Returns:

string crated

inline std::vector<int> &get(std::vector<int> &data) const
template<typename T>
inline T at(size_t index)

retuns the values by index

Note

it is slow

Parameters:

index

Returns:

values