@@ -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
4858TEST (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