diff --git a/example_14/hardware/rrbot_actuator_without_feedback.cpp b/example_14/hardware/rrbot_actuator_without_feedback.cpp index 5a9ba378..3c7a6b88 100644 --- a/example_14/hardware/rrbot_actuator_without_feedback.cpp +++ b/example_14/hardware/rrbot_actuator_without_feedback.cpp @@ -26,6 +26,7 @@ #include #include "hardware_interface/actuator_interface.hpp" +#include "hardware_interface/lexical_casts.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "rclcpp/rclcpp.hpp" @@ -41,8 +42,10 @@ hardware_interface::CallbackReturn RRBotActuatorWithoutFeedback::on_init( return hardware_interface::CallbackReturn::ERROR; } // START: This part here is for exemplary purposes - Please do not copy to your production code - hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]); - hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]); + hw_start_sec_ = + hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]); + hw_stop_sec_ = + hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]); socket_port_ = std::stoi(info_.hardware_parameters["example_param_socket_port"]); // END: This part here is for exemplary purposes - Please do not copy to your production code diff --git a/example_14/hardware/rrbot_sensor_for_position_feedback.cpp b/example_14/hardware/rrbot_sensor_for_position_feedback.cpp index 7eee2359..395c922c 100644 --- a/example_14/hardware/rrbot_sensor_for_position_feedback.cpp +++ b/example_14/hardware/rrbot_sensor_for_position_feedback.cpp @@ -27,6 +27,7 @@ #include #include +#include "hardware_interface/lexical_casts.hpp" #include "hardware_interface/sensor_interface.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "rclcpp/rclcpp.hpp" @@ -43,9 +44,11 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init( return hardware_interface::CallbackReturn::ERROR; } // START: This part here is for exemplary purposes - Please do not copy to your production code - hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]); - hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]); - hw_slowdown_ = std::stod(info_.hardware_parameters["example_param_hw_slowdown"]); + hw_start_sec_ = + hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]); + hw_stop_sec_ = + hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]); + hw_slowdown_ = hardware_interface::stod(info_.hardware_parameters["example_param_hw_slowdown"]); socket_port_ = std::stoi(info_.hardware_parameters["example_param_socket_port"]); // END: This part here is for exemplary purposes - Please do not copy to your production code @@ -151,7 +154,7 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init( rclcpp::get_logger("RRBotSensorPositionFeedback"), "Read form buffer sockets data: '%s'", buffer); - rt_incomming_data_ptr_.writeFromNonRT(std::stod(buffer)); + rt_incomming_data_ptr_.writeFromNonRT(hardware_interface::stod(buffer)); } else { diff --git a/example_2/hardware/diffbot_system.cpp b/example_2/hardware/diffbot_system.cpp index 2602a5df..177b3a4f 100644 --- a/example_2/hardware/diffbot_system.cpp +++ b/example_2/hardware/diffbot_system.cpp @@ -21,6 +21,7 @@ #include #include +#include "hardware_interface/lexical_casts.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "rclcpp/rclcpp.hpp" @@ -37,8 +38,10 @@ hardware_interface::CallbackReturn DiffBotSystemHardware::on_init( } // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code - hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]); - hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]); + hw_start_sec_ = + hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]); + hw_stop_sec_ = + hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]); // END: This part here is for exemplary purposes - Please do not copy to your production code hw_positions_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); hw_velocities_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); diff --git a/example_8/hardware/rrbot_transmissions_system_position_only.cpp b/example_8/hardware/rrbot_transmissions_system_position_only.cpp index 6a64bf3b..7ce35285 100644 --- a/example_8/hardware/rrbot_transmissions_system_position_only.cpp +++ b/example_8/hardware/rrbot_transmissions_system_position_only.cpp @@ -22,6 +22,7 @@ #include #include +#include "hardware_interface/lexical_casts.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "rclcpp/clock.hpp" #include "rclcpp/logging.hpp" @@ -51,7 +52,7 @@ hardware_interface::CallbackReturn RRBotTransmissionsSystemPositionOnlyHardware: return hardware_interface::CallbackReturn::ERROR; } - actuator_slowdown_ = std::stod(info_.hardware_parameters["actuator_slowdown"]); + actuator_slowdown_ = hardware_interface::stod(info_.hardware_parameters["actuator_slowdown"]); const auto num_joints = std::accumulate( info_.transmissions.begin(), info_.transmissions.end(), 0ul,