Skip to content

Commit

Permalink
Use own implementation of stod() (#220)
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 24, 2024
1 parent 42a34da commit fc1543f
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions gz_ros2_control/src/gz_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@
#endif

#include <hardware_interface/hardware_info.hpp>
#include <hardware_interface/lexical_casts.hpp>
#include <hardware_interface/types/hardware_interface_type_values.hpp>

struct jointData
{
Expand Down Expand Up @@ -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;
}
Expand Down Expand Up @@ -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 {
Expand Down

0 comments on commit fc1543f

Please sign in to comment.