services, messages, neopixel driver

master
Drew Bednar 3 years ago
parent ac9baa5cd9
commit 2b9dffcdb1

@ -11,6 +11,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
## System dependencies are found with CMake's conventions
@ -47,18 +48,17 @@ find_package(catkin REQUIRED COMPONENTS
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
add_message_files(
FILES
Neopixel.msg
Neopixels.msg
)
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
add_service_files(
FILES
FillNeopixels.srv
)
## Generate actions in the 'action' folder
# add_action_files(
@ -68,10 +68,10 @@ find_package(catkin REQUIRED COMPONENTS
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs # Or other packages containing msgs
# )
generate_messages(
DEPENDENCIES
std_msgs # Or other packages containing msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
@ -107,6 +107,7 @@ catkin_package(
# LIBRARIES simple_example
# CATKIN_DEPENDS roscpp rospy stdmsgs
# DEPENDS system_lib
CATKIN_DEPENDS message_runtime
)
###########

@ -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

@ -37,13 +37,13 @@
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<build_depend>message_generation</build_depend>
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<exec_depend>message_runtime</exec_depend>
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->

@ -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.")

@ -33,7 +33,7 @@ def broadcaster():
global last_command
pub = rospy.Publisher("/command", String, queue_size=10)
rospy.init_node("keyb_commander", anonymous=True)
rospy.init_node("keyb_commander", anonymous=True, log_level=rospy.INFO)
rate = rospy.Rate(10)
print(msg)
@ -51,7 +51,8 @@ def broadcaster():
if command != last_command and command is not None:
print("Published command: {}".format(command))
# print("Published command: {}".format(command))
rospy.loginfo("Published command: {}".format(command))
last_command = command
if command is not None:

@ -20,7 +20,7 @@ def command_callback(message):
COMMAND_MAP.get(received_command, unknown_command)()
if received_command != last_received_command:
print("Received command: {}".format(received_command))
rospy.loginfo("Received command: {}".format(received_command))
last_received_command = received_command

@ -0,0 +1,8 @@
#request constants
#request fields
Neopixel pixel
---
#response constants
#response fields
Loading…
Cancel
Save