From dd0d740f65080b09e34f8ab29c343bbd41cb19be Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 13 Feb 2024 12:17:39 +0100 Subject: [PATCH] Fix crashing due to an invalid parameter in the initial value (#233) Signed-off-by: Alejandro Hernandez Cordero (cherry picked from commit a3beadb014f62e0808033de2c5ad84e2428c36e9) # Conflicts: # ign_ros2_control/src/ign_system.cpp --- ign_ros2_control/src/ign_system.cpp | 21 ++++++++++++++++++++- 1 file changed, 20 insertions(+), 1 deletion(-) diff --git a/ign_ros2_control/src/ign_system.cpp b/ign_ros2_control/src/ign_system.cpp index ac6d4161..696bd59f 100644 --- a/ign_ros2_control/src/ign_system.cpp +++ b/ign_ros2_control/src/ign_system.cpp @@ -284,14 +284,33 @@ bool IgnitionSystem::initSim( RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\tState:"); - auto get_initial_value = [this](const hardware_interface::InterfaceInfo & interface_info) { + auto get_initial_value = + [this, joint_name](const hardware_interface::InterfaceInfo & interface_info) { + double initial_value{0.0}; if (!interface_info.initial_value.empty()) { +<<<<<<< HEAD:ign_ros2_control/src/ign_system.cpp 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); + RCLCPP_INFO(this->nh_->get_logger(), "\t\t\t found initial value: %f", initial_value); + } catch (std::invalid_argument &) { + RCLCPP_ERROR_STREAM( + this->nh_->get_logger(), + "Failed converting initial_value string to real number for the joint " + << joint_name + << " and state interface " << interface_info.name + << ". Actual value of parameter: " << interface_info.initial_value + << ". 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)):gz_ros2_control/src/gz_system.cpp } + return initial_value; }; double initial_position = std::numeric_limits::quiet_NaN();