Replace gimbal_flags with FEATURE_CHANNEL_FORWARDING and gimbal_mode.

Gimbals are only one use of channel forwarding, PWM video switchers and
PWM buzzers are others.
This commit is contained in:
Dominic Clifton 2015-07-08 16:41:29 +01:00
parent 4ead898f6f
commit 7b91524ba2
10 changed files with 23 additions and 16 deletions

View File

@ -201,7 +201,7 @@ Re-apply any new defaults as desired.
| `failsafe_throttle` | | 1000 | 2000 | 1200 | Profile | UINT16 |
| `rx_min_usec` | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of `mid_rc`. | 100 | 2000 | 985 | Profile | UINT16 |
| `rx_max_usec` | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of `mid_rc`. | 100 | 3000 | 2115 | Profile | UINT16 |
| `gimbal_flags` | When feature SERVO_TILT is enabled, this can be a combination of the following numbers: 1=normal gimbal (default), 2=tiltmix gimbal, 4=in PPM (or SERIALRX) input mode, this will forward AUX1..4 RC inputs to PWM5..8 pins | 0 | 255 | 1 | Profile | UINT8 |
| `gimbal_mode` | When feature SERVO_TILT is enabled, this can be either 0=normal gimbal (default) or 1=tiltmix gimbal | 0 | 1 | 0 | Profile | UINT8 |
| `acc_hardware` | This is used to suggest which accelerometer driver should load, or to force no accelerometer in case gyro-only flight is needed. Default (0) will attempt to auto-detect among enabled drivers. Otherwise, to force a particular device, set it to 2 for ADXL345, 3 for MPU6050 integrated accelerometer, 4 for MMA8452, 5 for BMA280, 6 for LSM303DLHC, 7 for SPI_MPU6000, 8 for SPI_MPU6500 or 1 to disable accelerometer alltogether - resulting in gyro-only operation. | 0 | 9 | 0 | Master | UINT8 |
| `acc_lpf_factor` | This setting controls the Low Pass Filter factor for ACC. Increasing this value reduces ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter | 0 | 250 | 4 | Profile | UINT8 |
| `accxy_deadband` | | 0 | 100 | 40 | Profile | UINT8 |

View File

@ -98,3 +98,8 @@ reason: renamed to `3d_neutral` for consistency
### alt_hold_throttle_neutral
reason: renamed to `alt_hold_deadband` for consistency
### gimbal_flags
reason: seperation of features.
see `gimbal_mode` and `CHANNEL_FORWARDING` feature

View File

@ -487,7 +487,7 @@ static void resetConf(void)
}
// gimbal
currentProfile->gimbalConfig.gimbal_flags = GIMBAL_NORMAL;
currentProfile->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
#endif
#ifdef GPS

View File

@ -42,7 +42,8 @@ typedef enum {
FEATURE_LED_STRIP = 1 << 16,
FEATURE_DISPLAY = 1 << 17,
FEATURE_ONESHOT125 = 1 << 18,
FEATURE_BLACKBOX = 1 << 19
FEATURE_BLACKBOX = 1 << 19,
FEATURE_CHANNEL_FORWARDING = 1 << 20
} features_e;
void handleOneshotFeatureChangeOnRestart(void);

View File

@ -502,7 +502,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
#endif
}
if (init->extraServos && !init->airplane) {
if (init->useChannelForwarding && !init->airplane) {
#if defined(NAZE) && defined(LED_STRIP_TIMER)
// if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14
if (init->useLEDStrip) {

View File

@ -63,7 +63,7 @@ typedef struct drv_pwm_config_t {
#endif
#ifdef USE_SERVOS
bool useServos;
bool extraServos; // configure additional 4 channels in PPM mode as servos, not motors
bool useChannelForwarding; // configure additional channels as servos
uint16_t servoPwmRate;
uint16_t servoCenterPulse;
#endif

View File

@ -657,7 +657,7 @@ void writeServos(void)
}
// forward AUX to remaining servo outputs (not constrained)
if (gimbalConfig->gimbal_flags & GIMBAL_FORWARDAUX) {
if (feature(FEATURE_CHANNEL_FORWARDING)) {
forwardAuxChannelsToServos(servoIndex);
servoIndex += MAX_AUX_CHANNEL_COUNT;
}
@ -839,7 +839,7 @@ void mixTable(void)
servo[SERVO_GIMBAL_ROLL] = determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL);
if (IS_RC_MODE_ACTIVE(BOXCAMSTAB)) {
if (gimbalConfig->gimbal_flags & GIMBAL_MIXTILT) {
if (gimbalConfig->mode == GIMBAL_MODE_MIXTILT) {
servo[SERVO_GIMBAL_PITCH] -= (-(int32_t)servoConf[SERVO_GIMBAL_PITCH].rate) * inclination.values.pitchDeciDegrees / 50 - (int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * inclination.values.rollDeciDegrees / 50;
servo[SERVO_GIMBAL_ROLL] += (-(int32_t)servoConf[SERVO_GIMBAL_PITCH].rate) * inclination.values.pitchDeciDegrees / 50 + (int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * inclination.values.rollDeciDegrees / 50;
} else {

View File

@ -17,12 +17,13 @@
#pragma once
typedef enum GimbalFlags {
GIMBAL_NORMAL = 1 << 0,
GIMBAL_MIXTILT = 1 << 1,
GIMBAL_FORWARDAUX = 1 << 2,
} GimbalFlags;
typedef enum {
GIMBAL_MODE_NORMAL = 0,
GIMBAL_MODE_MIXTILT = 1
} gimbalMode_e;
#define GIMBAL_MODE_MAX (GIMBAL_MODE_MIXTILT)
typedef struct gimbalConfig_s {
uint8_t gimbal_flags; // in servotilt mode, various things that affect stuff
uint8_t mode;
} gimbalConfig_t;

View File

@ -162,7 +162,7 @@ static const char * const featureNames[] = {
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
"BLACKBOX", NULL
"BLACKBOX", "CHANNEL_FORWARDING", NULL
};
#ifndef CJMCU
@ -427,7 +427,7 @@ const clivalue_t valueTable[] = {
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, PWM_PULSE_MIN, PWM_PULSE_MAX },
#ifdef USE_SERVOS
{ "gimbal_flags", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gimbalConfig.gimbal_flags, 0, 255},
{ "gimbal_mode", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gimbalConfig.mode, 0, GIMBAL_MODE_MAX},
#endif
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.acc_hardware, 0, ACC_MAX },

View File

@ -249,7 +249,7 @@ void init(void)
#ifdef USE_SERVOS
pwm_params.useServos = isMixerUsingServos();
pwm_params.extraServos = currentProfile->gimbalConfig.gimbal_flags & GIMBAL_FORWARDAUX;
pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
pwm_params.servoCenterPulse = masterConfig.escAndServoConfig.servoCenterPulse;
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
#endif