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.9 kB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970
  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. # take track of minimum and maximum coordinates of turtle
  33. min_x = 1000
  34. max_x = 0
  35. min_y = 1000
  36. max_y = 0
  37. for i in range(500):
  38. event = dora_node.next()
  39. if event is None:
  40. break
  41. event_kind = event["kind"]
  42. # Dora event
  43. if event_kind == "dora":
  44. event_type = event["type"]
  45. if event_type == "INPUT":
  46. event_id = event["id"]
  47. if event_id == "direction":
  48. twist_writer.publish(event["value"])
  49. # ROS2 Event
  50. elif event_kind == "external":
  51. pose = event.inner()[0].as_py()
  52. min_x = min([min_x, pose["x"]])
  53. max_x = max([max_x, pose["x"]])
  54. min_y = min([min_y, pose["y"]])
  55. max_y = max([max_y, pose["y"]])
  56. dora_node.send_output("turtle_pose", event.inner())
  57. assert max_x - min_x > 1 or max_y - min_y > 1, "no turtle movement"