Cleanup ONESHOT125 feature // Default denom

This commit is contained in:
borisbstyle 2016-08-04 11:46:55 +02:00
parent 45f2ce04d5
commit 7d119ae669
14 changed files with 97 additions and 23 deletions

View File

@ -474,6 +474,9 @@ static void resetConf(void)
#ifdef STM32F10X
masterConfig.gyro_sync_denom = 8;
masterConfig.pid_process_denom = 1;
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500)
masterConfig.gyro_sync_denom = 8;
masterConfig.pid_process_denom = 4;
#else
masterConfig.gyro_sync_denom = 4;
masterConfig.pid_process_denom = 2;

View File

@ -46,16 +46,15 @@ typedef enum {
FEATURE_RSSI_ADC = 1 << 15,
FEATURE_LED_STRIP = 1 << 16,
FEATURE_DISPLAY = 1 << 17,
FEATURE_ONESHOT125 = 1 << 18,
FEATURE_OSD = 1 << 18,
FEATURE_BLACKBOX = 1 << 19,
FEATURE_CHANNEL_FORWARDING = 1 << 20,
FEATURE_TRANSPONDER = 1 << 21,
FEATURE_AIRMODE = 1 << 22,
FEATURE_SUPEREXPO_RATES = 1 << 23,
FEATURE_OSD = 1 << 24,
FEATURE_VTX = 1 << 25,
FEATURE_RX_NRF24 = 1 << 26,
FEATURE_SOFTSPI = 1 << 27,
FEATURE_VTX = 1 << 24,
FEATURE_RX_NRF24 = 1 << 25,
FEATURE_SOFTSPI = 1 << 26,
} features_e;
void latchActiveFeatures(void);

View File

@ -206,9 +206,8 @@ static const char * const featureNames[] = {
"RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES",
"OSD", NULL
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES", NULL
};
// sync this with rxFailsafeChannelMode_e

View File

@ -288,12 +288,6 @@ void init(void)
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
#endif
if (masterConfig.motor_pwm_protocol == PWM_TYPE_ONESHOT125) {
featureSet(FEATURE_ONESHOT125);
} else {
featureClear(FEATURE_ONESHOT125);
}
bool use_unsyncedPwm = masterConfig.use_unsyncedPwm || masterConfig.motor_pwm_protocol == PWM_TYPE_CONVENTIONAL || masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED;
// Configurator feature abused for enabling Fast PWM

View File

@ -72,7 +72,6 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void)
{
featureClear(FEATURE_ONESHOT125);
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;

View File

@ -77,7 +77,6 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
featureClear(FEATURE_ONESHOT125);
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;

View File

@ -77,7 +77,6 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
featureClear(FEATURE_ONESHOT125);
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;

View File

@ -138,7 +138,7 @@
#define CURRENT_METER_ADC_PIN PC2
#define RSSI_ADC_PIN PC1
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_ONESHOT125)
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS

View File

@ -150,7 +150,7 @@
#define RSSI_ADC_GPIO_PIN PC2
#define CURRENT_METER_ADC_PIN PC3
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_ONESHOT125)
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS

View File

@ -0,0 +1,82 @@
/*
* 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>
#include "build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// Motolab target supports 2 different type of boards Tornado / Cyclone.
void targetConfiguration(void) {
masterConfig.gyro_sync_denom = 4;
masterConfig.pid_process_denom = 1;
}

View File

@ -167,7 +167,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125)
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX)
#define BUTTONS
#define BUTTON_A_PORT GPIOB

View File

@ -121,7 +121,7 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125 | FEATURE_RX_SERIAL)
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL)
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -110,7 +110,7 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125)
#define DEFAULT_FEATURES (FEATURE_BLACKBOX)
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -156,7 +156,7 @@
#define RSSI_ADC_GPIO_PIN PB1
#define CURRENT_METER_ADC_PIN PA5
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_ONESHOT125 | FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS