diff --git a/03_ROS/ghost_io/CMakeLists.txt b/03_ROS/ghost_io/CMakeLists.txt new file mode 100644 index 00000000..5bb01bad --- /dev/null +++ b/03_ROS/ghost_io/CMakeLists.txt @@ -0,0 +1,71 @@ +cmake_minimum_required(VERSION 3.8) +project(ghost_io) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + + + + +###################### +#### Dependencies #### +###################### +# Set Package Dependencies +set(DEPENDENCIES + rclcpp + std_msgs + ) + +foreach(pkg ${DEPENDENCIES}) + find_package(${pkg} REQUIRED) +endforeach() +ament_export_dependencies(${DEPENDENCIES}) + +# Set Include Directories +set(INCLUDE + include +) + +include_directories(${INCLUDE}) +ament_export_include_directories(${INCLUDE}) + +# find dependencies +find_package(ament_cmake REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +# GPIO Expander +add_executable(gpio_expander + src/PCF8575.cpp + src/gpio_expander.cpp + #src/tcs_color_sensor.cpp +) +ament_target_dependencies(gpio_expander + ${DEPENDENCIES} +) +target_link_libraries(gpio_expander i2c) +target_include_directories(gpio_expander + PUBLIC + $ + $) +install(TARGETS + gpio_expander + DESTINATION lib/${PROJECT_NAME}) + + + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/03_ROS/ghost_io/include/PCF8575.hpp b/03_ROS/ghost_io/include/PCF8575.hpp new file mode 100644 index 00000000..c2ced0ca --- /dev/null +++ b/03_ROS/ghost_io/include/PCF8575.hpp @@ -0,0 +1,62 @@ +#pragma once + +#include +#include + +class PCF8575 { +public: + PCF8575(){}; + /** + * @brief Construct a new PCF8575 object. + * + * @param i2cBus Path to the I2C bus device (e.g. "/dev/i2c-1"). + * @param address I2C address of the PCF8575 (typically between 0x20 and 0x27). + */ + bool open(const std::string &i2cBus, uint8_t address, uint16_t initVal = 0xFFFF); + + /// Clean up and close the bus. + ~PCF8575(); + + /** + * @brief Set a single pin to HIGH or LOW. + * + * @param pin Pin number (0..15). + * @param value true for HIGH, false for LOW. + * @return true on success, false on error. + */ + bool setPin(uint8_t pin, bool value); + + /** + * @brief Read a single pin value. + * + * @param pin Pin number (0..15). + * @param value Reference to store the pin value (true for HIGH, false for LOW). + * @return true on success, false on error. + */ + bool getPin(uint8_t pin, bool &value); + + bool poll(); + +private: + /** + * @brief Read 16 bits from the expander. + * + * @return uint16_t 16-bit input value. + */ + uint16_t read16(); + + /** + * @brief Write 16 bits to the expander. + * + * @param value 16-bit output value. + * @return true on success, false on error. + */ + bool write16(uint16_t value); + + + int _fd; // File descriptor for the I2C bus. + uint8_t _address; // I2C address of the PCF8575. + + uint16_t current_in; + uint16_t current_out; +}; \ No newline at end of file diff --git a/03_ROS/ghost_io/include/ghost_io/gpio_expander.hpp b/03_ROS/ghost_io/include/ghost_io/gpio_expander.hpp new file mode 100644 index 00000000..5efd4979 --- /dev/null +++ b/03_ROS/ghost_io/include/ghost_io/gpio_expander.hpp @@ -0,0 +1,46 @@ +#pragma once + +#include "PCF8575.hpp" +#include +#include +#include + +#include +#include +#include +#include // Added to support std::set + + +namespace ghost_io +{ +struct GPIODevice +{ + std::vector pins; + bool output; // output to world + rclcpp::Subscription::SharedPtr sub; + rclcpp::Publisher::SharedPtr pub; +}; + +class GPIOExpander : public rclcpp::Node +{ + std::unique_ptr chip; + + double m_poll_freq; + + std::map m_gpio_map; + uint16_t output; + + rclcpp::TimerBase::SharedPtr m_publish_timer; + + void load_gpio_parameters(); + +public: + GPIOExpander(); + + + void poll(); + void callback(const std_msgs::msg::Int64::SharedPtr in, std::string name); + +}; + +} diff --git a/03_ROS/ghost_io/package.xml b/03_ROS/ghost_io/package.xml new file mode 100644 index 00000000..baedc4ba --- /dev/null +++ b/03_ROS/ghost_io/package.xml @@ -0,0 +1,18 @@ + + + + ghost_io + 0.0.0 + TODO: Package description + karmanyaahm + TODO: License declaration + + ament_cmake + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/03_ROS/ghost_io/src/PCF8575.cpp b/03_ROS/ghost_io/src/PCF8575.cpp new file mode 100644 index 00000000..b67dcd71 --- /dev/null +++ b/03_ROS/ghost_io/src/PCF8575.cpp @@ -0,0 +1,84 @@ +#include "PCF8575.hpp" +#include +#include +#include +#include +#include + +bool PCF8575::open(const std::string & i2cBus, uint8_t address, uint16_t initVal) +{ + printf("YO\n"); + _address = address; + + printf("YO2\n"); + _fd = ::open(i2cBus.c_str(), O_RDWR); + if (_fd < 0) { + perror("PCF8575: Failed to open I2C bus"); + return false; + } + printf("YO3\n"); + if (ioctl(_fd, I2C_SLAVE, _address) < 0) { + perror("PCF8575: Failed to set I2C address"); + return false; + } + current_out = initVal; + return true; +} + + +PCF8575::~PCF8575() +{ + if (_fd >= 0) { + close(_fd); + } +} + +uint16_t PCF8575::read16() +{ + uint8_t data[2]; + int ret = ::read(_fd, data, 2); + if (ret != 2) { + perror("PCF8575: Failed to read 2 bytes"); + return 0; + } + // Combine low and high byte into a 16-bit value. + return data[0] | (data[1] << 8); +} + +bool PCF8575::write16(uint16_t value) +{ + uint8_t data[2]; + data[0] = value & 0xFF; // low byte + data[1] = (value >> 8) & 0xFF; // high byte + // TODO: ^^ is so fucking dumb, chatgpt wrote it, todo fix using cast assignment or smth + int ret = ::write(_fd, data, 2); + if (ret != 2) { + perror("PCF8575: Failed to write 2 bytes"); + return false; + } + return true; +} + +bool PCF8575::setPin(uint8_t pin, bool value) +{ + if (pin > 15) {return false;} + if (value) { + current_out |= (1 << pin); + } else { + current_out &= ~(1 << pin); + } + return true; +} + +bool PCF8575::getPin(uint8_t pin, bool & value) +{ + if (pin > 15) {return false;} + value = (current_in >> pin) & 0x01; + return true; +} + +bool PCF8575::poll() +{ + current_in = read16(); + return write16(current_out); +} diff --git a/03_ROS/ghost_io/src/gpio_expander.cpp b/03_ROS/ghost_io/src/gpio_expander.cpp new file mode 100644 index 00000000..c258f025 --- /dev/null +++ b/03_ROS/ghost_io/src/gpio_expander.cpp @@ -0,0 +1,186 @@ +#include +#include +#include +#include +#include +#include +#include + +namespace ghost_io +{ +GPIOExpander::GPIOExpander() +: Node("gpio_expander", "", + rclcpp::NodeOptions() + .allow_undeclared_parameters(true) + .automatically_declare_parameters_from_overrides(true) +) +{ + //declare_parameter("system_i2c_bus_path", "/dev/i2c-null"); // required argument + declare_parameter("address", 0x20); // required argument + declare_parameter("poll_frequency", 25.); + + auto i2c_bus_path = get_parameter("system_i2c_bus_path").as_string(); + auto address = get_parameter("address").as_int(); + m_poll_freq = get_parameter("poll_frequency").as_double(); + + chip = std::make_unique(); + if (!chip->open(i2c_bus_path, address)) { + RCLCPP_ERROR(this->get_logger(), "CANNOT OPEN I2C BUS %s", i2c_bus_path.c_str()); + rclcpp::shutdown(); + } + + load_gpio_parameters(); + + for (auto & device : m_gpio_map) { + auto topic_name = device.first; + if (device.second.output) { + // device.second.sub = this->create_subscription( + // topic_name, 10, + // std::bind(&GPIOExpander::callback, this, std::placeholders::_1, topic_name)); + std::cout << "subscribe to " << topic_name << std::endl; + device.second.sub = this->create_subscription( + topic_name, 10, + [this, topic_name](const std_msgs::msg::Int64::SharedPtr msg) { + this->callback(msg, topic_name); + }); + + + } else { + std::cout << "pub " << topic_name << std::endl; + device.second.pub = this->create_publisher( + topic_name, 10); + + } + } + + poll(); + + m_publish_timer = + this->create_wall_timer( + std::chrono::seconds(1) / m_poll_freq, + std::bind(&GPIOExpander::poll, this)); + + RCLCPP_INFO(this->get_logger(), "Init Finished"); +} + + +void GPIOExpander::load_gpio_parameters() +{ + // List all parameter names with the prefix "gpio" + auto param_list = this->list_parameters({"gpio"}, 4); + + //std::cout << param_list.names.size() << std::endl; + //std::cout << param_list.prefixes.size() << std::endl; + + std::set device_names; + const std::string prefix = "gpio."; + + + // The parameters are flattened. For example: + // "gpio_expander.gpio./io/led.pins" + // "gpio_expander.gpio./io/button.output" + // Extract the device names from these keys. + for (const auto & full_name : param_list.names) { + //std::cout << full_name << std::endl; + if (full_name.rfind(prefix, 0) == 0) { // starts with prefix + std::string remainder = full_name.substr(prefix.size()); + auto dot_pos = remainder.find('.'); + if (dot_pos != std::string::npos) { + std::string device = remainder.substr(0, dot_pos); + device_names.insert(device); + } + } + } + for (const auto & prefix : param_list.prefixes) { + + //std::cout << prefix << std::endl; + } + + RCLCPP_INFO(this->get_logger(), "Loading GPIO devices:"); + + // For each detected device, build the parameter keys and retrieve values. + for (const auto & device : device_names) { + GPIODevice gpio_dev; + + std::string base = "gpio." + device + "."; + + // Retrieve pins parameter. Expecting an array of integers. + if (!this->has_parameter(base + "pins")) { + RCLCPP_WARN( + this->get_logger(), "Parameter %s not found, skipping device %s", + (base + "pins").c_str(), device.c_str()); + continue; + } + // Assume pins is stored as an integer array. + gpio_dev.pins = this->get_parameter(base + "pins").as_integer_array(); + gpio_dev.output = this->get_parameter(base + "output").as_bool(); + + m_gpio_map[device] = gpio_dev; + + // Build the pins string + std::ostringstream oss; + for (size_t i = 0; i < gpio_dev.pins.size(); ++i) { + oss << gpio_dev.pins[i] + << (i != gpio_dev.pins.size() - 1 ? ", " : ""); + } + std::string pins_str = oss.str(); + + // Log the information + RCLCPP_INFO( + this->get_logger(), + "Loaded device '%s': pins = [%s], output = %s", + device.c_str(), + pins_str.c_str(), + gpio_dev.output ? "true" : "false"); + } +} + + +void GPIOExpander::callback(const std_msgs::msg::Int64::SharedPtr in, std::string name) +{ + int64_t data = in->data; + auto pins = m_gpio_map[name].pins; + std::cout << name << " " << std::endl; + for (int i = pins.size() - 1; i >= 0; i--) { + std::cout << pins[i] << " " << std::to_string(data & 1) << std::endl; + chip->setPin(pins[i], !(data & 1)); + data >>= 1; + } +} + +void GPIOExpander::poll() +{ + chip->poll(); + + for (auto & device : m_gpio_map) { + if (!device.second.output) { // input into the world + int64_t data = 0; + + auto pins = device.second.pins; + + for (auto & p : pins) { + bool value; + chip->getPin(p, value); + data <<= 1; + data |= value; + } + + std_msgs::msg::Int64 msg; + msg.data = data; + device.second.pub->publish(msg); + } + } +} + + +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + + auto node = std::make_shared(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/03_ROS/ghost_ros_interfaces/package.xml b/03_ROS/ghost_ros_interfaces/package.xml index 377af990..a875b5cf 100644 --- a/03_ROS/ghost_ros_interfaces/package.xml +++ b/03_ROS/ghost_ros_interfaces/package.xml @@ -13,6 +13,7 @@ ghost_util ghost_msgs ghost_planners + ghost_io pluginlib diff --git a/03_ROS/ghost_ros_interfaces/src/bag_recorder/bag_recorder_service.cpp b/03_ROS/ghost_ros_interfaces/src/bag_recorder/bag_recorder_service.cpp index f1760f8f..17980b52 100644 --- a/03_ROS/ghost_ros_interfaces/src/bag_recorder/bag_recorder_service.cpp +++ b/03_ROS/ghost_ros_interfaces/src/bag_recorder/bag_recorder_service.cpp @@ -24,6 +24,7 @@ #include #include "ghost_msgs/srv/start_recorder.hpp" #include "ghost_msgs/srv/stop_recorder.hpp" +#include "std_msgs/msg/int64.hpp" #include "rclcpp/rclcpp.hpp" #include "unistd.h" @@ -55,6 +56,12 @@ class BagRecorderNode : public rclcpp::Node disk_check_period_, std::bind(&BagRecorderNode::EnforceFreeDiskSpace, this)); + // Create subscription to /io/buttons/bag and publisher to /io/leds/bag + button_subscriber_ = this->create_subscription( + "/io/buttons/bag", 10, + std::bind(&BagRecorderNode::ButtonCallback, this, _1)); + led_publisher_ = this->create_publisher("/io/leds/bag", 10); + std::string startup_string; startup_string += "Service Created.\n"; startup_string += "\tDisk Space Required (KB): " + std::to_string(disk_space_required_) + @@ -70,16 +77,23 @@ class BagRecorderNode : public rclcpp::Node void SpawnRecorderProcess(); void KillRecorderProcess(); void EnforceFreeDiskSpace(); + void ButtonCallback(const std_msgs::msg::Int64::SharedPtr msg); + void PublishLedStatus(int64_t status); private: rclcpp::Service::SharedPtr start_service_; rclcpp::Service::SharedPtr stop_service_; + rclcpp::Subscription::SharedPtr button_subscriber_; + rclcpp::Publisher::SharedPtr led_publisher_; + + bool recording_ = false; pid_t recorderPID_ = -1; unsigned long disk_space_required_; FILE * disk_check_output_; std::chrono::seconds disk_check_period_; rclcpp::TimerBase::SharedPtr disk_check_timer; + int64_t last_button_state_ = -1; // Initialized to an invalid state }; void BagRecorderNode::StartCallback( @@ -99,6 +113,7 @@ void BagRecorderNode::StopCallback( void BagRecorderNode::SpawnRecorderProcess() { + PublishLedStatus(1); // Turn LED on if (recording_) { RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Unable to start recorder; one already exists."); return; @@ -113,6 +128,7 @@ void BagRecorderNode::SpawnRecorderProcess() "/bin/sh", "sh", "-c", "exec ros2 bag record -a -o ~/bags/$(date +%m_%d_%Y-%H_%M_%S)", NULL); } + } void BagRecorderNode::KillRecorderProcess() @@ -134,6 +150,8 @@ void BagRecorderNode::KillRecorderProcess() std::string cmd_string = "kill -s INT " + std::to_string(recorderPID_); std::system(cmd_string.c_str()); + + PublishLedStatus(0); // Turn LED on } void BagRecorderNode::EnforceFreeDiskSpace() @@ -156,6 +174,34 @@ void BagRecorderNode::EnforceFreeDiskSpace() } } +// Subscription callback for /io/buttons/bag +void BagRecorderNode::ButtonCallback(const std_msgs::msg::Int64::SharedPtr msg) +{ + if (msg->data != last_button_state_) { + RCLCPP_INFO(this->get_logger(), "Button state changed from %ld to %ld", last_button_state_, msg->data); + + if (msg->data == 1) { + SpawnRecorderProcess(); + } else if (msg->data == 0) { + KillRecorderProcess(); + } else { + RCLCPP_WARN(this->get_logger(), "Received unknown button command: %ld", msg->data); + } + + // Update the last button state to the current value + last_button_state_ = msg->data; + } +} + +// Helper function to publish LED status on /io/leds/bag +void BagRecorderNode::PublishLedStatus(int64_t status) +{ + std_msgs::msg::Int64 led_msg; + led_msg.data = status; + led_publisher_->publish(led_msg); + RCLCPP_INFO(this->get_logger(), "Published LED status: %ld", led_msg.data); +} + int main(int argc, char ** argv) { rclcpp::init(argc, argv); diff --git a/09_External/casadi b/09_External/casadi new file mode 160000 index 00000000..2aa1eb21 --- /dev/null +++ b/09_External/casadi @@ -0,0 +1 @@ +Subproject commit 2aa1eb217a245856faab5002d339dca6ed9ebc38 diff --git a/11_Robots/ghost_high_stakes/config/ros_config.yaml b/11_Robots/ghost_high_stakes/config/ros_config.yaml index e83f8d96..07b1c3dd 100644 --- a/11_Robots/ghost_high_stakes/config/ros_config.yaml +++ b/11_Robots/ghost_high_stakes/config/ros_config.yaml @@ -739,4 +739,16 @@ map_ekf_node: dynamic_process_noise_covariance: true tts_music_node: ros__parameters: - volume: 11 # set to 0 to turn off, set to 100 at comp \ No newline at end of file + volume: 11 # set to 0 to turn off, set to 100 at comp +gpio_expander: + ros__parameters: + gpio: + "/io/leds/other": + pins: [8, 9,10] + output: True + "/io/leds/bag": + pins: [11] + output: True + "/io/buttons/bag": + pins: [0] + output: False \ No newline at end of file diff --git a/11_Robots/ghost_high_stakes/launch/hardware.launch.py b/11_Robots/ghost_high_stakes/launch/hardware.launch.py index 33e83a6c..5c0fdae2 100644 --- a/11_Robots/ghost_high_stakes/launch/hardware.launch.py +++ b/11_Robots/ghost_high_stakes/launch/hardware.launch.py @@ -98,6 +98,15 @@ def generate_launch_description(): output="screen", parameters=[ros_config_file], ) + gpio_expander = Node( + package="ghost_io", + executable="gpio_expander", + name="gpio_expander", + output="screen", + parameters=[ros_config_file, { + "system_i2c_bus_path" : "/dev/i2c-7" + }], + ) color_sensor_node = Node( package="ghost_sensing", @@ -184,4 +193,5 @@ def generate_launch_description(): color_sensor_node, tts_music_node, competition_state_machine_node, + gpio_expander, ]) diff --git a/scripts/hardware/service.sh b/scripts/hardware/service.sh index 31d0657c..f1f250d7 100755 --- a/scripts/hardware/service.sh +++ b/scripts/hardware/service.sh @@ -11,7 +11,7 @@ case "$1" in ;; "stop") systemctl --user stop 'ghost*service' - pkill -f -e ros + pkill -f -e /ros pkill -f -e ros2 pkill -f -e gz ;;