import inspect
import os
import logging
+import struct
from ctypes import *
from time import sleep
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
import rospy
import struct
-from i2c import i2c
+from i2c import *
from math import *
from geometry_msgs.msg import Twist
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):
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()