diff --git a/gz_ros2_control/src/gz_system.cpp b/gz_ros2_control/src/gz_system.cpp index 975ef631..bd30ea70 100644 --- a/gz_ros2_control/src/gz_system.cpp +++ b/gz_ros2_control/src/gz_system.cpp @@ -61,6 +61,8 @@ #endif #include +#include +#include struct jointData { @@ -299,7 +301,7 @@ bool GazeboSimSystem::initSim( 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; } @@ -336,7 +338,7 @@ bool GazeboSimSystem::initSim( 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 {