当前位置:   article > 正文

ROS学习笔记20 —— rospy中tf树的发布_ros publish tf python

ros publish tf python

1. TF数据的发送

使用tf.TransformBroadcaster类完成tf树的发布,有两个函数:

  • 法1: sendTransform(translation,rotation,time,child,parent)
  • 法2:sendTransformMessage(transform)

法1:发送手动封装的tf数据

sendTransform(translation,rotation,time,child,parent)需要将父子farme之间的平移、旋转手动打时间戳,然后发给/tf


案例1:

#!/usr/bin/env python  
# -*- coding:utf-8 -*-  
import tf
import rospy

if __name__ == '__main__':
	rospy.init_node('tf_test_node')
	br = tf.TransformBroadcaster()
	while not rospy.is_shutdown():
		br.sendTransform((1,2,0),
				tf.transformations.quaternion_from_euler(0,0,0),
				rospy.Time.now(),"world","test") 
  • 1
  • 2
  • 3
  • 4
  • 5
  • 6
  • 7
  • 8
  • 9
  • 10
  • 11
  • 12

在这里插入图片描述

案例2:

#!/usr/bin/env python  
# -*- coding:utf-8 -*-  

import rospy  
import math  
import tf   
  
if __name__ == '__main__':  
    rospy.init_node('py_tf_broadcaster')
    
    br = tf.TransformBroadcaster()

    x=1.0 
    y=2.0
    z=3.0  
    roll=0 
    pitch=0
    yaw=1.57 
    rate = rospy.Rate(1)
    while not rospy.is_shutdown(): 
        yaw=yaw+0.1   
        br.sendTransform((x,y,z),  
                     tf.transformations.quaternion_from_euler(roll,pitch,yaw),  
                     rospy.Time.now(),  
                     "base_link",  
                     "link1")  
        rate.sleep()  

  • 1
  • 2
  • 3
  • 4
  • 5
  • 6
  • 7
  • 8
  • 9
  • 10
  • 11
  • 12
  • 13
  • 14
  • 15
  • 16
  • 17
  • 18
  • 19
  • 20
  • 21
  • 22
  • 23
  • 24
  • 25
  • 26
  • 27
  • 28

法2:发布已经封装好的tf数据

sendTransformMessage(transform)发送的是已经封装好的Message


案例:

#!/usr/bin/env python  
# -*- coding:utf-8 -*-  

import rospy 
import geometry_msgs.msg
import tf2_ros.transform_broadcaster
import math  
import tf   
  
if __name__ == '__main__':  
    rospy.init_node('py_tf_broadcaster')
   
    m=tf.TransformBroadcaster()
    t = geometry_msgs.msg.TransformStamped()
    t.header.frame_id = 'base_link'
    t.header.stamp = rospy.Time(0)
    t.child_frame_id = 'link1'
    t.transform.translation.x = 1
    t.transform.translation.y = 2
    t.transform.translation.z = 3
    t.transform.rotation.w=1
    t.transform.rotation.x=0
    t.transform.rotation.y=0
    t.transform.rotation.z=0
	
	#输入相对原点的值和欧拉角
    rate = rospy.Rate(1)
    while not rospy.is_shutdown():
        m.sendTransformMessage(t)
        rate.sleep()  

  • 1
  • 2
  • 3
  • 4
  • 5
  • 6
  • 7
  • 8
  • 9
  • 10
  • 11
  • 12
  • 13
  • 14
  • 15
  • 16
  • 17
  • 18
  • 19
  • 20
  • 21
  • 22
  • 23
  • 24
  • 25
  • 26
  • 27
  • 28
  • 29
  • 30
  • 31

2. TF树的查看

(1)查看当前tf树:
rosrun rqt_tf_tree rqt_tf_tree
  • 1

(2)查看两个frame的变换关系
rosrun tf tf_echo [reference_frame] [target_frame]
  • 1

(3)根据当前tf树创建一个pdf图
rosrun tf view_frames
  • 1

3. 定义位姿的常用API

(1)定义空间点和空间向量
函数名称函数功能
tf.transformations.random_quaternion(rand=None)返回均匀随机单位四元数
tf.transformations.random_rotation_matrix(rand=None)返回均匀随机单位旋转矩阵
tf.transformations.random_vector(size)返回均匀随机单位向量
tf.transformations.translation_matrix(v)通过向量来求旋转矩阵
tf.transformations.translation_from_matrix(m)通过旋转矩阵来求向量
(2)定义四元数
函数名称函数功能
tf.transformations.quaternion_about_axis(angle axis)通过旋转轴和旋转角返回四元数
tf.transformations.quaternion_conjugate(quaternion)返回四元数的共轭
tf.transformations.quaternion_from_euler(ai,aj,ak, axes’ryxz’)从欧拉角和旋转轴,求四元数
tf.transformations.quaternion_from_matrix(matrix)从旋转矩阵中,返回四元数
tf.transformations.quaternion_multiply(quaternion1,quaternion2)两个四元数相乘
tf.transformations.euler_matrix(ai,aj,ak,axes=‘xyz’)由欧拉角和旋转轴返回旋转矩阵
tf.transformations.euler_from_matrix(matrix)由旋转矩阵和特定的旋转轴返回欧拉角
tf.transformations.euler_from_quaternion(quaternion)由四元数和特定的轴得到欧拉角
(3)欧拉角、位姿矩阵及四元数的转换
函数注释
euler_matrix(ai,aj,ak,axes=‘sxyz’)欧拉角到矩阵
euler_form_matrix(matrix,axes=‘sxyz’)矩阵到欧拉角
euler_from_quaternion(quaternion,axes=‘sxyz’)四元数到欧拉角
quaternion_form_euler(ai,aj,ak,axes=‘sxyz’)欧拉角到四元数
quaternion_matrix(quaternion)四元数到矩阵
quaternion_form_matrix(matrix)矩阵到四元数

参考:

声明:本文内容由网友自发贡献,不代表【wpsshop博客】立场,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:https://www.wpsshop.cn/w/Li_阴宅/article/detail/885305
推荐阅读
相关标签
  

闽ICP备14008679号