使用 ROS 1 桥接器通过“rosbag”记录和回放数据
本教程是“ROS 1 和 ROS 2 之间的桥接通信”演示的后续内容,可在“此处 <https://github.com/ros2/ros1_bridge/blob/master/README.md>”找到,下文假定您已经完成了该教程。
可以从 source 为这些示例构建 ros1_bridge。
接下来是一系列附加示例,例如前面提到的“ROS 1 和 ROS 2 之间的桥接通信”演示末尾的示例。
使用 rosbag 和 ROS 1 Bridge 记录主题数据
在此示例中,我们将使用 ROS 2 附带的“cam2image”演示程序和一个 Python 脚本来模拟一个简单的类似 turtlebot 的机器人的传感器数据,以便我们可以将其桥接到 ROS 1 并使用 rosbag 进行记录。
首先,我们将在新的 shell 中运行 ROS 1“roscore”:
# Shell A:
. /opt/ros/kinetic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
roscore
然后我们将在另一个 shell 中使用 --bridge-all-topics
选项运行 ROS 1 <=> ROS 2 ``dynamic_bridge``(这样我们就可以执行``rostopic list``并查看它们):
# Shell B:
. /opt/ros/kinetic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
. /opt/ros/ardent/setup.bash
# Or, if building ROS 2 from source:
# . <workspace-with-bridge>/install/setup.bash
export ROS_MASTER_URI=http://localhost:11311
ros2 run ros1_bridge dynamic_bridge --bridge-all-topics
请记住将“<workspace-with-bridge>”替换为您提取 ROS 2 二进制文件或从源代码构建 ROS 2 的路径。
现在我们可以启动 ROS 2 程序来模拟我们的 turtlebot 类机器人。 首先,我们将使用“-b”选项运行“cam2image”程序,这样它就不需要摄像头来工作了:
# Shell C:
. /opt/ros/ardent/setup.bash
# Or, if building ROS 2 from source:
# . <workspace-with-bridge>/install/setup.bash
ros2 run image_tools cam2image -- -b
TODO:使用命名空间主题名称
然后我们将运行一个简单的 Python 脚本来模拟来自 Kobuki 基础的“odom”和“imu_data”主题。 我会对 imu 数据使用更准确的“~sensors/imu_data”主题名称,但我们在 ROS 2 中还没有命名空间支持(即将推出!)。 将此脚本放在名为“emulate_kobuki_node.py”的文件中:
#!/usr/bin/env python3
import sys
import time
import rclpy
from nav_msgs.msg import Odometry
from sensor_msgs.msg import Imu
def main():
rclpy.init(args=sys.argv)
node = rclpy.create_node('emulate_kobuki_node')
imu_publisher = node.create_publisher(Imu, 'imu_data')
odom_publisher = node.create_publisher(Odometry, 'odom')
imu_msg = Imu()
odom_msg = Odometry()
counter = 0
while True:
counter += 1
now = time.time()
if (counter % 50) == 0:
odom_msg.header.stamp.sec = int(now)
odom_msg.header.stamp.nanosec = int(now * 1e9) % 1000000000
odom_publisher.publish(odom_msg)
if (counter % 100) == 0:
imu_msg.header.stamp.sec = int(now)
imu_msg.header.stamp.nanosec = int(now * 1e9) % 1000000000
imu_publisher.publish(imu_msg)
counter = 0
time.sleep(0.001)
if __name__ == '__main__':
sys.exit(main())
您可以在新的 ROS 2 shell 中运行此 python 脚本:
# Shell D:
. /opt/ros/ardent/setup.bash
# Or, if building ROS 2 from source:
# . <workspace-with-bridge>/install/setup.bash
python3 emulate_kobuki_node.py
现在所有数据源和动态桥都在运行,我们可以在新的 ROS 1 shell 中查看可用的主题:
# Shell E:
. /opt/ros/kinetic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
rostopic list
你应该看到类似这样的内容:
% rostopic list
/image
/imu_data
/odom
/rosout
/rosout_agg
我们现在可以在同一个 shell 中使用“rosbag record”来记录这些数据:
# Shell E:
rosbag record /image /imu_data /odom
几秒钟后,您可以按“Ctrl-c”键执行“rosbag”命令并执行“ls -lh”来查看文件有多大,您可能会看到类似这样的内容:
% ls -lh
total 0
-rw-rw-r-- 1 william william 12M Feb 23 16:59 2017-02-23-16-59-47.bag
虽然您的包的文件名会有所不同(因为它是从日期和时间派生出来的)。
使用 rosbag 和 ROS 1 Bridge 回放主题数据
现在我们有了一个包文件,您可以使用任何 ROS 1 工具来检查包文件,例如“rosbag info <bag file>”、“rostopic list -b <bag file>”或“rqt_bag <bag file>”。 但是,我们也可以使用“rosbag play”和 ROS 1 <=> ROS 2“dynamic_bridge”将包数据回放到 ROS 2 中。
首先关闭您在上一个教程中打开的所有 shell,停止所有正在运行的程序。
然后在新的 shell 中启动“roscore”:
# Shell P:
. /opt/ros/kinetic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
roscore
然后在另一个 shell 中运行“dynamic_bridge”:
# Shell Q:
. /opt/ros/kinetic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
. /opt/ros/ardent/setup.bash
# Or, if building ROS 2 from source:
# . <workspace-with-bridge>/install/setup.bash
export ROS_MASTER_URI=http://localhost:11311
ros2 run ros1_bridge dynamic_bridge --bridge-all-topics
然后在另一个新 shell 中使用“rosbag play”播放包数据,使用“–loop”选项,这样我们就不必为了短包而不断重新启动它:
# Shell R:
. /opt/ros/kinetic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
rosbag play --loop path/to/bag_file
确保将“path/to/bag_file”替换为您要播放的包文件的路径。
现在数据正在播放并且桥接器正在运行,我们可以在 ROS 2 中看到数据。
# Shell S:
. /opt/ros/ardent/setup.bash
# Or, if building ROS 2 from source:
# . <workspace-with-bridge>/install/setup.bash
ros2 topic list
ros2 topic echo /odom
You should see something like:
% ros2 topic list
/clock
/image
/imu_data
/odom
/parameter_events
您还可以使用“showimage”工具查看正在从包中播放的图像:
ros2 run image_tools showimage