diff --git a/make/source.mk b/make/source.mk
index 5b2ec5c7ab..243cb4b1bd 100644
--- a/make/source.mk
+++ b/make/source.mk
@@ -42,6 +42,7 @@ COMMON_SRC = \
drivers/pwm_esc_detect.c \
drivers/pwm_mapping.c \
drivers/pwm_output.c \
+ drivers/pinio.c \
drivers/rcc.c \
drivers/rx_pwm.c \
drivers/serial.c \
@@ -79,6 +80,7 @@ COMMON_SRC = \
io/beeper.c \
io/lights.c \
io/pwmdriver_i2c.c \
+ io/piniobox.c \
io/serial.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h
index dd37d7466d..40859c574e 100644
--- a/src/main/config/parameter_group_ids.h
+++ b/src/main/config/parameter_group_ids.h
@@ -101,7 +101,8 @@
#define PG_OPFLOW_CONFIG 1012
#define PG_DISPLAY_CONFIG 1013
#define PG_LIGHTS_CONFIG 1014
-#define PG_INAV_END 1014
+#define PG_PINIOBOX_CONFIG 1015
+#define PG_INAV_END 1015
// OSD configuration (subject to change)
//#define PG_OSD_FONT_CONFIG 2047
diff --git a/src/main/drivers/pinio.c b/src/main/drivers/pinio.c
new file mode 100644
index 0000000000..c093b78d82
--- /dev/null
+++ b/src/main/drivers/pinio.c
@@ -0,0 +1,104 @@
+/*
+ * This file is part of Cleanflight, Betaflight and INAV
+ *
+ * Cleanflight, Betaflight and INAV are free software. You can
+ * redistribute this software and/or modify this software 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.
+ *
+ * Cleanflight, Betaflight and INAV are distributed in the hope that
+ * they 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 software.
+ *
+ * If not, see .
+ */
+
+#include
+
+#include "platform.h"
+
+#ifdef USE_PINIO
+
+#include "build/debug.h"
+#include "common/memory.h"
+#include "drivers/io.h"
+#include "drivers/pinio.h"
+
+/*** Hardware definitions ***/
+const pinioHardware_t pinioHardware[] = {
+#if defined(PINIO1_PIN)
+ { .ioTag = IO_TAG(PINIO1_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 },
+#endif
+
+#if defined(PINIO2_PIN)
+ { .ioTag = IO_TAG(PINIO2_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 },
+#endif
+
+#if defined(PINIO3_PIN)
+ { .ioTag = IO_TAG(PINIO3_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 },
+#endif
+
+#if defined(PINIO4_PIN)
+ { .ioTag = IO_TAG(PINIO4_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 },
+#endif
+};
+
+const int pinioHardwareCount = sizeof(pinioHardware) / sizeof(pinioHardware[0]);
+
+/*** Runtime configuration ***/
+typedef struct pinioRuntime_s {
+ IO_t io;
+ bool inverted;
+ bool state;
+} pinioRuntime_t;
+
+static pinioRuntime_t pinioRuntime[PINIO_COUNT];
+
+void pinioInit(void)
+{
+ if (pinioHardwareCount == 0) {
+ return;
+ }
+
+ for (int i = 0; i < pinioHardwareCount; i++) {
+ IO_t io = IOGetByTag(pinioHardware[i].ioTag);
+
+ if (!io) {
+ continue;
+ }
+
+ IOInit(io, OWNER_PINIO, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
+ IOConfigGPIO(io, pinioHardware[i].ioMode);
+
+ if (pinioHardware[i].flags & PINIO_FLAGS_INVERTED) {
+ pinioRuntime[i].inverted = true;
+ IOHi(io);
+ } else {
+ pinioRuntime[i].inverted = false;
+ IOLo(io);
+ }
+
+ pinioRuntime[i].io = io;
+ pinioRuntime[i].state = false;
+ }
+}
+
+void pinioSet(int index, bool on)
+{
+ const bool newState = on ^ pinioRuntime[index].inverted;
+
+ if (!pinioRuntime[index].io) {
+ return;
+ }
+
+ if (newState != pinioRuntime[index].state) {
+ IOWrite(pinioRuntime[index].io, newState);
+ pinioRuntime[index].state = newState;
+ }
+}
+#endif
diff --git a/src/main/drivers/pinio.h b/src/main/drivers/pinio.h
new file mode 100644
index 0000000000..baecc35a18
--- /dev/null
+++ b/src/main/drivers/pinio.h
@@ -0,0 +1,41 @@
+/*
+ * This file is part of Cleanflight, Betaflight and INAV
+ *
+ * Cleanflight, Betaflight and INAV are free software. You can
+ * redistribute this software and/or modify this software 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.
+ *
+ * Cleanflight, Betaflight and INAV are distributed in the hope that
+ * they 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 software.
+ *
+ * If not, see .
+ */
+
+#pragma once
+
+#include
+#include
+
+#include "drivers/io_types.h"
+
+#define PINIO_COUNT 4
+#define PINIO_FLAGS_INVERTED 0x80
+
+typedef struct pinioHardware_s {
+ ioTag_t ioTag;
+ ioConfig_t ioMode;
+ uint16_t flags;
+} pinioHardware_t;
+
+extern const pinioHardware_t pinioHardware[];
+extern const int pinioHardwareCount;
+
+void pinioInit(void);
+void pinioSet(int index, bool on);
diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h
index e9cfd3a1ff..8d1ce2bb30 100644
--- a/src/main/drivers/resource.h
+++ b/src/main/drivers/resource.h
@@ -53,6 +53,7 @@ typedef enum {
OWNER_COMPASS,
OWNER_AIRSPEED,
OWNER_OLED_DISPLAY,
+ OWNER_PINIO,
OWNER_TOTAL_COUNT
} resourceOwner_e;
diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c
index 3b3fda0a9a..d9b42b1e9b 100755
--- a/src/main/fc/fc_core.c
+++ b/src/main/fc/fc_core.c
@@ -64,6 +64,7 @@
#include "io/serial.h"
#include "io/statusindicator.h"
#include "io/asyncfatfs/asyncfatfs.h"
+#include "io/piniobox.h"
#include "msp/msp_serial.h"
@@ -485,6 +486,10 @@ void processRx(timeUs_t currentTimeUs)
updateActivatedModes();
+#ifdef USE_PINIOBOX
+ pinioBoxUpdate();
+#endif
+
if (!cliMode) {
bool canUseRxData = rxIsReceivingSignal() && !FLIGHT_MODE(FAILSAFE_MODE);
updateAdjustmentStates(canUseRxData);
diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c
index ed29ef09ed..2a51d74910 100644
--- a/src/main/fc/fc_init.c
+++ b/src/main/fc/fc_init.c
@@ -107,6 +107,7 @@
#include "io/vtx_control.h"
#include "io/vtx_smartaudio.h"
#include "io/vtx_tramp.h"
+#include "io/piniobox.h"
#include "msp/msp_serial.h"
@@ -482,6 +483,14 @@ void init(void)
adcInit(&adc_params);
#endif
+#ifdef USE_PINIO
+ pinioInit();
+#endif
+
+#ifdef USE_PINIOBOX
+ pinioBoxInit();
+#endif
+
#if defined(USE_GPS) || defined(USE_MAG)
delay(500);
diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c
index 1003b64eba..443a59177e 100644
--- a/src/main/fc/fc_msp_box.c
+++ b/src/main/fc/fc_msp_box.c
@@ -81,6 +81,8 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
{ BOXOSDALT3, "OSD ALT 3", 44 },
{ BOXNAVCRUISE, "NAV CRUISE", 45 },
{ BOXBRAKING, "MC BRAKING", 46 },
+ { BOXUSER1, "USER1", 47 },
+ { BOXUSER2, "USER2", 48 },
{ CHECKBOX_ITEM_COUNT, NULL, 0xFF }
};
@@ -266,6 +268,12 @@ void initActiveBoxIds(void)
activeBoxIds[activeBoxIdCount++] = BOXCAMERA3;
#endif
+#ifdef USE_PINIOBOX
+ // USER modes are only used for PINIO at the moment
+ activeBoxIds[activeBoxIdCount++] = BOXUSER1;
+ activeBoxIds[activeBoxIdCount++] = BOXUSER2;
+#endif
+
#if defined(USE_OSD) && defined(OSD_LAYOUT_COUNT)
#if OSD_LAYOUT_COUNT > 0
activeBoxIds[activeBoxIdCount++] = BOXOSDALT1;
diff --git a/src/main/fc/fc_msp_box.h b/src/main/fc/fc_msp_box.h
index 0c3d1a8dfe..b5ca255991 100644
--- a/src/main/fc/fc_msp_box.h
+++ b/src/main/fc/fc_msp_box.h
@@ -19,6 +19,8 @@
#include "fc/rc_modes.h"
+#define PERMANENT_ID_NONE 255 // A permanent ID for no box mode
+
typedef struct box_s {
const uint8_t boxId; // see boxId_e
const char *boxName; // GUI-readable box name
diff --git a/src/main/fc/rc_modes.h b/src/main/fc/rc_modes.h
index 6c55253dcc..8bd889bdf5 100755
--- a/src/main/fc/rc_modes.h
+++ b/src/main/fc/rc_modes.h
@@ -23,6 +23,8 @@
#include "config/parameter_group.h"
+#define BOXID_NONE 255
+
typedef enum {
BOXARM = 0,
BOXANGLE = 1,
@@ -61,6 +63,8 @@ typedef enum {
BOXOSDALT3 = 34,
BOXNAVCRUISE = 35,
BOXBRAKING = 36,
+ BOXUSER1 = 37,
+ BOXUSER2 = 38,
CHECKBOX_ITEM_COUNT
} boxId_e;
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 5c5fcc6f9f..77315c1f97 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -1719,3 +1719,22 @@ groups:
min: VTX_SETTINGS_MIN_FREQUENCY_MHZ
max: VTX_SETTINGS_MAX_FREQUENCY_MHZ
condition: VTX_SETTINGS_FREQCMD
+
+ - name: PG_PINIOBOX_CONFIG
+ type: pinioBoxConfig_t
+ headers: ["io/piniobox.h"]
+ condition: USE_PINIOBOX
+ members:
+ - name: pinio_box1
+ field: permanentId[0]
+ type: uint8_t
+ - name: pinio_box2
+ field: permanentId[1]
+ type: uint8_t
+ - name: pinio_box3
+ field: permanentId[2]
+ type: uint8_t
+ - name: pinio_box4
+ field: permanentId[3]
+ type: uint8_t
+
diff --git a/src/main/io/piniobox.c b/src/main/io/piniobox.c
new file mode 100644
index 0000000000..3bcc7cd5b8
--- /dev/null
+++ b/src/main/io/piniobox.c
@@ -0,0 +1,71 @@
+/*
+ * This file is part of Cleanflight, Betaflight and INAV
+ *
+ * Cleanflight, Betaflight and INAV are free software. You can
+ * redistribute this software and/or modify this software 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.
+ *
+ * Cleanflight, Betaflight and INAV are distributed in the hope that
+ * they 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 software.
+ *
+ * If not, see .
+ */
+
+#include
+#include
+
+#include "platform.h"
+
+#ifdef USE_PINIOBOX
+
+#include "build/debug.h"
+#include "common/utils.h"
+
+#include "config/parameter_group.h"
+#include "config/parameter_group_ids.h"
+
+#include "fc/fc_msp.h"
+#include "fc/fc_msp_box.h"
+
+#include "io/piniobox.h"
+
+
+PG_REGISTER_WITH_RESET_TEMPLATE(pinioBoxConfig_t, pinioBoxConfig, PG_PINIOBOX_CONFIG, 1);
+
+PG_RESET_TEMPLATE(pinioBoxConfig_t, pinioBoxConfig,
+ { PERMANENT_ID_NONE, PERMANENT_ID_NONE, PERMANENT_ID_NONE, PERMANENT_ID_NONE }
+);
+
+typedef struct pinioBoxRuntimeConfig_s {
+ uint8_t boxId[PINIO_COUNT];
+} pinioBoxRuntimeConfig_t;
+
+static pinioBoxRuntimeConfig_t pinioBoxRuntimeConfig;
+
+void pinioBoxInit(void)
+{
+ // Convert permanentId to boxId_e
+ for (int i = 0; i < PINIO_COUNT; i++) {
+ const box_t *box = findBoxByPermanentId(pinioBoxConfig()->permanentId[i]);
+
+ pinioBoxRuntimeConfig.boxId[i] = box ? box->boxId : BOXID_NONE;
+ }
+}
+
+void pinioBoxUpdate(void)
+{
+ for (int i = 0; i < PINIO_COUNT; i++) {
+ if (pinioBoxRuntimeConfig.boxId[i] != BOXID_NONE) {
+ pinioSet(i, IS_RC_MODE_ACTIVE(pinioBoxRuntimeConfig.boxId[i]));
+ }
+ }
+}
+
+#endif
\ No newline at end of file
diff --git a/src/main/io/piniobox.h b/src/main/io/piniobox.h
new file mode 100644
index 0000000000..74ba398a32
--- /dev/null
+++ b/src/main/io/piniobox.h
@@ -0,0 +1,36 @@
+/*
+ * This file is part of Cleanflight, Betaflight and INAV
+ *
+ * Cleanflight, Betaflight and INAV are free software. You can
+ * redistribute this software and/or modify this software 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.
+ *
+ * Cleanflight, Betaflight and INAV are distributed in the hope that
+ * they 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 software.
+ *
+ * If not, see .
+ */
+
+#pragma once
+
+#include
+#include
+
+#include "common/time.h"
+#include "drivers/pinio.h"
+
+typedef struct pinioBoxConfig_s {
+ uint8_t permanentId[PINIO_COUNT];
+} pinioBoxConfig_t;
+
+PG_DECLARE(pinioBoxConfig_t, pinioBoxConfig);
+
+void pinioBoxInit(void);
+void pinioBoxUpdate(void);
diff --git a/src/main/target/MATEKF722SE/config.c b/src/main/target/MATEKF722SE/config.c
new file mode 100644
index 0000000000..c7d6689cdd
--- /dev/null
+++ b/src/main/target/MATEKF722SE/config.c
@@ -0,0 +1,26 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight 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.
+ *
+ * Cleanflight 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 Cleanflight. If not, see .
+ */
+
+#include
+#include "platform.h"
+#include "io/piniobox.h"
+
+void targetConfiguration(void)
+{
+ pinioBoxConfigMutable()->permanentId[0] = 47;
+ pinioBoxConfigMutable()->permanentId[1] = 48;
+}
diff --git a/src/main/target/MATEKF722SE/target.c b/src/main/target/MATEKF722SE/target.c
index c0d44df1e8..daeed6b62c 100644
--- a/src/main/target/MATEKF722SE/target.c
+++ b/src/main/target/MATEKF722SE/target.c
@@ -23,6 +23,7 @@
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
+#include "drivers/pinio.h"
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE);
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE);
diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h
index abe25d5ee0..353e4de4a7 100644
--- a/src/main/target/MATEKF722SE/target.h
+++ b/src/main/target/MATEKF722SE/target.h
@@ -20,6 +20,7 @@
#define USE_TARGET_CONFIG
+#define USE_TARGET_CONFIG
#define TARGET_BOARD_IDENTIFIER "MF7S"
#define USBD_PRODUCT_STRING "MatekF722SE"
@@ -164,12 +165,12 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define AIRSPEED_ADC_CHANNEL ADC_CHN_4
-/*
+
+// *************** ADC *****************************
#define USE_PINIO
-#define PINIO1_PIN PC8 // VTX power switcher
-#define PINIO2_PIN PC9 // 2xCamera switcher
#define USE_PINIOBOX
-*/
+#define PINIO1_PIN PC8 // VTX power switcher
+#define PINIO2_PIN PC9 // 2xCamera switcher
/*
#define CAMERA_CONTROL_PIN PA1 //RX4 pad with 200ohm