From 5cadcf5ba7cdb6f8f6eb74324cd129d24387434e Mon Sep 17 00:00:00 2001 From: mithun chakladar Date: Wed, 1 Apr 2026 19:57:59 +0530 Subject: [PATCH 1/2] fix(joint_state_broadcaster): suppress confusing warning for standard interfaces When using standard interfaces like 'velocity' with the default mapping, the warning 'Mapping from velocity to interface velocity will not be done' is confusing because no mapping is actually needed. This change only shows the warning when there's a custom mapping being ignored (i.e., when interface name differs from the JointState field name). Fixes #2261 --- .../src/joint_state_broadcaster.cpp | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/joint_state_broadcaster/src/joint_state_broadcaster.cpp b/joint_state_broadcaster/src/joint_state_broadcaster.cpp index b24152b0d8..36bde0c9d5 100644 --- a/joint_state_broadcaster/src/joint_state_broadcaster.cpp +++ b/joint_state_broadcaster/src/joint_state_broadcaster.cpp @@ -124,11 +124,16 @@ controller_interface::CallbackReturn JointStateBroadcaster::on_configure( params_.interfaces.end()) { map_interface_to_joint_state_[interface] = interface; - RCLCPP_WARN( - get_node()->get_logger(), - "Mapping from '%s' to interface '%s' will not be done, because '%s' is defined " - "in 'interface' parameter.", - interface_to_map.c_str(), interface.c_str(), interface.c_str()); + // Only warn if there's a custom mapping being ignored (interface != interface_to_map) + // When they're equal (e.g., both "velocity"), it's the standard case and no warning is needed + if (interface != interface_to_map) + { + RCLCPP_WARN( + get_node()->get_logger(), + "Mapping from '%s' to interface '%s' will not be done, because '%s' is defined " + "in 'interface' parameter.", + interface_to_map.c_str(), interface.c_str(), interface.c_str()); + } } else { From da60c193bc73ec19b2be0e73c1c00d449fce7595 Mon Sep 17 00:00:00 2001 From: Mithun Chakladar <129988983+greencookie-afk@users.noreply.github.com> Date: Fri, 3 Apr 2026 13:14:38 +0530 Subject: [PATCH 2/2] Update joint_state_broadcaster/src/joint_state_broadcaster.cpp Co-authored-by: Surya! --- joint_state_broadcaster/src/joint_state_broadcaster.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/joint_state_broadcaster/src/joint_state_broadcaster.cpp b/joint_state_broadcaster/src/joint_state_broadcaster.cpp index 36bde0c9d5..fd0dd16800 100644 --- a/joint_state_broadcaster/src/joint_state_broadcaster.cpp +++ b/joint_state_broadcaster/src/joint_state_broadcaster.cpp @@ -124,8 +124,7 @@ controller_interface::CallbackReturn JointStateBroadcaster::on_configure( params_.interfaces.end()) { map_interface_to_joint_state_[interface] = interface; - // Only warn if there's a custom mapping being ignored (interface != interface_to_map) - // When they're equal (e.g., both "velocity"), it's the standard case and no warning is needed + // Warn if custom mapping is being ignored if (interface != interface_to_map) { RCLCPP_WARN(