From 86149361abcc94ce9e7862a95f43a6be1b0ca4fc Mon Sep 17 00:00:00 2001 From: jflyper Date: Sun, 4 Feb 2018 12:29:22 +0900 Subject: [PATCH] Drop softpwm option Also separates PG related code to pg directory. --- make/source.mk | 1 + src/main/drivers/camera_control.c | 105 +----------------------------- src/main/drivers/camera_control.h | 18 ----- src/main/interface/cli.c | 1 + src/main/interface/settings.c | 2 +- src/main/pg/camera_control.c | 46 +++++++++++++ src/main/pg/camera_control.h | 35 ++++++++++ 7 files changed, 87 insertions(+), 121 deletions(-) create mode 100644 src/main/pg/camera_control.c create mode 100644 src/main/pg/camera_control.h diff --git a/make/source.mk b/make/source.mk index addba3b85..e0750cbe4 100644 --- a/make/source.mk +++ b/make/source.mk @@ -65,6 +65,7 @@ COMMON_SRC = \ pg/beeper_dev.c \ pg/bus_i2c.c \ pg/bus_spi.c \ + pg/camera_control.c \ pg/max7456.c \ pg/pg.c \ pg/rx_pwm.c \ diff --git a/src/main/drivers/camera_control.c b/src/main/drivers/camera_control.c index 7c6ec7038..5307ecb91 100644 --- a/src/main/drivers/camera_control.c +++ b/src/main/drivers/camera_control.c @@ -25,7 +25,7 @@ #include "nvic.h" #include "pwm_output.h" #include "time.h" -#include "pg/pg_ids.h" +#include "pg/camera_control.h" #if defined(STM32F40_41xxx) #define CAMERA_CONTROL_TIMER_HZ MHZ_TO_HZ(84) @@ -36,7 +36,6 @@ #endif #define CAMERA_CONTROL_PWM_RESOLUTION 128 -#define CAMERA_CONTROL_SOFT_PWM_RESOLUTION 448 #ifdef CURRENT_TARGET_CPU_VOLTAGE #define ADC_VOLTAGE CURRENT_TARGET_CPU_VOLTAGE @@ -44,32 +43,13 @@ #define ADC_VOLTAGE 3.3f #endif -#if !defined(STM32F411xE) && !defined(STM32F7) -#define CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE -#include "build/atomic.h" -#endif - #define CAMERA_CONTROL_HARDWARE_PWM_AVAILABLE #include "timer.h" -#ifndef CAMERA_CONTROL_PIN -#define CAMERA_CONTROL_PIN NONE -#endif - #ifdef USE_OSD #include "io/osd.h" #endif -PG_REGISTER_WITH_RESET_TEMPLATE(cameraControlConfig_t, cameraControlConfig, PG_CAMERA_CONTROL_CONFIG, 0); - -PG_RESET_TEMPLATE(cameraControlConfig_t, cameraControlConfig, - .mode = CAMERA_CONTROL_MODE_HARDWARE_PWM, - .refVoltage = 330, - .keyDelayMs = 180, - .internalResistance = 470, - .ioTag = IO_TAG(CAMERA_CONTROL_PIN) -); - static struct { bool enabled; IO_t io; @@ -79,22 +59,6 @@ static struct { static uint32_t endTimeMillis; -#ifdef CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE -void TIM6_DAC_IRQHandler(void) -{ - IOHi(cameraControlRuntime.io); - - TIM6->SR = 0; -} - -void TIM7_IRQHandler(void) -{ - IOLo(cameraControlRuntime.io); - - TIM7->SR = 0; -} -#endif - void cameraControlInit(void) { if (cameraControlConfig()->ioTag == IO_TAG_NONE) @@ -122,27 +86,6 @@ void cameraControlInit(void) cameraControlRuntime.period = CAMERA_CONTROL_PWM_RESOLUTION; *cameraControlRuntime.channel.ccr = cameraControlRuntime.period; cameraControlRuntime.enabled = true; -#endif - } else if (CAMERA_CONTROL_MODE_SOFTWARE_PWM == cameraControlConfig()->mode) { -#ifdef CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE - IOConfigGPIO(cameraControlRuntime.io, IOCFG_OUT_PP); - IOHi(cameraControlRuntime.io); - - cameraControlRuntime.period = CAMERA_CONTROL_SOFT_PWM_RESOLUTION; - cameraControlRuntime.enabled = true; - - NVIC_InitTypeDef nvicTIM6 = { - TIM6_DAC_IRQn, NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER), NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER), ENABLE - }; - NVIC_Init(&nvicTIM6); - NVIC_InitTypeDef nvicTIM7 = { - TIM7_IRQn, NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER), NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER), ENABLE - }; - NVIC_Init(&nvicTIM7); - - RCC->APB1ENR |= RCC_APB1Periph_TIM6 | RCC_APB1Periph_TIM7; - TIM6->PSC = 0; - TIM7->PSC = 0; #endif } else if (CAMERA_CONTROL_MODE_DAC == cameraControlConfig()->mode) { // @todo not yet implemented @@ -154,8 +97,6 @@ void cameraControlProcess(uint32_t currentTimeUs) if (endTimeMillis && currentTimeUs >= 1000 * endTimeMillis) { if (CAMERA_CONTROL_MODE_HARDWARE_PWM == cameraControlConfig()->mode) { *cameraControlRuntime.channel.ccr = cameraControlRuntime.period; - } else if (CAMERA_CONTROL_MODE_SOFTWARE_PWM == cameraControlConfig()->mode) { - } endTimeMillis = 0; @@ -170,7 +111,7 @@ static float calculateKeyPressVoltage(const cameraControlKey_e key) return 1.0e-2f * cameraControlConfig()->refVoltage * buttonResistance / (100 * cameraControlConfig()->internalResistance + buttonResistance); } -#if defined(CAMERA_CONTROL_HARDWARE_PWM_AVAILABLE) || defined(CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE) +#if defined(CAMERA_CONTROL_HARDWARE_PWM_AVAILABLE) static float calculatePWMDutyCycle(const cameraControlKey_e key) { const float voltage = calculateKeyPressVoltage(key); @@ -187,7 +128,7 @@ void cameraControlKeyPress(cameraControlKey_e key, uint32_t holdDurationMs) if (key >= CAMERA_CONTROL_KEYS_COUNT) return; -#if defined(CAMERA_CONTROL_HARDWARE_PWM_AVAILABLE) || defined(CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE) +#if defined(CAMERA_CONTROL_HARDWARE_PWM_AVAILABLE) const float dutyCycle = calculatePWMDutyCycle(key); #else (void) holdDurationMs; @@ -202,46 +143,6 @@ void cameraControlKeyPress(cameraControlKey_e key, uint32_t holdDurationMs) #ifdef CAMERA_CONTROL_HARDWARE_PWM_AVAILABLE *cameraControlRuntime.channel.ccr = lrintf(dutyCycle * cameraControlRuntime.period); endTimeMillis = millis() + cameraControlConfig()->keyDelayMs + holdDurationMs; -#endif - } else if (CAMERA_CONTROL_MODE_SOFTWARE_PWM == cameraControlConfig()->mode) { -#ifdef CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE - const uint32_t hiTime = lrintf(dutyCycle * cameraControlRuntime.period); - - if (0 == hiTime) { - IOLo(cameraControlRuntime.io); - delay(cameraControlConfig()->keyDelayMs + holdDurationMs); - IOHi(cameraControlRuntime.io); - } else { - TIM6->CNT = hiTime; - TIM6->ARR = cameraControlRuntime.period; - - TIM7->CNT = 0; - TIM7->ARR = cameraControlRuntime.period; - - // Start two timers as simultaneously as possible - ATOMIC_BLOCK(NVIC_PRIO_TIMER) { - TIM6->CR1 = TIM_CR1_CEN; - TIM7->CR1 = TIM_CR1_CEN; - } - - // Enable interrupt generation - TIM6->DIER = TIM_IT_Update; - TIM7->DIER = TIM_IT_Update; - - const uint32_t endTime = millis() + cameraControlConfig()->keyDelayMs + holdDurationMs; - - // Wait to give the camera a chance at registering the key press - while (millis() < endTime); - - // Disable timers and interrupt generation - TIM6->CR1 &= ~TIM_CR1_CEN; - TIM7->CR1 &= ~TIM_CR1_CEN; - TIM6->DIER = 0; - TIM7->DIER = 0; - - // Reset to idle state - IOHi(cameraControlRuntime.io); - } #endif } else if (CAMERA_CONTROL_MODE_DAC == cameraControlConfig()->mode) { // @todo not yet implemented diff --git a/src/main/drivers/camera_control.h b/src/main/drivers/camera_control.h index b825900b8..e4c142058 100644 --- a/src/main/drivers/camera_control.h +++ b/src/main/drivers/camera_control.h @@ -17,9 +17,6 @@ #pragma once -#include "io_types.h" -#include "pg/pg.h" - typedef enum { CAMERA_CONTROL_KEY_ENTER, CAMERA_CONTROL_KEY_LEFT, @@ -31,25 +28,10 @@ typedef enum { typedef enum { CAMERA_CONTROL_MODE_HARDWARE_PWM, - CAMERA_CONTROL_MODE_SOFTWARE_PWM, CAMERA_CONTROL_MODE_DAC, CAMERA_CONTROL_MODES_COUNT } cameraControlMode_e; -typedef struct cameraControlConfig_s { - cameraControlMode_e mode; - // measured in 10 mV steps - uint16_t refVoltage; - uint16_t keyDelayMs; - // measured 100 Ohm steps - uint16_t internalResistance; - - ioTag_t ioTag; -} cameraControlConfig_t; - -PG_DECLARE(cameraControlConfig_t, cameraControlConfig); - void cameraControlInit(void); - void cameraControlProcess(uint32_t currentTimeUs); void cameraControlKeyPress(cameraControlKey_e key, uint32_t holdDurationMs); diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c index e7c02a121..0ae1520ff 100644 --- a/src/main/interface/cli.c +++ b/src/main/interface/cli.c @@ -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/camera_control.h" #include "pg/pg.h" #include "pg/pg_ids.h" #include "pg/rx_pwm.h" diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index fdb09829a..197a1dd8b 100644 --- a/src/main/interface/settings.c +++ b/src/main/interface/settings.c @@ -67,6 +67,7 @@ #include "pg/max7456.h" #include "pg/pg.h" #include "pg/pg_ids.h" +#include "pg/camera_control.h" #include "pg/rx_pwm.h" #include "pg/sdcard.h" #include "pg/vcd.h" @@ -229,7 +230,6 @@ static const char * const lookupTableGyroLpf[] = { #ifdef USE_CAMERA_CONTROL static const char * const lookupTableCameraControlMode[] = { "HARDWARE_PWM", - "SOFTWARE_PWM", "DAC" }; #endif diff --git a/src/main/pg/camera_control.c b/src/main/pg/camera_control.c new file mode 100644 index 000000000..0241f653e --- /dev/null +++ b/src/main/pg/camera_control.c @@ -0,0 +1,46 @@ +/* + * 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 + +#ifdef USE_CAMERA_CONTROL + +#include "pg/pg_ids.h" +#include "pg/camera_control.h" +#include "drivers/camera_control.h" +#include "drivers/io.h" + +//#include "math.h" +//#include "nvic.h" +//#include "pwm_output.h" +//#include "time.h" + +#ifndef CAMERA_CONTROL_PIN +#define CAMERA_CONTROL_PIN NONE +#endif + +PG_REGISTER_WITH_RESET_TEMPLATE(cameraControlConfig_t, cameraControlConfig, PG_CAMERA_CONTROL_CONFIG, 0); + +PG_RESET_TEMPLATE(cameraControlConfig_t, cameraControlConfig, + .mode = CAMERA_CONTROL_MODE_HARDWARE_PWM, + .refVoltage = 330, + .keyDelayMs = 180, + .internalResistance = 470, + .ioTag = IO_TAG(CAMERA_CONTROL_PIN) +); + +#endif diff --git a/src/main/pg/camera_control.h b/src/main/pg/camera_control.h new file mode 100644 index 000000000..2bbd9bb43 --- /dev/null +++ b/src/main/pg/camera_control.h @@ -0,0 +1,35 @@ +/* + * 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 . + */ + +#pragma once + +#include "drivers/io_types.h" +#include "drivers/camera_control.h" +#include "pg/pg.h" + +typedef struct cameraControlConfig_s { + cameraControlMode_e mode; + // measured in 10 mV steps + uint16_t refVoltage; + uint16_t keyDelayMs; + // measured 100 Ohm steps + uint16_t internalResistance; + + ioTag_t ioTag; +} cameraControlConfig_t; + +PG_DECLARE(cameraControlConfig_t, cameraControlConfig);