]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/move_base.py
updated to motor controller
[ros_wild_thumper.git] / scripts / move_base.py
index 6886ec0cbfd69a303bcea8ff482c6aa61397ba2d..fbd265fb9c6001c75879da1d0cb406ab7d110f9a 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,11 +15,16 @@ 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)
                while not rospy.is_shutdown():
+                       #self.get_dist_forward()
+                       #self.get_dist_backward()
+                       #self.get_dist_left()
+                       #self.get_dist_right()
                        rate.sleep()
 
        def set_speed(self, left, right):
@@ -33,8 +38,8 @@ class MoveBase:
                if right > 255: right=255
                elif right < -255: right=-255
 
-               dev = i2c(0x56)
-               s = struct.pack(">Bhh", 0x1, left, right)
+               dev = i2c(0x50)
+               s = struct.pack(">Bhhhh", 0x1, right, right, left, left)
                dev.write(s)
                dev.close()
 
@@ -46,6 +51,48 @@ class MoveBase:
                left = trans*2-right
                self.set_speed(left, right)
 
+       # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
+       def get_dist_ir(self, num):
+               dev = i2c(0x52)
+               s = struct.pack("B", num)
+               dev.write(s)
+               dev.close()
+
+               sleep(2e-6)
+
+               dev = i2c(0x52)
+               s = dev.read(2)
+               dev.close()
+
+               val = struct.unpack(">H", s)[0]
+               return 15221/(val - -276.42)/100;
+       
+       def get_dist_srf(self, num):
+               dev = i2c(0x52)
+               s = struct.pack("B", num)
+               dev.write(s)
+               dev.close()
+
+               sleep(50e-3)
+
+               dev = i2c(0x52)
+               s = dev.read(2)
+               dev.close()
+
+               return struct.unpack(">H", s)[0]/1000.0
+
+       def get_dist_left(self):
+               dist = self.get_dist_ir(0x1)
+
+       def get_dist_right(self):
+                dist = self.get_dist_ir(0x3)
+
+       def get_dist_forward(self):
+               dist = self.get_dist_srf(0x5)
+
+       def get_dist_backward(self):
+               dist = self.get_dist_srf(0x7)
+
 
 if __name__ == "__main__":
        MoveBase()