services, messages, neopixel driver
parent
ac9baa5cd9
commit
2b9dffcdb1
@ -0,0 +1,6 @@
|
||||
<launch>
|
||||
<group ns="simple_example1">
|
||||
<node pkg="simple_example" name="command_node" type="command_node.py" output="screen"/>
|
||||
<node pkg="simple_example" name="drive_node" type="drive_node.py" output="screen" />
|
||||
</group>
|
||||
</launch>
|
@ -0,0 +1,4 @@
|
||||
uint8 r
|
||||
uint8 g
|
||||
uint8 b
|
||||
uint8 w
|
@ -0,0 +1 @@
|
||||
Neopixel[] pixels
|
@ -0,0 +1,37 @@
|
||||
#!/usr/bin/env python3
|
||||
import rospy
|
||||
|
||||
from serial import Serial
|
||||
|
||||
from simple_example.msg import Neopixel, Neopixels
|
||||
from simple_example.srv import FillNeopixels, FillNeopixelsResponse
|
||||
|
||||
|
||||
class NeopixelDriverNode:
|
||||
"""ROS Node for controllering NeoPixels."""
|
||||
|
||||
def __init__(self):
|
||||
self._msg = Neopixels()
|
||||
self.pixel_count = rospy.get_param('/simple_example/pixel_count', 1)
|
||||
self.port = rospy.get_param('/simple_example/port', "/dev/ttyUSB0")
|
||||
self.serial = Serial(self.port, 115200, timeout=1)
|
||||
|
||||
def listen(self):
|
||||
rospy.init_node("light_ctrl", anonymous=True)
|
||||
rospy.Subscriber("/neopixel", Neopixels, self.neopixel_ctrl_callback)
|
||||
rate = rospy.spin()
|
||||
|
||||
def neopixel_ctrl_callback(self, data):
|
||||
cmds = ""
|
||||
for i, pixel in data.pixels:
|
||||
cmds += f"{i},{pixel.r},{pixel.g},{pixel.b};"
|
||||
cmds += "\n"
|
||||
rospy.logdebug(f"Sending: {cmds}")
|
||||
self.serial.write(cmds.encode("ascii"))
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
rospy.loginfo("Firing up neopixel driver.")
|
||||
node = NeopixelDriverNode()
|
||||
node.listen()
|
||||
rospy.loginfo("Neopixel driver is shutting down.")
|
@ -0,0 +1,8 @@
|
||||
#request constants
|
||||
|
||||
#request fields
|
||||
Neopixel pixel
|
||||
---
|
||||
#response constants
|
||||
|
||||
#response fields
|
Loading…
Reference in New Issue