diff --git a/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.cpp b/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.cpp index 9cb6e4a474..6768000d13 100644 --- a/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.cpp @@ -134,7 +134,6 @@ void GetUrdfService::initialize() const auto start = full_urdf_string.find("urdf_string += substring.substr(0, substring.find(JOINT_ELEMENT_CLOSING) + JOINT_ELEMENT_CLOSING.size()); - RCLCPP_ERROR(getLogger(), "%s", joint_name.c_str()); // If parent link model is not part of the joint group, add it const auto parent_link_element = subgroup->getJointModel(joint_name)->getParentLinkModel()->getName();