From be5167491f62f8f0d8729e7c4c5a24d51d219080 Mon Sep 17 00:00:00 2001 From: Wiktor Bajor <69388767+Wiktor-99@users.noreply.github.com> Date: Mon, 12 Feb 2024 16:31:22 +0100 Subject: [PATCH 1/2] Fix crashing due to an invalid parameter in the initial value. (#271) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero (cherry picked from commit cdae6b8a8f638d87146482e99bf76cf36530e5a6) # Conflicts: # gazebo_ros2_control/src/gazebo_system.cpp --- gazebo_ros2_control/src/gazebo_system.cpp | 21 ++++++++++++++++++++- 1 file changed, 20 insertions(+), 1 deletion(-) diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index a9292bd9..1bdd171f 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -205,14 +205,33 @@ void GazeboSystem::registerJoints( 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 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"); + } +>>>>>>> cdae6b8 (Fix crashing due to an invalid parameter in the initial value. (#271)) } + return initial_value; }; double initial_position = std::numeric_limits::quiet_NaN(); From afafb608a835e2301557939fe573fe65792d16e2 Mon Sep 17 00:00:00 2001 From: Alejandro Hernandez Cordero Date: Mon, 12 Feb 2024 22:34:44 +0100 Subject: [PATCH 2/2] Fixed crash Signed-off-by: Alejandro Hernandez Cordero --- gazebo_ros2_control/src/gazebo_system.cpp | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index 1bdd171f..2b76adc9 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -209,15 +209,8 @@ void GazeboSystem::registerJoints( [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( @@ -229,7 +222,6 @@ void GazeboSystem::registerJoints( << ". Initial value will be set to 0.0"); throw std::invalid_argument("Failed converting initial_value string"); } ->>>>>>> cdae6b8 (Fix crashing due to an invalid parameter in the initial value. (#271)) } return initial_value; };