ROS_rosbag命令行以及检查topic

发布时间 2023-03-22 21:11:48作者: 辰令

rosbag

 rosbag 既可以指命令行中数据包相关命令,也可以指 c++/python 的 rosbag 库。这里的 rosbag 是指前者 
    rosbag -基于离线数据快速重现曾经的实际场景,进行可重复、低成本的分析和调试
rosbag常用的操作指令:
 info:bag包的信息 -y, –yaml 
 record:录制特定topic的rosbag包  -d, –duration  -o 
 play:回放一个或多个bag包
 check:核对某bag包是否可播放
 fix:修复bag包以在当前系统播放
 filter:转换包
 compress:压缩包
 decompress:接压缩包

bag中提取pcd

#注意数据的shape
import numpy  as np

if __name__ == '__main__':
    data = np.array([1.1,3,4,5,6])
    data2 = np.array([[1.1,3,4,5,6]])
    data3 = np.array([[1.1],[3],[4],[5],[6]])
    print(data.shape,data2.shape,data3.shape)
    print(data2.reshape(-1).shape,data3.reshape(-1).shape)
	
from sensor_msgs import point_cloud2
import open3d as o3d
import rosbag
bag_pcd = point_cloud2.read_points(msg,field_names=["x","y","z","intensity"])
pcd = o3d.t.geometry.PointCloud()
pcd.point["positions"] = o3d.core.Tensor(bag_pcd[:,:3], dtype=o3d.core.Dtype.Floated2) 
print(bag_pcd[:,3].shape,bag_pcd[:,3].reshape(-1,1).shape)
pcd.point["intensity"] = o3d.core.Tensor(bag_pcd[:,3].reshape(-1,1), dtype, device) 
#############eg#############
import numpy as np
import rosbag
import sensor_msgs.point_cloud2
pcd = o3d.t.geometry.PointCloud()
for topic, msg, t in tqdm(bag.read_messages(topics=topics)):
    bag_pcd =  np.array(list(point_cloud2.read_points(msg,field_names=["x","y","z","intensity"])))
	pcd.point["positions"] = o3d.core.Tensor(bag_pcd[:,:3], dtype=o3d.core.Dtype.Floated2) 
    pcd.point["intensity"] = o3d.core.Tensor(bag_pcd[:,3].reshape(-1,1), dtype, device) 
	o3d.t.io.write_point_cloud("./test.pcd",pcd,write_ascii=true)

利用ros工具提取pcd

 rosrun是运行一个单独节点的命令
 roslaunch采用XML的格式对需要运行的节点进行描述,可以同时运行多个节点	

 rosrun pcl_ros bag_to_pcd <input_file.bag> <topic> <output_directory>
 rosrun pcl_ros pointcloud_to_pcd input:=/velodyne/pointcloud2 点云最后的保存形式为时间戳.pcd	 

bag提取图像

import cv2
from rosbags.image import message_to_cvimage
for topic, msg, t in tqdm(bag.read_messages(topics=topics)):
     cv_image = message_to_cvimage(msg,color_space="bgr8")
	 cv2.imwrite(image_file, cv_image)

利用ros工具提取图片

rosrun image_view extract_images _sec_per_frame:=0.01 image:=/front_wide/image_raw
rosrun image_view image_view _sec_per_frame:=0.01 image:=/front_wide/image_raw

rosrun image_view image_saver  _encoding:='bgr8' _filename_format:=%s image:=/front_wide/image_raw
rosrun image_view image_saver  _encoding:='bgr8' _filename_format:="cam%i.png" image:=/camera0/color/image_raw 

发布图像

rosrun image_publisher image_publisher /absolute/path.png

命令行查看ros运行和检查rosbag录制情况

--运行过程中查看 
   "/novatel/odom" >  /opt/test.txt
   "/ption/pcd" >> /opt/test.txt
  for file_nm in `cat /opt/test.txt`  ;do result=$(timeout 2s rostopic echo -n 2 $file_nm);  if [[ $result != "" ]] ; then echo  "$file_nm" ;fi;done;
  
--运行结束后查看  
  find ./ -maxdepth 1 -type f -iname "*.bag" | while read dir; do count=$(rosbag info -y -k topics $dir |wc -l); echo "$dir : $count "; done 

rostopic

rostopic包含rostopic命令行工具,用于显示有关ROS 主题的调试信息,包括发布者,订阅者,发布频率和ROS消息
 rostopic list   显示所有活动状态下的主题
 rostopic hz     显示主题的发布频率
 rostopic info   显示主题相关信息
 rostopic echo   打印消息到屏幕
 rostopic find   根据类型查找主题
 rostopic pub    将数据发布到主题
 rostopic type   打印主题类型
 rostopic bw     显示主题使用的带宽
 rostopic delay  显示带有 header 的主题延迟
      rostopic pub [topic] [msg_type] [args]

参考

 https://wiki.ros.org/image_view
 http://wiki.ros.org/pcl_ros 
 https://leooo48.github.io/2018/11/28/rosbag/
 http://www.autolabor.com.cn/book/ROSTutorials/
 https://songapore.gitbook.io/ros-tutorials/6-li-jie-ros-hua-ti-topics/6.4-ji-xu-xue-xi-rostopic
 ROS中那些好用的功能包推荐(2)—— image_pipeline图像管道  https://www.guyuehome.com/34043