|
26 | 26 | #include <vector> |
27 | 27 |
|
28 | 28 | #include "hardware_interface/component_parser.hpp" |
| 29 | +#include "hardware_interface/lexical_casts.hpp" |
29 | 30 | #include "hardware_interface/types/hardware_interface_type_values.hpp" |
30 | 31 | #include "rcutils/logging_macros.h" |
31 | 32 |
|
32 | 33 | namespace mock_components |
33 | 34 | { |
34 | | -double parse_double(const std::string & text) |
35 | | -{ |
36 | | - double result_value; |
37 | | - const auto parse_result = std::from_chars(text.data(), text.data() + text.size(), result_value); |
38 | | - if (parse_result.ec == std::errc()) |
39 | | - { |
40 | | - return result_value; |
41 | | - } |
42 | | - |
43 | | - return 0.0; |
44 | | -} |
45 | 35 |
|
46 | 36 | CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & info) |
47 | 37 | { |
@@ -123,7 +113,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i |
123 | 113 | it = info_.hardware_parameters.find("position_state_following_offset"); |
124 | 114 | if (it != info_.hardware_parameters.end()) |
125 | 115 | { |
126 | | - position_state_following_offset_ = parse_double(it->second); |
| 116 | + position_state_following_offset_ = hardware_interface::stod(it->second); |
127 | 117 | it = info_.hardware_parameters.find("custom_interface_with_following_offset"); |
128 | 118 | if (it != info_.hardware_parameters.end()) |
129 | 119 | { |
@@ -169,7 +159,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i |
169 | 159 | auto param_it = joint.parameters.find("multiplier"); |
170 | 160 | if (param_it != joint.parameters.end()) |
171 | 161 | { |
172 | | - mimic_joint.multiplier = parse_double(joint.parameters.at("multiplier")); |
| 162 | + mimic_joint.multiplier = hardware_interface::stod(joint.parameters.at("multiplier")); |
173 | 163 | } |
174 | 164 | mimic_joints_.push_back(mimic_joint); |
175 | 165 | } |
@@ -696,7 +686,7 @@ void GenericSystem::initialize_storage_vectors( |
696 | 686 | // Check the initial_value param is used |
697 | 687 | if (!interface.initial_value.empty()) |
698 | 688 | { |
699 | | - states[index][i] = parse_double(interface.initial_value); |
| 689 | + states[index][i] = hardware_interface::stod(interface.initial_value); |
700 | 690 | } |
701 | 691 | } |
702 | 692 | } |
|
0 commit comments