Generic pin output driver
This commit is contained in:
parent
1a6964b6b7
commit
8f76a11081
|
@ -34,6 +34,7 @@ COMMON_SRC = \
|
|||
drivers/exti.c \
|
||||
drivers/io.c \
|
||||
drivers/light_led.c \
|
||||
drivers/pinio.c \
|
||||
drivers/resource.c \
|
||||
drivers/rcc.c \
|
||||
drivers/serial.c \
|
||||
|
@ -67,6 +68,7 @@ COMMON_SRC = \
|
|||
pg/bus_spi.c \
|
||||
pg/dashboard.c \
|
||||
pg/max7456.c \
|
||||
pg/pinio.c \
|
||||
pg/pg.c \
|
||||
pg/rx_pwm.c \
|
||||
pg/sdcard.c \
|
||||
|
|
|
@ -0,0 +1,76 @@
|
|||
/*
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef USE_PINIO
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "pg/pinio.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
|
||||
typedef struct pinioRuntime_s {
|
||||
IO_t io;
|
||||
bool inverted;
|
||||
bool state;
|
||||
} pinioRuntime_t;
|
||||
|
||||
static pinioRuntime_t pinioRuntime[PINIO_COUNT];
|
||||
|
||||
void pinioInit(const pinioConfig_t *pinioConfig)
|
||||
{
|
||||
for (int i = 0; i < PINIO_COUNT; i++) {
|
||||
IO_t io = IOGetByTag(pinioConfig->ioTag[i]);
|
||||
|
||||
if (!io) {
|
||||
continue;
|
||||
}
|
||||
|
||||
IOInit(io, OWNER_PINIO, RESOURCE_INDEX(i));
|
||||
|
||||
switch (pinioConfig->config[i] & PINIO_CONFIG_MODE_MASK) {
|
||||
case PINIO_CONFIG_MODE_OUT_PP:
|
||||
IOConfigGPIO(io, IOCFG_OUT_PP);
|
||||
break;
|
||||
}
|
||||
|
||||
if (pinioConfig->config[i] & PINIO_CONFIG_OUT_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)
|
||||
{
|
||||
bool newState = on ^ pinioRuntime[index].inverted;
|
||||
if (newState != pinioRuntime[index].state) {
|
||||
IOWrite(pinioRuntime[index].io, newState);
|
||||
pinioRuntime[index].state = newState;
|
||||
}
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,31 @@
|
|||
/*
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#ifndef PINIO_COUNT
|
||||
#define PINIO_COUNT 4
|
||||
#endif
|
||||
|
||||
#define PINIO_CONFIG_OUT_INVERTED 0x80
|
||||
#define PINIO_CONFIG_MODE_MASK 0x7F
|
||||
#define PINIO_CONFIG_MODE_OUT_PP 0x01
|
||||
|
||||
struct pinioConfig_s;
|
||||
|
||||
void pinioInit(const struct pinioConfig_s *pinioConfig);
|
||||
void pinioSet(int index, bool on);
|
|
@ -69,5 +69,6 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|||
"CAMERA_CONTROL",
|
||||
"TIMUP",
|
||||
"RANGEFINDER",
|
||||
"RX_SPI"
|
||||
"RX_SPI",
|
||||
"PINIO",
|
||||
};
|
||||
|
|
|
@ -70,6 +70,7 @@ typedef enum {
|
|||
OWNER_TIMUP,
|
||||
OWNER_RANGEFINDER,
|
||||
OWNER_RX_SPI,
|
||||
OWNER_PINIO,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_e;
|
||||
|
||||
|
|
|
@ -87,6 +87,7 @@
|
|||
#include "pg/bus_i2c.h"
|
||||
#include "pg/bus_spi.h"
|
||||
#include "pg/flash.h"
|
||||
#include "pg/pinio.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/rx_pwm.h"
|
||||
#include "pg/sdcard.h"
|
||||
|
@ -533,6 +534,10 @@ void init(void)
|
|||
servosFilterInit();
|
||||
#endif
|
||||
|
||||
#ifdef USE_PINIO
|
||||
pinioInit(pinioConfig());
|
||||
#endif
|
||||
|
||||
LED1_ON;
|
||||
LED0_OFF;
|
||||
LED2_OFF;
|
||||
|
|
|
@ -118,6 +118,7 @@ extern uint8_t __config_end;
|
|||
#include "pg/beeper_dev.h"
|
||||
#include "pg/bus_i2c.h"
|
||||
#include "pg/bus_spi.h"
|
||||
#include "pg/pinio.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx_pwm.h"
|
||||
|
@ -3223,6 +3224,9 @@ const cliResourceValue_t resourceTable[] = {
|
|||
{ OWNER_SDCARD_CS, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, chipSelectTag), 0 },
|
||||
{ OWNER_SDCARD_DETECT, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, cardDetectTag), 0 },
|
||||
#endif
|
||||
#ifdef USE_PINIO
|
||||
{ OWNER_PINIO, PG_PINIO_CONFIG, offsetof(pinioConfig_t, ioTag), PINIO_COUNT },
|
||||
#endif
|
||||
};
|
||||
|
||||
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/camera_control.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/pinio.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
@ -68,6 +69,7 @@
|
|||
#include "pg/max7456.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/pinio.h"
|
||||
#include "pg/rx_pwm.h"
|
||||
#include "pg/sdcard.h"
|
||||
#include "pg/vcd.h"
|
||||
|
@ -860,6 +862,11 @@ const clivalue_t valueTable[] = {
|
|||
#ifdef USE_RANGEFINDER
|
||||
{ "rangefinder_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RANGEFINDER_HARDWARE }, PG_RANGEFINDER_CONFIG, offsetof(rangefinderConfig_t, rangefinder_hardware) },
|
||||
#endif
|
||||
|
||||
// PG_PINIO_CONFIG
|
||||
#ifdef USE_PINIO
|
||||
{ "pinio_config", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = PINIO_COUNT, PG_PINIO_CONFIG, offsetof(pinioConfig_t, config) },
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
|
||||
|
|
|
@ -119,7 +119,8 @@
|
|||
#define PG_TIME_CONFIG 526
|
||||
#define PG_RANGEFINDER_CONFIG 527 // iNav
|
||||
#define PG_TRICOPTER_CONFIG 528
|
||||
#define PG_BETAFLIGHT_END 528
|
||||
#define PG_PINIO_CONFIG 529
|
||||
#define PG_BETAFLIGHT_END 529
|
||||
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
|
|
|
@ -0,0 +1,55 @@
|
|||
/*
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_PINIO
|
||||
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pinio.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#ifndef PINIO1_PIN
|
||||
#define PINIO1_PIN NONE
|
||||
#endif
|
||||
#ifndef PINIO2_PIN
|
||||
#define PINIO2_PIN NONE
|
||||
#endif
|
||||
#ifndef PINIO3_PIN
|
||||
#define PINIO3_PIN NONE
|
||||
#endif
|
||||
#ifndef PINIO4_PIN
|
||||
#define PINIO4_PIN NONE
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(pinioConfig_t, pinioConfig, PG_PINIO_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(pinioConfig_t, pinioConfig,
|
||||
.ioTag = {
|
||||
IO_TAG(PINIO1_PIN),
|
||||
IO_TAG(PINIO2_PIN),
|
||||
IO_TAG(PINIO3_PIN),
|
||||
IO_TAG(PINIO4_PIN),
|
||||
},
|
||||
.config = {
|
||||
PINIO_CONFIG_MODE_OUT_PP,
|
||||
PINIO_CONFIG_MODE_OUT_PP,
|
||||
PINIO_CONFIG_MODE_OUT_PP,
|
||||
PINIO_CONFIG_MODE_OUT_PP
|
||||
},
|
||||
);
|
||||
#endif
|
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "drivers/io_types.h"
|
||||
#include "drivers/pinio.h"
|
||||
|
||||
typedef struct pinioConfig_s {
|
||||
ioTag_t ioTag[PINIO_COUNT];
|
||||
uint8_t config[PINIO_COUNT];
|
||||
} pinioConfig_t;
|
||||
|
||||
PG_DECLARE(pinioConfig_t, pinioConfig);
|
|
@ -136,6 +136,7 @@
|
|||
#define USE_MSP_OVER_TELEMETRY
|
||||
#define USE_OSD
|
||||
#define USE_OSD_OVER_MSP_DISPLAYPORT
|
||||
#define USE_PINIO
|
||||
#define USE_RCDEVICE
|
||||
#define USE_RTC_TIME
|
||||
#define USE_RX_MSP
|
||||
|
|
Loading…
Reference in New Issue