Skip to content

Commit 8676ab0

Browse files
Fix integer literal for size_t (backport #1986) (#1987)
1 parent cdcacb5 commit 8676ab0

File tree

4 files changed

+4
-4
lines changed

4 files changed

+4
-4
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
@@ -1012,7 +1012,7 @@ TEST_F(JointStateBroadcasterTest, UpdatePerformanceTest)
10121012
}
10131013

10141014
RCLCPP_INFO(
1015-
state_broadcaster_->get_node()->get_logger(), "Number of test interfaces: %lu",
1015+
state_broadcaster_->get_node()->get_logger(), "Number of test interfaces: %zu",
10161016
test_interfaces_.size());
10171017

10181018
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
@@ -791,7 +791,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
791791
for (size_t i = 0; i < command_joint_names_.size(); i++)
792792
{
793793
RCLCPP_DEBUG(
794-
logger, "Command joint %lu: '%s' maps to joint %lu: '%s'.", i,
794+
logger, "Command joint %zu: '%s' maps to joint %zu: '%s'.", i,
795795
command_joint_names_[i].c_str(), map_cmd_to_joints_[i],
796796
params_.joints.at(map_cmd_to_joints_[i]).c_str());
797797
}

0 commit comments

Comments
 (0)