Skip to content

Commit 17d82e6

Browse files
Improve lexical casts methods (#2343) (#2345)
Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent ca98a45 commit 17d82e6

File tree

3 files changed

+186
-53
lines changed

3 files changed

+186
-53
lines changed

hardware_interface/include/hardware_interface/lexical_casts.hpp

Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,11 @@
1515
#ifndef HARDWARE_INTERFACE__LEXICAL_CASTS_HPP_
1616
#define HARDWARE_INTERFACE__LEXICAL_CASTS_HPP_
1717

18+
#include <regex>
19+
#include <sstream>
20+
#include <stdexcept>
1821
#include <string>
22+
#include <type_traits>
1923
#include <vector>
2024

2125
namespace hardware_interface
@@ -30,6 +34,77 @@ double stod(const std::string & s);
3034

3135
bool parse_bool(const std::string & bool_string);
3236

37+
template <typename T>
38+
std::vector<T> parse_array(const std::string & array_string)
39+
{
40+
// Use regex to check for a flat array: starts with [, ends with ], no nested brackets
41+
const std::regex array_regex(R"(^\[\s*([^\[\]]*\s*(,\s*[^\[\]]+\s*)*)?\]$)");
42+
if (!std::regex_match(array_string, array_regex))
43+
{
44+
throw std::invalid_argument(
45+
"String must be a flat array: starts with '[' and ends with ']', no nested arrays");
46+
}
47+
48+
// Use regex for the expression that either empty or contains only spaces
49+
const std::regex empty_or_spaces_regex(R"(^\[\s*\]$)");
50+
if (std::regex_match(array_string, empty_or_spaces_regex))
51+
{
52+
return {}; // Return empty array if input is "[]"
53+
}
54+
55+
// Use regex to find cases of comma-separated but only whitespaces or no spaces between them like
56+
// "[,]" "[a,b,,c]"
57+
const std::regex comma_separated_regex(R"(^\[\s*([^,\s]+(\s*,\s*[^,\s]+)*)?\s*\]$)");
58+
if (!std::regex_match(array_string, comma_separated_regex))
59+
{
60+
throw std::invalid_argument(
61+
"String must be a flat array with comma-separated values and no spaces between them");
62+
}
63+
64+
std::vector<T> result = {};
65+
if (array_string == "[]")
66+
{
67+
return result; // Return empty array if input is "[]"
68+
}
69+
70+
// regex for comma separated values and no spaces between them or just content like "[a,b,c]" or
71+
// "[a]" or "[a, b, c]"
72+
const std::regex value_regex(R"([^\s,\[\]]+)");
73+
auto begin = std::sregex_iterator(array_string.begin(), array_string.end(), value_regex);
74+
auto end = std::sregex_iterator();
75+
76+
for (auto it = begin; it != end; ++it)
77+
{
78+
const std::string value_str = it->str(); // Get the first capturing group
79+
if constexpr (std::is_same_v<T, std::string>)
80+
{
81+
result.push_back(value_str);
82+
}
83+
else if constexpr (std::is_same_v<T, bool>)
84+
{
85+
result.push_back(parse_bool(value_str));
86+
}
87+
else if constexpr (std::is_floating_point_v<T> || std::is_integral_v<T>)
88+
{
89+
try
90+
{
91+
const T value = static_cast<T>(hardware_interface::stod(value_str));
92+
result.push_back(value);
93+
}
94+
catch (const std::exception &)
95+
{
96+
throw std::invalid_argument(
97+
"Failed converting string to floating point or integer: " + value_str);
98+
}
99+
}
100+
else
101+
{
102+
throw std::invalid_argument("Unsupported type for parsing: " + std::string(typeid(T).name()));
103+
}
104+
}
105+
return result;
106+
}
107+
33108
std::vector<std::string> parse_string_array(const std::string & string_array_string);
34109

35110
} // namespace hardware_interface

hardware_interface/src/lexical_casts.cpp

Lines changed: 19 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,11 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include <algorithm>
16+
#include <cctype>
1517
#include <locale>
1618
#include <optional>
17-
#include <sstream>
19+
#include <stdexcept>
1820
#include <string>
1921
#include <vector>
2022

@@ -62,60 +64,28 @@ double stod(const std::string & s)
6264

6365
bool parse_bool(const std::string & bool_string)
6466
{
65-
return bool_string == "true" || bool_string == "True";
66-
}
67-
68-
std::vector<std::string> parse_string_array(const std::string & string_array_string)
69-
{
70-
// Check string starts with '[' and ends with ']'
71-
if (
72-
string_array_string.empty() || string_array_string.front() != '[' ||
73-
string_array_string.back() != ']')
74-
{
75-
throw std::invalid_argument("String must start with '[' and end with ']'");
76-
}
77-
78-
// Check there are no "sub arrays"
79-
if (
80-
string_array_string.find("[") != 0u ||
81-
string_array_string.find("]") != string_array_string.size() - 1u)
82-
{
83-
throw std::invalid_argument("String contains nested arrays");
84-
}
67+
// Copy input to temp and make lowercase
68+
std::string temp = bool_string;
69+
std::transform(
70+
temp.begin(), temp.end(), temp.begin(), [](unsigned char c) { return std::tolower(c); });
8571

86-
// Check for empty array
87-
if (string_array_string == "[]")
72+
if (temp == "true")
8873
{
89-
return {};
74+
return true;
9075
}
91-
92-
std::vector<std::string> result;
93-
std::string current_string;
94-
for (char c : string_array_string)
76+
if (temp == "false")
9577
{
96-
if (c == ',' || c == ']')
97-
{
98-
if (!current_string.empty())
99-
{
100-
result.push_back(current_string);
101-
current_string.clear();
102-
}
103-
else
104-
{
105-
throw std::invalid_argument("Empty string found in array");
106-
}
107-
}
108-
else if (c == '[' || c == ' ')
109-
{
110-
// Ignore opening brackets and spaces
111-
}
112-
else
113-
{
114-
current_string += c; // Add character to current string
115-
}
78+
return false;
11679
}
80+
// If input is not "true" or "false" (any casing), throw or handle as error
81+
throw std::invalid_argument(
82+
"Input string : '" + bool_string +
83+
"' is not a valid boolean value. Expected 'true' or 'false'.");
84+
}
11785

118-
return result;
86+
std::vector<std::string> parse_string_array(const std::string & string_array_string)
87+
{
88+
return parse_array<std::string>(string_array_string);
11989
}
12090

12191
} // namespace hardware_interface

hardware_interface/test/test_lexical_casts.cpp

Lines changed: 92 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,23 @@ TEST(TestLexicalCasts, test_parse_bool)
3636

3737
ASSERT_TRUE(parse_bool("true"));
3838
ASSERT_TRUE(parse_bool("True"));
39+
ASSERT_TRUE(parse_bool("TRUE"));
40+
ASSERT_TRUE(parse_bool("TrUe"));
3941

4042
// Any other value should return false
4143
ASSERT_FALSE(parse_bool("false"));
4244
ASSERT_FALSE(parse_bool("False"));
43-
ASSERT_FALSE(parse_bool(""));
44-
ASSERT_FALSE(parse_bool("abc"));
45-
ASSERT_FALSE(parse_bool("1"));
45+
ASSERT_FALSE(parse_bool("FALSE"));
46+
ASSERT_FALSE(parse_bool("fAlSe"));
47+
48+
// Invalid inputs should throw an exception
49+
ASSERT_THROW(parse_bool("1"), std::invalid_argument);
50+
ASSERT_THROW(parse_bool("0"), std::invalid_argument);
51+
ASSERT_THROW(parse_bool("yes"), std::invalid_argument);
52+
ASSERT_THROW(parse_bool("no"), std::invalid_argument);
53+
ASSERT_THROW(parse_bool(""), std::invalid_argument);
54+
ASSERT_THROW(parse_bool("abc"), std::invalid_argument);
55+
ASSERT_THROW(parse_bool("1"), std::invalid_argument);
4656
}
4757

4858
TEST(TestLexicalCasts, test_parse_string_array)
@@ -54,15 +64,93 @@ TEST(TestLexicalCasts, test_parse_string_array)
5464
ASSERT_THROW(parse_string_array("[abc"), std::invalid_argument);
5565
ASSERT_THROW(parse_string_array("abc]"), std::invalid_argument);
5666
ASSERT_THROW(parse_string_array("[[abc, def], hij]"), std::invalid_argument);
57-
ASSERT_THROW(parse_string_array("[ ]"), std::invalid_argument);
5867
ASSERT_THROW(parse_string_array("[,]"), std::invalid_argument);
5968
ASSERT_THROW(parse_string_array("[abc,]"), std::invalid_argument);
6069
ASSERT_THROW(parse_string_array("[,abc]"), std::invalid_argument);
6170
ASSERT_THROW(parse_string_array("[abc,,def]"), std::invalid_argument);
6271

6372
ASSERT_EQ(parse_string_array("[]"), std::vector<std::string>());
73+
ASSERT_EQ(parse_string_array("[ ]"), std::vector<std::string>());
6474
ASSERT_EQ(parse_string_array("[abc]"), std::vector<std::string>({"abc"}));
6575
ASSERT_EQ(parse_string_array("[abc,def]"), std::vector<std::string>({"abc", "def"}));
6676
ASSERT_EQ(parse_string_array("[abc, def]"), std::vector<std::string>({"abc", "def"}));
6777
ASSERT_EQ(parse_string_array("[ abc, def ]"), std::vector<std::string>({"abc", "def"}));
6878
}
79+
80+
TEST(TestLexicalCasts, test_parse_double_array)
81+
{
82+
using hardware_interface::parse_array;
83+
84+
ASSERT_THROW(parse_array<double>(""), std::invalid_argument);
85+
ASSERT_THROW(parse_array<double>("1.23"), std::invalid_argument);
86+
ASSERT_THROW(parse_array<double>("[1.23"), std::invalid_argument);
87+
ASSERT_THROW(parse_array<double>("1.23]"), std::invalid_argument);
88+
ASSERT_THROW(parse_array<double>("[[1.23, 4.56], 7.89]"), std::invalid_argument);
89+
ASSERT_THROW(parse_array<double>("[,]"), std::invalid_argument);
90+
ASSERT_THROW(parse_array<double>("[ , ]"), std::invalid_argument);
91+
ASSERT_THROW(parse_array<double>("[1.23,]"), std::invalid_argument);
92+
ASSERT_THROW(parse_array<double>("[,1.234]"), std::invalid_argument);
93+
ASSERT_THROW(parse_array<double>("[1.232,,1.324]"), std::invalid_argument);
94+
95+
ASSERT_EQ(parse_array<double>("[]"), std::vector<double>());
96+
ASSERT_EQ(parse_array<double>("[ ]"), std::vector<double>());
97+
ASSERT_EQ(parse_array<double>("[1.23]"), std::vector<double>({1.23}));
98+
ASSERT_EQ(parse_array<double>("[-1.23]"), std::vector<double>({-1.23}));
99+
ASSERT_EQ(parse_array<double>("[1.23,4.56]"), std::vector<double>({1.23, 4.56}));
100+
ASSERT_EQ(parse_array<double>("[-1.23,-4.56]"), std::vector<double>({-1.23, -4.56}));
101+
ASSERT_EQ(parse_array<double>("[-1.23, 4.56]"), std::vector<double>({-1.23, 4.56}));
102+
ASSERT_EQ(parse_array<double>("[ -1.23, -124.56 ]"), std::vector<double>({-1.23, -124.56}));
103+
ASSERT_EQ(parse_array<double>("[ 1.23, 4 ]"), std::vector<double>({1.23, 4.0}));
104+
ASSERT_EQ(parse_array<double>("[ 1.23, 4.56, -7 ]"), std::vector<double>({1.23, 4.56, -7.0}));
105+
ASSERT_EQ(parse_array<double>("[ 1.23, 123, -7.89 ]"), std::vector<double>({1.23, 123.0, -7.89}));
106+
ASSERT_EQ(parse_array<double>("[ 1.23, 4.56, -7.89 ]"), std::vector<double>({1.23, 4.56, -7.89}));
107+
}
108+
109+
TEST(TestLexicalCasts, test_parse_int_array)
110+
{
111+
using hardware_interface::parse_array;
112+
113+
ASSERT_THROW(parse_array<int>(""), std::invalid_argument);
114+
ASSERT_THROW(parse_array<int>("123"), std::invalid_argument);
115+
ASSERT_THROW(parse_array<int>("[232"), std::invalid_argument);
116+
ASSERT_THROW(parse_array<int>("123]"), std::invalid_argument);
117+
ASSERT_THROW(parse_array<int>("[[1.23, 4], 7]"), std::invalid_argument);
118+
ASSERT_THROW(parse_array<int>("[,]"), std::invalid_argument);
119+
ASSERT_THROW(parse_array<int>("[ , ]"), std::invalid_argument);
120+
ASSERT_THROW(parse_array<int>("[1,]"), std::invalid_argument);
121+
ASSERT_THROW(parse_array<int>("[,1]"), std::invalid_argument);
122+
ASSERT_THROW(parse_array<int>("[1,,2]"), std::invalid_argument);
123+
124+
ASSERT_EQ(parse_array<int>("[]"), std::vector<int>());
125+
ASSERT_EQ(parse_array<int>("[ ]"), std::vector<int>());
126+
ASSERT_EQ(parse_array<int>("[1]"), std::vector<int>({1}));
127+
ASSERT_EQ(parse_array<int>("[-1]"), std::vector<int>({-1}));
128+
ASSERT_EQ(parse_array<int>("[1,2]"), std::vector<int>({1, 2}));
129+
ASSERT_EQ(parse_array<int>("[-1,-2]"), std::vector<int>({-1, -2}));
130+
ASSERT_EQ(parse_array<int>("[ -1, -124 ]"), std::vector<int>({-1, -124}));
131+
ASSERT_EQ(parse_array<int>("[ -1, -124, +123 ]"), std::vector<int>({-1, -124, 123}));
132+
}
133+
134+
TEST(TestLexicalCasts, test_parse_bool_array)
135+
{
136+
using hardware_interface::parse_array;
137+
138+
ASSERT_THROW(parse_array<bool>(""), std::invalid_argument);
139+
ASSERT_THROW(parse_array<bool>("true"), std::invalid_argument);
140+
ASSERT_THROW(parse_array<bool>("[true"), std::invalid_argument);
141+
ASSERT_THROW(parse_array<bool>("true]"), std::invalid_argument);
142+
ASSERT_THROW(parse_array<bool>("[[true, false], true]"), std::invalid_argument);
143+
ASSERT_THROW(parse_array<bool>("[,]"), std::invalid_argument);
144+
ASSERT_THROW(parse_array<bool>("[ , ]"), std::invalid_argument);
145+
ASSERT_THROW(parse_array<bool>("[true,]"), std::invalid_argument);
146+
ASSERT_THROW(parse_array<bool>("[,false]"), std::invalid_argument);
147+
ASSERT_THROW(parse_array<bool>("[true,,false]"), std::invalid_argument);
148+
149+
ASSERT_EQ(parse_array<bool>("[]"), std::vector<bool>());
150+
ASSERT_EQ(parse_array<bool>("[ ]"), std::vector<bool>());
151+
ASSERT_EQ(parse_array<bool>("[true]"), std::vector<bool>({true}));
152+
ASSERT_EQ(parse_array<bool>("[false]"), std::vector<bool>({false}));
153+
ASSERT_EQ(parse_array<bool>("[true,false]"), std::vector<bool>({true, false}));
154+
ASSERT_EQ(parse_array<bool>("[false,true]"), std::vector<bool>({false, true}));
155+
ASSERT_EQ(parse_array<bool>("[ true, false ]"), std::vector<bool>({true, false}));
156+
}

0 commit comments

Comments
 (0)