+++ /dev/null
-#!/usr/bin/env python
-# -*- coding: iso-8859-15 -*-
-
-import sys
-import struct
-from time import sleep
-from i2c import i2c_write_reg, i2c_read_reg
-
-
-def set(trans, rot):
- i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
-
-if __name__ == "__main__":
- set(float(sys.argv[1]), float(sys.argv[2]))
- while True:
- speed1, speed2, speed3, speed4 = struct.unpack(">hhhh", i2c_read_reg(0x50, 0x30, 8))
- print speed1, speed2, speed3, speed4
- sleep(0.1)
self.cmd_vel = None
self.set_speed(0, 0)
rospy.loginfo("Init done")
+ i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
self.handicap_last = (-1, -1)
self.pStripe = LPD8806(1, 0, 12)
rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
+ rospy.Subscriber("imu", Imu, self.imuReceived)
rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
self.run()
self.cmd_vel = None
rate.sleep()
+ def set_motor_handicap(self, front, aft): # percent
+ if front > 100: front = 100
+ if aft > 100: aft = 100
+ if self.handicap_last != (front, aft):
+ i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
+ self.handicap_last = (front, aft)
+
+ def imuReceived(self, msg):
+ (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
+ if pitch > 30*pi/180:
+ val = (100.0/60)*abs(pitch)*180/pi
+ self.set_motor_handicap(int(val), 0)
+ elif pitch < -30*pi/180:
+ val = (100.0/60)*abs(pitch)*180/pi
+ self.set_motor_handicap(0, int(val))
+ else:
+ self.set_motor_handicap(0, 0)
+
def get_reset(self):
reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]