From 94f542d3b9d61a8d609b14bb45deef3d2a22e7da Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Thu, 27 Sep 2018 21:14:56 +0200 Subject: [PATCH] Move led stripe out of wt_node into own node in ruby --- scripts/ledstripe.rb | 79 ++++++++++++++++++++++++++++++++++++++++++++ scripts/wt_node.py | 37 --------------------- 2 files changed, 79 insertions(+), 37 deletions(-) create mode 100755 scripts/ledstripe.rb diff --git a/scripts/ledstripe.rb b/scripts/ledstripe.rb new file mode 100755 index 0000000..9f4119e --- /dev/null +++ b/scripts/ledstripe.rb @@ -0,0 +1,79 @@ +#!/usr/bin/env ruby + +require "spi" +require "ros" +require 'wild_thumper/LedStripe' + +class LPD8806 + def initialize(device, num_leds) + @spi = SPI.new(device: device) + @spi.driver.mode=[0b00] + @spi.speed=2e6 + @num_leds = num_leds + self.latch() + @l = [[0, 0, 0]] * num_leds + self.update() + end + + def set(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") + end + @l[i] = [red, green, blue] + end + + def latch + @spi.xfer(txdata: (0...(@num_leds+31)/32).map { |i| 0 }) + end + + def update + l = [] + (0...@num_leds).each do |i| + red, green, blue = @l[i] + l.push(0x80 | green) + l.push(0x80 | red) + l.push(0x80 | blue) + end + @spi.xfer(txdata: l) + self.latch() + end +end + +if __FILE__ == $0 + def test + puts "Starting.." + (0...16).each do |i| + stripe.set(i, 10, 0, 0) + stripe.update() + sleep(0.1) + end + (0...16).each do |i| + stripe.set(i, 0, 10, 0) + stripe.update() + sleep(0.1) + end + (0...16).each do |i| + stripe.set(i, 0, 0, 10) + stripe.update() + sleep(0.1) + end + (0...16).each do |i| + stripe.set(i, 0, 0, 0) + end + stripe.update() + end + + stripe = LPD8806.new("/dev/spidev1.0", 16) + node = ROS::Node.new('wild_thumper/led_stripe') + node.subscribe('led_stripe', Wild_thumper::LedStripe) do |msg| + msg.leds.each do |led| + stripe.set(led.num, red=led.red, green=led.green, blue=led.blue) + stripe.update() + end + end + + while node.ok? + node.spin_once + sleep(1) + end +end 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") -- 2.39.5