X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=dfa69b0c6e2a2d097c57d78cc23b2a7343527764;hp=f7b02f5b009626e9a6dc90544705ed9c1287fd08;hb=94f542d3b9d61a8d609b14bb45deef3d2a22e7da;hpb=5288ffaa49480c1a4d556a288fb4bc38bfb88d97 diff --git a/scripts/wt_node.py b/scripts/wt_node.py index f7b02f5..dfa69b0 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -15,40 +15,10 @@ from nav_msgs.msg import Odometry from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue from dynamic_reconfigure.server import Server from sensor_msgs.msg import Imu, Range, BatteryState -from wild_thumper.msg import LedStripe from wild_thumper.cfg import WildThumperConfig WHEEL_DIST = 0.248 -class LPD8806: - def __init__(self, bus, device, num_leds): - self.spi = spidev.SpiDev() - self.spi.open(bus, device) - self.spi.mode=0b00 - self.spi.max_speed_hz=int(2e6) - self.num_leds = num_leds - self.latch() - self.l = [(0, 0, 0)] * num_leds - self.update() - - def set(self, i, red=0, green=0, blue=0): - if red > 127 or green > 127 or blue > 127 or red < 0 or green < 0 or blue < 0: - raise Exception("Bad RGB Value") - self.l[i] = (red, green, blue) - - def latch(self): - self.spi.writebytes([0x0 for i in range((self.num_leds+31)/32)]) - - def update(self): - l = [] - for i in range(self.num_leds): - red, green, blue = self.l[i] - l.append(0x80 | green) - l.append(0x80 | red) - l.append(0x80 | blue) - self.spi.writebytes(l) - self.latch() - class WTBase: def __init__(self): rospy.init_node('wild_thumper') @@ -74,9 +44,7 @@ class WTBase: self.volt_last_warn = rospy.Time.now() rospy.loginfo("Init done") i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction - self.pStripe = LPD8806(1, 0, 16) rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived) - rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received) rospy.Subscriber("imu", Imu, self.imuReceived) self.bDocked = False self.bDocked_last = False @@ -370,11 +338,6 @@ class WTBase: if self.pub_range_fwd_right.get_num_connections() > 0: self.start_dist_srf(0xb) - def led_stripe_received(self, msg): - for led in msg.leds: - self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue) - self.pStripe.update() - def check_docked(self): if self.bDocked and not self.bDocked_last: rospy.loginfo("Docking event")