From 8400d190d80d8f2a31061c6fdadd18d7fe54fa3c Mon Sep 17 00:00:00 2001 From: Cx330 <1487537121@qq.com> Date: Wed, 2 Jul 2025 15:54:13 +0800 Subject: [PATCH] =?UTF-8?q?=E8=B0=83=E6=95=B4?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/Service/scripts/Subscriber_Client_S.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/Service/scripts/Subscriber_Client_S.py b/src/Service/scripts/Subscriber_Client_S.py index 3979923..2676abc 100644 --- a/src/Service/scripts/Subscriber_Client_S.py +++ b/src/Service/scripts/Subscriber_Client_S.py @@ -110,17 +110,17 @@ def position_callback(msg): res = fft_client(data_x=noisy_x_history[-FFT_WINDOW_SIZE:], data_y=noisy_y_history[-FFT_WINDOW_SIZE:], window_size=FFT_WINDOW_SIZE) - rospy.loginfo("FFT computed successfully") + rospy.loginfo("FFT计算成功") current_x_magnitudes[:] = res.magnitude_x current_y_magnitudes[:] = res.magnitude_y except rospy.ServiceException as e: - rospy.logerr("Failed to call FFT service: %s" % e) + rospy.logerr("FFT计算失败: %s" % e) # 判断频谱,生成频谱图 if current_x_magnitudes and current_y_magnitudes: x_spectrum = Marker() x_spectrum.header = msg.header - x_spectrum.ns = "坐标x频谱" + x_spectrum.ns = "x_spectrum" x_spectrum.id = 2 x_spectrum.type = Marker.CUBE_LIST x_spectrum.action = Marker.ADD @@ -132,7 +132,7 @@ def position_callback(msg): y_spectrum = Marker() y_spectrum.header = msg.header - y_spectrum.ns = "坐标y频谱" + y_spectrum.ns = "y_spectrum" y_spectrum.id = 3 y_spectrum.type = Marker.CUBE_LIST y_spectrum.action = Marker.ADD