Browse Source

Migrate example into `examples` folder

tags/v0.2.5-alpha.2
haixuanTao 2 years ago
parent
commit
37b2ce4d7f
4 changed files with 38 additions and 30 deletions
  1. +1
    -0
      Cargo.toml
  2. +37
    -0
      examples/python-dataflow/random_turtle.py
  3. +0
    -0
      examples/rust-standalone-bridge/random_turtle.rs
  4. +0
    -30
      python/random_turtle.py

+ 1
- 0
Cargo.toml View File

@@ -8,6 +8,7 @@ edition = "2021"

[[example]]
name = "random_turtle"
path = "examples/rust-standalone-bridge/random_turtle.rs"
required-features = ["ros2-examples"]

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


+ 37
- 0
examples/python-dataflow/random_turtle.py View File

@@ -0,0 +1,37 @@
import time, random
from dora_ros2_bridge import *
from dora import Node

node = Node()
context = Ros2Context()
node = context.new_node("turtle_teleop", "/ros2_demo", Ros2NodeOptions(rosout=True))

topic_qos = Ros2QosPolicies(reliable=True, max_blocking_time=0.1)

turtle_twist_topic = node.create_topic(
"/turtle1/cmd_vel", "geometry_msgs::Twist", topic_qos
)
twist_writer = node.create_publisher(turtle_twist_topic)

turtle_pose_topic = node.create_topic("/turtle1/pose", "turtlesim::Pose", topic_qos)
pose_reader = node.create_subscription(turtle_pose_topic)

for event in node:
match event["type"]:
case "INPUT":
match event["id"]:
case "direction":
direction = {
"linear": {
"x": event["data"][0],
},
"angular": {
"z": event["data"][5],
},
}
twist_writer.publish(direction)
case "tick":
pose = pose_reader.next()
if pose == None:
break
node.send_output(pose)

examples/random_turtle.rs → examples/rust-standalone-bridge/random_turtle.rs View File


+ 0
- 30
python/random_turtle.py View File

@@ -1,30 +0,0 @@
from dora_ros2_bridge import *
import time, random

context = Ros2Context()
node = context.new_node("turtle_teleop", "/ros2_demo", Ros2NodeOptions(rosout = True))

topic_qos = Ros2QosPolicies(reliable = True, max_blocking_time = 0.1)

turtle_twist_topic = node.create_topic("/turtle1/cmd_vel", "geometry_msgs::Twist", topic_qos)
twist_writer = node.create_publisher(turtle_twist_topic)

turtle_pose_topic = node.create_topic("/turtle1/pose", "turtlesim::Pose", topic_qos)
pose_reader = node.create_subscription(turtle_pose_topic)

for i in range(500):
direction = {
'linear': {
'x': random.random() + 1,
},
'angular': {
'z': (random.random() - 0.5) * 5,
}
}
twist_writer.publish(direction);
while True:
pose = pose_reader.next()
if pose == None:
break
print(pose)
time.sleep(0.5)

Loading…
Cancel
Save