Skip to content

Commit 63bae1b

Browse files
Fix integer literal for size_t (#1986)
1 parent a496412 commit 63bae1b

File tree

5 files changed

+5
-5
lines changed

5 files changed

+5
-5
lines changed

gpio_controllers/src/gpio_command_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -313,7 +313,7 @@ bool GpioCommandController::check_if_configured_interfaces_matches_received(
313313
if (!(configured_interfaces.size() == interfaces_from_params.size()))
314314
{
315315
RCLCPP_ERROR(
316-
get_node()->get_logger(), "Expected %ld interfaces, got %ld", interfaces_from_params.size(),
316+
get_node()->get_logger(), "Expected %zu interfaces, got %zu", interfaces_from_params.size(),
317317
configured_interfaces.size());
318318
for (const auto & interface : interfaces_from_params)
319319
{

joint_state_broadcaster/test/test_joint_state_broadcaster.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1032,7 +1032,7 @@ TEST_F(JointStateBroadcasterTest, UpdatePerformanceTest)
10321032
}
10331033

10341034
RCLCPP_INFO(
1035-
state_broadcaster_->get_node()->get_logger(), "Number of test interfaces: %lu",
1035+
state_broadcaster_->get_node()->get_logger(), "Number of test interfaces: %zu",
10361036
test_interfaces_.size());
10371037

10381038
std::vector<LoanedStateInterface> state_interfaces;

joint_trajectory_controller/include/joint_trajectory_controller/tolerances.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -316,7 +316,7 @@ inline bool check_state_tolerance_per_joint(
316316
if (show_errors)
317317
{
318318
const auto logger = rclcpp::get_logger("tolerances");
319-
RCLCPP_ERROR(logger, "State tolerances failed for joint %lu:", joint_idx);
319+
RCLCPP_ERROR(logger, "State tolerances failed for joint %zu:", joint_idx);
320320

321321
if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
322322
{

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -813,7 +813,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
813813
for (size_t i = 0; i < command_joint_names_.size(); i++)
814814
{
815815
RCLCPP_DEBUG(
816-
logger, "Command joint %lu: '%s' maps to joint %lu: '%s'.", i,
816+
logger, "Command joint %zu: '%s' maps to joint %zu: '%s'.", i,
817817
command_joint_names_[i].c_str(), map_cmd_to_joints_[i],
818818
params_.joints.at(map_cmd_to_joints_[i]).c_str());
819819
}

motion_primitives_controllers/src/motion_primitives_base_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ void MotionPrimitivesBaseController::reset_command_interfaces()
120120
{
121121
if (!command_interfaces_[i].set_value(std::numeric_limits<double>::quiet_NaN()))
122122
{
123-
RCLCPP_ERROR(get_node()->get_logger(), "Failed to reset command interface %ld", i);
123+
RCLCPP_ERROR(get_node()->get_logger(), "Failed to reset command interface %zu", i);
124124
}
125125
}
126126
}

0 commit comments

Comments
 (0)