It is one of the simplest library for raw working with GPIO with ROS2. Based on lgpio
library for linux systems.
It service only 3 operations:
read_bit
- read digital (boolean) signal value on pin.write_bit
- write didital (boolean) value in pin.write_pwm
- set software Pulse-Width Modulation (frequency
+duty
) pin output.
You can configure every pin (input or output, mode flags) only one time (at first access) per ROS node runtime. On futher access operations, passed mode flags will be ignored
Input operation support pre-pulling modes (pull up, pull down).
Output operations supports OD/OS modes, and signal inversion (see below).
OPEN_SOURCE
OPEN_DRAIN
ACTIVE_LOW
(inversion)
Can be explained by this simple electrical schematics for output pin:
VDD
|
OD ||--+
+--/ ---o|| P-MOS-FET
| ||--+
IN --+ +----- out
| ||--+
+--/ ----|| N-MOS-FET
OS ||--+
|
GND
Install python3-lgpio
manually, because rosdep
don't know about this package for now:
sudo apt install python3-lgpio
or install latest version manually from:
https://github.com/joan2937/lg/tree/master
Install packets:
# Suppose that your ROS2 home path is ~/ros2_ws/
cd ~/ros2_ws/src
git clone https://github.com/AndreyTulyakov/ros2_easy_gpio.git
cd ~/ros2_ws
colcon build --symlink-install --packages-select easy_gpio_interfaces
colcon build --symlink-install --packages-select easy_gpio
source install/local_setup.bash
Use your GPIO device chip pin numbering (for example Raspberry PI - broadcom (BCM) chip numbering).
ros2 run easy_gpio gpio_node
-
Read from pin 12 (floating)
# Example: connect pin to external pulled device or line ros2 service call /gpio/read_bit easy_gpio_interfaces/ReadBit "pin: 12"
-
Read from pin 12 (pre-pulled UP):
# Example: connect pin button to ground ros2 service call /gpio/read_bit easy_gpio_interfaces/ReadBit "{pin: 12, pull: UP}"
-
Read from pin 12 (pre-pulled DOWN):
# Example: connect pin button to compatible VCC ros2 service call /gpio/read_bit easy_gpio_interfaces/ReadBit "{pin: 12, pull: DOWN}"
-
Write bit to pin 12:
# Be sure, that pin not connected to heavy load (< 10-30mA) ros2 service call /gpio/write_bit easy_gpio_interfaces/WriteBit "{pin: 12, value: 1}"
-
Write bit to pin 12 with open drain configured:
ros2 service call /gpio/write_bit easy_gpio_interfaces/WriteBit "{pin: 12, value: 1, mode: OPEN_DRAIN}"
-
Write bit to pin 12 with open source configured:
ros2 service call /gpio/write_bit easy_gpio_interfaces/WriteBit "{pin: 12, value: 1, mode: OPEN_SOURCE}"
-
Write bit to pin 12 with open source and inverted configured:
ros2 service call /gpio/write_bit easy_gpio_interfaces/WriteBit "{pin: 12, value: 0, mode: OPEN_SOURCE|ACTIVE_LOW }"
-
Setup PWM signal on pin 12 with 1/4 duty at 1000hz:
ros2 service call /gpio/write_pwm easy_gpio_interfaces/WritePWM "{pin: 12, frequency: 1000, duty: 25}"
Response with empty error
string indicates success.