编写监听器 (Python)
目标: 了解如何使用 tf2 访问框架转换。
教程级别: 中级
时间: 10 分钟
背景
在之前的教程中,我们创建了一个 tf2 广播器,用于将乌龟的姿势发布到 tf2。
在本教程中,我们将创建一个 tf2 监听器以开始使用 tf2。
先决条件
本教程假设您已完成 tf2 静态广播器教程 (Python) 和 tf2 广播器教程 (Python)。
在之前的教程中,我们创建了一个 learning_tf2_py
包,我们将从这里继续工作。
任务
1 编写监听器节点
让我们首先创建源文件。 转到我们在上一个教程中创建的“learning_tf2_py”包。 在“src/learning_tf2_py/learning_tf2_py”目录中,输入以下命令下载示例监听器代码:
wget https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener.py
wget https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener.py
In a Windows command line prompt:
curl -sk https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener.py -o turtle_tf2_listener.py
Or in powershell:
curl https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener.py -o turtle_tf2_listener.py
现在使用您喜欢的文本编辑器打开名为“turtle_tf2_listener.py”的文件。
import math
from geometry_msgs.msg import Twist
import rclpy
from rclpy.node import Node
from tf2_ros import TransformException
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener
from turtlesim.srv import Spawn
class FrameListener(Node):
def __init__(self):
super().__init__('turtle_tf2_frame_listener')
# Declare and acquire `target_frame` parameter
self.target_frame = self.declare_parameter(
'target_frame', 'turtle1').get_parameter_value().string_value
self.tf_buffer = Buffer()
self.tf_listener = TransformListener(self.tf_buffer, self)
# Create a client to spawn a turtle
self.spawner = self.create_client(Spawn, 'spawn')
# Boolean values to store the information
# if the service for spawning turtle is available
self.turtle_spawning_service_ready = False
# if the turtle was successfully spawned
self.turtle_spawned = False
# Create turtle2 velocity publisher
self.publisher = self.create_publisher(Twist, 'turtle2/cmd_vel', 1)
# Call on_timer function every second
self.timer = self.create_timer(1.0, self.on_timer)
def on_timer(self):
# Store frame names in variables that will be used to
# compute transformations
from_frame_rel = self.target_frame
to_frame_rel = 'turtle2'
if self.turtle_spawning_service_ready:
if self.turtle_spawned:
# Look up for the transformation between target_frame and turtle2 frames
# and send velocity commands for turtle2 to reach target_frame
try:
t = self.tf_buffer.lookup_transform(
to_frame_rel,
from_frame_rel,
rclpy.time.Time())
except TransformException as ex:
self.get_logger().info(
f'Could not transform {to_frame_rel} to {from_frame_rel}: {ex}')
return
msg = Twist()
scale_rotation_rate = 1.0
msg.angular.z = scale_rotation_rate * math.atan2(
t.transform.translation.y,
t.transform.translation.x)
scale_forward_speed = 0.5
msg.linear.x = scale_forward_speed * math.sqrt(
t.transform.translation.x ** 2 +
t.transform.translation.y ** 2)
self.publisher.publish(msg)
else:
if self.result.done():
self.get_logger().info(
f'Successfully spawned {self.result.result().name}')
self.turtle_spawned = True
else:
self.get_logger().info('Spawn is not finished')
else:
if self.spawner.service_is_ready():
# Initialize request with turtle name and coordinates
# Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
request = Spawn.Request()
request.name = 'turtle2'
request.x = float(4)
request.y = float(2)
request.theta = float(0)
# Call request
self.result = self.spawner.call_async(request)
self.turtle_spawning_service_ready = True
else:
# Check if the service is ready
self.get_logger().info('Service is not ready')
def main():
rclpy.init()
node = FrameListener()
try:
rclpy.spin(node)
except KeyboardInterrupt:
pass
rclpy.shutdown()
1.1 检查代码
要了解生成海龟背后的服务如何工作,请参阅:doc:`编写简单的服务和客户端(Python)<../../Beginner-Client-Libraries/Writing-A-Simple-Py-Service-And-Client>`教程。
现在,让我们看一下与获取框架转换相关的代码。
tf2_ros
包提供了 TransformListener
的实现,以帮助简化接收转换的任务。
from tf2_ros.transform_listener import TransformListener
在这里,我们创建一个 TransformListener
对象。
一旦创建了侦听器,它就会开始通过网络接收 tf2 转换,并缓冲它们长达 10 秒。
self.tf_listener = TransformListener(self.tf_buffer, self)
最后,我们向侦听器查询特定的转换。 我们使用以下参数调用“lookup_transform”方法:
目标帧
源帧
我们想要转换的时间
提供“rclpy.time.Time()”只会让我们获得最新的可用转换。 所有这些都包装在 try-except 块中以处理可能的异常。
t = self.tf_buffer.lookup_transform(
to_frame_rel,
from_frame_rel,
rclpy.time.Time())
1.2 添加入口点
要允许“ros2 run”命令运行您的节点,您必须将入口点添加到“setup.py”(位于“src/learning_tf2_py”目录中)。
在“’console_scripts’:”括号之间添加以下行:
'turtle_tf2_listener = learning_tf2_py.turtle_tf2_listener:main',
2 更新启动文件
使用文本编辑器打开“src/learning_tf2_py/launch”目录中名为“turtle_tf2_demo.launch.py”的启动文件,向启动描述中添加两个新节点,添加启动参数,然后添加导入。 生成的文件应如下所示:
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='turtlesim',
executable='turtlesim_node',
name='sim'
),
Node(
package='learning_tf2_py',
executable='turtle_tf2_broadcaster',
name='broadcaster1',
parameters=[
{'turtlename': 'turtle1'}
]
),
DeclareLaunchArgument(
'target_frame', default_value='turtle1',
description='Target frame name.'
),
Node(
package='learning_tf2_py',
executable='turtle_tf2_broadcaster',
name='broadcaster2',
parameters=[
{'turtlename': 'turtle2'}
]
),
Node(
package='learning_tf2_py',
executable='turtle_tf2_listener',
name='listener',
parameters=[
{'target_frame': LaunchConfiguration('target_frame')}
]
),
])
这将声明一个“target_frame”启动参数,为我们将生成的第二只海龟启动一个广播器,并为订阅这些转换的监听器启动一个监听器。
3 构建
在工作区的根目录中运行“rosdep”以检查是否缺少依赖项。
rosdep install -i --from-path src --rosdistro rolling -y
rosdep only runs on Linux, so you will need to install geometry_msgs
and turtlesim
dependencies yourself
rosdep only runs on Linux, so you will need to install geometry_msgs
and turtlesim
dependencies yourself
仍然在工作区的根目录中,构建您的包:
colcon build --packages-select learning_tf2_py
colcon build --packages-select learning_tf2_py
colcon build --merge-install --packages-select learning_tf2_py
打开一个新终端,导航到工作区的根目录,然后获取安装文件:
. install/setup.bash
. install/setup.bash
# CMD
call install\setup.bat
# Powershell
.\install\setup.ps1
4 运行
现在您可以开始完整的海龟演示了:
ros2 launch learning_tf2_py turtle_tf2_demo.launch.py
您应该看到有两只海龟的海龟模拟器。 在第二个终端窗口中输入以下命令:
ros2 run turtlesim turtle_teleop_key
要查看是否有效,只需使用箭头键绕着第一只海龟行驶(确保您的终端窗口处于活动状态,而不是模拟器窗口),您就会看到第二只海龟跟在第一只海龟后面!
摘要
在本教程中,您学习了如何使用 tf2 来访问框架转换。 您还完成了编写自己的 turtlesim 演示,该演示是您在 Introduction to tf2 教程中首次尝试的。