]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
updated to motor controller
authorErik Andresen <erik@vontaene.de>
Fri, 14 Aug 2015 01:16:49 +0000 (01:16 +0000)
committerErik Andresen <erik@vontaene.de>
Fri, 14 Aug 2015 01:16:49 +0000 (01:16 +0000)
scripts/i2c.py
scripts/move_base.py

index 2e9a109e0fe2891175726af4e6d739958e032208..4522c5ff52e0c5b8a999f9213f5bd48c76c53c62 100755 (executable)
@@ -5,6 +5,7 @@ import threading
 import inspect
 import os
 import logging
 import inspect
 import os
 import logging
+import struct
 from ctypes import *
 from time import sleep
 
 from ctypes import *
 from time import sleep
 
@@ -62,6 +63,23 @@ class i2c:
        def __del__(self):
                self.close()
 
        def __del__(self):
                self.close()
 
+
+def i2c_write_reg(addr, reg, buf):
+       dev = i2c(addr)
+       s = struct.pack("B", reg) + buf
+       dev.write(s)
+       dev.close()
+
+
+def i2c_read_reg(addr, reg, num=1):
+       dev = i2c(addr)
+       s = struct.pack("B", reg)
+       dev.write(s)
+       s = dev.read(num)
+       dev.close()
+       return s
+
+
 if __name__ == "__main__":
        import struct
        import sys
 if __name__ == "__main__":
        import struct
        import sys
index bac2742386fd45c2c6b3e2c69bef366507835fac..fbd265fb9c6001c75879da1d0cb406ab7d110f9a 100755 (executable)
@@ -3,7 +3,7 @@
 
 import rospy
 import struct
 
 import rospy
 import struct
-from i2c import i2c
+from i2c import *
 from math import *
 from geometry_msgs.msg import Twist
 
 from math import *
 from geometry_msgs.msg import Twist
 
@@ -15,6 +15,7 @@ class MoveBase:
                rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
                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):
                self.run()
        
        def run(self):
@@ -37,8 +38,8 @@ class MoveBase:
                if right > 255: right=255
                elif right < -255: right=-255
 
                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()
 
                dev.write(s)
                dev.close()