在ros中动态调整雷达,线激光雷达等设备的静态坐标关系
在ros中动态调整雷达,线激光雷达等设备的静态坐标关系
摘要:本文介绍了一个ROS动态坐标变换工具(dynamic_tf_keyboard.py),用于实时调整雷达等设备的安装位置和姿态。该工具通过键盘控制(WASD调整XYZ位置,IJKLUO调整RPY姿态)来修改坐标变换,并实时发布TF变换关系。程序采用tf2_ros发布静态变换,支持将变换参数直接用于launch文件配置。该方案为设备外参标定提供了交互式调试手段,适用于线激光雷达等传感器的安装位置校准。
实现类似 rosrun tf2_ros static_transform_publisher...
的功能
依赖:
确保安装了 ros-noetic-tf2-ros
, geometry_msgs
, pynput
:
ynamic_tf_keyboard.py示例代码:
#!/usr/bin/env python3
import rospy
import tf2_ros
import geometry_msgs.msg
from tf.transformations import quaternion_from_euler
from pynput import keyboard'''
苏凯 2025 6 13
动态调整线激光的安装坐标(标定外参)
chmod +x dynamic_tf_keyboard.py
rosrun ydlidar_ros_driver dynamic_tf_keyboard.py🧪 示例控制:W/S:X 增/减;A/D:Y 增/减;R/F:Z 增/减;I/K:Roll 增/减;J/L:Pitch 增/减;U/O:Yaw 增/减;控制台更改坐标 xyz rzryrx :rosrun tf2_ros static_transform_publisher 0.1973 0.152 0.75841 0.83733 0.52333 0.087222 base_link laser_line_left在launch文件中启动坐标 xyz rzryrx <node pkg="tf2_ros" type="static_transform_publisher" name="base_link_to_laser4"args="0.1973 0.152 0.75841 2.4033 -0.087222 2.10 /base_link /laser_line_left" />'''# 初始变换参数
x, y, z = 0.1973, 0.152, 0.75841
roll, pitch, yaw = 1.57, 0.0, 1.57
step_pos = 0.01
step_rot = 0.05def publish_tf():global x, y, z, roll, pitch, yawbr = tf2_ros.TransformBroadcaster()rate = rospy.Rate(10)while not rospy.is_shutdown():t = geometry_msgs.msg.TransformStamped()t.header.stamp = rospy.Time.now()t.header.frame_id = "base_link"#填入相对坐标t.child_frame_id = "laser_line_left"t.transform.translation.x = xt.transform.translation.y = yt.transform.translation.z = zq = quaternion_from_euler(roll, pitch, yaw)t.transform.rotation.x = q[0]t.transform.rotation.y = q[1]t.transform.rotation.z = q[2]t.transform.rotation.w = q[3]br.sendTransform(t)rate.sleep()def on_press(key):global x, y, z, roll, pitch, yawtry:if key.char == 'w': x += step_posif key.char == 's': x -= step_posif key.char == 'a': y += step_posif key.char == 'd': y -= step_posif key.char == 'r': z += step_posif key.char == 'f': z -= step_posif key.char == 'i': roll += step_rotif key.char == 'k': roll -= step_rotif key.char == 'j': pitch += step_rotif key.char == 'l': pitch -= step_rotif key.char == 'u': yaw += step_rotif key.char == 'o': yaw -= step_rotprint(f"[TF] x={x:.3f}, y={y:.3f}, z={z:.3f}, roll={roll:.2f}, pitch={pitch:.2f}, yaw={yaw:.2f}")except AttributeError:passif __name__ == '__main__':rospy.init_node('dynamic_tf_publisher')print("控制指令:\n""位置:WASD控制X/Y,R/F控制Z\n""姿态:I/K=roll,J/L=pitch,U/O=yaw\n")from threading import ThreadThread(target=publish_tf).start()with keyboard.Listener(on_press=on_press) as listener:listener.join()