From cb9aa69d5928f90c2ee6fc54fa4f4a6b5fc055ee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 22 Jan 2024 10:13:49 +0100 Subject: [PATCH] Use lexical casts (#260) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero --- gazebo_ros2_control/src/gazebo_system.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index af3e73be..16cd23d0 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -25,6 +25,7 @@ #include "gazebo/sensors/SensorManager.hh" #include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/lexical_casts.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" struct MimicJoint @@ -218,7 +219,7 @@ void GazeboSystem::registerJoints( hardware_info.joints.begin(), mimicked_joint_it); auto param_it = joint_info.parameters.find("multiplier"); if (param_it != joint_info.parameters.end()) { - mimic_joint.multiplier = std::stod(joint_info.parameters.at("multiplier")); + mimic_joint.multiplier = hardware_interface::stod(joint_info.parameters.at("multiplier")); } else { mimic_joint.multiplier = 1.0; } @@ -234,7 +235,7 @@ void GazeboSystem::registerJoints( auto get_initial_value = [this](const hardware_interface::InterfaceInfo & interface_info) { if (!interface_info.initial_value.empty()) { - double value = std::stod(interface_info.initial_value); + double value = hardware_interface::stod(interface_info.initial_value); RCLCPP_INFO(this->nh_->get_logger(), "\t\t\t found initial value: %f", value); return value; } else {