Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 """
00029 ROS node for Neato XV-11 Robot Vacuum.
00030 """
00031
00032 __author__ = "ferguson@cs.albany.edu (Michael Ferguson)"
00033
00034 import roslib; roslib.load_manifest("neato_node")
00035 import rospy
00036 from math import sin,cos
00037
00038 from sensor_msgs.msg import LaserScan
00039 from geometry_msgs.msg import Quaternion
00040 from geometry_msgs.msg import Twist
00041 from nav_msgs.msg import Odometry
00042 from tf.broadcaster import TransformBroadcaster
00043
00044 from neato_driver import xv11, BASE_WIDTH, MAX_SPEED
00045
00046 class NeatoNode:
00047
00048 def __init__(self):
00049 """ Start up connection to the Neato Robot. """
00050 rospy.init_node('neato')
00051
00052 self.port = rospy.get_param('~port', "/dev/ttyUSB0")
00053 rospy.loginfo("Using port: %s"%(self.port))
00054
00055 self.robot = xv11(self.port)
00056
00057 rospy.Subscriber("cmd_vel", Twist, self.cmdVelCb)
00058 self.scanPub = rospy.Publisher('base_scan', LaserScan)
00059 self.odomPub = rospy.Publisher('odom',Odometry)
00060 self.odomBroadcaster = TransformBroadcaster()
00061
00062 self.cmd_vel = [0,0]
00063
00064 def spin(self):
00065 encoders = [0,0]
00066
00067 self.x = 0
00068 self.y = 0
00069 self.th = 0
00070 then = rospy.Time.now()
00071
00072
00073 scan_link = rospy.get_param('~frame_id','base_laser_link')
00074 scan = LaserScan(header=rospy.Header(frame_id=scan_link))
00075 scan.angle_min = 0
00076 scan.angle_max = 6.26
00077 scan.angle_increment = 0.017437326
00078 scan.range_min = 0.020
00079 scan.range_max = 5.0
00080 odom = Odometry(header=rospy.Header(frame_id="odom"), child_frame_id='base_link')
00081
00082
00083 r = rospy.Rate(5)
00084 self.robot.requestScan()
00085 while not rospy.is_shutdown():
00086
00087 scan.header.stamp = rospy.Time.now()
00088
00089 scan.ranges = self.robot.getScanRanges()
00090
00091
00092 left, right = self.robot.getMotors()
00093
00094
00095 self.robot.setMotors(self.cmd_vel[0], self.cmd_vel[1], max(abs(self.cmd_vel[0]),abs(self.cmd_vel[1])))
00096
00097
00098 self.robot.requestScan()
00099
00100
00101 dt = (scan.header.stamp - then).to_sec()
00102 then = scan.header.stamp
00103
00104 d_left = (left - encoders[0])/1000.0
00105 d_right = (right - encoders[1])/1000.0
00106 encoders = [left, right]
00107
00108 dx = (d_left+d_right)/2
00109 dth = (d_right-d_left)/(BASE_WIDTH/1000.0)
00110
00111 x = cos(dth)*dx
00112 y = -sin(dth)*dx
00113 self.x += cos(self.th)*x - sin(self.th)*y
00114 self.y += sin(self.th)*x + cos(self.th)*y
00115 self.th += dth
00116
00117
00118 quaternion = Quaternion()
00119 quaternion.z = sin(self.th/2.0)
00120 quaternion.w = cos(self.th/2.0)
00121
00122
00123 odom.header.stamp = rospy.Time.now()
00124 odom.pose.pose.position.x = self.x
00125 odom.pose.pose.position.y = self.y
00126 odom.pose.pose.position.z = 0
00127 odom.pose.pose.orientation = quaternion
00128 odom.twist.twist.linear.x = dx/dt
00129 odom.twist.twist.angular.z = dth/dt
00130
00131
00132 self.odomBroadcaster.sendTransform( (self.x, self.y, 0), (quaternion.x, quaternion.y, quaternion.z, quaternion.w),
00133 then, "base_link", "odom" )
00134 self.scanPub.publish(scan)
00135 self.odomPub.publish(odom)
00136
00137
00138 r.sleep()
00139
00140
00141 self.robot.setLDS("off")
00142 self.robot.setTestMode("off")
00143
00144 def cmdVelCb(self,req):
00145 x = req.linear.x * 1000
00146 th = req.angular.z * (BASE_WIDTH/2)
00147 k = max(abs(x-th),abs(x+th))
00148
00149 if k > MAX_SPEED:
00150 x = x*MAX_SPEED/k; th = th*MAX_SPEED/k
00151 self.cmd_vel = [ int(x-th) , int(x+th) ]
00152
00153 if __name__ == "__main__":
00154 robot = NeatoNode()
00155 robot.spin()
00156