Skip to content

Commit 91aa1a3

Browse files
Add mimic tutorial
1 parent 6180c0a commit 91aa1a3

File tree

2 files changed

+55
-0
lines changed

2 files changed

+55
-0
lines changed

examples/turtlesim_rs/Cargo.toml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,10 @@ path = "src/turtlesim.rs"
1818
name = "turtle_teleop_key"
1919
path = "tutorials/turtle_teleop_key.rs"
2020

21+
[[bin]]
22+
name = "mimic"
23+
path = "tutorials/mimic.rs"
24+
2125
[dependencies.rclrs]
2226
version = "0.4"
2327

Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
use rclrs::{Context, Node, Publisher, Subscription, QOS_PROFILE_DEFAULT};
2+
use std::env;
3+
use std::sync::Arc;
4+
5+
#[allow(unused)]
6+
struct Mimic {
7+
output_nh: Arc<Node>,
8+
input_nh: Arc<Node>,
9+
twist_pub: Arc<Publisher<geometry_msgs::msg::Twist>>,
10+
pose_sub: Arc<Subscription<turtlesim_rs_msgs::msg::Pose>>,
11+
}
12+
13+
impl Mimic {
14+
fn new() -> Self {
15+
let context = Context::new(env::args()).unwrap();
16+
let output_nh = rclrs::create_node(&context, "output").unwrap();
17+
18+
let twist_pub = output_nh
19+
.create_publisher("/output/cmd_vel", QOS_PROFILE_DEFAULT)
20+
.unwrap();
21+
22+
let input_nh = rclrs::create_node(&context, "input").unwrap();
23+
24+
let twist_pub_clone = Arc::clone(&twist_pub);
25+
let pose_sub = input_nh
26+
.create_subscription(
27+
"/input/pose",
28+
QOS_PROFILE_DEFAULT,
29+
move |pose_msg: turtlesim_rs_msgs::msg::Pose| {
30+
let mut twist_msg = geometry_msgs::msg::Twist::default();
31+
twist_msg.linear.x = pose_msg.linear_velocity as f64;
32+
twist_msg.angular.z = pose_msg.angular_velocity as f64;
33+
twist_pub_clone.publish(twist_msg).unwrap();
34+
},
35+
)
36+
.unwrap();
37+
38+
Self {
39+
output_nh,
40+
input_nh,
41+
twist_pub,
42+
pose_sub,
43+
}
44+
}
45+
}
46+
47+
fn main() -> Result<(), rclrs::RclrsError> {
48+
let mimic = Mimic::new();
49+
rclrs::spin(mimic.input_nh.clone())?;
50+
Ok(())
51+
}

0 commit comments

Comments
 (0)