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

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465
  1. #!/usr/bin/env python
  2. # -*- coding: utf-8 -*-
  3. from dora import Node, Ros2Context, Ros2NodeOptions, Ros2QosPolicies
  4. CHECK_TICK = 50
  5. # Create a ROS2 Context
  6. ros2_context = Ros2Context()
  7. ros2_node = ros2_context.new_node(
  8. "turtle_teleop",
  9. "/ros2_demo",
  10. Ros2NodeOptions(rosout=True),
  11. )
  12. # Define a ROS2 QOS
  13. topic_qos = Ros2QosPolicies(reliable=True, max_blocking_time=0.1)
  14. # Create a publisher to cmd_vel topic
  15. turtle_twist_topic = ros2_node.create_topic(
  16. "/turtle1/cmd_vel", "geometry_msgs/Twist", topic_qos
  17. )
  18. twist_writer = ros2_node.create_publisher(turtle_twist_topic)
  19. # Create a listener to pose topic
  20. turtle_pose_topic = ros2_node.create_topic("/turtle1/pose", "turtlesim/Pose", topic_qos)
  21. pose_reader = ros2_node.create_subscription(turtle_pose_topic)
  22. # Create a dora node
  23. dora_node = Node()
  24. # Listen for both stream on the same loop as Python does not handle well multiprocessing
  25. dora_node.merge_external_events(pose_reader)
  26. print("looping", flush=True)
  27. # take track of minimum and maximum coordinates of turtle
  28. min_x = 1000
  29. max_x = 0
  30. min_y = 1000
  31. max_y = 0
  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["value"][0].as_py()
  47. min_x = min([min_x, pose["x"]])
  48. max_x = max([max_x, pose["x"]])
  49. min_y = min([min_y, pose["y"]])
  50. max_y = max([max_y, pose["y"]])
  51. dora_node.send_output("turtle_pose", event["value"])
  52. assert max_x - min_x > 1 or max_y - min_y > 1, "no turtle movement"