bring back flying wing w/all configuration options
config version bumped, settings cleared. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@213 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
b94c13b1c5
commit
70884d69d5
5577
obj/baseflight.hex
5577
obj/baseflight.hex
File diff suppressed because it is too large
Load Diff
10
src/cli.c
10
src/cli.c
|
@ -119,6 +119,16 @@ 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 },
|
||||
{ "wing_left_min", VAR_UINT16, &cfg.wing_left_min, 0, 2000 },
|
||||
{ "wing_left_mid", VAR_UINT16, &cfg.wing_left_mid, 0, 2000 },
|
||||
{ "wing_left_max", VAR_UINT16, &cfg.wing_left_max, 0, 2000 },
|
||||
{ "wing_right_min", VAR_UINT16, &cfg.wing_right_min, 0, 2000 },
|
||||
{ "wing_right_mid", VAR_UINT16, &cfg.wing_right_mid, 0, 2000 },
|
||||
{ "wing_right_max", VAR_UINT16, &cfg.wing_right_max, 0, 2000 },
|
||||
{ "pitch_direction_l", VAR_INT8, &cfg.pitch_direction_l, -1, 1 },
|
||||
{ "pitch_direction_r", VAR_INT8, &cfg.pitch_direction_r, -1, 1 },
|
||||
{ "roll_direction_l", VAR_INT8, &cfg.roll_direction_l, -1, 1 },
|
||||
{ "roll_direction_r", VAR_INT8, &cfg.roll_direction_r, -1, 1 },
|
||||
{ "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 },
|
||||
|
|
16
src/config.c
16
src/config.c
|
@ -13,7 +13,7 @@ config_t cfg;
|
|||
const char rcChannelLetters[] = "AERT1234";
|
||||
|
||||
static uint32_t enabledSensors = 0;
|
||||
uint8_t checkNewConf = 28;
|
||||
uint8_t checkNewConf = 29;
|
||||
|
||||
void parseRcChannels(const char *input)
|
||||
{
|
||||
|
@ -155,7 +155,7 @@ void checkFirstTime(bool reset)
|
|||
cfg.retarded_arm = 0; // disable arm/disarm on roll left/right
|
||||
|
||||
// Failsafe Variables
|
||||
cfg.failsafe_delay = 10; // 1sec
|
||||
cfg.failsafe_delay = 10; // 1sec
|
||||
cfg.failsafe_off_delay = 200; // 20sec
|
||||
cfg.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people.
|
||||
|
||||
|
@ -172,6 +172,18 @@ void checkFirstTime(bool reset)
|
|||
cfg.tri_yaw_min = 1020;
|
||||
cfg.tri_yaw_max = 2000;
|
||||
|
||||
// flying wing
|
||||
cfg.wing_left_min = 1020;
|
||||
cfg.wing_left_mid = 1500;
|
||||
cfg.wing_left_max = 2000;
|
||||
cfg.wing_right_min = 1020;
|
||||
cfg.wing_right_mid = 1500;
|
||||
cfg.wing_right_max = 2000;
|
||||
cfg.pitch_direction_l = 1;
|
||||
cfg.pitch_direction_r = -1;
|
||||
cfg.roll_direction_l = 1;
|
||||
cfg.roll_direction_r = 1;
|
||||
|
||||
// gimbal
|
||||
cfg.gimbal_pitch_gain = 10;
|
||||
cfg.gimbal_roll_gain = 10;
|
||||
|
|
18
src/mixer.c
18
src/mixer.c
|
@ -322,15 +322,17 @@ void mixTable(void)
|
|||
|
||||
case MULTITYPE_FLYING_WING:
|
||||
motor[0] = rcCommand[THROTTLE];
|
||||
if (f.PASSTHRU_MODE) { // do not use sensors for correction, simple 2 channel mixing
|
||||
int p = 0, r = 0;
|
||||
servo[0] = p * (rcData[PITCH] - cfg.midrc) + r * (rcData[ROLL] - cfg.midrc);
|
||||
servo[1] = p * (rcData[PITCH] - cfg.midrc) + r * (rcData[ROLL] - cfg.midrc);
|
||||
} else { // use sensors to correct (gyro only or gyro+acc)
|
||||
int p = 0, r = 0;
|
||||
servo[0] = p * axisPID[PITCH] + r * axisPID[ROLL];
|
||||
servo[1] = p * axisPID[PITCH] + r * axisPID[ROLL];
|
||||
if (f.PASSTHRU_MODE) {
|
||||
// do not use sensors for correction, simple 2 channel mixing
|
||||
servo[0] = cfg.pitch_direction_l * (rcData[PITCH] - cfg.midrc) + cfg.roll_direction_l * (rcData[ROLL] - cfg.midrc);
|
||||
servo[1] = cfg.pitch_direction_r * (rcData[PITCH] - cfg.midrc) + cfg.roll_direction_r * (rcData[ROLL] - cfg.midrc);
|
||||
} else {
|
||||
// use sensors to correct (gyro only or gyro + acc)
|
||||
servo[0] = cfg.pitch_direction_l * axisPID[PITCH] + cfg.roll_direction_l * axisPID[ROLL];
|
||||
servo[1] = cfg.pitch_direction_r * axisPID[PITCH] + cfg.roll_direction_r * axisPID[ROLL];
|
||||
}
|
||||
servo[0] = constrain(servo[0] + cfg.wing_left_mid, cfg.wing_left_min, cfg.wing_left_max);
|
||||
servo[1] = constrain(servo[1] + cfg.wing_right_mid, cfg.wing_right_min, cfg.wing_right_max);
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
12
src/mw.h
12
src/mw.h
|
@ -180,6 +180,18 @@ typedef struct config_t {
|
|||
uint16_t tri_yaw_min; // tail servo min
|
||||
uint16_t tri_yaw_max; // tail servo max
|
||||
|
||||
// flying wing related configuration
|
||||
uint16_t wing_left_min; // min/mid/max servo travel
|
||||
uint16_t wing_left_mid;
|
||||
uint16_t wing_left_max;
|
||||
uint16_t wing_right_min;
|
||||
uint16_t wing_right_mid;
|
||||
uint16_t wing_right_max;
|
||||
int8_t pitch_direction_l; // left servo - pitch orientation
|
||||
int8_t pitch_direction_r; // right servo - pitch orientation (opposite sign to pitch_direction_l if servos are mounted mirrored)
|
||||
int8_t roll_direction_l; // left servo - roll orientation
|
||||
int8_t roll_direction_r; // right servo - roll orientation (same sign as ROLL_DIRECTION_L, if servos are mounted in mirrored orientation)
|
||||
|
||||
// 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
|
||||
|
|
Loading…
Reference in New Issue