renamed 'tilt_*_prop' stuff into gimbal_[axis]_gain and added more dynamically-configurable gimbal/camstab stuff into cli.

whitespace fixes in mw.h and trashed the old XA-XB based mixer setting leftovers.
settings are cleared again due to updated config struct.

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@138 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop 2012-03-31 03:52:16 +00:00
parent 58eb2b966f
commit 703234b608
5 changed files with 2473 additions and 2448 deletions

File diff suppressed because it is too large Load Diff

View File

@ -102,8 +102,14 @@ 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 },
{ "tilt_pitch_prop", VAR_INT8, &cfg.tilt_pitch_prop, -100, 100 },
{ "tilt_roll_prop", VAR_INT8, &cfg.tilt_roll_prop, -100, 100 },
{ "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 },
{ "gimbal_pitch_max", VAR_UINT16, &cfg.gimbal_pitch_max, 100, 3000 },
{ "gimbal_pitch_mid", VAR_UINT16, &cfg.gimbal_pitch_mid, 100, 3000 },
{ "gimbal_roll_min", VAR_UINT16, &cfg.gimbal_roll_min, 100, 3000 },
{ "gimbal_roll_max", VAR_UINT16, &cfg.gimbal_roll_max, 100, 3000 },
{ "gimbal_roll_mid", VAR_UINT16, &cfg.gimbal_roll_mid, 100, 3000 },
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 32 },
{ "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 },
{ "gps_baudrate", VAR_UINT32, &cfg.gps_baudrate, 1200, 115200 },

View File

@ -13,7 +13,7 @@ config_t cfg;
const char rcChannelLetters[] = "AERT1234";
static uint32_t enabledSensors = 0;
static uint8_t checkNewConf = 11;
static uint8_t checkNewConf = 12;
void parseRcChannels(const char *input)
{
@ -149,8 +149,14 @@ void checkFirstTime(bool reset)
cfg.tri_yaw_max = 2000;
// gimbal
cfg.tilt_pitch_prop = 10;
cfg.tilt_roll_prop = 10;
cfg.gimbal_pitch_gain = 10;
cfg.gimbal_roll_gain = 10;
cfg.gimbal_pitch_min = 1020;
cfg.gimbal_pitch_max = 2000;
cfg.gimbal_pitch_mid = 1500;
cfg.gimbal_roll_min = 1020;
cfg.gimbal_roll_max = 2000;
cfg.gimbal_roll_mid = 1500;
// gps baud-rate
cfg.gps_baudrate = 9600;

View File

@ -212,8 +212,8 @@ void mixTable(void)
break;
case MULTITYPE_GIMBAL:
servo[0] = constrain(TILT_PITCH_MIDDLE + cfg.tilt_pitch_prop * angle[PITCH] / 16 + rcCommand[PITCH], TILT_PITCH_MIN, TILT_PITCH_MAX);
servo[1] = constrain(TILT_ROLL_MIDDLE + cfg.tilt_roll_prop * angle[ROLL] / 16 + rcCommand[ROLL], TILT_ROLL_MIN, TILT_ROLL_MAX);
servo[0] = constrain(cfg.gimbal_pitch_mid + cfg.gimbal_pitch_gain * angle[PITCH] / 16 + rcCommand[PITCH], cfg.gimbal_pitch_min, cfg.gimbal_pitch_max);
servo[1] = constrain(cfg.gimbal_roll_mid + cfg.gimbal_roll_gain * angle[ROLL] / 16 + rcCommand[ROLL], cfg.gimbal_roll_min, cfg.gimbal_roll_max);
break;
case MULTITYPE_FLYING_WING:
@ -232,16 +232,16 @@ void mixTable(void)
// do camstab
if (feature(FEATURE_SERVO_TILT)) {
servo[0] = TILT_PITCH_MIDDLE + rcData[AUX3] - 1500;
servo[1] = TILT_ROLL_MIDDLE + rcData[AUX4] - 1500;
servo[0] = cfg.gimbal_pitch_mid + rcData[AUX3] - cfg.midrc;
servo[1] = cfg.gimbal_roll_mid + rcData[AUX4] - cfg.midrc;
if (rcOptions[BOXCAMSTAB]) {
servo[0] += cfg.tilt_pitch_prop * angle[PITCH] / 16;
servo[1] += cfg.tilt_roll_prop * angle[ROLL] / 16;
servo[0] += cfg.gimbal_pitch_gain * angle[PITCH] / 16;
servo[1] += cfg.gimbal_roll_gain * angle[ROLL] / 16;
}
servo[0] = constrain(servo[0], TILT_PITCH_MIN, TILT_PITCH_MAX);
servo[1] = constrain(servo[1], TILT_ROLL_MIN, TILT_ROLL_MAX);
servo[0] = constrain(servo[0], cfg.gimbal_pitch_min, cfg.gimbal_pitch_max);
servo[1] = constrain(servo[1], cfg.gimbal_roll_min, cfg.gimbal_roll_max);
}
// do camtrig (this doesn't actually work)

View File

@ -33,16 +33,6 @@
#define WING_RIGHT_MIN 1020 // limit servo travel range must be inside [1020;2000]
#define WING_RIGHT_MAX 2000 // limit servo travel range must be inside [1020;2000]
/* The following lines apply only for a pitch/roll tilt stabilization system
On promini board, it is not compatible with config with 6 motors or more
Uncomment the first line to activate it */
#define TILT_PITCH_MIN 1020 //servo travel min, don't set it below 1020
#define TILT_PITCH_MAX 2000 //servo travel max, max value=2000
#define TILT_PITCH_MIDDLE 1500 //servo neutral value
#define TILT_ROLL_MIN 1020
#define TILT_ROLL_MAX 2000
#define TILT_ROLL_MIDDLE 1500
/* experimental
camera trigger function : activated via Rc Options in the GUI, servo output=A2 on promini */
#define CAM_SERVO_HIGH 2000 // the position of HIGH state servo
@ -65,23 +55,23 @@
// Syncronized with GUI. Only exception is mixer > 11, which is always returned as 11 during serialization.
typedef enum MultiType
{
MULTITYPE_TRI = 1, // XA
MULTITYPE_QUADP = 2, // XB
MULTITYPE_QUADX = 3, // XC
MULTITYPE_BI = 4, // XD
MULTITYPE_GIMBAL = 5, // XE
MULTITYPE_Y6 = 6, // XF
MULTITYPE_HEX6 = 7, // XG
MULTITYPE_FLYING_WING = 8, // XH
MULTITYPE_Y4 = 9, // XI
MULTITYPE_HEX6X = 10, // XJ
MULTITYPE_OCTOX8 = 11, // XK
MULTITYPE_OCTOFLATP = 12, // XL the GUI is the same for all 8 motor configs
MULTITYPE_OCTOFLATX = 13, // XM the GUI is the same for all 8 motor configs
MULTITYPE_AIRPLANE = 14, // XN
MULTITYPE_HELI_120_CCPM = 15, // XO simple model
MULTITYPE_HELI_90_DEG = 16, // XP simple model
MULTITYPE_VTAIL4 = 17, // XO
MULTITYPE_TRI = 1,
MULTITYPE_QUADP = 2,
MULTITYPE_QUADX = 3,
MULTITYPE_BI = 4,
MULTITYPE_GIMBAL = 5,
MULTITYPE_Y6 = 6,
MULTITYPE_HEX6 = 7,
MULTITYPE_FLYING_WING = 8,
MULTITYPE_Y4 = 9,
MULTITYPE_HEX6X = 10,
MULTITYPE_OCTOX8 = 11,
MULTITYPE_OCTOFLATP = 12, // the GUI is the same for all 8 motor configs
MULTITYPE_OCTOFLATX = 13, // the GUI is the same for all 8 motor configs
MULTITYPE_AIRPLANE = 14,
MULTITYPE_HELI_120_CCPM = 15, // simple model
MULTITYPE_HELI_90_DEG = 16, // simple model
MULTITYPE_VTAIL4 = 17,
MULTITYPE_LAST = 18
} MultiType;
@ -142,7 +132,7 @@ typedef struct config_t {
int16_t accZero[3];
int16_t magZero[3];
int16_t accTrim[2];
// sensor-related stuff
uint8_t acc_lpf_factor; // Set the Low Pass Filter factor for ACC. Increasing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
uint16_t gyro_lpf; // mpuX050 LPF setting
@ -154,7 +144,7 @@ typedef struct config_t {
uint8_t vbatscale; // adjust this to match battery voltage to reported value
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V)
// Radio/ESC-related configuration
uint8_t rcmap[8]; // mapping of radio channels to internal RPYTA+ order
uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero.
@ -178,10 +168,16 @@ typedef struct config_t {
uint16_t tri_yaw_middle; // tail servo center pos. - use this for initial trim
uint16_t tri_yaw_min; // tail servo min
uint16_t tri_yaw_max; // tail servo max
// gimbal-related configuration
int8_t tilt_pitch_prop; // servo proportional (tied to angle) ; can be negative to invert movement
int8_t tilt_roll_prop; // servo proportional (tied to angle) ; can be negative to invert movement
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
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
uint16_t gimbal_roll_min; // gimbal roll servo min travel
uint16_t gimbal_roll_max; // gimbal roll servo max travel
uint16_t gimbal_roll_mid; // gimbal roll servo neutral value
// gps baud-rate
uint32_t gps_baudrate;