ROS2 tf2广播器(broadcaster)、侦听器(listener)

2023-05-16

tf2介绍

安装依赖

sudo apt-get install ros-foxy-turtle-tf2-py ros-foxy-tf2-tools

transforms3d(它提供四元数和欧拉角转换功能)

pip3 install transforms3d

运行结果

启动turtle_tf2_demo.launch.py文件

ros2 launch turtle_tf2_py turtle_tf2_demo.launch.py

键盘控制turtlesim

ros2 run turtlesim turtle_teleop_key

在这里插入图片描述
使用键盘控制乌龟,可以看到一只乌龟会跟随另一只乌龟。

使用view_frames

ros2 run tf2_tools view_frames

生成的文件
在这里插入图片描述
frames.pdf
在这里插入图片描述

使用tf2_echo(报告通过 ROS 广播的任意两帧之间的转换)

ros2 run tf2_ros tf2_echo [reference_frame] [target_frame]

turtle2框架相对于turtle1框架的变换

ros2 run tf2_ros tf2_echo turtle2 turtle1

可以在终端显示turtle2框架相对于turtle1框架的变换
在这里插入图片描述

tf2广播器(broadcaster)

先决条件

创建工作区间和功能包

创建一个turtle_tf2_broadcaster.py文件

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()

创建一个turtle_tf2_broadcaster.launch.py文件

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='py_package',
            executable='turtle_tf2_broadcaster',
            name='broadcaster1',
            parameters=[
                {'turtlename': 'turtle1'}
            ]
        ),
    ])

添加依赖

修改setup.py文件

'console_scripts': [
    'turtle_tf2_broadcaster = py_package.turtle_tf2_broadcaster:main',
],
data_files=[
    ...
    (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*.launch.py'))),
],

修改package.xml文件

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

编译

colcon build
. install/setup.bash

运行结果

运行turtle_tf2_broadcaster.launch.py文件

(同时启动turtlesim节点和turtle_tf2_broadcaster节点)

ros2 launch learning_tf2_py turtle_tf2_broadcaster.launch.py

键盘控制turtlesim

ros2 run turtlesim turtle_teleop_key

在这里插入图片描述

使用tf2_echo工具检测海龟位姿是否广播到tf2

ros2 run tf2_ros tf2_echo world turtle1

可以在终端显示world框架相对于turtle1框架的变换
在这里插入图片描述

tf2侦听器(listener)

创建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.declare_parameter('target_frame', 'turtle1')
        self.target_frame = self.get_parameter(
            'target_frame').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:
                    now = rclpy.time.Time()
                    trans = self.tf_buffer.lookup_transform(
                        to_frame_rel,
                        from_frame_rel,
                        now)
                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(
                    trans.transform.translation.y,
                    trans.transform.translation.x)

                scale_forward_speed = 0.5
                msg.linear.x = scale_forward_speed * math.sqrt(
                    trans.transform.translation.x ** 2 +
                    trans.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()

创建turtle_tf2_listener.launch.py文件

from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
       
        Node(
            package='py_package',
            executable='turtle_tf2_listener',
            name='listener',
            parameters=[
                {'target_frame': 'turtle2'}
            ]
        ),
    ])

添加依赖

'console_scripts': [
    'turtle_tf2_listener = py_package.turtle_tf2_listener:main',
],

编译

colcon build
. install/setup.bash

运行结果

运行turtle_tf2_broadcaster.launch.py文件

ros2 launch learning_tf2_py turtle_tf2_broadcaster.launch.py

运行turtle_tf2_listener.launch.py文件

ros2 launch py_package turtle_tf2_listener.launch.py

键盘控制turtlesim

ros2 run turtlesim turtle_teleop_key

在这里插入图片描述
使用键盘控制turtle1,可以看到turtle2会跟随turtle1
这里turtle_tf2_broadcaster节点会广播(broadcaster) turtle1位姿
turtle_tf2_listener节点会监听(listener) turtle1位姿

参考链接

tf2 介绍

编写 tf2 广播器 (Python)

编写 tf2 侦听器 (Python)

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

ROS2 tf2广播器(broadcaster)、侦听器(listener) 的相关文章

  • pixhawk源码下载与编译

    今天和同学在一起讨论发现自己还在看的pixhawk源码的版本好低啊 xff0c 就下个最新的吧 想起有些人还不会下载源码 xff0c 以及用什么工具查看 源码的下载我用的是git shell工具下的 xff0c px4的github网址是h
  • pixhawk开发环境

    Windows 7 64bit 软件安装 首先 xff0c 需要安装一些软件 xff0c CMake 32位的Java jdk以及PX4 Toolchain Installer CMake的话笔者使用的是CMake 3 3 2 win32
  • Pixhawk-信息流浅解析

    根深方能叶茂 在等待的日子里 xff0c 刻苦读书 xff0c 谦卑做人 xff0c 养得深根 xff0c 日后才能枝叶茂盛 Better 根爷 之前我们已经谈到系统框架 xff0c 之前谈到了定制自己功能的两部 xff1a 添加模块和修改
  • Python跨进程共享数据/对象

    1 跨进程共享方式 在multiprocess库中 xff0c 跨进程对象共享有三种方式 xff1a xff08 1 xff09 第一种仅适用于原生机器类型 xff0c 即python ctypes当中的类型 xff0c 这种在mp库的文档
  • Pixhawk-姿态解算-互补滤波

    根深方能叶茂 在等待的日子里 xff0c 刻苦读书 xff0c 谦卑做人 xff0c 养得深根 xff0c 日后才能枝叶茂盛 Better 根爷 终于说到了正题 xff0c 姿态解算这一部分很重要 xff0c 主要的基础就是惯性导航和多传感
  • Pixhawk-姿态解算源码注释

    根深方能叶茂 在等待的日子里 xff0c 刻苦读书 xff0c 谦卑做人 xff0c 养得深根 xff0c 日后才能枝叶茂盛 Better 根爷 这一部分是我在看源码时 xff0c 自己注释的一点笔记 xff0c 现在直接贴上来 当然这其中
  • Pixhawk-串级pid介绍

    根深方能叶茂 在等待的日子里 xff0c 刻苦读书 xff0c 谦卑做人 xff0c 养得深根 xff0c 日后才能枝叶茂盛 Better 根爷 鉴于串级PID在pixhawk系统中的重要性 xff0c 无论是误差的补偿 xff0c 如姿态
  • pixhawk串口读取传感器数据

    1 Pixhawk板上串口说明 xff1a 测试 使用Pixhawk板上TELEM2接口的USART2 xff0c 对应的Nuttx UART设备文件尾 dev ttyS2 xff1a 2 读取数据测试 步骤 xff1a 在Firmware
  • Android调用系统自带的文件管理器进行文件选择

    这几天在做的项目网盘 上传时需要用到调用系统自带的文件管理器来选择文件 xff0c 后来就在考虑怎么调用 xff0c 网上也搜了很久 xff0c 没有很好的解决方法 xff0c 后来在一瞬间发现了一篇不错的文章 xff0c 借鉴了一下代码
  • Android下如何读取文件的内容

    唉 xff0c 尝试了好半天了 xff0c 才弄懂 xff0c 1 首先权限的问题 我们需要在根文件中添加权限 lt uses permission android name 61 34 android permission WRITE E
  • Mavlink地面站编写之二–Mission PLanner地面站构架分析之MAVLINK航点读写

    转载请注明出处 http www amovauto com 阿木社区 玩也要玩的专业 xff01 3DR这个地面站还是非常专业的 xff0c 最近研究MAVLINK通信协议 就来分析下Mission planner的构架 至于Msissio
  • Mavlink地面站编写之三–Mission PLanner地面站构架分析之MAVLINK航点写入

    转载注意出处 xff1a http www amovauto com p 61 601 more 601 阿木社区 玩也要玩的专业 xff01 我们知道了怎么利用mavlink读取航点 xff0c 那么如果我们要写入航点 xff0c 也是一
  • Mavlink地面站编写之四-Mission Planner中ProgressReporterDialogue和读串口线程serialreaderthread的分析

    转载请注明出处 http www amovauto com p 61 660 阿木社区 xff0c 玩也要玩的专业 QQ群 526221258 ProgressReporterDialogue 这个对话框很有意思 xff0c 在MP中连接阶
  • Mavlink地面站编写之八–MAVLINK消息自定义

    PIXHAWk MAVLINK消息自定义 对于PIXHAWK这个系统来讲 xff0c MAVLINK是个小型的数据通信协议 xff0c 负责地面站和飞控本身的数据交互和地面站向飞控发送数据指令 前面的文章已经讲过MAVLINK这个数据格式解
  • Python参数校验工具:validate.py

    一直都在找一个比较好用的参数校验工具包 xff08 Python xff09 xff0c 这次终于找到了就做个记录 包名 xff1a validate py 安装方式 xff1a xff08 pip已收入 当前最新版本是1 3 0 xff0
  • Mavlink-1-概述介绍

    1 MAVLink简介 MAVLink xff08 Micro Air Vehicle Link xff0c 微型空中飞行器链路通讯协议 xff09 是无人飞行器与地面站 xff08 Ground Control Station xff0c
  • PX4位置控制offboard模式说明

    offboard模式的开发及应用 一 px4固件的模式 px4固件支持10几种飞行模式 xff0c 从代码结构上分析 xff0c 分为基本模式 自定义模式和自定义子模式 1 基本模式 基本模式又分为 xff0c 位置控制模式 自稳模式 手动
  • Nuttx启动过程

    start 处理器执行的第一条指令 v stm32 clockconfig 初始化时钟 v rcc reset 复位rcc stm32 stdclockconfig 初始化标准时钟 rcc enableperipherals 使能外设时钟
  • 飞控打信息打印

    如果打印到地面站可以使用mavlink log critical mavlink log critical mavlink log pub local 34 HIL platform Connect to simulator before
  • console和nsh的区别

    PX4在调试过程中 console口和NSH口原来功能不一样 xff0c Console只是负责往外吐数据 xff0c 比如打印飞控启动的过程 xff0c 或者输出源码中warnx或者printf这样的打印信息 而NSH飞控上电的启动过程并

随机推荐

  • C++ Primer 好不好?投票呗

    我的C 43 43 Primer 11好不好 xff1f 投票呗 为了能写出更好的C 43 43 Primer xff0c 我在这里向大家问一下 xff1a 我写得好不好 xff1f 认为好的选上面 xff0c 认为不好的选下面 xff0c
  • C++Primer 非常适合入门

    C 43 43 Primer 非常适合入门 就像题目所说的那样 xff1a C 43 43 Primer 非常适合入门 这是事实 xff01 xff01
  • 用户态和内核态的转换 (转)

    1 xff09 用户态切换到内核态的3种方式 a 系统调用 这是用户态进程主动要求切换到内核态的一种方式 xff0c 用户态进程通过系统调用申请使用操作系统提供的服务程序完成工作 xff0c 比如前例中fork 实际上就是执行了一个创建新进
  • 嵌入式数字电路中的各种逻辑电平

    在通用的电子器件设备中 xff0c TTL和CMOS电路的应用非常广泛 但是面对现在系统日益复杂 xff0c 传输的数据量越来越大 xff0c 实时性要求越来越高 xff0c 传输距离越来越长的发展趋势 xff0c 掌握高速数据传输的逻辑电
  • 永久保存屏幕显示方向

    修改屏幕的显示方向 xff1a 在终端输入 xrandr o left 向左旋转90度 xrandr o right 向右旋转90度 xrandr o inverted 上下翻转 code code code xrandr o normal
  • RabbitMQ 与 Kafka深度解析(二)

    介绍 作为一名处理大量基于微服务的系统的软件架构师 xff0c 我经常会遇到一个反复出现的问题 xff1a 我应该使用RabbitMQ还是Kafka xff1f 出于某种原因 xff0c 许多开发人员认为这些技术是可以互换的 虽然在某些情况
  • 物联网时代25大开源IoT框架

    相当长一段时间以来 xff0c 互联网一直被用来连接人类并简化生活 xff0c 这是21世纪初的启示 今天 xff0c 我们将讨论各种物联网框架 现在 xff0c 我们正在进入一个基于互联网技术的新世界 xff0c 该世界不仅连接人 xff
  • 如何用maven使用低版本的jdk编译工程

    背景 xff1a 项目中自定义了一些二方库 xff0c 需要把一些工程编译成jar xff0c 给其他项目或者工程做为依赖引入 由于自己的项目使用的是JDK1 8 xff0c 而使用方是一个比较老的项目 xff0c 使用的是JDK 1 6
  • Docker 1.7.1版本pull私有镜像仓库报错,V1,V2等

    注意 xff1a 如下解决方案 xff0c 只能解决pull的问题 xff0c 不能解决push的问题 xff0c 方案请参考 xff1a 解决docker push问题 Docker 1 7版本和Docker CE的配置文件的位置是不同的
  • 解决docker push镜像时denied: requested access to the resource is denied : docker

    背景 xff1a 我用的是harbor管理镜像仓库 xff0c 之前没有上传下载过harbor上的镜像 在我配置了daemon json文件后 xff0c 可以pull镜像了 xff0c 但是我往library目录push的时候仍然有问题
  • Jenkins增加node节点

    setp 1 添加节点 setp 2 配置 1 Launch method 选择Launch slaver agents via SSH 2 填写主机ip 3 添加Credentiais xff0c 也就是主机的username和passw
  • Linux如何设置时区、时间

    查看时间命令 xff1a root span class hljs variable 64 123 span span class hljs symbol work test span span class hljs variable sp
  • centos如何查看linux内核,版本号等

    查看全部信息 xff1a zhangsan span class hljs variable 64 localhost span span class hljs variable span uname a span class hljs c
  • linux如何切换用户

    1 一般的用户增删改查 useradd test 执行后会在 home目录下添加test用户的目录 cat etc passwd 可以查看系统当前的用户 su test 切换用户 passwd test 给test用户创建密码 2 另类用户
  • 解决kubernetes启动容器时,容器一直是ContainerCreating不能running

    表象 kubectl f span class hljs operator span class hljs keyword create span redis yaml kubectl span class hljs keyword get
  • Eclipse创建的Maven项目报错Could not calculate build plan: Plugin

    1 错误描述 br Could not calculate build plan Plugin br org apache maven plugins maven resources plugin 2 5 or one of its dep
  • JAVA同一个类内方法调用AOP解决办法

    1 问题现象 64 Around 34 execution com unicom hl service TowerPayService processInsert 34 public Object around ProceedingJoin
  • Python多进程任务如何识别谁是谁

    在Python多进程 多线程编程中 xff0c 如果使用future和add done callback 经常会遇到如何区分异步任务的问题 这里推荐两种方式 方式一 xff1a 给future新增属性 def call back futur
  • spring如何将环境变量映射到JaveBean里

    spring 获取 xff0c 打印环境变量 public static void main String args Map lt String String gt env 61 System getenv Set lt Map Entry
  • ROS2 tf2广播器(broadcaster)、侦听器(listener)

    tf2介绍 安装依赖 span class token function sudo span span class token function apt get span span class token function install