Difference between revisions of "HamsterPythonExample3"
(Created page with "=== Python Example 3 === File:VID_20190319_171636.mp4 * The Hamster robot is a Ackermann steering system https://en.wikipedia.org/wiki/Ackermann_steering_geometry *...") |
|||
Line 54: | Line 54: | ||
$ python example3.py | $ python example3.py | ||
</syntaxhighlight> | </syntaxhighlight> | ||
+ | |||
+ | == Ex 3 == | ||
+ | * change this program to continue moving while trying to avoid obstacles |
Latest revision as of 09:18, 24 March 2019
Python Example 3
- The Hamster robot is a Ackermann steering system [[1]]
- This example drives the robot forward until it senses from the Lidar that there is less than a meter free ahead of it
- Motion commands should be usually published at 10Hz.
- If no motion command arrives to the robot after a second (10 messages period) the robot will stop
- Hence we send an empty message (with speed 0) to stop the robot immediately once the area is blocked ahead of it, otherwise it would stop closer to the obstacle due to the delay
<syntaxhighlight lang="python" line='line'>
- !/usr/bin/env python
import rospy from sensor_msgs.msg import LaserScan from ackermann_msgs.msg import AckermannDriveStamped
pub = rospy.Publisher('/agent14/ackermann_cmd',AckermannDriveStamped, queue_size=1)
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):
global pub
if is_free(msg.ranges,160,200,1):
ack_msg = AckermannDriveStamped()
ack_msg.header.stamp = rospy.Time.now()
ack_msg.header.frame_id = 'your_frame_here'
ack_msg.drive.steering_angle = 0
ack_msg.drive.speed = 1
pub.publish(ack_msg)
else:
ack_msg = AckermannDriveStamped()
pub.publish(ack_msg)
rospy.init_node('driving_hamster')
- 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()
</syntaxhighlight>
To execute save this example in example3.py and type in the terminal
<syntaxhighlight lang="bash" line='line'>
$ python example3.py
</syntaxhighlight>
Ex 3
- change this program to continue moving while trying to avoid obstacles