follower.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 """
00004     follower.py - Version 1.1 2013-12-20
00005     
00006     Follow a "person" by tracking the nearest object in x-y-z space.
00007     
00008     Based on the follower application by Tony Pratkanis at:
00009     
00010     http://ros.org/wiki/turtlebot_follower
00011     
00012     Created for the Pi Robot Project: http://www.pirobot.org
00013     Copyright (c) 2012 Patrick Goebel.  All rights reserved.
00014 
00015     This program is free software; you can redistribute it and/or modify
00016     it under the terms of the GNU General Public License as published by
00017     the Free Software Foundation; either version 2 of the License, or
00018     (at your option) any later version.
00019     
00020     This program is distributed in the hope that it will be useful,
00021     but WITHOUT ANY WARRANTY; without even the implied warranty of
00022     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00023     GNU General Public License for more details at:
00024     
00025     http://www.gnu.org/licenses/gpl.html
00026 """
00027 
00028 import rospy
00029 from roslib import message
00030 from sensor_msgs import point_cloud2
00031 from sensor_msgs.msg import PointCloud2
00032 from geometry_msgs.msg import Twist
00033 from math import copysign
00034 
00035 class Follower():
00036     def __init__(self):
00037         rospy.init_node("follower")
00038         
00039         # Set the shutdown function (stop the robot)
00040         rospy.on_shutdown(self.shutdown)
00041         
00042         # The dimensions (in meters) of the box in which we will search
00043         # for the person (blob). These are given in camera coordinates
00044         # where x is left/right,y is up/down and z is depth (forward/backward)
00045         self.min_x = rospy.get_param("~min_x", -0.2)
00046         self.max_x = rospy.get_param("~max_x", 0.2)
00047         self.min_y = rospy.get_param("~min_y", -0.3)
00048         self.max_y = rospy.get_param("~max_y", 0.5)
00049         self.max_z = rospy.get_param("~max_z", 1.2)
00050         
00051         # The goal distance (in meters) to keep between the robot and the person
00052         self.goal_z = rospy.get_param("~goal_z", 0.6)
00053         
00054         # How far away from the goal distance (in meters) before the robot reacts
00055         self.z_threshold = rospy.get_param("~z_threshold", 0.05)
00056         
00057         # How far away from being centered (x displacement) on the person
00058         # before the robot reacts
00059         self.x_threshold = rospy.get_param("~x_threshold", 0.05)
00060         
00061         # How much do we weight the goal distance (z) when making a movement
00062         self.z_scale = rospy.get_param("~z_scale", 1.0)
00063 
00064         # How much do we weight left/right displacement of the person when making a movement        
00065         self.x_scale = rospy.get_param("~x_scale", 2.5)
00066         
00067         # The maximum rotation speed in radians per second
00068         self.max_angular_speed = rospy.get_param("~max_angular_speed", 2.0)
00069         
00070         # The minimum rotation speed in radians per second
00071         self.min_angular_speed = rospy.get_param("~min_angular_speed", 0.0)
00072         
00073         # The max linear speed in meters per second
00074         self.max_linear_speed = rospy.get_param("~max_linear_speed", 0.3)
00075         
00076         # The minimum linear speed in meters per second
00077         self.min_linear_speed = rospy.get_param("~min_linear_speed", 0.1)
00078         
00079         # Slow down factor when stopping
00080         self.slow_down_factor = rospy.get_param("~slow_down_factor", 0.8)
00081         
00082         # Initialize the movement command
00083         self.move_cmd = Twist()
00084 
00085         # Publisher to control the robot's movement
00086         self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=5)
00087 
00088         # Subscribe to the point cloud
00089         self.depth_subscriber = rospy.Subscriber('point_cloud', PointCloud2, self.set_cmd_vel, queue_size=1)
00090 
00091         rospy.loginfo("Subscribing to point cloud...")
00092         
00093         # Wait for the pointcloud topic to become available
00094         rospy.wait_for_message('point_cloud', PointCloud2)
00095 
00096         rospy.loginfo("Ready to follow!")
00097         
00098     def set_cmd_vel(self, msg):
00099         # Initialize the centroid coordinates point count
00100         x = y = z = n = 0
00101 
00102         # Read in the x, y, z coordinates of all points in the cloud
00103         for point in point_cloud2.read_points(msg, skip_nans=True):
00104             pt_x = point[0]
00105             pt_y = point[1]
00106             pt_z = point[2]
00107             
00108             # Keep only those points within our designated boundaries and sum them up
00109             if -pt_y > self.min_y and -pt_y < self.max_y and pt_x < self.max_x and pt_x > self.min_x and pt_z < self.max_z:
00110                 x += pt_x
00111                 y += pt_y
00112                 z += pt_z
00113                 n += 1
00114         
00115        # If we have points, compute the centroid coordinates
00116         if n:
00117             x /= n 
00118             y /= n 
00119             z /= n
00120             
00121             # Check our movement thresholds
00122             if (abs(z - self.goal_z) > self.z_threshold):
00123                 # Compute the angular component of the movement
00124                 linear_speed = (z - self.goal_z) * self.z_scale
00125                 
00126                 # Make sure we meet our min/max specifications
00127                 self.move_cmd.linear.x = copysign(max(self.min_linear_speed, 
00128                                         min(self.max_linear_speed, abs(linear_speed))), linear_speed)
00129             else:
00130                 self.move_cmd.linear.x *= self.slow_down_factor
00131                 
00132             if (abs(x) > self.x_threshold):     
00133                 # Compute the linear component of the movement
00134                 angular_speed = -x * self.x_scale
00135                 
00136                 # Make sure we meet our min/max specifications
00137                 self.move_cmd.angular.z = copysign(max(self.min_angular_speed, 
00138                                         min(self.max_angular_speed, abs(angular_speed))), angular_speed)
00139             else:
00140                 # Stop the rotation smoothly
00141                 self.move_cmd.angular.z *= self.slow_down_factor
00142                 
00143         else:
00144             # Stop the robot smoothly
00145             self.move_cmd.linear.x *= self.slow_down_factor
00146             self.move_cmd.angular.z *= self.slow_down_factor
00147             
00148         # Publish the movement command
00149         self.cmd_vel_pub.publish(self.move_cmd)
00150 
00151         
00152     def shutdown(self):
00153         rospy.loginfo("Stopping the robot...")
00154         
00155         # Unregister the subscriber to stop cmd_vel publishing
00156         self.depth_subscriber.unregister()
00157         rospy.sleep(1)
00158         
00159         # Send an emtpy Twist message to stop the robot
00160         self.cmd_vel_pub.publish(Twist())
00161         rospy.sleep(1)        
00162                    
00163 if __name__ == '__main__':
00164     try:
00165         Follower()
00166         rospy.spin()
00167     except rospy.ROSInterruptException:
00168         rospy.loginfo("Follower node terminated.")


gapter
Author(s):
autogenerated on Thu Jun 6 2019 22:05:13