Skip to content

Commit 78bb0ca

Browse files
Make double parsing locale independent (#921)
1 parent 8486a98 commit 78bb0ca

File tree

3 files changed

+57
-15
lines changed

3 files changed

+57
-15
lines changed

hardware_interface/src/component_parser.cpp

Lines changed: 16 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
// limitations under the License.
1414

1515
#include <tinyxml2.h>
16+
#include <charconv>
1617
#include <regex>
1718
#include <stdexcept>
1819
#include <string>
@@ -123,26 +124,30 @@ double get_parameter_value_or(
123124
{
124125
while (params_it)
125126
{
126-
try
127+
// Fill the map with parameters
128+
const auto tag_name = params_it->Name();
129+
if (strcmp(tag_name, parameter_name) == 0)
127130
{
128-
// Fill the map with parameters
129-
const auto tag_name = params_it->Name();
130-
if (strcmp(tag_name, parameter_name) == 0)
131+
const auto tag_text = params_it->GetText();
132+
if (tag_text)
131133
{
132-
const auto tag_text = params_it->GetText();
133-
if (tag_text)
134+
// Parse and return double value if there is no parsing error
135+
double result_value;
136+
const auto parse_result =
137+
std::from_chars(tag_text, tag_text + std::strlen(tag_text), result_value);
138+
if (parse_result.ec == std::errc())
134139
{
135-
return std::stod(tag_text);
140+
return result_value;
136141
}
142+
143+
// Parsing failed - exit loop and return default value
144+
break;
137145
}
138146
}
139-
catch (const std::exception & e)
140-
{
141-
return default_value;
142-
}
143147

144148
params_it = params_it->NextSiblingElement();
145149
}
150+
146151
return default_value;
147152
}
148153

hardware_interface/src/mock_components/generic_system.cpp

Lines changed: 17 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include "mock_components/generic_system.hpp"
1818

1919
#include <algorithm>
20+
#include <charconv>
2021
#include <cmath>
2122
#include <iterator>
2223
#include <limits>
@@ -29,6 +30,18 @@
2930

3031
namespace mock_components
3132
{
33+
double parse_double(const std::string & text)
34+
{
35+
double result_value;
36+
const auto parse_result = std::from_chars(text.data(), text.data() + text.size(), result_value);
37+
if (parse_result.ec == std::errc())
38+
{
39+
return result_value;
40+
}
41+
42+
return 0.0;
43+
}
44+
3245
CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & info)
3346
{
3447
if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS)
@@ -101,7 +114,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i
101114
it = info_.hardware_parameters.find("position_state_following_offset");
102115
if (it != info_.hardware_parameters.end())
103116
{
104-
position_state_following_offset_ = std::stod(it->second);
117+
position_state_following_offset_ = parse_double(it->second);
105118
it = info_.hardware_parameters.find("custom_interface_with_following_offset");
106119
if (it != info_.hardware_parameters.end())
107120
{
@@ -147,7 +160,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i
147160
auto param_it = joint.parameters.find("multiplier");
148161
if (param_it != joint.parameters.end())
149162
{
150-
mimic_joint.multiplier = std::stod(joint.parameters.at("multiplier"));
163+
mimic_joint.multiplier = parse_double(joint.parameters.at("multiplier"));
151164
}
152165
mimic_joints_.push_back(mimic_joint);
153166
}
@@ -455,15 +468,15 @@ void GenericSystem::initialize_storage_vectors(
455468
// Check the initial_value param is used
456469
if (!interface.initial_value.empty())
457470
{
458-
states[index][i] = std::stod(interface.initial_value);
471+
states[index][i] = parse_double(interface.initial_value);
459472
}
460473
else
461474
{
462475
// Initialize the value in old way with warning message
463476
auto it2 = component.parameters.find("initial_" + interface.name);
464477
if (it2 != component.parameters.end())
465478
{
466-
states[index][i] = std::stod(it2->second);
479+
states[index][i] = parse_double(it2->second);
467480
print_hint = true;
468481
}
469482
else

hardware_interface/test/test_component_parser.cpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -510,6 +510,30 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_actuator_only)
510510
EXPECT_EQ(transmission.parameters.at("additional_special_parameter"), "1337");
511511
}
512512

513+
TEST_F(TestComponentParser, successfully_parse_locale_independent_double)
514+
{
515+
// Set to locale with comma-separated decimals
516+
std::setlocale(LC_NUMERIC, "de_DE.UTF-8");
517+
518+
std::string urdf_to_test = std::string(ros2_control_test_assets::urdf_head) +
519+
ros2_control_test_assets::valid_urdf_ros2_control_actuator_only +
520+
ros2_control_test_assets::urdf_tail;
521+
522+
const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test);
523+
ASSERT_THAT(control_hardware, SizeIs(1));
524+
const auto hardware_info = control_hardware.at(0);
525+
526+
EXPECT_EQ(hardware_info.hardware_parameters.at("example_param_write_for_sec"), "1.13");
527+
528+
ASSERT_THAT(hardware_info.transmissions, SizeIs(1));
529+
const auto transmission = hardware_info.transmissions[0];
530+
EXPECT_THAT(transmission.joints, SizeIs(1));
531+
const auto joint = transmission.joints[0];
532+
533+
// Test that we still parse doubles using dot notation
534+
EXPECT_THAT(joint.mechanical_reduction, DoubleEq(325.949));
535+
}
536+
513537
TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_robot_with_gpio)
514538
{
515539
std::string urdf_to_test =

0 commit comments

Comments
 (0)