当前位置:网站首页>Experiment notes - Convert Carmen (.Log.Clf) file to rosbag
Experiment notes - Convert Carmen (.Log.Clf) file to rosbag
2022-06-27 10:20:00 【gwpscut】
The direct source code is as follows , For more information, please refer to the blog :
Study notes —— Generation of data set _gwpscut The blog of -CSDN Blog
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
import rosbag
from sensor_msgs.msg import LaserScan
from nav_msgs.msg import Odometry
from math import pi
from tf2_msgs.msg import TFMessage
from geometry_msgs.msg import TransformStamped
import tf
def make_tf_msg(x, y, z,theta, t,parentid,childid):
trans = TransformStamped()
trans.header.stamp = t
trans.header.frame_id = parentid
trans.child_frame_id = childid
trans.transform.translation.x = x
trans.transform.translation.y = y
trans.transform.translation.z = z
q = tf.transformations.quaternion_from_euler(0, 0, theta)
trans.transform.rotation.x = q[0]
trans.transform.rotation.y = q[1]
trans.transform.rotation.z = q[2]
trans.transform.rotation.w = q[3]
msg = TFMessage()
msg.transforms.append(trans)
return msg
# 0 | 1 | 2 - 1+num_readings | 2+num_readings | 3+num_readings |
# xLASER | num_readings | [range_readings] | x | y |
#-------------------------------------------------------------------------------
# 4+num_readings | 5+num_readings | 6+num_readings | 7+num_readings |
# theta | odom_x | odom_y | odom_theta |
#-------------------------------------------------------------------------------
# 8+num_readings | 9+num_readings | 10+num_readings
# ipc_timestamp | ipc_hostname |logger_timestamp
with open('mit-killian.clf') as dataset:
with rosbag.Bag('MIT.bag', 'w') as bag:
for line in dataset.readlines():
line = line.strip()
tokens = line.split(' ')
if len(tokens) <= 2:
continue
if tokens[0] == 'FLASER': #FLASER This is the original laser data marked in the original file , Generally, there is no need to change
msg = LaserScan()
num_scans = int(tokens[1])
if num_scans != 180 or len(tokens) < num_scans + 9:
rospy.logwarn("unsupported scan format")
continue
msg.header.frame_id = 'base_laser' # This is the laser coordinate system id, Change... As needed , stay ROS When reading data in, you will use , Generally, there is no need to change .
t = rospy.Time(float(tokens[(num_scans + 8)])) # Acquisition time
msg.header.stamp = t
msg.angle_min = -90.0 / 180.0 * pi
msg.angle_max = 90.0 / 180.0 * pi
msg.angle_increment = pi / num_scans
msg.time_increment = 0.2 / 360.0
msg.scan_time = 0.2
msg.range_min = 0.001
msg.range_max = 50.0
msg.ranges = [float(r) for r in tokens[2:(num_scans + 2)]]
bag.write('scan', msg, t) # This is the topic of laser data release , Change according to the specific topic subscribed by the node program .
tf_msg = make_tf_msg(0.1, 0, 0.2, 0, t,'base_link','base_laser')
bag.write('tf', tf_msg, t)
# odom_x, odom_y, odom_theta = [float(r) for r in tokens[(num_scans + 2):(num_scans + 5)]]
# odom_x, odom_y, odom_theta = [float(r) for r in tokens[(num_scans + 5):(num_scans + 8)]]
# msg1=Odometry()
# msg1.header.stamp=t
# msg1.header.frame_id='odom'
# msg1.child_frame_id='base_link'
# msg1.pose.pose.position.x=odom_x
# msg1.pose.pose.position.y=odom_y
# msg1.pose.pose.position.z=0
# q = tf.transformations.quaternion_from_euler(0, 0, odom_theta)
# msg1.pose.pose.orientation.x = q[0]
# msg1.pose.pose.orientation.y = q[1]
# msg1.pose.pose.orientation.z = q[2]
# msg1.pose.pose.orientation.w = q[3]
# bag.write('odom', msg1, t)
# 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9
# ODOM| x | y |theta| tv| rv|accel|ipc_timestamp|ipc_hostname|logger_timestamp
elif tokens[0] == 'ODOM': # Mark odometer data
odom_x, odom_y, odom_theta = [float(t) for t in tokens[1:4]]
t = rospy.Time(float(tokens[7]))
msg=Odometry()
msg.header.stamp=t
msg.header.frame_id='odom'
msg.child_frame_id='base_link'
msg.pose.pose.position.x=odom_x
msg.pose.pose.position.y=odom_y
msg.pose.pose.position.z=0
q = tf.transformations.quaternion_from_euler(0, 0, odom_theta)
msg.pose.pose.orientation.x = q[0]
msg.pose.pose.orientation.y = q[1]
msg.pose.pose.orientation.z = q[2]
msg.pose.pose.orientation.w = q[3]
bag.write('odom', msg, t)
# tf_msg = make_tf_msg(odom_x, odom_y,0 , odom_theta, t,'odom','base_link')
# bag.write('tf', tf_msg, t)边栏推荐
- C any() and aii() methods
- 产品力对标海豹/Model 3,长安深蓝SL03预售17.98万起
- Border affects the height of the parent element - solution
- C# Any()和AII()方法
- Test how students participate in codereview
- C language learning day_ 05
- Mail system (based on SMTP protocol and POP3 protocol -c language implementation)
- R语言plotly可视化:plotly可视化二维直方图等高线图、在等高线上添加数值标签、自定义标签字体色彩、设置鼠标悬浮显示效果(Styled 2D Histogram Contour)
- R语言使用econocharts包创建微观经济或宏观经济图、demand函数可视化需求曲线(demand curve)、自定义配置demand函数的参数丰富可视化效果
- Dimitt's law
猜你喜欢

导师邀请你继续跟他读博,你会不会立马答应?

详细记录YOLACT实例分割ncnn实现

Multi thread implementation rewrites run (), how to inject and use mapper file to operate database

Tcp/ip explanation (version 2) notes / 3 link layer / 3.4 bridge and switch / 3.4.1 spanning tree protocol (STP)
![[200 opencv routines] 212 Draw a slanted rectangle](/img/cf/da8fff386d011c939946326c55671f.png)
[200 opencv routines] 212 Draw a slanted rectangle

小哥凭“量子速读”绝技吸粉59万:看街景图0.1秒,“啪的一下”在世界地图精准找到!...

Design and Simulation of direct torque control system for induction motor (motion control matlab/simulink)

2-4Kali下安装nessus

TCP/IP 详解(第 2 版) 笔记 / 3 链路层 / 3.4 桥接器与交换机 / 3.4.1 生成树协议(Spanning Tree Protocol (STP))

leetcode:522. 最长特殊序列 II【贪心 + 子序列判断】
随机推荐
[从零开始学习FPGA编程-47]:视野篇 - 第三代半导体技术现状与发展趋势
Learning notes - data set generation
迪米特法则
For a moment, the ban of the US e-cigarette giant has been postponed, and products can be sold in the US for the time being
leetcode待做题目
Advantages and disadvantages of distributed file storage system
[cloud enjoys freshness] community weekly · vol.68- Huawei cloud recruits partners in the field of industrial intelligence to provide strong support + business realization
并发,并行,异步,同步,多线程,互斥的概念
leetcode:522. 最长特殊序列 II【贪心 + 子序列判断】
Product strength benchmarking seal /model 3, with 179800 pre-sales of Chang'an dark blue sl03
三层架构中,数据库的设计在哪一层实现,不是在数据存储层吗?
C any() and aii() methods
使用Karmada实现Helm应用的跨集群部署【云原生开源】
你睡觉时大脑真在自动学习!首个人体实验证据来了:加速1-4倍重放,深度睡眠阶段效果最好...
闭包的常见问题
C# Any()和AII()方法
On June 23, the video address of station B in the third episode of rust chat room
运维一线工作常用shell脚本再整理
audiotrack与audioflinger
[noodle classic] Yunze Technology