Difference between revisions of "HamsterPython"

From cogniteam
Jump to: navigation, search
(Created page with "Test")
 
Line 1: Line 1:
Test
+
#!/usr/bin/env python
 +
import rospy
 +
from sensor_msgs.msg import LaserScan
 +
 
 +
def is_free(ranges ,start_index, end_index ,min_distance):
 +
s_ranges = ranges[start_index:end_index]
 +
b_ranges = [i for i in s_ranges if i <= min_distance]
 +
if len(b_ranges) > 1 :print "BLOCKED"
 +
else : print "FREE"
 +
 
 +
 +
def callback(msg):    
 +
is_free(msg.ranges,160,200,0.2)
 +
 +
rospy.init_node('scan_values')
 +
 
 +
#Put your Hamster number instead of agent<number>
 +
#The agent number is printed on the Hamster cover
 +
sub = rospy.Subscriber('/agent14/scan', LaserScan, callback)
 +
 
 +
 
 +
rospy.spin()

Revision as of 13:34, 19 March 2019

  1. !/usr/bin/env python

import rospy from sensor_msgs.msg import LaserScan

def is_free(ranges ,start_index, end_index ,min_distance): s_ranges = ranges[start_index:end_index] b_ranges = [i for i in s_ranges if i <= min_distance] if len(b_ranges) > 1 :print "BLOCKED" else : print "FREE"


def callback(msg): is_free(msg.ranges,160,200,0.2)

rospy.init_node('scan_values')

  1. Put your Hamster number instead of agent<number>
  2. The agent number is printed on the Hamster cover

sub = rospy.Subscriber('/agent14/scan', LaserScan, callback)


rospy.spin()