From 528306174cb50be48ef8007d41494088e75c9c45 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 13 Feb 2024 12:33:10 +0100 Subject: [PATCH] Fixed merge MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- gz_ros2_control/src/gz_system.cpp | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/gz_ros2_control/src/gz_system.cpp b/gz_ros2_control/src/gz_system.cpp index 4f97b04a..ecbebf7c 100644 --- a/gz_ros2_control/src/gz_system.cpp +++ b/gz_ros2_control/src/gz_system.cpp @@ -310,15 +310,8 @@ bool GazeboSimSystem::initSim( [this, joint_name](const hardware_interface::InterfaceInfo & interface_info) { double initial_value{0.0}; if (!interface_info.initial_value.empty()) { -<<<<<<< HEAD - double value = std::stod(interface_info.initial_value); - RCLCPP_INFO(this->nh_->get_logger(), "\t\t\t found initial value: %f", value); - return value; - } else { - return 0.0; -======= try { - initial_value = hardware_interface::stod(interface_info.initial_value); + initial_value = std::stod(interface_info.initial_value); RCLCPP_INFO(this->nh_->get_logger(), "\t\t\t found initial value: %f", initial_value); } catch (std::invalid_argument &) { RCLCPP_ERROR_STREAM( @@ -330,7 +323,6 @@ bool GazeboSimSystem::initSim( << ". Initial value will be set to 0.0"); throw std::invalid_argument("Failed converting initial_value string"); } ->>>>>>> a3beadb (Fix crashing due to an invalid parameter in the initial value (#233)) } return initial_value; };