object_tracker.py 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170
  1. #!/usr/bin/env python
  2. """
  3. object_tracker.py - Version 1.1 2013-12-20
  4. Rotate the robot left or right to follow a target published on the /roi topic.
  5. Created for the Pi Robot Project: http://www.pirobot.org
  6. Copyright (c) 2012 Patrick Goebel. All rights reserved.
  7. This program is free software; you can redistribute it and/or modify
  8. it under the terms of the GNU General Public License as published by
  9. the Free Software Foundation; either version 2 of the License, or
  10. (at your option) any later version.
  11. This program is distributed in the hope that it will be useful,
  12. but WITHOUT ANY WARRANTY; without even the implied warranty of
  13. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  14. GNU General Public License for more details at:
  15. http://www.gnu.org/licenses/gpl.html
  16. """
  17. import rospy
  18. from sensor_msgs.msg import RegionOfInterest, CameraInfo
  19. from geometry_msgs.msg import Twist
  20. import thread
  21. class ObjectTracker():
  22. def __init__(self):
  23. rospy.init_node("object_tracker")
  24. # Set the shutdown function (stop the robot)
  25. rospy.on_shutdown(self.shutdown)
  26. # How often should we update the robot's motion?
  27. self.rate = rospy.get_param("~rate", 10)
  28. r = rospy.Rate(self.rate)
  29. # The maximum rotation speed in radians per second
  30. self.max_rotation_speed = rospy.get_param("~max_rotation_speed", 2.0)
  31. # The minimum rotation speed in radians per second
  32. self.min_rotation_speed = rospy.get_param("~min_rotation_speed", 0.5)
  33. # Sensitivity to target displacements. Setting this too high
  34. # can lead to oscillations of the robot.
  35. self.gain = rospy.get_param("~gain", 2.0)
  36. # The x threshold (% of image width) indicates how far off-center
  37. # the ROI needs to be in the x-direction before we react
  38. self.x_threshold = rospy.get_param("~x_threshold", 0.1)
  39. # Publisher to control the robot's movement
  40. self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=5)
  41. # Intialize the movement command
  42. self.move_cmd = Twist()
  43. # Get a lock for updating the self.move_cmd values
  44. self.lock = thread.allocate_lock()
  45. # We will get the image width and height from the camera_info topic
  46. self.image_width = 0
  47. self.image_height = 0
  48. # Set flag to indicate when the ROI stops updating
  49. self.target_visible = False
  50. # Wait for the camera_info topic to become available
  51. rospy.loginfo("Waiting for camera_info topic...")
  52. rospy.wait_for_message('camera_info', CameraInfo)
  53. # Subscribe the camera_info topic to get the image width and height
  54. rospy.Subscriber('camera_info', CameraInfo, self.get_camera_info, queue_size=1)
  55. # Wait until we actually have the camera data
  56. while self.image_width == 0 or self.image_height == 0:
  57. rospy.sleep(1)
  58. # Subscribe to the ROI topic and set the callback to update the robot's motion
  59. rospy.Subscriber('roi', RegionOfInterest, self.set_cmd_vel, queue_size=1)
  60. # Wait until we have an ROI to follow
  61. rospy.loginfo("Waiting for messages on /roi...")
  62. rospy.wait_for_message('roi', RegionOfInterest)
  63. rospy.loginfo("ROI messages detected. Starting tracker...")
  64. # Begin the tracking loop
  65. while not rospy.is_shutdown():
  66. # Acquire a lock while we're setting the robot speeds
  67. self.lock.acquire()
  68. try:
  69. # If the target is not visible, stop the robot
  70. if not self.target_visible:
  71. self.move_cmd = Twist()
  72. else:
  73. # Reset the flag to False by default
  74. self.target_visible = False
  75. # Send the Twist command to the robot
  76. self.cmd_vel_pub.publish(self.move_cmd)
  77. finally:
  78. # Release the lock
  79. self.lock.release()
  80. # Sleep for 1/self.rate seconds
  81. r.sleep()
  82. def set_cmd_vel(self, msg):
  83. # Acquire a lock while we're setting the robot speeds
  84. self.lock.acquire()
  85. try:
  86. # If the ROI has a width or height of 0, we have lost the target
  87. if msg.width == 0 or msg.height == 0:
  88. self.target_visible = False
  89. return
  90. # If the ROI stops updating this next statement will not happen
  91. self.target_visible = True
  92. # Compute the displacement of the ROI from the center of the image
  93. target_offset_x = msg.x_offset + msg.width / 2 - self.image_width / 2
  94. try:
  95. percent_offset_x = float(target_offset_x) / (float(self.image_width) / 2.0)
  96. except:
  97. percent_offset_x = 0
  98. # Rotate the robot only if the displacement of the target exceeds the threshold
  99. if abs(percent_offset_x) > self.x_threshold:
  100. # Set the rotation speed proportional to the displacement of the target
  101. try:
  102. speed = self.gain * percent_offset_x
  103. if speed < 0:
  104. direction = -1
  105. else:
  106. direction = 1
  107. self.move_cmd.angular.z = -direction * max(self.min_rotation_speed,
  108. min(self.max_rotation_speed, abs(speed)))
  109. except:
  110. self.move_cmd = Twist()
  111. else:
  112. # Otherwise stop the robot
  113. self.move_cmd = Twist()
  114. finally:
  115. # Release the lock
  116. self.lock.release()
  117. def get_camera_info(self, msg):
  118. self.image_width = msg.width
  119. self.image_height = msg.height
  120. def shutdown(self):
  121. rospy.loginfo("Stopping the robot...")
  122. self.cmd_vel_pub.publish(Twist())
  123. rospy.sleep(1)
  124. if __name__ == '__main__':
  125. try:
  126. ObjectTracker()
  127. rospy.spin()
  128. except rospy.ROSInterruptException:
  129. rospy.loginfo("Object tracking node terminated.")