Skip to content

Commit

Permalink
Fix clang errors
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 3, 2024
1 parent e1d08a0 commit 03d321a
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 8 deletions.
4 changes: 2 additions & 2 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<size_t>(std::stoi(s));
}
else
{
Expand Down Expand Up @@ -885,7 +885,7 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
{
throw std::runtime_error("Mimic joint '" + name + "' not found in <ros2_control> tag");
}
return std::distance(hw_info.joints.begin(), it);
return static_cast<size_t>(std::distance(hw_info.joints.begin(), it));
};

MimicJoint mimic_joint;
Expand Down
14 changes: 8 additions & 6 deletions hardware_interface/src/mock_components/generic_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<size_t>::max();

// Initialize storage for standard interfaces
Expand Down Expand Up @@ -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<size_t>(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(),
Expand Down Expand Up @@ -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<size_t>(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;
Expand Down Expand Up @@ -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<size_t>(std::distance(info.joints.begin(), joint_it_found));

if (key == info.joints[joint_index].name + "/" + hardware_interface::HW_IF_POSITION)
{
Expand Down Expand Up @@ -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<size_t>(std::distance(interface_list.begin(), it));
interfaces.emplace_back(name, *it, &values[j][vector_index]);
return true;
}
Expand Down Expand Up @@ -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<size_t>(std::distance(interfaces.begin(), it));

// Check the initial_value param is used
if (!interface.initial_value.empty())
Expand Down

0 comments on commit 03d321a

Please sign in to comment.