Skip to content

Commit

Permalink
unit test for GPIO race condition on Linux
Browse files Browse the repository at this point in the history
Related to ArduPilot#25007
  • Loading branch information
rsaxvc committed Sep 17, 2023
1 parent d9818ae commit bfa99c1
Show file tree
Hide file tree
Showing 5 changed files with 97 additions and 0 deletions.
1 change: 1 addition & 0 deletions libraries/AP_HAL/GPIO.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ class AP_HAL::GPIO {
GPIO() {}
virtual void init() = 0;
virtual void pinMode(uint8_t pin, uint8_t output) = 0;
virtual void pinModeValidate(uint8_t pin, uint8_t output) = 0;

// optional interface on some boards
virtual void pinMode(uint8_t pin, uint8_t output, uint8_t alt) {};
Expand Down
24 changes: 24 additions & 0 deletions libraries/AP_HAL_Linux/GPIO_RPI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ const char* GPIO_RPI::_system_memory_device_path = "/dev/mem";

GPIO_RPI::GPIO_RPI()
{
fprintf(stderr,"%s:%i\n",__func__,__LINE__);
}

void GPIO_RPI::set_gpio_mode_alt(int pin, int alternative)
Expand Down Expand Up @@ -93,6 +94,21 @@ void GPIO_RPI::set_gpio_mode_out(int pin)
_gpio[pin / pins_per_register] = register_value | mask_with_bit;
}

uint8_t GPIO_RPI::get_gpio_mode(int pin)
{
// Each register can contain 10 pins
const uint8_t pins_per_register = 10;
// Calculates the position of the 3 bit mask in the 32 bits register
const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3;
// Create a mask to enable the bit that sets output functionality
// 0b00'000'000'000'000'000'000'001'000'000'000 enables output for the 4th pin
const uint32_t mask_with_bit = 0b001 << tree_bits_position_in_register;
// Clear all bits in our position and apply our mask with alt values
const uint32_t register_value = _gpio[pin / pins_per_register];
return !!(register_value & mask_with_bit);
}


void GPIO_RPI::set_gpio_high(int pin)
{
// Calculate index of the array for the register GPSET0 (0x7E20'001C)
Expand Down Expand Up @@ -160,6 +176,7 @@ void GPIO_RPI::closeMemoryDevice()

void GPIO_RPI::init()
{
fprintf(stderr,"%s:%i\n",__func__,__LINE__);
const LINUX_BOARD_TYPE rpi_version = UtilRPI::from(hal.util)->detect_linux_board_type();

GPIO_RPI::Address peripheral_base;
Expand Down Expand Up @@ -200,6 +217,13 @@ void GPIO_RPI::pinMode(uint8_t pin, uint8_t output)
}
}

void GPIO_RPI::pinModeValidate(uint8_t pin, uint8_t output)
{
if(get_gpio_mode(pin) != output) {
AP_HAL::panic("GPIO mode validation failed!");
}
}

void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
{
if (output == HAL_GPIO_INPUT) {
Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_HAL_Linux/GPIO_RPI.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ class GPIO_RPI : public AP_HAL::GPIO {
GPIO_RPI();
void init() override;
void pinMode(uint8_t pin, uint8_t output) override;
void pinModeValidate(uint8_t pin, uint8_t output) override;
void pinMode(uint8_t pin, uint8_t output, uint8_t alt) override;
uint8_t read(uint8_t pin) override;
void write(uint8_t pin, uint8_t value) override;
Expand Down Expand Up @@ -85,6 +86,15 @@ class GPIO_RPI : public AP_HAL::GPIO {
*/
uint32_t get_address(GPIO_RPI::Address address, GPIO_RPI::PeripheralOffset offset) const;

/**
* @brief Get a specific GPIO's mode
* Check Linux::GPIO_RPI::set_gpio_mode_alt for more information.
*
* @param pin
* @return int mode
*/
uint8_t get_gpio_mode(int pin);

/**
* @brief Change functionality of GPIO Function Select Registers (GPFSELn) to any alternative function.
* Each GPIO pin is mapped to 3 bits inside a 32 bits register, E.g:
Expand Down
56 changes: 56 additions & 0 deletions libraries/AP_HAL_Linux/tests/test_gpio_dir_race.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
/*
* Copyright (C) 2016 Intel Corporation. All rights reserved.
*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_gtest.h>

#include <pthread.h>
#include <unistd.h>

#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_Linux/GPIO.h>

using namespace Linux;

const AP_HAL::HAL &hal = AP_HAL::get_HAL();

#define TEST_PIN 12

class TestGpioMode1 {
public:
TestGpioMode1() { }

bool run() {
hal.gpio->pinMode(TEST_PIN, HAL_GPIO_INPUT);
hal.gpio->pinModeValidate(TEST_PIN, HAL_GPIO_INPUT);
hal.gpio->pinMode(TEST_PIN, HAL_GPIO_OUTPUT);
hal.gpio->pinModeValidate(TEST_PIN, HAL_GPIO_OUTPUT);
return true;
}

protected:
};

TEST(LinuxGpio, override_run)
{
TestGpioMode1 gpio;
fprintf(stderr,"Initializing HAL\n");
hal.gpio->init();
fprintf(stderr,"Launching test run\n");
while (gpio.run()) {
}
}

AP_GTEST_MAIN()
6 changes: 6 additions & 0 deletions libraries/AP_HAL_Linux/tests/test_gpio_dir_racer.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
UNRELATED_PIN=13
while :
do
sudo raspi-gpio set ${UNRELATED_PIN} ip
sudo raspi-gpio set ${UNRELATED_PIN} op
done

0 comments on commit bfa99c1

Please sign in to comment.