5 require 'wild_thumper/LedStripe'
8 def initialize(device, num_leds)
9 @spi = SPI.new(device: device)
10 @spi.driver.mode=[0b00]
14 @l = [[0, 0, 0]] * num_leds
18 def set(i, red=0, green=0, blue=0)
19 if red > 127 or green > 127 or blue > 127 or red < 0 or green < 0 or blue < 0
20 raise Exception("Bad RGB Value")
22 @l[i] = [red, green, blue]
26 @spi.xfer(txdata: (0...(@num_leds+31)/32).map { |i| 0 })
31 (0...@num_leds).each do |i|
32 red, green, blue = @l[i]
46 stripe.set(i, 10, 0, 0)
51 stripe.set(i, 0, 10, 0)
56 stripe.set(i, 0, 0, 10)
61 stripe.set(i, 0, 0, 0)
66 stripe = LPD8806.new("/dev/spidev1.0", 16)
67 node = ROS::Node.new('wild_thumper/led_stripe')
68 node.subscribe('led_stripe', Wild_thumper::LedStripe) do |msg|
69 msg.leds.each do |led|
70 stripe.set(led.num, red=led.red, green=led.green, blue=led.blue)