diff --git a/hardware_interface/src/component_parser.cpp b/hardware_interface/src/component_parser.cpp index 0f186531e9..9125e40850 100644 --- a/hardware_interface/src/component_parser.cpp +++ b/hardware_interface/src/component_parser.cpp @@ -186,7 +186,7 @@ std::size_t parse_size_attribute(const tinyxml2::XMLElement * elem) std::regex int_re("[1-9][0-9]*"); if (std::regex_match(s, int_re)) { - size = std::stoi(s); + size = static_cast(std::stoi(s)); } else { @@ -885,7 +885,7 @@ std::vector parse_control_resources_from_urdf(const std::string & { throw std::runtime_error("Mimic joint '" + name + "' not found in tag"); } - return std::distance(hw_info.joints.begin(), it); + return static_cast(std::distance(hw_info.joints.begin(), it)); }; MimicJoint mimic_joint; diff --git a/hardware_interface/src/mock_components/generic_system.cpp b/hardware_interface/src/mock_components/generic_system.cpp index 8b46d21f4d..2b1d635c97 100644 --- a/hardware_interface/src/mock_components/generic_system.cpp +++ b/hardware_interface/src/mock_components/generic_system.cpp @@ -117,7 +117,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i custom_interface_with_following_offset_ = it->second; } } - // it's extremely improbable that std::distance results int this value - therefore default + // it's extremely improbable that std::distance results in this value - therefore default index_custom_interface_with_following_offset_ = std::numeric_limits::max(); // Initialize storage for standard interfaces @@ -157,7 +157,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i if (if_it != other_interfaces_.end()) { index_custom_interface_with_following_offset_ = - std::distance(other_interfaces_.begin(), if_it); + static_cast(std::distance(other_interfaces_.begin(), if_it)); RCLCPP_INFO( get_logger(), "Custom interface with following offset '%s' found at index: %zu.", custom_interface_with_following_offset_.c_str(), @@ -348,7 +348,8 @@ return_type GenericSystem::prepare_command_mode_switch( if (joint_it_found != info.joints.end()) { - const size_t joint_index = std::distance(info.joints.begin(), joint_it_found); + const size_t joint_index = + static_cast(std::distance(info.joints.begin(), joint_it_found)); if (joint_found_in_x_requests_[joint_index] == 0) { joint_found_in_x_requests_[joint_index] = FOUND_ONCE_FLAG; @@ -436,7 +437,8 @@ return_type GenericSystem::perform_command_mode_switch( if (joint_it_found != info.joints.end()) { - const size_t joint_index = std::distance(info.joints.begin(), joint_it_found); + const size_t joint_index = + static_cast(std::distance(info.joints.begin(), joint_it_found)); if (key == info.joints[joint_index].name + "/" + hardware_interface::HW_IF_POSITION) { @@ -630,7 +632,7 @@ bool GenericSystem::get_interface( auto it = std::find(interface_list.begin(), interface_list.end(), interface_name); if (it != interface_list.end()) { - auto j = std::distance(interface_list.begin(), it); + auto j = static_cast(std::distance(interface_list.begin(), it)); interfaces.emplace_back(name, *it, &values[j][vector_index]); return true; } @@ -662,7 +664,7 @@ void GenericSystem::initialize_storage_vectors( // If interface name is found in the interfaces list if (it != interfaces.end()) { - auto index = std::distance(interfaces.begin(), it); + auto index = static_cast(std::distance(interfaces.begin(), it)); // Check the initial_value param is used if (!interface.initial_value.empty())