mirror of
https://github.com/meshtastic/firmware.git
synced 2025-04-25 17:42:48 +00:00
Move to portduino GPIO, adding user button support
This commit is contained in:
parent
18cf8ca4fa
commit
102efd4954
@ -24,3 +24,8 @@ Lora:
|
|||||||
# Reset: 22
|
# Reset: 22
|
||||||
# CS: 7
|
# CS: 7
|
||||||
# IRQ: 25
|
# IRQ: 25
|
||||||
|
|
||||||
|
# Define GPIO buttons here:
|
||||||
|
|
||||||
|
GPIO:
|
||||||
|
# User: 6
|
||||||
|
@ -36,6 +36,9 @@ class ButtonThread : public concurrency::OSThread
|
|||||||
#endif
|
#endif
|
||||||
#ifdef BUTTON_PIN_TOUCH
|
#ifdef BUTTON_PIN_TOUCH
|
||||||
OneButton userButtonTouch;
|
OneButton userButtonTouch;
|
||||||
|
#endif
|
||||||
|
#if defined(ARCH_RASPBERRY_PI)
|
||||||
|
OneButton userButton;
|
||||||
#endif
|
#endif
|
||||||
static bool shutdown_on_long_stop;
|
static bool shutdown_on_long_stop;
|
||||||
|
|
||||||
@ -45,8 +48,13 @@ class ButtonThread : public concurrency::OSThread
|
|||||||
// callback returns the period for the next callback invocation (or 0 if we should no longer be called)
|
// callback returns the period for the next callback invocation (or 0 if we should no longer be called)
|
||||||
ButtonThread() : OSThread("Button")
|
ButtonThread() : OSThread("Button")
|
||||||
{
|
{
|
||||||
#ifdef BUTTON_PIN
|
#if defined(ARCH_RASPBERRY_PI)
|
||||||
|
if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC)
|
||||||
|
userButton = OneButton(settingsMap[user], true, true);
|
||||||
|
#elif defined(BUTTON_PIN)
|
||||||
|
|
||||||
userButton = OneButton(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, true, true);
|
userButton = OneButton(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, true, true);
|
||||||
|
#endif
|
||||||
#ifdef INPUT_PULLUP_SENSE
|
#ifdef INPUT_PULLUP_SENSE
|
||||||
// Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did
|
// Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did
|
||||||
pinMode(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, INPUT_PULLUP_SENSE);
|
pinMode(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, INPUT_PULLUP_SENSE);
|
||||||
@ -58,6 +66,10 @@ class ButtonThread : public concurrency::OSThread
|
|||||||
userButton.attachMultiClick(userButtonMultiPressed);
|
userButton.attachMultiClick(userButtonMultiPressed);
|
||||||
userButton.attachLongPressStart(userButtonPressedLongStart);
|
userButton.attachLongPressStart(userButtonPressedLongStart);
|
||||||
userButton.attachLongPressStop(userButtonPressedLongStop);
|
userButton.attachLongPressStop(userButtonPressedLongStop);
|
||||||
|
#if defined(ARCH_RASPBERRY_PI)
|
||||||
|
if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC)
|
||||||
|
wakeOnIrq(settingsMap[user], FALLING);
|
||||||
|
#else
|
||||||
wakeOnIrq(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, FALLING);
|
wakeOnIrq(config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN, FALLING);
|
||||||
#endif
|
#endif
|
||||||
#ifdef BUTTON_PIN_ALT
|
#ifdef BUTTON_PIN_ALT
|
||||||
@ -87,9 +99,14 @@ class ButtonThread : public concurrency::OSThread
|
|||||||
{
|
{
|
||||||
canSleep = true; // Assume we should not keep the board awake
|
canSleep = true; // Assume we should not keep the board awake
|
||||||
|
|
||||||
#ifdef BUTTON_PIN
|
#if defined(BUTTON_PIN)
|
||||||
userButton.tick();
|
userButton.tick();
|
||||||
canSleep &= userButton.isIdle();
|
canSleep &= userButton.isIdle();
|
||||||
|
#elif defined(ARCH_RASPBERRY_PI)
|
||||||
|
if (settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) {
|
||||||
|
userButton.tick();
|
||||||
|
canSleep &= userButton.isIdle();
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
#ifdef BUTTON_PIN_ALT
|
#ifdef BUTTON_PIN_ALT
|
||||||
userButtonAlt.tick();
|
userButtonAlt.tick();
|
||||||
@ -121,6 +138,13 @@ class ButtonThread : public concurrency::OSThread
|
|||||||
!moduleConfig.canned_message.enabled) {
|
!moduleConfig.canned_message.enabled) {
|
||||||
powerFSM.trigger(EVENT_PRESS);
|
powerFSM.trigger(EVENT_PRESS);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
#if defined(ARCH_RASPBERRY_PI)
|
||||||
|
if ((settingsMap.count(user) != 0 && settingsMap[user] != RADIOLIB_NC) &&
|
||||||
|
(settingsMap[user] != moduleConfig.canned_message.inputbroker_pin_press) ||
|
||||||
|
!moduleConfig.canned_message.enabled) {
|
||||||
|
powerFSM.trigger(EVENT_PRESS);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
static void userButtonPressedLong()
|
static void userButtonPressedLong()
|
||||||
|
@ -75,7 +75,7 @@ NRF52Bluetooth *nrf52Bluetooth;
|
|||||||
#include <string>
|
#include <string>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_BUTTON
|
#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI)
|
||||||
#include "ButtonThread.h"
|
#include "ButtonThread.h"
|
||||||
#endif
|
#endif
|
||||||
#include "PowerFSMThread.h"
|
#include "PowerFSMThread.h"
|
||||||
@ -206,13 +206,13 @@ static int32_t ledBlinker()
|
|||||||
|
|
||||||
uint32_t timeLastPowered = 0;
|
uint32_t timeLastPowered = 0;
|
||||||
|
|
||||||
#if HAS_BUTTON
|
#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI)
|
||||||
bool ButtonThread::shutdown_on_long_stop = false;
|
bool ButtonThread::shutdown_on_long_stop = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static Periodic *ledPeriodic;
|
static Periodic *ledPeriodic;
|
||||||
static OSThread *powerFSMthread;
|
static OSThread *powerFSMthread;
|
||||||
#if HAS_BUTTON
|
#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI)
|
||||||
static OSThread *buttonThread;
|
static OSThread *buttonThread;
|
||||||
uint32_t ButtonThread::longPressTime = 0;
|
uint32_t ButtonThread::longPressTime = 0;
|
||||||
#endif
|
#endif
|
||||||
@ -583,7 +583,7 @@ void setup()
|
|||||||
else
|
else
|
||||||
router = new ReliableRouter();
|
router = new ReliableRouter();
|
||||||
|
|
||||||
#if HAS_BUTTON
|
#if HAS_BUTTON || defined(ARCH_RASPBERRY_PI)
|
||||||
// Buttons. Moved here cause we need NodeDB to be initialized
|
// Buttons. Moved here cause we need NodeDB to be initialized
|
||||||
buttonThread = new ButtonThread();
|
buttonThread = new ButtonThread();
|
||||||
#endif
|
#endif
|
||||||
|
@ -7,6 +7,8 @@
|
|||||||
// include the library for Raspberry GPIO pins
|
// include the library for Raspberry GPIO pins
|
||||||
#include "pigpio.h"
|
#include "pigpio.h"
|
||||||
|
|
||||||
|
#include "linux/gpio/LinuxGPIOPin.h"
|
||||||
|
|
||||||
// create a new Raspberry Pi hardware abstraction layer
|
// create a new Raspberry Pi hardware abstraction layer
|
||||||
// using the pigpio library
|
// using the pigpio library
|
||||||
// the HAL must inherit from the base RadioLibHal class
|
// the HAL must inherit from the base RadioLibHal class
|
||||||
@ -54,8 +56,7 @@ class PiHal : public RadioLibHal
|
|||||||
if (pin == RADIOLIB_NC) {
|
if (pin == RADIOLIB_NC) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
::pinMode(pin, RADIOLIB_ARDUINOHAL_PIN_MODE_CAST mode);
|
||||||
gpioSetMode(pin, mode);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void digitalWrite(uint32_t pin, uint32_t value) override
|
void digitalWrite(uint32_t pin, uint32_t value) override
|
||||||
@ -63,8 +64,7 @@ class PiHal : public RadioLibHal
|
|||||||
if (pin == RADIOLIB_NC) {
|
if (pin == RADIOLIB_NC) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
::digitalWrite(pin, RADIOLIB_ARDUINOHAL_PIN_STATUS_CAST value);
|
||||||
gpioWrite(pin, value);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t digitalRead(uint32_t pin) override
|
uint32_t digitalRead(uint32_t pin) override
|
||||||
@ -73,7 +73,7 @@ class PiHal : public RadioLibHal
|
|||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
|
|
||||||
return (gpioRead(pin));
|
return (::digitalRead(pin));
|
||||||
}
|
}
|
||||||
|
|
||||||
void attachInterrupt(uint32_t interruptNum, void (*interruptCb)(void), uint32_t mode) override
|
void attachInterrupt(uint32_t interruptNum, void (*interruptCb)(void), uint32_t mode) override
|
||||||
@ -81,11 +81,7 @@ class PiHal : public RadioLibHal
|
|||||||
if (interruptNum == RADIOLIB_NC) {
|
if (interruptNum == RADIOLIB_NC) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (gpioRead(interruptNum) == 1) {
|
::attachInterrupt(interruptNum, interruptCb, RADIOLIB_ARDUINOHAL_INTERRUPT_MODE_CAST mode);
|
||||||
interruptCb();
|
|
||||||
} else {
|
|
||||||
gpioSetAlertFunc(interruptNum, (gpioISRFunc_t)interruptCb);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void detachInterrupt(uint32_t interruptNum) override
|
void detachInterrupt(uint32_t interruptNum) override
|
||||||
@ -94,7 +90,7 @@ class PiHal : public RadioLibHal
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
gpioSetAlertFunc(interruptNum, NULL);
|
::detachInterrupt(interruptNum);
|
||||||
}
|
}
|
||||||
|
|
||||||
void delay(unsigned long ms) override { gpioDelay(ms * 1000); }
|
void delay(unsigned long ms) override { gpioDelay(ms * 1000); }
|
||||||
@ -111,19 +107,8 @@ class PiHal : public RadioLibHal
|
|||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
|
|
||||||
this->pinMode(pin, PI_INPUT);
|
return (::pulseIn(pin, state, timeout));
|
||||||
uint32_t start = this->micros();
|
|
||||||
uint32_t curtick = this->micros();
|
|
||||||
|
|
||||||
while (this->digitalRead(pin) == state) {
|
|
||||||
if ((this->micros() - curtick) > timeout) {
|
|
||||||
return (0);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return (this->micros() - start);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void spiBegin()
|
void spiBegin()
|
||||||
{
|
{
|
||||||
if (_spiHandle < 0) {
|
if (_spiHandle < 0) {
|
||||||
|
@ -10,6 +10,7 @@
|
|||||||
|
|
||||||
#ifdef ARCH_RASPBERRY_PI
|
#ifdef ARCH_RASPBERRY_PI
|
||||||
#include "PortduinoGlue.h"
|
#include "PortduinoGlue.h"
|
||||||
|
#include "linux/gpio/LinuxGPIOPin.h"
|
||||||
#include "pigpio.h"
|
#include "pigpio.h"
|
||||||
#include "yaml-cpp/yaml.h"
|
#include "yaml-cpp/yaml.h"
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
@ -101,6 +102,7 @@ void portduinoSetup()
|
|||||||
printf("Setting up Meshtastic on Portduino...\n");
|
printf("Setting up Meshtastic on Portduino...\n");
|
||||||
|
|
||||||
#ifdef ARCH_RASPBERRY_PI
|
#ifdef ARCH_RASPBERRY_PI
|
||||||
|
gpioInit();
|
||||||
YAML::Node yamlConfig;
|
YAML::Node yamlConfig;
|
||||||
|
|
||||||
if (access("config.yaml", R_OK) == 0) {
|
if (access("config.yaml", R_OK) == 0) {
|
||||||
@ -138,6 +140,9 @@ void portduinoSetup()
|
|||||||
settingsMap[busy] = yamlConfig["Lora"]["Busy"].as<int>(RADIOLIB_NC);
|
settingsMap[busy] = yamlConfig["Lora"]["Busy"].as<int>(RADIOLIB_NC);
|
||||||
settingsMap[reset] = yamlConfig["Lora"]["Reset"].as<int>(RADIOLIB_NC);
|
settingsMap[reset] = yamlConfig["Lora"]["Reset"].as<int>(RADIOLIB_NC);
|
||||||
}
|
}
|
||||||
|
if (yamlConfig["GPIO"]) {
|
||||||
|
settingsMap[user] = yamlConfig["GPIO"]["User"].as<int>(RADIOLIB_NC);
|
||||||
|
}
|
||||||
|
|
||||||
} catch (YAML::Exception e) {
|
} catch (YAML::Exception e) {
|
||||||
std::cout << "*** Exception " << e.what() << std::endl;
|
std::cout << "*** Exception " << e.what() << std::endl;
|
||||||
@ -147,6 +152,34 @@ void portduinoSetup()
|
|||||||
std::cout << "Cannot read Bluetooth MAC Address. Please run as root" << std::endl;
|
std::cout << "Cannot read Bluetooth MAC Address. Please run as root" << std::endl;
|
||||||
exit(EXIT_FAILURE);
|
exit(EXIT_FAILURE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Need to bind all the configured GPIO pins so they're not simulated
|
||||||
|
if (settingsMap.count(cs) > 0 && settingsMap[cs] != RADIOLIB_NC) {
|
||||||
|
if (initGPIOPin(settingsMap[cs]) != ERRNO_OK) {
|
||||||
|
settingsMap[cs] = RADIOLIB_NC;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (settingsMap.count(irq) > 0 && settingsMap[irq] != RADIOLIB_NC) {
|
||||||
|
if (initGPIOPin(settingsMap[irq]) != ERRNO_OK) {
|
||||||
|
settingsMap[irq] = RADIOLIB_NC;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (settingsMap.count(busy) > 0 && settingsMap[busy] != RADIOLIB_NC) {
|
||||||
|
if (initGPIOPin(settingsMap[busy]) != ERRNO_OK) {
|
||||||
|
settingsMap[busy] = RADIOLIB_NC;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (settingsMap.count(reset) > 0 && settingsMap[reset] != RADIOLIB_NC) {
|
||||||
|
if (initGPIOPin(settingsMap[reset]) != ERRNO_OK) {
|
||||||
|
settingsMap[reset] = RADIOLIB_NC;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (settingsMap.count(user) > 0 && settingsMap[user] != RADIOLIB_NC) {
|
||||||
|
if (initGPIOPin(settingsMap[user]) != ERRNO_OK) {
|
||||||
|
settingsMap[user] = RADIOLIB_NC;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
return;
|
return;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -195,3 +228,20 @@ void portduinoSetup()
|
|||||||
// gpioBind((new SimGPIOPin(LORA_CS, "LORA_CS"))->setSilent());
|
// gpioBind((new SimGPIOPin(LORA_CS, "LORA_CS"))->setSilent());
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef ARCH_RASPBERRY_PI
|
||||||
|
int initGPIOPin(int pinNum)
|
||||||
|
{
|
||||||
|
std::string gpio_name = "GPIO" + std::to_string(pinNum);
|
||||||
|
try {
|
||||||
|
GPIOPin *csPin;
|
||||||
|
csPin = new LinuxGPIOPin(pinNum, "gpiochip0", pinNum, gpio_name.c_str());
|
||||||
|
csPin->setSilent();
|
||||||
|
gpioBind(csPin);
|
||||||
|
return ERRNO_OK;
|
||||||
|
} catch (std::invalid_argument &e) {
|
||||||
|
std::cout << "Warning, cannot claim pin" << gpio_name << std::endl;
|
||||||
|
return ERRNO_DISABLED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
@ -4,6 +4,7 @@
|
|||||||
|
|
||||||
extern std::map<int, int> settingsMap;
|
extern std::map<int, int> settingsMap;
|
||||||
|
|
||||||
enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95 };
|
enum { use_sx1262, cs, irq, busy, reset, dio2_as_rf_switch, use_rf95, user };
|
||||||
|
int initGPIOPin(int pinNum);
|
||||||
|
|
||||||
#endif
|
#endif
|
Loading…
Reference in New Issue
Block a user