fix for pwm preload (not possible with this firmware, reported by marcin)
added gimbal flags to mixer. allows making gimbal tilt only or pantilt or disabling all pan/tilt by aux3/4 git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@149 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
8f80611324
commit
f3a4e9f731
4886
obj/baseflight.hex
4886
obj/baseflight.hex
File diff suppressed because it is too large
Load Diff
|
@ -102,6 +102,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "tri_yaw_middle", VAR_UINT16, &cfg.tri_yaw_middle, 0, 2000 },
|
||||
{ "tri_yaw_min", VAR_UINT16, &cfg.tri_yaw_min, 0, 2000 },
|
||||
{ "tri_yaw_max", VAR_UINT16, &cfg.tri_yaw_max, 0, 2000 },
|
||||
{ "gimbal_flags", VAR_UINT8, &cfg.gimbal_flags, 0, 255},
|
||||
{ "gimbal_pitch_gain", VAR_INT8, &cfg.gimbal_pitch_gain, -100, 100 },
|
||||
{ "gimbal_roll_gain", VAR_INT8, &cfg.gimbal_roll_gain, -100, 100 },
|
||||
{ "gimbal_pitch_min", VAR_UINT16, &cfg.gimbal_pitch_min, 100, 3000 },
|
||||
|
|
|
@ -13,7 +13,7 @@ config_t cfg;
|
|||
const char rcChannelLetters[] = "AERT1234";
|
||||
|
||||
static uint32_t enabledSensors = 0;
|
||||
static uint8_t checkNewConf = 12;
|
||||
static uint8_t checkNewConf = 13;
|
||||
|
||||
void parseRcChannels(const char *input)
|
||||
{
|
||||
|
@ -149,6 +149,7 @@ void checkFirstTime(bool reset)
|
|||
// gimbal
|
||||
cfg.gimbal_pitch_gain = 10;
|
||||
cfg.gimbal_roll_gain = 10;
|
||||
cfg.gimbal_flags = GIMBAL_NORMAL;
|
||||
cfg.gimbal_pitch_min = 1020;
|
||||
cfg.gimbal_pitch_max = 2000;
|
||||
cfg.gimbal_pitch_mid = 1500;
|
||||
|
|
|
@ -339,11 +339,18 @@ bool pwmInit(drv_pwm_config_t *init)
|
|||
// PWM1,2
|
||||
TIM_OC1Init(TIM1, &TIM_OCInitStructure);
|
||||
TIM_OC4Init(TIM1, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(TIM1, TIM_OCPreload_Enable);
|
||||
TIM_OC4PreloadConfig(TIM1, TIM_OCPreload_Enable);
|
||||
|
||||
// PWM3,4,5,6
|
||||
TIM_OC1Init(TIM4, &TIM_OCInitStructure);
|
||||
TIM_OC2Init(TIM4, &TIM_OCInitStructure);
|
||||
TIM_OC3Init(TIM4, &TIM_OCInitStructure);
|
||||
TIM_OC4Init(TIM4, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(TIM4, TIM_OCPreload_Enable);
|
||||
TIM_OC2PreloadConfig(TIM4, TIM_OCPreload_Enable);
|
||||
TIM_OC3PreloadConfig(TIM4, TIM_OCPreload_Enable);
|
||||
TIM_OC4PreloadConfig(TIM4, TIM_OCPreload_Enable);
|
||||
|
||||
TIM_Cmd(TIM1, ENABLE);
|
||||
TIM_Cmd(TIM4, ENABLE);
|
||||
|
@ -374,6 +381,10 @@ bool pwmInit(drv_pwm_config_t *init)
|
|||
TIM_OC2Init(TIM3, &TIM_OCInitStructure);
|
||||
TIM_OC3Init(TIM3, &TIM_OCInitStructure);
|
||||
TIM_OC4Init(TIM3, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
|
||||
TIM_OC2PreloadConfig(TIM3, TIM_OCPreload_Enable);
|
||||
TIM_OC3PreloadConfig(TIM3, TIM_OCPreload_Enable);
|
||||
TIM_OC4PreloadConfig(TIM3, TIM_OCPreload_Enable);
|
||||
|
||||
TIM_Cmd(TIM3, ENABLE);
|
||||
TIM_CtrlPWMOutputs(TIM3, ENABLE);
|
||||
|
|
|
@ -300,9 +300,14 @@ bool pwmInit(drv_pwm_config_t *init)
|
|||
TIM_OC2Init(TIM4, &TIM_OCInitStructure);
|
||||
TIM_OC3Init(TIM4, &TIM_OCInitStructure);
|
||||
TIM_OC4Init(TIM4, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(TIM4, TIM_OCPreload_Enable);
|
||||
TIM_OC2PreloadConfig(TIM4, TIM_OCPreload_Enable);
|
||||
TIM_OC3PreloadConfig(TIM4, TIM_OCPreload_Enable);
|
||||
TIM_OC4PreloadConfig(TIM4, TIM_OCPreload_Enable);
|
||||
|
||||
TIM_Cmd(TIM4, ENABLE);
|
||||
TIM_CtrlPWMOutputs(TIM4, ENABLE);
|
||||
TIM_OC1PreloadConfig (TIM4, TIM_OCPreload_Enable);
|
||||
|
||||
// turn on more motor outputs if we're using ppm / not using pwm input
|
||||
if (!init->enableInput || init->usePPM) {
|
||||
|
|
11
src/mixer.c
11
src/mixer.c
|
@ -232,8 +232,15 @@ void mixTable(void)
|
|||
|
||||
// do camstab
|
||||
if (feature(FEATURE_SERVO_TILT)) {
|
||||
servo[0] = cfg.gimbal_pitch_mid + rcData[AUX3] - cfg.midrc;
|
||||
servo[1] = cfg.gimbal_roll_mid + rcData[AUX4] - cfg.midrc;
|
||||
uint16_t aux[2] = { 0, 0 };
|
||||
|
||||
if ((cfg.gimbal_flags & GIMBAL_NORMAL) || (cfg.gimbal_flags & GIMBAL_TILTONLY))
|
||||
aux[0] = rcData[AUX3];
|
||||
if (!(cfg.gimbal_flags & GIMBAL_DISABLEAUX34))
|
||||
aux[1] = rcData[AUX4];
|
||||
|
||||
servo[0] = cfg.gimbal_pitch_mid + aux[0] - cfg.midrc;
|
||||
servo[1] = cfg.gimbal_roll_mid + aux[1] - cfg.midrc;
|
||||
|
||||
if (rcOptions[BOXCAMSTAB]) {
|
||||
servo[0] += cfg.gimbal_pitch_gain * angle[PITCH] / 16;
|
||||
|
|
7
src/mw.h
7
src/mw.h
|
@ -75,6 +75,12 @@ typedef enum MultiType
|
|||
MULTITYPE_LAST = 18
|
||||
} MultiType;
|
||||
|
||||
typedef enum GimbalFlags {
|
||||
GIMBAL_NORMAL = 1 << 0,
|
||||
GIMBAL_TILTONLY = 1 << 1,
|
||||
GIMBAL_DISABLEAUX34 = 1 << 2,
|
||||
} GimbalFlags;
|
||||
|
||||
/*********** RC alias *****************/
|
||||
#define ROLL 0
|
||||
#define PITCH 1
|
||||
|
@ -168,6 +174,7 @@ typedef struct config_t {
|
|||
// gimbal-related configuration
|
||||
int8_t gimbal_pitch_gain; // gimbal pitch servo gain (tied to angle) can be negative to invert movement
|
||||
int8_t gimbal_roll_gain; // gimbal roll servo gain (tied to angle) can be negative to invert movement
|
||||
uint8_t gimbal_flags; // in servotilt mode, various things that affect stuff
|
||||
uint16_t gimbal_pitch_min; // gimbal pitch servo min travel
|
||||
uint16_t gimbal_pitch_max; // gimbal pitch servo max travel
|
||||
uint16_t gimbal_pitch_mid; // gimbal pitch servo neutral value
|
||||
|
|
Loading…
Reference in New Issue