Browse Source

Updated scan filter script.

pull/1/head
Alan Sanchez 3 years ago
parent
commit
336def46df
1 changed files with 19 additions and 21 deletions
  1. +19
    -21
      src/scan_filter.py

+ 19
- 21
src/scan_filter.py View File

@ -9,35 +9,30 @@ from sensor_msgs.msg import LaserScan
class Scanfilter:
def __init__(self):
# We're going to assume that the robot is pointing up the x-axis, so that
# We're going to assume that the robot is pointing up the x-axis, so that any points with y coordinates further
# than half a robot width from the axis are not in front of the robot.
self.extent = .5 / 2.0
# any points with y coordinates further than half of the defined
# width (1 meter) from the axis are not considered.
self.width = 1
self.extent = self.width / 2.0
# Set up a subscriber. We're going to subscribe to the topic "counter",
# looking for Int64 messages. When a message comes in, ROS is going to pass
# it to the function "callback" automatically.
# Set up a subscriber. We're going to subscribe to the topic "scan",
# looking for LaserScan messages. When a message comes in, ROS is going
# to pass it to the function "callback" automatically.
self.sub = rospy.Subscriber('/scan', LaserScan, self.callback)
self.pub = rospy.Publisher('filtered_scan', LaserScan, queue_size=10)
# Set up a publisher. This will publish on a topic called "filtered_scan",
# with a LaserScan message type.
self.pub = rospy.Publisher('filtered_scan', LaserScan, queue_size=10)
def callback(self,msg):
# print('Minimum scan value = ' + str(len(msg.ranges)))
#
# center_index = len(msg.ranges)/3
# rospy.sleep(1)
"""
:param self: Self reference.
:param msg: LaserScan message.
"""
# Figure out the angles of the scan. We're going to do this each time, in case we're subscribing to more than one
# laser, with different numbers of beams.
angles = linspace(msg.angle_min, msg.angle_max, len(msg.ranges))
# # Work out the y coordinates of the ranges.
# Work out the y coordinates of the ranges.
points = [r * sin(theta) if (theta < -2.5 or theta > 2.5) else inf for r,theta in zip(msg.ranges, angles)]
#
# If we're close to the x axis, keep the range, otherwise use inf, which means "no return".
new_ranges = [r if abs(y) < self.extent else inf for r,y in zip(msg.ranges, points)]
@ -46,10 +41,13 @@ class Scanfilter:
self.pub.publish(msg)
if __name__ == '__main__':
# Initialize the node, and call it "move".
# Initialize the node, and call it "scan_filter".
rospy.init_node('scan_filter')
# Setup Move class to base_motion
Scan()
# Setup Scanfilter class
Scanfilter()
# Give control to ROS. This will allow the callback to be called whenever new
# messages come in. If we don't put this line in, then the node will not work,
# and ROS will not process any messages.
rospy.spin()

Loading…
Cancel
Save