15#ifndef HARDWARE_INTERFACE__LEXICAL_CASTS_HPP_
16#define HARDWARE_INTERFACE__LEXICAL_CASTS_HPP_
34double stod(
const std::string & s);
39float stof(
const std::string & s);
48 static_assert(std::is_integral_v<T> && std::is_signed_v<T>,
"T must be a signed integral type");
51 const auto v = std::stol(s, &pos);
52 if (pos != s.length())
54 throw std::invalid_argument(
"Invalid characters in string");
56 if (v < std::numeric_limits<T>::min() || v > std::numeric_limits<T>::max())
58 throw std::out_of_range(
"value not in range of target type");
61 return static_cast<T
>(v);
65inline int8_t stoi8(
const std::string & s) {
return stoi_generic<int8_t>(s); }
66inline int16_t stoi16(
const std::string & s) {
return stoi_generic<int16_t>(s); }
67inline int32_t stoi32(
const std::string & s) {
return stoi_generic<int32_t>(s); }
77 std::is_integral_v<T> && std::is_unsigned_v<T>,
"T must be an unsigned integral type");
80 const auto v = std::stoul(s, &pos);
81 if (pos != s.length())
83 throw std::invalid_argument(
"Invalid characters in string");
85 if (v > std::numeric_limits<T>::max())
87 throw std::out_of_range(
"value not in range of target type");
90 return static_cast<T
>(v);
94inline uint8_t stoui8(
const std::string & s) {
return stoui_generic<uint8_t>(s); }
95inline uint16_t stoui16(
const std::string & s) {
return stoui_generic<uint16_t>(s); }
96inline uint32_t stoui32(
const std::string & s) {
return stoui_generic<uint32_t>(s); }
111bool parse_bool(
const std::string & bool_string);
114std::vector<T> parse_array(
const std::string & array_string)
117 const std::regex array_regex(R
"(^\[\s*([^\[\]]*\s*(,\s*[^\[\]]+\s*)*)?\]$)");
118 if (!std::regex_match(array_string, array_regex))
120 throw std::invalid_argument(
121 "String must be a flat array: starts with '[' and ends with ']', no nested arrays");
125 const std::regex empty_or_spaces_regex(R
"(^\[\s*\]$)");
126 if (std::regex_match(array_string, empty_or_spaces_regex))
133 const std::regex comma_separated_regex(R
"(^\[\s*([^,\s]+(\s*,\s*[^,\s]+)*)?\s*\]$)");
134 if (!std::regex_match(array_string, comma_separated_regex))
136 throw std::invalid_argument(
137 "String must be a flat array with comma-separated values and no spaces between them");
140 std::vector<T> result = {};
141 if (array_string ==
"[]")
148 const std::regex value_regex(R
"([^\s,\[\]]+)");
149 auto begin = std::sregex_iterator(array_string.begin(), array_string.end(), value_regex);
150 auto end = std::sregex_iterator();
152 for (
auto it = begin; it != end; ++it)
154 const std::string value_str = it->str();
155 if constexpr (std::is_same_v<T, std::string>)
157 result.push_back(value_str);
159 else if constexpr (std::is_same_v<T, bool>)
163 else if constexpr (std::is_floating_point_v<T> || std::is_integral_v<T>)
168 result.push_back(value);
170 catch (
const std::exception &)
172 throw std::invalid_argument(
173 "Failed converting string to floating point or integer: " + value_str);
178 throw std::invalid_argument(
"Unsupported type for parsing: " + std::string(
typeid(T).name()));
184std::vector<std::string> parse_string_array(
const std::string & string_array_string);
Definition actuator.hpp:22
T stoui_generic(const std::string &s)
Overflow-safe conversion from string to uint32_t.
Definition lexical_casts.hpp:74
std::string to_lower_case(const std::string &string)
Convert a string to lower case.
Definition lexical_casts.cpp:103
T stoi_generic(const std::string &s)
Overflow-safe conversion from string to int32_t.
Definition lexical_casts.hpp:46
float stof(const std::string &s)
Helper function to convert a std::string to float in a locale-independent way.
Definition lexical_casts.cpp:94
double stod(const std::string &s)
Helper function to convert a std::string to double in a locale-independent way.
Definition lexical_casts.cpp:85
bool parse_bool(const std::string &bool_string)
Parse a boolean value from a string.
Definition lexical_casts.cpp:112