Browse Source

Add a `rust-ros2-dataflow` example using the dora-ros2-bridge

The bridge allows nodes to send and receive to/from both ros2 and dora.
tags/v0.2.5-alpha
Philipp Oppermann 2 years ago
parent
commit
8631304527
Failed to extract signature
6 changed files with 1056 additions and 268 deletions
  1. +833
    -268
      Cargo.lock
  2. +10
    -0
      Cargo.toml
  3. +9
    -0
      examples/rust-ros2-dataflow/dataflow.yml
  4. +15
    -0
      examples/rust-ros2-dataflow/node/Cargo.toml
  5. +134
    -0
      examples/rust-ros2-dataflow/node/src/main.rs
  6. +55
    -0
      examples/rust-ros2-dataflow/run.rs

+ 833
- 268
Cargo.lock
File diff suppressed because it is too large
View File


+ 10
- 0
Cargo.toml View File

@@ -12,6 +12,7 @@ members = [
"binaries/daemon",
"binaries/runtime",
"examples/rust-dataflow/*",
"examples/rust-ros2-dataflow/*",
"examples/benchmark/*",
"examples/multiple-daemons/*",
"libraries/communication-layer/*",
@@ -56,6 +57,10 @@ edition = "2021"
license = "Apache-2.0"


[features]
# enables examples that depend on a sourced ROS2 installation
ros2-examples = []

[dev-dependencies]
eyre = "0.6.8"
tokio = "1.24.2"
@@ -79,6 +84,11 @@ path = "examples/c-dataflow/run.rs"
name = "rust-dataflow"
path = "examples/rust-dataflow/run.rs"

[[example]]
name = "rust-ros2-dataflow"
path = "examples/rust-ros2-dataflow/run.rs"
required-features = ["ros2-examples"]

[[example]]
name = "rust-dataflow-url"
path = "examples/rust-dataflow-url/run.rs"


+ 9
- 0
examples/rust-ros2-dataflow/dataflow.yml View File

@@ -0,0 +1,9 @@
nodes:
- id: rust-node
custom:
build: cargo build -p rust-ros2-dataflow-example-node
source: ../../target/debug/rust-ros2-dataflow-example-node
inputs:
tick: dora/timer/millis/500
outputs:
- pose

+ 15
- 0
examples/rust-ros2-dataflow/node/Cargo.toml View File

@@ -0,0 +1,15 @@
[package]
name = "rust-ros2-dataflow-example-node"
version.workspace = true
edition = "2021"

# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html

[dependencies]
dora-node-api = { workspace = true, features = ["tracing"] }
eyre = "0.6.8"
futures = "0.3.21"
rand = "0.8.5"
tokio = { version = "1.24.2", features = ["rt", "macros"] }
dora-ros2-bridge = { git = "https://github.com/dora-rs/dora-ros2-bridge.git" }
serde_json = "1.0.99"

+ 134
- 0
examples/rust-ros2-dataflow/node/src/main.rs View File

@@ -0,0 +1,134 @@
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)?;

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", // name
"/ros2_demo", // namespace
NodeOptions::new().enable_rosout(true),
)
.context("failed to create ros2 node")
}

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")?;

// The point here is to publish Twist for the turtle
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)
}

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)
}

+ 55
- 0
examples/rust-ros2-dataflow/run.rs View File

@@ -0,0 +1,55 @@
use eyre::{bail, Context};
use std::path::Path;
use tracing::metadata::LevelFilter;
use tracing_subscriber::Layer;

#[derive(Debug, Clone, clap::Parser)]
pub struct Args {
#[clap(long)]
pub run_dora_runtime: bool,
}

#[tokio::main]
async fn main() -> eyre::Result<()> {
let Args { run_dora_runtime } = clap::Parser::parse();

if run_dora_runtime {
return tokio::task::block_in_place(dora_daemon::run_dora_runtime);
}

set_up_tracing().wrap_err("failed to set up tracing subscriber")?;

let root = Path::new(env!("CARGO_MANIFEST_DIR"));
std::env::set_current_dir(root.join(file!()).parent().unwrap())
.wrap_err("failed to set working dir")?;

let dataflow = Path::new("dataflow.yml");
build_dataflow(dataflow).await?;

dora_daemon::Daemon::run_dataflow(dataflow).await?;

Ok(())
}

async fn build_dataflow(dataflow: &Path) -> eyre::Result<()> {
let cargo = std::env::var("CARGO").unwrap();
let mut cmd = tokio::process::Command::new(&cargo);
cmd.arg("run");
cmd.arg("--package").arg("dora-cli");
cmd.arg("--").arg("build").arg(dataflow);
if !cmd.status().await?.success() {
bail!("failed to build dataflow");
};
Ok(())
}

fn set_up_tracing() -> eyre::Result<()> {
use tracing_subscriber::prelude::__tracing_subscriber_SubscriberExt;

let stdout_log = tracing_subscriber::fmt::layer()
.pretty()
.with_filter(LevelFilter::DEBUG);
let subscriber = tracing_subscriber::Registry::default().with(stdout_log);
tracing::subscriber::set_global_default(subscriber)
.context("failed to set tracing global subscriber")
}

Loading…
Cancel
Save