Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix crashing due to an invalid parameter in the initial value. #271

Merged
Merged
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 16 additions & 6 deletions gazebo_ros2_control/src/gazebo_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,14 +233,24 @@ 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()) {
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 {
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");
Wiktor-99 marked this conversation as resolved.
Show resolved Hide resolved
}
}
return initial_value;
};

double initial_position = std::numeric_limits<double>::quiet_NaN();
Expand Down
Loading