Merge pull request #5824 from blckmn/timer_config

Timer configuration
This commit is contained in:
Michael Keller 2018-05-06 15:53:02 +12:00 committed by GitHub
commit 717444175c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
10 changed files with 376 additions and 10 deletions

View File

@ -703,3 +703,25 @@
#define DEF_TIM_AF__PI7__TCH_TIM8_CH3 D(3, 8)
#endif
#ifdef USE_TIMER_MGMT
#if defined(STM32F7) || defined(STM32F4)
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11) | TIM_N(12) | TIM_N(13) | TIM_N(14) )
#elif defined(STM32F3)
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
#elif defined(STM32F1)
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
#else
#error "No timer / channel tag definition found for CPU"
#endif
#define TIMER_COUNT BITCOUNT(USED_TIMERS)
#endif

View File

@ -128,6 +128,7 @@ extern uint8_t __config_end;
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx_pwm.h"
#include "pg/timerio.h"
#include "pg/usb.h"
#include "rx/rx.h"
@ -3609,6 +3610,115 @@ static void cliDma(char* cmdLine)
}
#endif /* USE_RESOURCE_MGMT */
#ifdef USE_TIMER_MGMT
static void printTimer(uint8_t dumpMask)
{
cliPrintLine("# examples: ");
const char *format = "timer %c%02d %d";
cliPrint("#");
cliPrintLinef(format, 'A', 1, 1);
cliPrint("#");
cliPrintLinef(format, 'A', 1, 0);
for (unsigned int i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
const ioTag_t ioTag = timerIOConfig(i)->ioTag;
const uint8_t timerIndex = timerIOConfig(i)->index;
if (!ioTag) {
continue;
}
if (timerIndex != 0 && !(dumpMask & HIDE_UNUSED)) {
cliDumpPrintLinef(dumpMask, false, format,
IO_GPIOPortIdxByTag(ioTag) + 'A',
IO_GPIOPinIdxByTag(ioTag),
timerIndex
);
}
}
}
static void cliTimer(char *cmdline)
{
int len = strlen(cmdline);
if (len == 0) {
printTimer(DUMP_MASTER | HIDE_UNUSED);
return;
} else if (strncasecmp(cmdline, "list", len) == 0) {
printTimer(DUMP_MASTER);
return;
}
char *pch = NULL;
char *saveptr;
int timerIOIndex = -1;
ioTag_t ioTag = 0;
pch = strtok_r(cmdline, " ", &saveptr);
if (!pch || !(strToPin(pch, &ioTag) && IOGetByTag(ioTag))) {
goto error;
}
/* find existing entry, or go for next available */
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
if (timerIOConfig(i)->ioTag == ioTag) {
timerIOIndex = i;
break;
}
/* first available empty slot */
if (timerIOIndex < 0 && timerIOConfig(i)->ioTag == IO_TAG_NONE) {
timerIOIndex = i;
}
}
if (timerIOIndex < 0) {
cliPrintLine("Error: out of index");
return;
}
uint8_t timerIndex = 0;
pch = strtok_r(NULL, " ", &saveptr);
if (pch) {
if (strcasecmp(pch, "list") == 0) {
/* output the list of available options */
uint8_t index = 1;
for (unsigned i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].tag == ioTag) {
cliPrintLinef("# %d. TIM%d CH%d",
index,
timerGetTIMNumber(timerHardware[i].tim),
CC_INDEX_FROM_CHANNEL(timerHardware[i].channel)
);
index++;
}
}
return;
} else if (strcasecmp(pch, "none") == 0) {
goto success;
} else {
timerIndex = atoi(pch);
}
} else {
goto error;
}
success:
timerIOConfigMutable(timerIOIndex)->ioTag = timerIndex == 0 ? IO_TAG_NONE : ioTag;
timerIOConfigMutable(timerIOIndex)->index = timerIndex;
cliPrintLine("Success");
return;
error:
cliShowParseError();
}
#endif
static void backupConfigs(void)
{
// make copies of configs to do differencing
@ -3870,6 +3980,9 @@ const clicmd_t cmdTable[] = {
#endif
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "[nosave]", cliDefaults),
CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|profile|rates|all] {defaults}", cliDiff),
#ifdef USE_RESOURCE_MGMT
CLI_COMMAND_DEF("dma", "list dma utilisation", NULL, cliDma),
#endif
#ifdef USE_DSHOT
CLI_COMMAND_DEF("dshotprog", "program DShot ESC(s)", "<index> <command>+", cliDshotProg),
#endif
@ -3913,6 +4026,9 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
#endif
CLI_COMMAND_DEF("motor", "get/set motor", "<index> [<value>]", cliMotor),
#ifdef USE_USB_MSC
CLI_COMMAND_DEF("msc", "switch into msc mode", NULL, cliMsc),
#endif
CLI_COMMAND_DEF("name", "name of craft", NULL, cliName),
#ifndef MINIMAL_CLI
CLI_COMMAND_DEF("play_sound", NULL, "[<index>]", cliPlaySound),
@ -3921,7 +4037,6 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
#ifdef USE_RESOURCE_MGMT
CLI_COMMAND_DEF("resource", "show/set resources", NULL, cliResource),
CLI_COMMAND_DEF("dma", "list dma utilisation", NULL, cliDma),
#endif
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFailsafe),
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
@ -3946,14 +4061,14 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
#ifndef SKIP_TASK_STATISTICS
CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
#endif
#ifdef USE_TIMER_MGMT
CLI_COMMAND_DEF("timer", "show timer configuration", NULL, cliTimer),
#endif
CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
#ifdef USE_VTX_CONTROL
CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
#endif
#ifdef USE_USB_MSC
CLI_COMMAND_DEF("msc", "switch into msc mode", NULL, cliMsc),
#endif
};
static void cliHelp(char *cmdline)

View File

@ -127,7 +127,8 @@
#define PG_USB_CONFIG 531
#define PG_SDIO_CONFIG 532
#define PG_DISPLAY_PORT_CRSF_CONFIG 533
#define PG_BETAFLIGHT_END 533
#define PG_TIMER_IO_CONFIG 534 // used to store the index for timer use in timerHardware array in target.c
#define PG_BETAFLIGHT_END 534
// OSD configuration (subject to change)

View File

@ -49,11 +49,7 @@ PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig)
{
#ifdef PPM_PIN
ppmConfig->ioTag = IO_TAG(PPM_PIN);
#else
ppmConfig->ioTag = timerioTagGetByUsage(TIM_USE_PPM, 0);
#endif
}
#endif

27
src/main/pg/timerio.c Normal file
View File

@ -0,0 +1,27 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight 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 and Betaflight 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 <http://www.gnu.org/licenses/>.
*/
#include "timerio.h"
#ifdef USE_TIMER_MGMT
PG_REGISTER_ARRAY(timerIOConfig_t, MAX_TIMER_PINMAP_COUNT, timerIOConfig, PG_TIMER_IO_CONFIG, 0);
#endif

39
src/main/pg/timerio.h Normal file
View File

@ -0,0 +1,39 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight 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 and Betaflight 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 <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "drivers/io.h"
#ifdef USE_TIMER_MGMT
#define MAX_TIMER_PINMAP_COUNT 10
typedef struct timerIOConfig_s {
ioTag_t ioTag;
uint8_t index;
} timerIOConfig_t;
PG_DECLARE_ARRAY(timerIOConfig_t, MAX_TIMER_PINMAP_COUNT, timerIOConfig);
#endif

View File

@ -136,4 +136,5 @@
#define TARGET_IO_PORTD (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) )
#define USE_TIMER_MGMT

View File

@ -0,0 +1,59 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight 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 and Betaflight 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 <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM | TIM_USE_PPM, 0, 0),
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0),
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0),
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0),
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0),
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1),
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0),
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0),
DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 0, 0),
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0),
//11
DEF_TIM(TIM10, CH1, PB8, 0, 0, 0),
DEF_TIM(TIM5, CH4, PA3, 0, 0, 0),
DEF_TIM(TIM9, CH2, PA3, 0, 0, 0),
DEF_TIM(TIM11, CH1, PB9, 0, 0, 0),
DEF_TIM(TIM1, CH1N, PB13, 0, 0, 0),
DEF_TIM(TIM1, CH2N, PB14, 0, 0, 0),
DEF_TIM(TIM8, CH2N, PB14, 0, 0, 0),
DEF_TIM(TIM12, CH1, PB14, 0, 0, 0),
DEF_TIM(TIM1, CH3N, PB15, 0, 0, 0),
DEF_TIM(TIM8, CH3N, PB15, 0, 0, 0),
DEF_TIM(TIM3, CH1, PC6, 0, 0, 0),
DEF_TIM(TIM3, CH2, PC7, 0, 0, 0),
DEF_TIM(TIM3, CH4, PC9, 0, 0, 0),
DEF_TIM(TIM3, CH3, PC8, 0, 0, 0),
};

View File

@ -0,0 +1,97 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight 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 and Betaflight 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 <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "S7X2"
#define USBD_PRODUCT_STRING "S7X2"
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
// MPU6500 interrupt
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_ACC
#define USE_FAKE_ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
#define USE_GYRO
#define USE_FAKE_GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
// MPU6050 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_INT_EXTI PB15
#define USE_EXTI
#define USE_MAG
#define USE_FAKE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_BARO
#define USE_FAKE_BARO
#define USE_BARO_MS5611
#define USE_SDCARD
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
#define USE_I2C
#define USE_I2C_DEVICE_1
#define USE_VCP
#define USE_UART1
#define USE_UART3
#define USE_UART6
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 6
#define USE_ESCSERIAL
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3
#define USE_ADC
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0xffff
#define USABLE_TIMER_CHANNEL_COUNT 25
#define USE_TIMER_MGMT

View File

@ -0,0 +1,9 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \
$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c