Difference between revisions of "HamsterPythonExample1"

From cogniteam
Jump to: navigation, search
(Scan)
 
Line 5: Line 5:
 
#!/usr/bin/env python
 
#!/usr/bin/env python
 
import rospy
 
import rospy
from sensor_msgs.msg import Imu
+
from sensor_msgs.msg import LaserScan
  
 
def is_free(ranges ,start_index, end_index ,min_distance):
 
def is_free(ranges ,start_index, end_index ,min_distance):

Latest revision as of 09:12, 20 June 2019

Python Example 1

  • Receive laser scan from robot to decide if free

<syntaxhighlight lang="python" line='line'>

  1. !/usr/bin/env python

import rospy from sensor_msgs.msg import LaserScan

def is_free(ranges ,start_index, end_index ,min_distance): #sub array from angle to angle s_ranges = ranges[start_index:end_index] #filter the array b_ranges = filter(lambda x: x <= min_distance, s_ranges) return len(b_ranges) == 0


def callback(msg): if is_free(msg.ranges,160,200,0.2): print "FREE" else: print "BLOCKED"

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()

</syntaxhighlight>

To execute save this example in example1.py and type in the terminal

<syntaxhighlight lang="bash" line='line'>

$ python example1.py

</syntaxhighlight>

Ex. 1

  • Put the hamster in front of a planar obstacle and save a file with readings of distances to that plane
  • Calculate the average noise of the range scanner (take into account the angle of the reading)
  • Add filtering to remove peaks in the laser scan readings at each angle taking into account possible noise