Skip to content

Commit c9742eb

Browse files
Use own implementation of stod (ros-controls#428)
1 parent f471a3f commit c9742eb

File tree

4 files changed

+19
-9
lines changed

4 files changed

+19
-9
lines changed

example_14/hardware/rrbot_actuator_without_feedback.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
#include <vector>
2727

2828
#include "hardware_interface/actuator_interface.hpp"
29+
#include "hardware_interface/lexical_casts.hpp"
2930
#include "hardware_interface/types/hardware_interface_type_values.hpp"
3031
#include "rclcpp/rclcpp.hpp"
3132

@@ -41,8 +42,10 @@ hardware_interface::CallbackReturn RRBotActuatorWithoutFeedback::on_init(
4142
return hardware_interface::CallbackReturn::ERROR;
4243
}
4344
// START: This part here is for exemplary purposes - Please do not copy to your production code
44-
hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
45-
hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
45+
hw_start_sec_ =
46+
hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
47+
hw_stop_sec_ =
48+
hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
4649
socket_port_ = std::stoi(info_.hardware_parameters["example_param_socket_port"]);
4750
// END: This part here is for exemplary purposes - Please do not copy to your production code
4851

example_14/hardware/rrbot_sensor_for_position_feedback.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
#include <thread>
2828
#include <vector>
2929

30+
#include "hardware_interface/lexical_casts.hpp"
3031
#include "hardware_interface/sensor_interface.hpp"
3132
#include "hardware_interface/types/hardware_interface_type_values.hpp"
3233
#include "rclcpp/rclcpp.hpp"
@@ -43,9 +44,11 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init(
4344
return hardware_interface::CallbackReturn::ERROR;
4445
}
4546
// START: This part here is for exemplary purposes - Please do not copy to your production code
46-
hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
47-
hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
48-
hw_slowdown_ = std::stod(info_.hardware_parameters["example_param_hw_slowdown"]);
47+
hw_start_sec_ =
48+
hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
49+
hw_stop_sec_ =
50+
hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
51+
hw_slowdown_ = hardware_interface::stod(info_.hardware_parameters["example_param_hw_slowdown"]);
4952
socket_port_ = std::stoi(info_.hardware_parameters["example_param_socket_port"]);
5053
// END: This part here is for exemplary purposes - Please do not copy to your production code
5154

@@ -151,7 +154,7 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init(
151154
rclcpp::get_logger("RRBotSensorPositionFeedback"),
152155
"Read form buffer sockets data: '%s'", buffer);
153156

154-
rt_incomming_data_ptr_.writeFromNonRT(std::stod(buffer));
157+
rt_incomming_data_ptr_.writeFromNonRT(hardware_interface::stod(buffer));
155158
}
156159
else
157160
{

example_2/hardware/diffbot_system.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <memory>
2222
#include <vector>
2323

24+
#include "hardware_interface/lexical_casts.hpp"
2425
#include "hardware_interface/types/hardware_interface_type_values.hpp"
2526
#include "rclcpp/rclcpp.hpp"
2627

@@ -37,8 +38,10 @@ hardware_interface::CallbackReturn DiffBotSystemHardware::on_init(
3738
}
3839

3940
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
40-
hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
41-
hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
41+
hw_start_sec_ =
42+
hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
43+
hw_stop_sec_ =
44+
hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
4245
// END: This part here is for exemplary purposes - Please do not copy to your production code
4346
hw_positions_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
4447
hw_velocities_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());

example_8/hardware/rrbot_transmissions_system_position_only.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <sstream>
2323
#include <vector>
2424

25+
#include "hardware_interface/lexical_casts.hpp"
2526
#include "hardware_interface/types/hardware_interface_type_values.hpp"
2627
#include "rclcpp/clock.hpp"
2728
#include "rclcpp/logging.hpp"
@@ -51,7 +52,7 @@ hardware_interface::CallbackReturn RRBotTransmissionsSystemPositionOnlyHardware:
5152
return hardware_interface::CallbackReturn::ERROR;
5253
}
5354

54-
actuator_slowdown_ = std::stod(info_.hardware_parameters["actuator_slowdown"]);
55+
actuator_slowdown_ = hardware_interface::stod(info_.hardware_parameters["actuator_slowdown"]);
5556

5657
const auto num_joints = std::accumulate(
5758
info_.transmissions.begin(), info_.transmissions.end(), 0ul,

0 commit comments

Comments
 (0)