diff --git a/.rustfmt.toml b/.rustfmt.toml
new file mode 100755
index 0000000..230ec33
--- /dev/null
+++ b/.rustfmt.toml
@@ -0,0 +1,2 @@
+imports_granularity = "Crate"
+
diff --git a/your_package_name/Cargo.toml b/your_package_name/Cargo.toml
new file mode 100755
index 0000000..68e49d1
--- /dev/null
+++ b/your_package_name/Cargo.toml
@@ -0,0 +1,15 @@
+[package]
+name = "your_package_name"
+version = "0.1.0"
+edition = "2021"
+
+# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html
+[[bin]]
+name="simple_publisher"
+path="src/simple_publisher.rs"
+[[bin]]
+name="simple_subscriber"
+path="src/simple_subscriber.rs"
+[dependencies]
+rclrs = "*"
+std_msgs = "*"
diff --git a/your_package_name/package.xml b/your_package_name/package.xml
new file mode 100755
index 0000000..b7aa0df
--- /dev/null
+++ b/your_package_name/package.xml
@@ -0,0 +1,14 @@
+
+ your_project_name
+ 0.0.0
+ TODO: Package description. Seriously. Please make a Package description. We all will thank for it.
+ user
+ TODO: License declaration. Licenses are Great. Please add a Licence
+
+ rclrs
+ std_msgs
+
+
+ ament_cargo
+
+
diff --git a/your_package_name/src/simple_publisher.rs b/your_package_name/src/simple_publisher.rs
new file mode 100755
index 0000000..8316d4f
--- /dev/null
+++ b/your_package_name/src/simple_publisher.rs
@@ -0,0 +1,69 @@
+use rclrs::{create_node, Context, Node, Publisher, RclrsError, QOS_PROFILE_DEFAULT};
+/// Creates a SimplePublisherNode, initializes a node and publisher, and provides
+/// methods to publish a simple "Hello World" message on a loop in separate threads.
+
+/// Imports the Arc type from std::sync, used for thread-safe reference counting pointers,
+/// and the StringMsg message type from std_msgs for publishing string messages.
+use std::{sync::Arc, thread, time::Duration};
+use std_msgs::msg::String as StringMsg;
+// / SimplePublisherNode struct contains node and publisher members.
+// / Used to initialize a ROS 2 node and publisher, and publish messages.
+struct SimplePublisherNode {
+ node: Arc,
+ _publisher: Arc>,
+}
+/// The `new` function takes a context and returns a Result containing the
+/// initialized SimplePublisherNode or an error. It creates a node with the
+/// given name and creates a publisher on the "publish_hello" topic.
+///
+/// The SimplePublisherNode contains the node and publisher members.
+impl SimplePublisherNode {
+ /// Creates a new SimplePublisherNode by initializing a node and publisher.
+ ///
+ /// This function takes a context and returns a Result containing the
+ /// initialized SimplePublisherNode or an error. It creates a node with the
+ /// given name and creates a publisher on the "publish_hello" topic.
+ ///
+ /// The SimplePublisherNode contains the node and publisher members.
+ fn new(context: &Context) -> Result {
+ let node = create_node(context, "simple_publisher").unwrap();
+ let _publisher = node
+ .create_publisher("publish_hello", QOS_PROFILE_DEFAULT)
+ .unwrap();
+ Ok(Self { node, _publisher })
+ }
+
+ /// Publishes a "Hello World" message on the publisher.
+ ///
+ /// Creates a StringMsg with "Hello World" as the data, publishes it on
+ /// the `_publisher`, and returns a Result. This allows regularly publishing
+ /// a simple message on a loop.
+ fn publish_data(&self, increment: i32) -> Result {
+ let msg: StringMsg = StringMsg {
+ data: format!("Hello World {}", increment),
+ };
+ self._publisher.publish(msg).unwrap();
+ Ok(increment + 1_i32)
+ }
+}
+
+/// The main function initializes a ROS 2 context, node and publisher,
+/// spawns a thread to publish messages repeatedly, and spins the node
+/// to receive callbacks.
+///
+/// It creates a context, initializes a SimplePublisherNode which creates
+/// a node and publisher, clones the publisher to pass to the thread,
+/// spawns a thread to publish "Hello World" messages repeatedly, and
+/// calls spin() on the node to receive callbacks. This allows publishing
+/// messages asynchronously while spinning the node.
+fn main() -> Result<(), RclrsError> {
+ let context = Context::new(std::env::args()).unwrap();
+ let publisher = Arc::new(SimplePublisherNode::new(&context).unwrap());
+ let publisher_other_thread = Arc::clone(&publisher);
+ let mut count: i32 = 0;
+ thread::spawn(move || loop {
+ thread::sleep(Duration::from_millis(1000));
+ count = publisher_other_thread.publish_data(count).unwrap();
+ });
+ rclrs::spin(publisher.node.clone())
+}
diff --git a/your_package_name/src/simple_subscriber.rs b/your_package_name/src/simple_subscriber.rs
new file mode 100755
index 0000000..befda23
--- /dev/null
+++ b/your_package_name/src/simple_subscriber.rs
@@ -0,0 +1,63 @@
+use rclrs::{create_node, Context, Node, RclrsError, Subscription, QOS_PROFILE_DEFAULT};
+use std::{
+ env,
+ sync::{Arc, Mutex},
+ thread,
+ time::Duration,
+};
+use std_msgs::msg::String as StringMsg;
+/// A simple ROS2 subscriber node that receives and prints "hello" messages.
+///
+/// This node creates a subscription to the "publish_hello" topic and prints the
+/// received messages to the console. It runs the subscription in a separate
+/// thread, while the main thread calls `rclrs::spin()` to keep the node running.
+pub struct SimpleSubscriptionNode {
+ node: Arc,
+ _subscriber: Arc>,
+ data: Arc>>,
+}
+/// Implements a simple ROS2 subscriber node that receives and prints "hello" messages.
+/// The `new` function creates the node and the subscription, and returns a `SimpleSubscriptionNode`
+/// instance. The `data_callback` function can be used to access the latest received message.
+impl SimpleSubscriptionNode {
+ fn new(context: &Context) -> Result {
+ let node = create_node(context, "simple_subscription").unwrap();
+ let data: Arc>> = Arc::new(Mutex::new(None));
+ let data_mut: Arc>> = Arc::clone(&data);
+ let _subscriber = node
+ .create_subscription::(
+ "publish_hello",
+ QOS_PROFILE_DEFAULT,
+ move |msg: StringMsg| {
+ *data_mut.lock().unwrap() = Some(msg);
+ },
+ )
+ .unwrap();
+ Ok(Self {
+ node,
+ _subscriber,
+ data,
+ })
+ }
+ fn data_callback(&self) -> Result<(), RclrsError> {
+ if let Some(data) = self.data.lock().unwrap().as_ref() {
+ println!("{}", data.data);
+ } else {
+ println!("No message available yet.");
+ }
+ Ok(())
+ }
+}
+/// The `main` function creates a new ROS2 context, a `SimpleSubscriptionNode` instance, and starts a separate thread to periodically call the `data_callback` method on the subscription. The main thread then calls `rclrs::spin()` to keep the node running and receive messages.
+///
+/// The separate thread is used to ensure that the `data_callback` method is called regularly, even if the main thread is blocked in `rclrs::spin()`. This allows the subscriber to continuously process and print the received "hello" messages.
+fn main() -> Result<(), RclrsError> {
+ let context = Context::new(env::args()).unwrap();
+ let subscription = Arc::new(SimpleSubscriptionNode::new(&context).unwrap());
+ let subscription_other_thread = Arc::clone(&subscription);
+ thread::spawn(move || loop {
+ thread::sleep(Duration::from_millis(1000));
+ subscription_other_thread.data_callback().unwrap()
+ });
+ rclrs::spin(subscription.node.clone())
+}