桥接 ROS2
dora-ros2-bridge is an extension that we have built for people to use ROS2 easily. One of the main issues with ROS2 is the complex build system. It would have been really hard for people to use dora on top of the ros2 build system so we have built this bridge to be ROS2 compiler free. 为了做到这一点,我们在运行时将每条消息转换为 arrow struct 格式。 This can be used to rapidly use AI models through numpy, pandas, ...
什么是 dora-ros2-bridge ?
当前的机器人社区使用大量 ROS2 来构建机器人。 他们很难完全从 ROS2 切换。 为 ROS 2 构建易于使用的桥接有助于提供一种更简单的方法来集成和转换项目到 dora 或从 dora 转换项目。 This also makes it easy to reuse ROS2 sensor nodes that do not provide any other API.
从 Python 开始
以下示例可以使用 dora 操作一个 ROS2 turtlebot 的模拟器。 它不需要 colcon 的任何编译,只需要使用 dora 运行。
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import dora
from dora import Node
ros2_context = dora.Ros2Context()
ros2_node = ros2_context.new_node(
"turtle_teleop", # 名字
"/ros2_demo", # 名字空间
dora.Ros2NodeOptions(rosout=True),
)
# 定义一个 ROS2 QOS
topic_qos = dora.Ros2QosPolicies(
reliable=True, max_blocking_time=0.1
)
# 创建一个发布者至 cmd_vel 主题
turtle_twist_topic = ros2_node.create_topic(
"/turtle1/cmd_vel", "geometry_msgs/Twist", topic_qos
)
twist_writer = ros2_node.create_publisher(turtle_twist_topic)
# 创建一个监听者至 pose 主题
turtle_pose_topic = ros2_node.create_topic(
"/turtle1/pose", "turtlesim/Pose", topic_qos
)
pose_reader = ros2_node.create_subscription(turtle_pose_topic)
# 创建一个 dora 节点
dora_node = Node()
# 在同一个循环上监听两个流,因为 Python 不能很好处理多进程
dora_node.merge_external_events(pose_reader)
for i in range(500):
event = dora_node.next()
if event is None:
break
match event["kind"]:
# Dora 事件
case "dora":
match event["type"]:
case "INPUT":
match event["id"]:
case "direction":
twist_writer.publish(event["value"])
# 在本 case 分支中为 ROS2 事件
case "external":
pose = event["value"][0].as_py()
dora_node.send_output("turtle_pose", event["value"])
从 Rust 开始
以下示例可以使用 dora 操作 ROS2 turtlebot。 它不需要colcon,只需要用cargo
进行本地编译,然后用dora运行。
use dora_node_api::{
self,
dora_core::config::DataId,
merged::{MergeExternal, MergedEvent},
DoraNode, Event,
};
use dora_ros2_bridge::{
geometry_msgs::msg::{Twist, Vector3},
ros2_client::{self, ros2, NodeOptions},
rustdds::{self, policy},
turtlesim::msg::Pose,
};
use eyre::Context;
fn main() -> eyre::Result<()> {
let mut ros_node = init_ros_node()?;
let turtle_vel_publisher = create_vel_publisher(&mut ros_node)?;
let turtle_pose_reader = create_pose_reader(&mut ros_node)?;
// 初始化 dora 节点
let output = DataId::from("pose".to_owned());
let (mut node, dora_events) = DoraNode::init_from_env()?;
// 合并流至一个循环
let merged = dora_events.merge_external(Box::pin(turtle_pose_reader.async_stream()));
let mut events = futures::executor::block_on_stream(merged);
for i in 0..1000 {
let event = match events.next() {
Some(input) => input,
None => break,
};
match event {
MergedEvent::Dora(event) => match event {
Event::Input {
id,
metadata: _,
data: _,
} => match id.as_str() {
"tick" => {
let direction = Twist {
linear: Vector3 {
x: rand::random::<f64>() + 1.0,
..Default::default()
},
angular: Vector3 {
z: (rand::random::<f64>() - 0.5) * 5.0,
..Default::default()
},
};
println!("tick {i}, sending {direction:?}");
turtle_vel_publisher.publish(direction).unwrap();
}
other => eprintln!("Ignoring unexpected input `{other}`"),
},
Event::Stop => println!("Received manual stop"),
other => eprintln!("Received unexpected input: {other:?}"),
},
MergedEvent::External(pose) => {
println!("received pose event: {pose:?}");
if let Ok((pose, _)) = pose {
let serialized = serde_json::to_string(&pose)?;
node.send_output_bytes(
output.clone(),
Default::default(),
serialized.len(),
serialized.as_bytes(),
)?;
}
}
}
}
Ok(())
}
fn init_ros_node() -> eyre::Result<ros2_client::Node> {
let ros_context = ros2_client::Context::new().unwrap();
ros_context
.new_node(
"turtle_teleop", // 名称
"/ros2_demo", // 名字空间
NodeOptions::new().enable_rosout(true),
)
.context("failed to create ros2 node")
}
// 发布在 vel_cmd 主题
fn create_vel_publisher(
ros_node: &mut ros2_client::Node,
) -> eyre::Result<ros2_client::Publisher<Twist>> {
let topic_qos: rustdds::QosPolicies = {
rustdds::QosPolicyBuilder::new()
.durability(policy::Durability::Volatile)
.liveliness(policy::Liveliness::Automatic {
lease_duration: ros2::Duration::DURATION_INFINITE,
})
.reliability(policy::Reliability::Reliable {
max_blocking_time: ros2::Duration::from_millis(100),
})
.history(policy::History::KeepLast { depth: 1 })
.build()
};
let turtle_cmd_vel_topic = ros_node
.create_topic(
"/turtle1/cmd_vel",
String::from("geometry_msgs::msg::dds_::Twist_"),
&topic_qos,
)
.context("failed to create topic")?;
// 这里的重点是为 turtle 发布 Twist
let turtle_cmd_vel_writer = ros_node
.create_publisher::<Twist>(&turtle_cmd_vel_topic, None)
.context("failed to create publisher")?;
Ok(turtle_cmd_vel_writer)
}
// 监听 pose 主题
fn create_pose_reader(
ros_node: &mut ros2_client::Node,
) -> eyre::Result<ros2_client::Subscription<Pose>> {
let turtle_pose_topic = ros_node
.create_topic(
"/turtle1/pose",
String::from("turtlesim::msg::dds_::Pose_"),
&Default::default(),
)
.context("failed to create topic")?;
let turtle_pose_reader = ros_node
.create_subscription::<Pose>(&turtle_pose_topic, None)
.context("failed to create subscription")?;
Ok(turtle_pose_reader)
}