00001 #! /usr/bin/python 00002 #*********************************************************** 00003 # Software License Agreement (BSD License) 00004 # 00005 # Copyright (c) 2008, Willow Garage, Inc. 00006 # All rights reserved. 00007 # 00008 # Redistribution and use in source and binary forms, with or without 00009 # modification, are permitted provided that the following conditions 00010 # are met: 00011 # 00012 # * Redistributions of source code must retain the above copyright 00013 # notice, this list of conditions and the following disclaimer. 00014 # * Redistributions in binary form must reproduce the above 00015 # copyright notice, this list of conditions and the following 00016 # disclaimer in the documentation and/or other materials provided 00017 # with the distribution. 00018 # * Neither the name of the Willow Garage nor the names of its 00019 # contributors may be used to endorse or promote products derived 00020 # from this software without specific prior written permission. 00021 # 00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 # POSSIBILITY OF SUCH DAMAGE. 00034 # 00035 00036 # Author: Wim Meeussen 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: 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 angle=atan2((-sum_x*sum_y+num*sum_xy)/(num*sum_xx-sum_x*sum_x), 1) 00075 res = ScanAngle() 00076 res.header = msg.header 00077 res.scan_angle = angle 00078 self.pub.publish(res) 00079 00080 00081 00082 def main(): 00083 rospy.init_node('scan_to_angle') 00084 s = ScanToAngle() 00085 rospy.spin() 00086 00087 00088 if __name__ == '__main__': 00089 main()