编写tf2广播器 (Python) [待校准@8660]

Goal目标: Learn了解如何向tf2广播机器人的状态。 [待校准@8622]

Tutorial教程级别: Intermediate中级 [待校准@6713]

时间: 15分钟 [Alyssa@6755]

背景

在接下来的两个教程中,我们将编写代码来重现 Introduction to tf2 教程中的例程。之后,以下教程将重点放在使用更高级的tf2功能扩展例程上,包括在转换查找和时间穿梭中使用超时。 [待校准@8623]

先决条件

本教程假设您具有ROS 2的工作知识,并且您已经完成了 Introduction to tf2 tutorial. In previous tutorials, you learned how to create a workspace and create a package. You also have created the learning_tf2_py package ,这是我们将继续工作的地方。 [待校准@8661]

任务

1写入广播器节点 [待校准@8625]

让我们先创建源文件。转到我们在上一教程中创建的 learning_tf2_py 包。在 src/learning_tf2_py/learning_tf2_py 目录中,通过输入以下命令下载示例广播器代码: [待校准@8662]

wget https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_py/turtle_tf2_py/turtle_tf2_broadcaster.py

使用您喜欢的文本编辑器打开文件。 [待校准@8591]

from geometry_msgs.msg import TransformStamped

import rclpy
from rclpy.node import Node

from tf2_ros import TransformBroadcaster

import tf_transformations

from turtlesim.msg import Pose


class FramePublisher(Node):

    def __init__(self):
        super().__init__('turtle_tf2_frame_publisher')

        # Declare and acquire `turtlename` parameter
        self.declare_parameter('turtlename', 'turtle')
        self.turtlename = self.get_parameter(
            'turtlename').get_parameter_value().string_value

        # Initialize the transform broadcaster
        self.br = TransformBroadcaster(self)

        # Subscribe to a turtle{1}{2}/pose topic and call handle_turtle_pose
        # callback function on each message
        self.subscription = self.create_subscription(
            Pose,
            f'/{self.turtlename}/pose',
            self.handle_turtle_pose,
            1)
        self.subscription

    def handle_turtle_pose(self, msg):
        t = TransformStamped()

        # Read message content and assign it to
        # corresponding tf variables
        t.header.stamp = self.get_clock().now().to_msg()
        t.header.frame_id = 'world'
        t.child_frame_id = self.turtlename

        # Turtle only exists in 2D, thus we get x and y translation
        # coordinates from the message and set the z coordinate to 0
        t.transform.translation.x = msg.x
        t.transform.translation.y = msg.y
        t.transform.translation.z = 0.0

        # For the same reason, turtle can only rotate around one axis
        # and this why we set rotation in x and y to 0 and obtain
        # rotation in z axis from the message
        q = tf_transformations.quaternion_from_euler(0, 0, msg.theta)
        t.transform.rotation.x = q[0]
        t.transform.rotation.y = q[1]
        t.transform.rotation.z = q[2]
        t.transform.rotation.w = q[3]

        # Send the transformation
        self.br.sendTransform(t)


def main():
    rclpy.init()
    node = FramePublisher()
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass

    rclpy.shutdown()

1.1检查代码 [待校准@8367]

现在,让我们来看看与将海龟姿势发布到tf2相关的代码。首先,我们定义并获得一个单一参数 turtlename ,它指定了海龟的名字,例如 turtle1turtle2[待校准@8627]

self.declare_parameter('turtlename', 'turtle')
self.turtlename = self.get_parameter(
    'turtlename').get_parameter_value().string_value

之后,节点订阅话题 turtleX/pose ,并对每一条传入的消息运行功能 handle_turtle_pose[待校准@8628]

self .subscription = self.create_subscription(
    Pose,
    f'/{self.turtlename}/pose',
    self.handle_turtle_pose,
    1)

现在,我们创建一个 TransformStamped 对象并为其提供适当的元数据。 [待校准@8629]

  1. 我们需要给正在发布的转换一个时间戳,我们只需通过调用 self.get_clock().now() 来标记当前时间。这将返回 Node 使用的当前时间。 [待校准@8663]

  2. 然后,我们需要设置正在创建的链接的父帧的名称,在本例中为 world[待校准@8631]

  3. 最后,我们需要设置我们正在创建的链接的子节点的名称,在这种情况下,这是turtle本身的名称。 [待校准@8632]

海龟姿势信息的处理函数广播海龟的平移和旋转,并将其发布为从帧 world 到帧 turtleX 的转换。 [待校准@8633]

t = TransformStamped()

# Read message content and assign it to
# corresponding tf variables
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'world'
t.child_frame_id = self.turtlename

在这里,我们将信息从3D海龟姿势复制到3D变换中。 [待校准@8634]

# Turtle only exists in 2D, thus we get x and y translation
# coordinates from the message and set the z coordinate to 0
t.transform.translation.x = msg.x
t.transform.translation.y = msg.y
t.transform.translation.z = 0.0

# For the same reason, turtle can only rotate around one axis
# and this why we set rotation in x and y to 0 and obtain
# rotation in z axis from the message
q = tf_transformations.quaternion_from_euler(0, 0, msg.theta)
t.transform.rotation.x = q[0]
t.transform.rotation.y = q[1]
t.transform.rotation.z = q[2]
t.transform.rotation.w = q[3]

最后我们采取变换建构并把它传递给 sendTransform 方法 TransformBroadcaster 负责广播。 [待校准@8635]

# Send the transformation
self.br.sendTransform(t)

注解

您也可以通过实例化 tf2_ros.StaticTransformBroadcaster 而不是 tf2_ros.TransformBroadcaster 来发布具有相同模式的静态变换。静态转换将在 /tf_static 话题上发布,并且仅在需要时发送,而不是周期调用y。更多详情见 here[待校准@8664]

1.2添加入口点 [待校准@8665]

要允许 ros2 run 命令运行您的节点,您必须将入口点添加到 setup.py (位于 src/learning_tf2_py 目录中)。 [待校准@8666]

最后,在 “'console_scripts':” 括号中添加以下一行: [待校准@8667]

'turtle_tf2_broadcaster = learning_tf2_py.turtle_tf2_broadcaster:main',

2写launch文件 [待校准@7572]

现在为此例程创建一个launch文件。使用文本编辑器,在 “ launch ” 文件夹中创建一个调用ed turtle_tf2_demo.launch.py 的新文件,并添加以下几行: [待校准@8641]

from launch import LaunchDescription
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'}
            ]
        ),
    ])

2.1检查代码 [待校准@8007]

首先,我们从 launchlaunch_ros 包中导入所需模块。应该注意的是, launch 是一个通用的launch帧工作 (不是特定于ROS 2), launch_ros 有特定于ROS 2的东西,比如我们在这里导入的节点。 [待校准@8642]

from launch import LaunchDescription
from launch_ros.actions import Node

现在,我们运行启动turtlesim仿真的节点,并使用我们的 turtle_tf2_broadcaster 节点向tf2广播 turtle1 状态。 [待校准@8643]

Node(
    package='turtlesim',
    executable='turtlesim_node',
    name='sim'
),
Node(
    package='learning_tf2_py',
    executable='turtle_tf2_broadcaster',
    name='broadcaster1',
    parameters=[
        {'turtlename': 'turtle1'}
    ]
),

2.2添加依赖项 [待校准@8644]

导航一层回到 src/learning_tf2_py 目录, setup.pysetup.cfgpackage.xml 文件就在那里。 [待校准@8668]

用文本编辑器打开 package.xml 。添加以下与您的launch文件的导入语句相对应的依赖项: [待校准@8645]

<exec_depend>launch</exec_depend>
<exec_depend>launch_ros</exec_depend>

这声明了在执行其代码时所需的额外 launchlaunch_ros 依赖关系。 [待校准@8646]

确保保存文件。 [待校准@8647]

2.3更新安装程序 [待校准@8669]

重新打开 setup.py 并添加行,以便安装 launch/ 文件夹中的launch文件。 data_files 油田现在应该是这样的: [待校准@8670]

data_files=[
    ...
    (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*.launch.py'))),
],

同时在文件顶部添加适当的导入: [待校准@8671]

import os
from glob import glob

您可以了解更多关于在 this tutorial 中创建launch文件的信息。 [待校准@8650]

3构建和运行 [待校准@8033]

在工作区的根目录下运行 rosdep ,以检查是否缺少依赖项。 [待校准@8651]

rosdep install -i --from-path src --rosdistro foxy -y

构建更新的包,并源文件安装文件。 [待校准@8653]

现在运行将启动turtlesim仿真节点和 turtle_tf2_broadcaster 节点的launch文件: [待校准@8654]

ros2 launch learning_tf2_py turtle_tf2_demo.launch.py

在第二个终端窗口中,键入以下命令: [待校准@8442]

ros2 run turtlesim turtle_teleop_key

现在,您将看到turtlesim仿真已经从您可以控制的一只乌龟开始。 [待校准@8655]

../../_images/turtlesim_broadcast.png

现在,使用 tf2_echo 工具检查海龟姿势是否真的被广播到tf2: [待校准@8656]

ros2 run tf2_ros tf2_echo world turtle1

这应该会告诉你第一只乌龟的姿势。使用箭头键绕着海龟行驶 (确保你的 turtle_teleop_key 终端窗口处于活动状态,而不是你的模拟器窗口)。在控制台输出中,您将看到类似的内容: [待校准@8657]

At time 1625137663.912474878
- Translation: [5.276, 7.930, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.934, -0.357]
At time 1625137664.950813527
- Translation: [3.750, 6.563, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.934, -0.357]
At time 1625137665.906280726
- Translation: [2.320, 5.282, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.934, -0.357]
At time 1625137666.850775673
- Translation: [2.153, 5.133, 0.000]
- Rotation: in Quaternion [0.000, 0.000, -0.365, 0.931]

如果你用 tf2_echoworldturtle2 之间转换,你不应该看到转换,因为第二只乌龟还没有出现。然而,一旦我们在下一个教程中添加了第二只乌龟, turtle2 的姿势将被广播到tf2。 [待校准@8658]

总结

在本教程中,您学习了如何向tf2广播机器人的姿势 (海龟的位置和方向) 以及如何使用 tf2_echo 工具。要实际使用广播到tf2的转换,您应该继续下一个关于创建 tf2 listener 的教程。 [待校准@8672]