Raspberry Pi 4 setup:
sudo apt update
sudo apt upgrade
sudo raspi-config
enable VNC 1080p resolution
expand filesystem
enable SPI
#Increasing Swap because this RPI has only 2gb of memory\
sudo dphys-swapfile swapoff
sudo nano /etc/dphys-swapfile
CONF_SWAPSIZE=2048
sudo dphys-swapfile setup
sudo dphys-swapfile swapon
sudo reboot
Setting up Docker:
curl -fsSL https://get.docker.com -o get-docker.sh
sudo sh ./get-docker.sh
sudo docker run -it ros:iron-ros-core #use --privileged to use spi and gpio
sudo docker rename e8b9c16b0544 ROS-TEST
sudo docker exec -ti ROS-TEST /bin/bash
apt update
apt install apt-utils nano whiptail apt install python3-colcon-common-extensions python3-rosdep
python3 -m pip install gpiozero
apt upgrade
mkdir -p ~/colcon_venv/src
cd ~/colcon_venv/
# Make a virtual env and activate it
#apt install python3.10-venv #from raspberry pi
#python3 -m venv env #from raspberry pi
#Modified from ROS
virtualenv -p python3 --system-site-packages ./rosvenv
source ./rosvenv/bin/activate
#Make sure that colcon doesn’t try to build the venv
touch ./rosvenv/COLCON_IGNORE
pip install gpiozero adafruit-circuitpython-mcp3xxx
Building a package:
~/colcon_venv/src# ros2 pkg create --build-type ament_python --license Apache-2.0 CustomController
#Warnings thrown:/usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools.
#setuptools version 59.6.0
ROS Build
#Modify /root/colcon_venv/src/control_package/control_package/control_node.py with codes below.
colcon build --packages-select control_package
source install/local_setup.bash
ros2 run control_package control_node
Docker reentry
sudo docker start existing_container_ID_or_name
sudo docker exec -it existing_container_ID_or_name /bin/bash
3D printed Controller on the workbench:
Custom Pi Hat:
The joystick has 3 analog outputs. These run through an
MCP3008.
ANALOG:
- Up/down is chan1,
- Left/Right is chan2
- Twist is chan0.
#!/usr/bin/env python3
#ROS2
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Joy
from std_msgs.msg import String
#RaspberryPi
import RPi.GPIO
#from gpiozero import MCP3008, Button
import adafruit_mcp3xxx.mcp3008 as MCP
from adafruit_mcp3xxx.analog_in import AnalogIn
import busio
import digitalio
import board
import time
def gpio_callback(data, channels, pub):
# Process GPIO inputs here
analog_values = [mcp[i].value for i in range(3)]
# Display the input values
print(f"Analog Inputs (MCP3008): {analog_values}")
def main():
rclpy.init()
# Set up MCP3008 on SPI0 with CE0 as the chip select
# create the spi bus
spi = busio.SPI(clock=board.SCK, MISO=board.MISO, MOSI=board.MOSI)
# create the cs (chip select)
cs = digitalio.DigitalInOut(board.D24)
# create the mcp object
mcp = MCP.MCP3008(spi, cs)
#gpio0 mcp = [MCP3008(channel=i) for i in range(3)]
# define the channel pins
channel_pins = [MCP.P0, MCP.P1, MCP.P2]
# create an array of analog input channels
channels = [AnalogIn(mcp, pin) for pin in channel_pins]
# iterate over the channels
for channel, chan in enumerate(channels):
print(f'Raw ADC Value (Channel {channel}): ', chan.value)
print(f'ADC Voltage (Channel {channel}): {chan.voltage}V')
print()
node = rclpy.create_node('joy_publisher')
# create a Joy publisher
joy_publisher = node.create_publisher(Joy, 'joy', 10)
# set the publishing rate
publish_rate = 1 # 1 Hz
timer_period = 1.0 / publish_rate
def publish_joy():
# create a Joy message
joy_msg = Joy()
# iterate over the channels and add readings to the axes
for channel, chan in enumerate(channels):
joy_msg.axes.append(chan.value)
# publish the Joy message
joy_publisher.publish(joy_msg)
timer = node.create_timer(timer_period, publish_joy)
rclpy.spin(node)
# shutdown when done
node.destroy_node()
rclpy.shutdown()
print("DONE!")
if __name__ == '__main__':
main()
This was the first input challenge. It took all day to get the RPI/Docker/ROS to cooperate. It looks like my twist is wired backward and it tampers with other readings when i bring it high.
DIGITAL:
- Joystick button
- D-Pad
- Up
- Down
- Left
- Right
- Center
- Rotary Encoder
import RPi.GPIO as GPIO
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Joy
from std_msgs.msg import Header
from builtin_interfaces.msg import Time
from adafruit_mcp3xxx.analog_in import AnalogIn
import adafruit_mcp3xxx.mcp3008 as MCP
import busio
import digitalio
import board
import time
class JoyPublisherNode(Node):
def __init__(self):
super().__init__('joy_publisher')
# Set up MCP3008 on SPI0 with CE0 as the chip select
spi = busio.SPI(clock=board.SCK, MISO=board.MISO, MOSI=board.MOSI)
cs = digitalio.DigitalInOut(board.D24)
mcp = MCP.MCP3008(spi, cs)
# Define the channel pins
channel_pins = [MCP.P0, MCP.P1, MCP.P2]
self.channels = [AnalogIn(mcp, pin) for pin in channel_pins]
# Define GPIO pins for buttons
self.button_pins = [12, 26, 17, 27, 22, 4]
GPIO.setmode(GPIO.BCM)
GPIO.setup(self.button_pins, GPIO.IN, pull_up_down=GPIO.PUD_UP)
# Define GPIO pins for rotary encoder
self.encoder_pin_a = 19 # CW
self.encoder_pin_b = 13 # DT - these might need to be switched
GPIO.setup(self.encoder_pin_a, GPIO.IN, pull_up_down=GPIO.PUD_UP)
GPIO.setup(self.encoder_pin_b, GPIO.IN, pull_up_down=GPIO.PUD_UP)
GPIO.add_event_detect(self.encoder_pin_a, GPIO.BOTH, callback=self.encoder_callback)
# Create a Joy publisher
self.joy_publisher = self.create_publisher(Joy, 'joy', 10)
# Set the publishing rate
publish_rate = 1 # 1 Hz
timer_period = 1.0 / publish_rate
self.timer = self.create_timer(timer_period, self.publish_joy)
self.last_encoder_state = GPIO.input(self.encoder_pin_a)
self.encoder_counter = 0 # Initialize the encoder counter
def publish_joy(self):
# Create a Joy message
joy_msg = Joy()
joy_msg.header = Header()
joy_msg.header.stamp = self.get_clock().now().to_msg()
joy_msg.header.frame_id = 'base_link'
# Read analog inputs
joy_msg.axes.extend([chan.value for chan in self.channels])
# Read button states
joy_msg.buttons.extend(GPIO.input(button_pin) for button_pin in self.button_pins)
# No rotation initially
joy_msg.axes.append(self.encoder_counter)
# Publish the Joy message
self.joy_publisher.publish(joy_msg)
def encoder_callback(self, channel):
# Callback function for rotary encoder
a_state = GPIO.input(self.encoder_pin_a)
b_state = GPIO.input(self.encoder_pin_b)
if a_state != self.last_encoder_state:
if b_state != a_state:
self.last_encoder_state = a_state
# Counter-clockwise rotation
self.publish_encoder_rotation(-1.0)
else:
self.last_encoder_state = a_state
# Clockwise rotation
self.publish_encoder_rotation(1.0)
def publish_encoder_rotation(self, rotation):
# Create a Joy message for rotary encoder
joy_msg = Joy()
joy_msg.header = Header()
joy_msg.header.stamp = self.get_clock().now().to_msg()
joy_msg.header.frame_id = 'base_link'
# Read analog inputs
joy_msg.axes.extend([chan.value for chan in self.channels])
# Read button states
joy_msg.buttons.extend(GPIO.input(button_pin) for button_pin in self.button_pins)
# Update the encoder counter based on rotation direction
if rotation > 0:
self.encoder_counter += 15
elif rotation < 0:
self.encoder_counter -= 15
# Set axes for rotary encoder
joy_msg.axes.append(self.encoder_counter)
# Publish the Joy message
self.joy_publisher.publish(joy_msg)
def main():
rclpy.init()
joy_publisher_node = JoyPublisherNode()
rclpy.spin(joy_publisher_node)
joy_publisher_node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
I had problems with the twist joystick impacting the other potentiometers. This was because my particular stick had the colors off from what I expected.
As you can see, the resistance across the red-black was 5k, not 10k.
Below you can see, that I found the full resistance. I used red as 3.3V, white to ground, and black as the signal.