refactor: switch from libgpiod C++ bindings to C API; update GPIO handling and memory management
parent
82cf1cb48e
commit
5db4bb8420
|
|
@ -10,9 +10,9 @@ find_package(ament_cmake REQUIRED)
|
||||||
find_package(rclcpp REQUIRED)
|
find_package(rclcpp REQUIRED)
|
||||||
find_package(blockly_interfaces REQUIRED)
|
find_package(blockly_interfaces REQUIRED)
|
||||||
|
|
||||||
# libgpiod C++ bindings (via pkg-config)
|
# libgpiod C API (via pkg-config)
|
||||||
find_package(PkgConfig REQUIRED)
|
find_package(PkgConfig REQUIRED)
|
||||||
pkg_check_modules(GPIOD REQUIRED libgpiodcxx)
|
pkg_check_modules(GPIOD REQUIRED libgpiod)
|
||||||
|
|
||||||
add_executable(gpio_node
|
add_executable(gpio_node
|
||||||
src/main.cpp
|
src/main.cpp
|
||||||
|
|
|
||||||
|
|
@ -1,11 +1,10 @@
|
||||||
#ifndef GPIO_NODE__GPIO_NODE_HPP_
|
#ifndef GPIO_NODE__GPIO_NODE_HPP_
|
||||||
#define GPIO_NODE__GPIO_NODE_HPP_
|
#define GPIO_NODE__GPIO_NODE_HPP_
|
||||||
|
|
||||||
#include <memory>
|
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
#include <gpiod.hpp>
|
#include <gpiod.h>
|
||||||
#include <rclcpp/rclcpp.hpp>
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
|
||||||
#include "blockly_interfaces/msg/gpio_read.hpp"
|
#include "blockly_interfaces/msg/gpio_read.hpp"
|
||||||
|
|
@ -25,9 +24,9 @@ private:
|
||||||
std::vector<int64_t> output_pins_;
|
std::vector<int64_t> output_pins_;
|
||||||
std::vector<int64_t> input_pins_;
|
std::vector<int64_t> input_pins_;
|
||||||
|
|
||||||
// gpiod v2.x line requests — one per direction group
|
// gpiod v2 C API — raw pointers managed manually via gpiod_*_free()
|
||||||
std::unique_ptr<gpiod::line_request> output_request_;
|
struct gpiod_line_request * output_request_ = nullptr;
|
||||||
std::unique_ptr<gpiod::line_request> input_request_;
|
struct gpiod_line_request * input_request_ = nullptr;
|
||||||
|
|
||||||
rclcpp::Subscription<blockly_interfaces::msg::GpioWrite>::SharedPtr write_sub_;
|
rclcpp::Subscription<blockly_interfaces::msg::GpioWrite>::SharedPtr write_sub_;
|
||||||
rclcpp::Publisher<blockly_interfaces::msg::GpioRead>::SharedPtr state_pub_;
|
rclcpp::Publisher<blockly_interfaces::msg::GpioRead>::SharedPtr state_pub_;
|
||||||
|
|
|
||||||
|
|
@ -57,50 +57,81 @@ GpioNode::GpioNode()
|
||||||
|
|
||||||
GpioNode::~GpioNode()
|
GpioNode::~GpioNode()
|
||||||
{
|
{
|
||||||
// gpiod::line_request releases lines automatically when destroyed,
|
|
||||||
// but we log it explicitly for visibility.
|
|
||||||
if (output_request_) {
|
if (output_request_) {
|
||||||
output_request_->release();
|
gpiod_line_request_release(output_request_);
|
||||||
output_request_.reset();
|
output_request_ = nullptr;
|
||||||
}
|
}
|
||||||
if (input_request_) {
|
if (input_request_) {
|
||||||
input_request_->release();
|
gpiod_line_request_release(input_request_);
|
||||||
input_request_.reset();
|
input_request_ = nullptr;
|
||||||
}
|
}
|
||||||
RCLCPP_INFO(this->get_logger(), "GPIO lines released");
|
RCLCPP_INFO(this->get_logger(), "GPIO lines released");
|
||||||
}
|
}
|
||||||
|
|
||||||
void GpioNode::setup_gpio(const std::string & chip_path)
|
void GpioNode::setup_gpio(const std::string & chip_path)
|
||||||
{
|
{
|
||||||
gpiod::chip chip(chip_path);
|
struct gpiod_chip * chip = gpiod_chip_open(chip_path.c_str());
|
||||||
|
if (!chip) {
|
||||||
|
throw std::runtime_error("Failed to open GPIO chip: " + chip_path);
|
||||||
|
}
|
||||||
|
|
||||||
// Request output lines as a single batch
|
// Request output lines as a single batch
|
||||||
if (!output_pins_.empty()) {
|
if (!output_pins_.empty()) {
|
||||||
auto out_settings = gpiod::line_settings();
|
struct gpiod_line_settings * settings = gpiod_line_settings_new();
|
||||||
out_settings.set_direction(gpiod::line::direction::OUTPUT);
|
gpiod_line_settings_set_direction(settings, GPIOD_LINE_DIRECTION_OUTPUT);
|
||||||
|
|
||||||
auto out_rb = chip.prepare_request().set_consumer("gpio_node");
|
struct gpiod_line_config * line_cfg = gpiod_line_config_new();
|
||||||
for (auto pin : output_pins_) {
|
for (auto pin : output_pins_) {
|
||||||
out_rb.add_line_settings(static_cast<unsigned int>(pin), out_settings);
|
unsigned int offset = static_cast<unsigned int>(pin);
|
||||||
|
gpiod_line_config_add_line_settings(line_cfg, &offset, 1, settings);
|
||||||
RCLCPP_INFO(this->get_logger(), "Configured pin %ld as OUTPUT", pin);
|
RCLCPP_INFO(this->get_logger(), "Configured pin %ld as OUTPUT", pin);
|
||||||
}
|
}
|
||||||
output_request_ = std::make_unique<gpiod::line_request>(out_rb.do_request());
|
|
||||||
|
struct gpiod_request_config * req_cfg = gpiod_request_config_new();
|
||||||
|
gpiod_request_config_set_consumer(req_cfg, "gpio_node");
|
||||||
|
|
||||||
|
output_request_ = gpiod_chip_request_lines(chip, req_cfg, line_cfg);
|
||||||
|
|
||||||
|
gpiod_request_config_free(req_cfg);
|
||||||
|
gpiod_line_config_free(line_cfg);
|
||||||
|
gpiod_line_settings_free(settings);
|
||||||
|
|
||||||
|
if (!output_request_) {
|
||||||
|
gpiod_chip_close(chip);
|
||||||
|
throw std::runtime_error("Failed to request output lines");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Request input lines as a single batch
|
// Request input lines as a single batch
|
||||||
if (!input_pins_.empty()) {
|
if (!input_pins_.empty()) {
|
||||||
auto in_settings = gpiod::line_settings();
|
struct gpiod_line_settings * settings = gpiod_line_settings_new();
|
||||||
in_settings.set_direction(gpiod::line::direction::INPUT);
|
gpiod_line_settings_set_direction(settings, GPIOD_LINE_DIRECTION_INPUT);
|
||||||
|
|
||||||
auto in_rb = chip.prepare_request().set_consumer("gpio_node");
|
struct gpiod_line_config * line_cfg = gpiod_line_config_new();
|
||||||
for (auto pin : input_pins_) {
|
for (auto pin : input_pins_) {
|
||||||
in_rb.add_line_settings(static_cast<unsigned int>(pin), in_settings);
|
unsigned int offset = static_cast<unsigned int>(pin);
|
||||||
|
gpiod_line_config_add_line_settings(line_cfg, &offset, 1, settings);
|
||||||
RCLCPP_INFO(this->get_logger(), "Configured pin %ld as INPUT", pin);
|
RCLCPP_INFO(this->get_logger(), "Configured pin %ld as INPUT", pin);
|
||||||
}
|
}
|
||||||
input_request_ = std::make_unique<gpiod::line_request>(in_rb.do_request());
|
|
||||||
|
struct gpiod_request_config * req_cfg = gpiod_request_config_new();
|
||||||
|
gpiod_request_config_set_consumer(req_cfg, "gpio_node");
|
||||||
|
|
||||||
|
input_request_ = gpiod_chip_request_lines(chip, req_cfg, line_cfg);
|
||||||
|
|
||||||
|
gpiod_request_config_free(req_cfg);
|
||||||
|
gpiod_line_config_free(line_cfg);
|
||||||
|
gpiod_line_settings_free(settings);
|
||||||
|
|
||||||
|
if (!input_request_) {
|
||||||
|
gpiod_chip_close(chip);
|
||||||
|
throw std::runtime_error("Failed to request input lines");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
gpiod_chip_close(chip);
|
||||||
|
}
|
||||||
|
|
||||||
void GpioNode::write_callback(
|
void GpioNode::write_callback(
|
||||||
const blockly_interfaces::msg::GpioWrite::SharedPtr msg)
|
const blockly_interfaces::msg::GpioWrite::SharedPtr msg)
|
||||||
{
|
{
|
||||||
|
|
@ -118,9 +149,10 @@ void GpioNode::write_callback(
|
||||||
}
|
}
|
||||||
|
|
||||||
if (output_request_) {
|
if (output_request_) {
|
||||||
output_request_->set_value(
|
enum gpiod_line_value value =
|
||||||
pin,
|
state ? GPIOD_LINE_VALUE_ACTIVE : GPIOD_LINE_VALUE_INACTIVE;
|
||||||
state ? gpiod::line::value::ACTIVE : gpiod::line::value::INACTIVE);
|
gpiod_line_request_set_value(
|
||||||
|
output_request_, static_cast<unsigned int>(pin), value);
|
||||||
}
|
}
|
||||||
|
|
||||||
RCLCPP_INFO(
|
RCLCPP_INFO(
|
||||||
|
|
@ -135,8 +167,10 @@ void GpioNode::read_callback()
|
||||||
msg.pin = static_cast<uint8_t>(pin);
|
msg.pin = static_cast<uint8_t>(pin);
|
||||||
|
|
||||||
if (input_request_) {
|
if (input_request_) {
|
||||||
msg.state =
|
enum gpiod_line_value value =
|
||||||
input_request_->get_value(pin) == gpiod::line::value::ACTIVE;
|
gpiod_line_request_get_value(
|
||||||
|
input_request_, static_cast<unsigned int>(pin));
|
||||||
|
msg.state = (value == GPIOD_LINE_VALUE_ACTIVE);
|
||||||
}
|
}
|
||||||
|
|
||||||
state_pub_->publish(msg);
|
state_pub_->publish(msg);
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue