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
00030
00031
00032
00033
00034
00035
00036
00037
00038 from __future__ import with_statement
00039
00040 import roslib; roslib.load_manifest('turtlebot_calibration')
00041 import yaml
00042 import rospy
00043 from sensor_msgs.msg import LaserScan
00044 from turtlebot_calibration.msg import ScanAngle
00045 from math import *
00046
00047
00048 class ScanToAngle:
00049 def __init__(self):
00050 self.min_angle = rospy.get_param('min_angle', -0.3)
00051 self.max_angle = rospy.get_param('max_angle', 0.3)
00052 self.pub = rospy.Publisher('scan_angle', ScanAngle)
00053 self.sub = rospy.Subscriber('scan', LaserScan, self.scan_cb)
00054
00055
00056 def scan_cb(self, msg):
00057 angle = msg.angle_min
00058 d_angle = msg.angle_increment
00059 sum_x = 0
00060 sum_y = 0
00061 sum_xx = 0
00062 sum_xy = 0
00063 num = 0
00064 for r in msg.ranges:
00065 if angle > self.min_angle and angle < self.max_angle and r < msg.range_max:
00066 x = sin(angle) * r
00067 y = cos(angle) * r
00068 sum_x += x
00069 sum_y += y
00070 sum_xx += x*x
00071 sum_xy += x*y
00072 num += 1
00073 angle += d_angle
00074 if num > 0:
00075 angle=atan2((-sum_x*sum_y+num*sum_xy)/(num*sum_xx-sum_x*sum_x), 1)
00076 res = ScanAngle()
00077 res.header = msg.header
00078 res.scan_angle = angle
00079 self.pub.publish(res)
00080 else:
00081 rospy.logerr("Please point me at a wall.")
00082
00083 def main():
00084 rospy.init_node('scan_to_angle')
00085 s = ScanToAngle()
00086 rospy.spin()
00087
00088
00089 if __name__ == '__main__':
00090 main()