Main Page
Namespaces
Classes
Files
File List
src
turtlebot_calibration
scan_to_angle.py
Go to the documentation of this file.
1
#! /usr/bin/python
2
#***********************************************************
3
# Software License Agreement (BSD License)
4
#
5
# Copyright (c) 2008, Willow Garage, Inc.
6
# All rights reserved.
7
#
8
# Redistribution and use in source and binary forms, with or without
9
# modification, are permitted provided that the following conditions
10
# are met:
11
#
12
# * Redistributions of source code must retain the above copyright
13
# notice, this list of conditions and the following disclaimer.
14
# * Redistributions in binary form must reproduce the above
15
# copyright notice, this list of conditions and the following
16
# disclaimer in the documentation and/or other materials provided
17
# with the distribution.
18
# * Neither the name of the Willow Garage nor the names of its
19
# contributors may be used to endorse or promote products derived
20
# from this software without specific prior written permission.
21
#
22
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
# POSSIBILITY OF SUCH DAMAGE.
34
#
35
36
# Author: Wim Meeussen
37
38
from
__future__
import
with_statement
39
40
import
roslib; roslib.load_manifest(
'turtlebot_calibration'
)
41
import
yaml
42
import
rospy
43
from
sensor_msgs.msg
import
LaserScan
44
from
turtlebot_calibration.msg
import
ScanAngle
45
from
math
import
*
46
47
48
class
ScanToAngle
:
49
def
__init__
(self):
50
self.
min_angle
= rospy.get_param(
'min_angle'
, -0.3)
51
self.
max_angle
= rospy.get_param(
'max_angle'
, 0.3)
52
self.
pub
= rospy.Publisher(
'scan_angle'
, ScanAngle)
53
self.
sub
= rospy.Subscriber(
'scan'
, LaserScan, self.
scan_cb
)
54
55
56
def
scan_cb
(self, msg):
57
angle = msg.angle_min
58
d_angle = msg.angle_increment
59
sum_x = 0
60
sum_y = 0
61
sum_xx = 0
62
sum_xy = 0
63
num = 0
64
for
r
in
msg.ranges:
65
if
angle > self.
min_angle
and
angle < self.
max_angle
and
r < msg.range_max:
66
x = sin(angle) * r
67
y = cos(angle) * r
68
sum_x += x
69
sum_y += y
70
sum_xx += x*x
71
sum_xy += x*y
72
num += 1
73
angle += d_angle
74
if
num > 0:
75
angle=atan2((-sum_x*sum_y+num*sum_xy)/(num*sum_xx-sum_x*sum_x), 1)
76
res = ScanAngle()
77
res.header = msg.header
78
res.scan_angle = angle
79
self.pub.publish(res)
80
else
:
81
rospy.logerr(
"Please point me at a wall."
)
82
83
def
main
():
84
rospy.init_node(
'scan_to_angle'
)
85
s =
ScanToAngle
()
86
rospy.spin()
87
88
89
if
__name__ ==
'__main__'
:
90
main
()
scan_to_angle.ScanToAngle
Definition:
scan_to_angle.py:48
scan_to_angle.ScanToAngle.max_angle
max_angle
Definition:
scan_to_angle.py:51
scan_to_angle.main
def main()
Definition:
scan_to_angle.py:83
scan_to_angle.ScanToAngle.__init__
def __init__(self)
Definition:
scan_to_angle.py:49
scan_to_angle.ScanToAngle.scan_cb
def scan_cb(self, msg)
Definition:
scan_to_angle.py:56
scan_to_angle.ScanToAngle.sub
sub
Definition:
scan_to_angle.py:53
scan_to_angle.ScanToAngle.min_angle
min_angle
Definition:
scan_to_angle.py:50
scan_to_angle.ScanToAngle.pub
pub
Definition:
scan_to_angle.py:52
turtlebot_calibration
Author(s): Wim Meeussen
autogenerated on Mon Jun 10 2019 15:44:05