]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/move_base.py
added test_speed script
[ros_wild_thumper.git] / scripts / move_base.py
index bac2742386fd45c2c6b3e2c69bef366507835fac..5ece2683f6d0ad31cee0dd0cebfd9efdb95b26e2 100755 (executable)
@@ -3,7 +3,7 @@
 
 import rospy
 import struct
-from i2c import i2c
+from i2c import *
 from math import *
 from geometry_msgs.msg import Twist
 
@@ -15,17 +15,24 @@ class MoveBase:
                rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
+               i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
                self.run()
        
        def run(self):
-               rate = rospy.Rate(10.0)
+               rate = rospy.Rate(20.0)
                while not rospy.is_shutdown():
+                       self.get_pos()
                        #self.get_dist_forward()
                        #self.get_dist_backward()
                        #self.get_dist_left()
                        #self.get_dist_right()
                        rate.sleep()
 
+       def get_pos(self):
+               s = i2c_read_reg(0x50, 0x10, 8)
+               hall1, hall2, hall3, hall4 = struct.unpack(">hhhh", s)
+               print hall1, hall2, hall3, hall4
+
        def set_speed(self, left, right):
                if left > 0: left+=80
                elif left < 0: left-=80
@@ -37,10 +44,7 @@ class MoveBase:
                if right > 255: right=255
                elif right < -255: right=-255
 
-               dev = i2c(0x56)
-               s = struct.pack(">Bhh", 0x1, left, right)
-               dev.write(s)
-               dev.close()
+               i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", right, right, left, left))
 
        def cmdVelReceived(self, msg):
                trans = msg.linear.x