dummy_scan.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 ## @author Hiroaki Yaguchi JSK
4 
5 import rospy
6 import tf
7 import math
8 import numpy
9 from sensor_msgs.msg import LaserScan
10 from nav_msgs.msg import OccupancyGrid, MapMetaData
11 
12 # [INFO] [WallTime: 1508148230.485155] msg:
13 # [INFO] [WallTime: 1508148230.485310] angle_min: -1.57079637051
14 # [INFO] [WallTime: 1508148230.485466] angle_max: 1.57079637051
15 # [INFO] [WallTime: 1508148230.485623] angle_increment: 0.00436332309619
16 # [INFO] [WallTime: 1508148230.485770] time_increment: 1.73611151695e-05
17 # [INFO] [WallTime: 1508148230.485927] scan_time: 0.0250000003725
18 # [INFO] [WallTime: 1508148230.486063] size(ranges): 721
19 # [INFO] [WallTime: 1508148230.486205] approx. size: 721
20 #range_min: 0.019999999553
21 #range_max: 30.0
22 
23 ## @brief publiush dummy scan range
24 class DummyScan:
25  def __init__(self):
26  self.pub = rospy.Publisher('scan', LaserScan, queue_size = 1)
27  self.tf_listener = tf.TransformListener()
28 
29  self.pi2 = math.pi * 2
30  self.pih = math.pi / 2
31  self.laser_height = 0.2344
32  self.mapgrid_list = []
33 
34  # emurate URG
35  self.scan = LaserScan()
36  self.scan.header.frame_id = 'wheels_base_laser_link'
37  self.scan.angle_min = -1.57079637051
38  self.scan.angle_max = 1.57079637051
39  self.scan.angle_increment = 0.00436332309619
40  self.scan.time_increment = 1.73611151695e-05
41  self.scan.scan_time = 0.0250000003725
42  self.scan.range_min = 0.019999999553
43  self.scan.range_max = 30.0
44  # ranges_size = 721
45  self.ranges_size = int(1.0 +
46  (self.scan.angle_max - self.scan.angle_min)
47  / self.scan.angle_increment)
48 
49  # subscribe map once
50  self.sub_map = rospy.Subscriber('map', OccupancyGrid,
51  self.map_to_points)
52 
53  ## @brief make constant range, if map and tf have not been recieved
55  for i in range(self.ranges_size):
56  self.scan.ranges.append(10.0)
57 
58  ## @brief map to points
59  ## @param msg nav_msgs/OccupancyGrid
60  def map_to_points(self, msg):
61  map_info = msg.info
62  cr = math.cos(math.acos(map_info.origin.orientation.w) * 2.0)
63  sr = math.sqrt(1.0 - cr * cr)
64  self.mapgrid_list = []
65  for y in range(map_info.height):
66  yidx = y * map_info.width
67  my = y * map_info.resolution + map_info.origin.position.y
68  for x in range(map_info.width):
69  val = msg.data[x + yidx]
70  if val >= 90:
71  mx = x * map_info.resolution + map_info.origin.position.x
72  pt = numpy.array([mx * cr - my * sr,
73  mx * sr + my * cr,
74  self.laser_height])
75  self.mapgrid_list.append(pt)
76  # if recievved once unregister
77  self.sub_map.unregister()
78 
79  ## @brief make range data from map and current pose
80  def make_map_range(self):
81  laser_pos = (0, 0, 0)
82  laser_theta = 0
83  try:
84  t = rospy.Time()
85  laser_pos, null = self.tf_listener.lookupTransform(
86  '/map',
87  'wheels_base_laser_link',
88  t)
89  # tf orientation is screwed up, calculate from base->laser
90  base_pos, null = self.tf_listener.lookupTransform(
91  '/map',
92  'base_link',
93  t)
94  laser_theta = math.atan2(laser_pos[1] - base_pos[1], laser_pos[0] - base_pos[0])
95  except (Exception):
96  None
97 
98  if len(self.mapgrid_list) < 0:
99  # create constant range if map has not been revieved yet
100  self.make_constant_range()
101  else:
102  self.scan.ranges = []
103  for i in range(self.ranges_size):
104  self.scan.ranges.append(0.0)
105 
106  for mp in self.mapgrid_list:
107  lx = mp[0] - laser_pos[0]
108  ly = mp[1] - laser_pos[1]
109  lrange = math.sqrt(lx * lx + ly * ly)
110  ltheta = math.atan2(ly, lx) - laser_theta
111  if ltheta > math.pi:
112  ltheta = ltheta - self.pi2
113  elif ltheta < -math.pi:
114  ltheta = ltheta + self.pi2
115 
116  if ltheta >= self.scan.angle_min and ltheta <= self.scan.angle_max:
117  li = int((ltheta - self.scan.angle_min) / self.scan.angle_increment)
118  if self.scan.ranges[li] < 1e-5:
119  self.scan.ranges[li] = lrange
120  elif self.scan.ranges[li] > lrange:
121  self.scan.ranges[li] = lrange
122 
123  # @brief create and publish range data
124  def publish(self):
125  self.make_map_range()
126  self.scan.header.stamp = rospy.get_rostime()
127  self.pub.publish(self.scan)
128 
129 if __name__ == '__main__':
130  rospy.init_node('dummy_scan', anonymous = True)
131  dummy_scan = DummyScan()
132 
133  rate = rospy.Rate(40)
134  while not rospy.is_shutdown():
135  dummy_scan.publish()
136  rate.sleep()
def make_constant_range(self)
make constant range, if map and tf have not been recieved
Definition: dummy_scan.py:54
def map_to_points(self, msg)
map to points
Definition: dummy_scan.py:60
publiush dummy scan range
Definition: dummy_scan.py:24
def __init__(self)
Definition: dummy_scan.py:25
def make_map_range(self)
make range data from map and current pose
Definition: dummy_scan.py:80


noid_mover_navigation
Author(s):
autogenerated on Sat Jul 20 2019 03:44:22