-
Notifications
You must be signed in to change notification settings - Fork 84
/
r2scanner.py
60 lines (47 loc) · 1.72 KB
/
r2scanner.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from sensor_msgs.msg import LaserScan
import numpy as np
class Scanner(Node):
def __init__(self):
super().__init__('scanner')
self.subscription = self.create_subscription(
LaserScan,
'scan',
self.listener_callback,
qos_profile_sensor_data)
self.subscription # prevent unused variable warning
def listener_callback(self, msg):
# create numpy array
laser_range = np.array(msg.ranges)
# replace 0's with nan
laser_range[laser_range==0] = np.nan
# find index with minimum value
lr2i = np.nanargmin(laser_range)
# log the info
self.get_logger().info('Shortest distance at %i degrees' % lr2i)
def main(args=None):
rclpy.init(args=args)
scanner = Scanner()
rclpy.spin(scanner)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
scanner.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()