|
|
| (23 intermediate revisions by the same user not shown) |
| Line 1: |
Line 1: |
| − | {{DISPLAYTITLE:Hamster python API}} | + | {{DISPLAYTITLE:Hamster Python API}} |
| | [[Category:Hamster]] | | [[Category:Hamster]] |
| | | | |
| Line 23: |
Line 23: |
| | </syntaxhighlight> | | </syntaxhighlight> |
| | | | |
| − | === Python Example 1 ===
| + | * Install dependencies |
| − | * Receive laser scan from robot to decide if free | |
| − | | |
| − | <syntaxhighlight lang="python" line='line'>
| |
| − | #!/usr/bin/env python
| |
| − | import rospy
| |
| − | from sensor_msgs.msg import Imu
| |
| − | | |
| − | 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')
| |
| − | | |
| − | #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 lang="bash" line='line'> |
| | + | sudo apt-get install ros-kinetic-desktop ros-kinetic-ackermann-* |
| | </syntaxhighlight> | | </syntaxhighlight> |
| | | | |
| − | === Python Example 2 === | + | === Beginner tutorials === |
| − | Detect right/left turn from IMU
| |
| − | * IMU angles are represented in Quaternions [[https://en.wikipedia.org/wiki/Quaternion]] hence translated to RPY (roll pitch yaw)
| |
| − | * RPY are in radians, translated to degrees
| |
| | | | |
| − | | + | * Exercise 1 - [https://wiki.cogni.io/index.php/HamsterPythonExample1 | Process laser Scan ] |
| − | <syntaxhighlight lang="python" line='line'>
| + | * Exercise 2 - [https://wiki.cogni.io/index.php/HamsterPythonExample2 | Process inertial measurement unit (IMU) ] |
| − | | + | * Exercise 3 - [https://wiki.cogni.io/index.php/HamsterPythonExample3 | Move until collision ] |
| − | #!/usr/bin/env python
| |
| − | import rospy
| |
| − | import math
| |
| − | from sensor_msgs.msg import Imu
| |
| − | from tf.transformations import euler_from_quaternion, quaternion_from_euler
| |
| − | | |
| − | def calculate_robot_angle(orientation):
| |
| − | quaternion = (
| |
| − | orientation.x,
| |
| − | orientation.y,
| |
| − | orientation.z,
| |
| − | orientation.w)
| |
| − | euler = euler_from_quaternion(quaternion)
| |
| − | roll = euler[0]
| |
| − | pitch = euler[1]
| |
| − | yaw = euler[2]
| |
| − | return math.degrees(yaw)
| |
| − | | |
| − | prev_angle = 0
| |
| − | def callback(msg):
| |
| − | global prev_angle
| |
| − | curr_angle = calculate_robot_angle(msg.orientation)
| |
| − | if curr_angle > prev_angle :
| |
| − | print "TURINING LEFT"
| |
| − | else:
| |
| − | print "TURINIGN RIGHT"
| |
| − | prev_angle = curr_angle
| |
| − | | |
| − | | |
| − | rospy.init_node('imu_values')
| |
| − | last_angle = 0
| |
| − | | |
| − | #Put your Hamster number instead of agent<number>
| |
| − | #The agent number is printed on the Hamster cover
| |
| − | sub = rospy.Subscriber('/agent14/imu', Imu, callback)
| |
| − | | |
| − | | |
| − | rospy.spin()
| |
| − | </syntaxhighlight>
| |
| − | | |
| − | === Python Example 3 ===
| |
| − | * Drives the robot forwards until senses from the Lidar that there is less than a meter free ahead of it | |
| − | | |
| − | <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)
| |
| − |
| |
| − | 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>
| |
</syntaxhighlight>
See imagery from the robot
<syntaxhighlight lang="bash" line='line'>
<syntaxhighlight lang="bash" line='line'>
sudo apt-get install ros-kinetic-desktop ros-kinetic-ackermann-*
</syntaxhighlight>