9 from sensor_msgs.msg
import LaserScan
10 from nav_msgs.msg
import OccupancyGrid, MapMetaData
26 self.
pub = rospy.Publisher(
'scan', LaserScan, queue_size = 1)
29 self.
pi2 = math.pi * 2
30 self.
pih = math.pi / 2
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
46 (self.scan.angle_max - self.scan.angle_min)
47 / self.scan.angle_increment)
50 self.
sub_map = rospy.Subscriber(
'map', OccupancyGrid,
56 self.scan.ranges.append(10.0)
62 cr = math.cos(math.acos(map_info.origin.orientation.w) * 2.0)
63 sr = math.sqrt(1.0 - cr * cr)
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]
71 mx = x * map_info.resolution + map_info.origin.position.x
72 pt = numpy.array([mx * cr - my * sr,
75 self.mapgrid_list.append(pt)
77 self.sub_map.unregister()
85 laser_pos, null = self.tf_listener.lookupTransform(
87 'wheels_base_laser_link',
90 base_pos, null = self.tf_listener.lookupTransform(
94 laser_theta = math.atan2(laser_pos[1] - base_pos[1], laser_pos[0] - base_pos[0])
102 self.scan.ranges = []
104 self.scan.ranges.append(0.0)
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
112 ltheta = ltheta - self.
pi2 113 elif ltheta < -math.pi:
114 ltheta = ltheta + self.
pi2 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
126 self.scan.header.stamp = rospy.get_rostime()
127 self.pub.publish(self.
scan)
129 if __name__ ==
'__main__':
130 rospy.init_node(
'dummy_scan', anonymous =
True)
133 rate = rospy.Rate(40)
134 while not rospy.is_shutdown():
def make_constant_range(self)
make constant range, if map and tf have not been recieved
def map_to_points(self, msg)
map to points
publiush dummy scan range
def make_map_range(self)
make range data from map and current pose