You can not select more than 25 topics Topics must start with a chinese character,a letter or number, can include dashes ('-') and can be up to 35 characters long.

random_turtle.py 1.7 kB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162
  1. #!/usr/bin/env python
  2. # -*- coding: utf-8 -*-
  3. import dora
  4. from dora import Node
  5. CHECK_TICK = 50
  6. # Create a ROS2 Context
  7. ros2_context = dora.experimental.ros2_bridge.Ros2Context()
  8. ros2_node = ros2_context.new_node(
  9. "turtle_teleop",
  10. "/ros2_demo",
  11. dora.experimental.ros2_bridge.Ros2NodeOptions(rosout=True),
  12. )
  13. # Define a ROS2 QOS
  14. topic_qos = dora.experimental.ros2_bridge.Ros2QosPolicies(
  15. reliable=True, max_blocking_time=0.1
  16. )
  17. # Create a publisher to cmd_vel topic
  18. turtle_twist_topic = ros2_node.create_topic(
  19. "/turtle1/cmd_vel", "geometry_msgs::Twist", topic_qos
  20. )
  21. twist_writer = ros2_node.create_publisher(turtle_twist_topic)
  22. # Create a listener to pose topic
  23. turtle_pose_topic = ros2_node.create_topic(
  24. "/turtle1/pose", "turtlesim::Pose", topic_qos
  25. )
  26. pose_reader = ros2_node.create_subscription(turtle_pose_topic)
  27. # Create a dora node
  28. dora_node = Node()
  29. # Listen for both stream on the same loop as Python does not handle well multiprocessing
  30. dora_node.merge_external_events(pose_reader)
  31. print("looping", flush=True)
  32. for i in range(500):
  33. event = dora_node.next()
  34. if event is None:
  35. break
  36. event_kind = event["kind"]
  37. # Dora event
  38. if event_kind == "dora":
  39. event_type = event["type"]
  40. if event_type == "INPUT":
  41. event_id = event["id"]
  42. if event_id == "direction":
  43. twist_writer.publish(event["value"])
  44. # ROS2 Event
  45. elif event_kind == "external":
  46. pose = event.inner()[0].as_py()
  47. if i == CHECK_TICK:
  48. assert (
  49. pose["x"] != 5.544444561004639
  50. ), "turtle should not be at initial x axis"
  51. dora_node.send_output("turtle_pose", event.inner())