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

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