diff --git a/templates/ros2_control/controller/dummy_chainable_controller.cpp b/templates/ros2_control/controller/dummy_chainable_controller.cpp index abc32a0b..9a66450f 100644 --- a/templates/ros2_control/controller/dummy_chainable_controller.cpp +++ b/templates/ros2_control/controller/dummy_chainable_controller.cpp @@ -83,7 +83,7 @@ controller_interface::CallbackReturn DummyClassName::on_configure( if (params_.joints.size() != state_joints_.size()) { RCLCPP_FATAL( get_node()->get_logger(), - "Size of 'joints' (%d) and 'state_joints' (%d) parameters has to be the same!", + "Size of 'joints' (%zu) and 'state_joints' (%zu) parameters has to be the same!", params_.joints.size(), state_joints_.size()); return CallbackReturn::FAILURE; } diff --git a/templates/ros2_control/controller/dummy_controller.cpp b/templates/ros2_control/controller/dummy_controller.cpp index 6b91f875..66ecdcd0 100644 --- a/templates/ros2_control/controller/dummy_controller.cpp +++ b/templates/ros2_control/controller/dummy_controller.cpp @@ -83,7 +83,7 @@ controller_interface::CallbackReturn DummyClassName::on_configure( if (params_.joints.size() != state_joints_.size()) { RCLCPP_FATAL( get_node()->get_logger(), - "Size of 'joints' (%d) and 'state_joints' (%d) parameters has to be the same!", + "Size of 'joints' (%zu) and 'state_joints' (%zu) parameters has to be the same!", params_.joints.size(), state_joints_.size()); return CallbackReturn::FAILURE; }