Difference between revisions of "HamsterPython"

From cogniteam
Jump to: navigation, search
(Python Example 2)
 
(28 intermediate revisions by the same user not shown)
Line 1: Line 1:
 +
{{DISPLAYTITLE:Hamster Python API}}
 +
[[Category:Hamster]]
 +
 
=== Python setup ===
 
=== Python setup ===
* Note you are on the HamsterNet
+
* Note you are connected to the hamster_net (wifi / router)
  
 
<syntaxhighlight lang="bash" line='line'>
 
<syntaxhighlight lang="bash" line='line'>
Line 10: Line 13:
 
</syntaxhighlight>
 
</syntaxhighlight>
  
 +
* If the Hamster is powered and your terminal is well configured you should be able to
 +
See all data streams
 +
<syntaxhighlight lang="bash" line='line'>
 +
$ rostopic list
 +
</syntaxhighlight>
 +
See imagery from the robot
 +
<syntaxhighlight lang="bash" line='line'>
 +
$ rqt_image_view
 +
</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
 
 
 
 
 
<syntaxhighlight lang="python" line='line'>
 
 
 
#!/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>
 
  
=== Example 3 ===
+
* Exercise 1 - [https://wiki.cogni.io/index.php/HamsterPythonExample1 | Process laser Scan ]
 +
* 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 ]

Latest revision as of 09:21, 24 March 2019


Python setup

  • Note you are connected to the hamster_net (wifi / router)

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

$ export ROS_IP=<your IP>

</syntaxhighlight>

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

$ export ROS_MASTER_URI=http://10.0.2.<HAMSTER AGENT Number>:11311

</syntaxhighlight>

  • If the Hamster is powered and your terminal is well configured you should be able to

See all data streams <syntaxhighlight lang="bash" line='line'>

$ rostopic list

</syntaxhighlight> See imagery from the robot <syntaxhighlight lang="bash" line='line'>

$ rqt_image_view

</syntaxhighlight>

  • Install dependencies

<syntaxhighlight lang="bash" line='line'> sudo apt-get install ros-kinetic-desktop ros-kinetic-ackermann-* </syntaxhighlight>

Beginner tutorials