Skip to content

Commit

Permalink
Use lexical casts (#260)
Browse files Browse the repository at this point in the history
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
christophfroehlich and ahcorde authored Jan 22, 2024
1 parent d44b879 commit cb9aa69
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions gazebo_ros2_control/src/gazebo_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
}
Expand All @@ -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 {
Expand Down

0 comments on commit cb9aa69

Please sign in to comment.