added acc_trim stuff into cli

spacing/indentation fixes
flyingwing is somewhat supported, reflect that in comment
added anti-moron gyro calibration routine... if model is getting moved while its arming... don't calculate gyro avearage because its gonna be wrong... example of fail see here: http://www.rcgroups.com/forums/showthread.php?t=1749966

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@229 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2012-10-13 12:08:56 +00:00
parent 9fc43d5357
commit 0976133f1f
5 changed files with 2594 additions and 2569 deletions

File diff suppressed because it is too large Load Diff

View File

@ -151,6 +151,8 @@ const clivalue_t valueTable[] = {
{ "acc_hardware", VAR_UINT8, &cfg.acc_hardware, 0, 3 },
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 250 },
{ "acc_lpf_for_velocity", VAR_UINT8, &cfg.acc_lpf_for_velocity, 1, 250 },
{ "acc_trim_pitch", VAR_INT16, &cfg.angleTrim[PITCH], -300, 300 },
{ "acc_trim_roll", VAR_INT16, &cfg.angleTrim[ROLL], -300, 300 },
{ "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 },
{ "gyro_cmpf_factor", VAR_UINT16, &cfg.gyro_cmpf_factor, 100, 1000 },
{ "mpu6050_scale", VAR_UINT8, &cfg.mpu6050_scale, 0, 1 },

View File

@ -1,7 +1,7 @@
#include "board.h"
#include "mw.h"
// July 2012 V2.1
// October 2012 V2.1-dev
flags_t f;
int16_t debug[4];
@ -35,20 +35,19 @@ int32_t GPS_coord[2];
int32_t GPS_home[2];
int32_t GPS_hold[2];
uint8_t GPS_numSat;
uint16_t GPS_distanceToHome; // distance to home point in meters
int16_t GPS_directionToHome; // direction to home or hol point in degrees
uint16_t GPS_altitude, GPS_speed; // altitude in 0.1m and speed in 0.1m/s
uint16_t GPS_distanceToHome; // distance to home point in meters
int16_t GPS_directionToHome; // direction to home or hol point in degrees
uint16_t GPS_altitude, GPS_speed; // altitude in 0.1m and speed in 0.1m/s
uint8_t GPS_update = 0; // it's a binary toogle to distinct a GPS position update
int16_t GPS_angle[2] = { 0, 0 }; // it's the angles that must be applied for GPS correction
uint16_t GPS_ground_course = 0; // degrees*10
uint16_t GPS_ground_course = 0; // degrees * 10
uint8_t GPS_Present = 0; // Checksum from Gps serial
uint8_t GPS_Enable = 0;
int16_t nav[2];
int16_t nav_rated[2]; // Adding a rate controller to the navigation to make it smoother
int8_t nav_mode = NAV_MODE_NONE; // Navigation mode
//Automatic ACC Offset Calibration
// **********************
// Automatic ACC Offset Calibration
uint16_t InflightcalibratingA = 0;
int16_t AccInflightCalibrationArmed;
uint16_t AccInflightCalibrationMeasurementDone = 0;
@ -56,8 +55,8 @@ uint16_t AccInflightCalibrationSavetoEEProm = 0;
uint16_t AccInflightCalibrationActive = 0;
// Battery monitoring stuff
uint8_t batteryCellCount = 3; // cell count
uint16_t batteryWarningVoltage; // annoying buzzer after this one, battery ready to be dead
uint8_t batteryCellCount = 3; // cell count
uint16_t batteryWarningVoltage; // annoying buzzer after this one, battery ready to be dead
void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
{
@ -65,7 +64,7 @@ void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
for (r = 0; r < repeat; r++) {
for (i = 0; i < num; i++) {
LED0_TOGGLE; // switch LEDPIN state
LED0_TOGGLE; // switch LEDPIN state
BEEP_ON;
delay(wait);
BEEP_OFF;
@ -390,9 +389,9 @@ void loop(void)
}
}
for(i = 0; i < 4; i++)
for (i = 0; i < 4; i++)
auxState |= (rcData[AUX1 + i] < 1300) << (3 * i) | (1300 < rcData[AUX1 + i] && rcData[AUX1 + i] < 1700) << (3 * i + 1) | (rcData[AUX1 + i] > 1700) << (3 * i + 2);
for(i = 0; i < CHECKBOXITEMS; i++)
for (i = 0; i < CHECKBOXITEMS; i++)
rcOptions[i] = (auxState & cfg.activate[i]) > 0;
// note: if FAILSAFE is disable, failsafeCnt > 5*FAILSAVE_DELAY is always false
@ -492,7 +491,7 @@ void loop(void)
} else {
f.PASSTHRU_MODE = 0;
}
if (cfg.mixerConfiguration == MULTITYPE_FLYING_WING || cfg.mixerConfiguration == MULTITYPE_AIRPLANE) {
f.HEADFREE_MODE = 0;
}

View File

@ -2,7 +2,6 @@
/* for VBAT monitoring frequency */
#define VBATFREQ 6 // to read battery voltage - nth number of loop iterations
#define BARO_TAB_SIZE_MAX 48
#define VERSION 211
@ -29,13 +28,13 @@ typedef enum MultiType
MULTITYPE_GIMBAL = 5,
MULTITYPE_Y6 = 6,
MULTITYPE_HEX6 = 7,
MULTITYPE_FLYING_WING = 8, // UNSUPPORTED, do not select!
MULTITYPE_FLYING_WING = 8,
MULTITYPE_Y4 = 9,
MULTITYPE_HEX6X = 10,
MULTITYPE_OCTOX8 = 11, // Java GUI is same for the next 3 configs
MULTITYPE_OCTOFLATP = 12, // MultiWinGui shows this differently
MULTITYPE_OCTOFLATX = 13, // MultiWinGui shows this differently
MULTITYPE_AIRPLANE = 14, // airplane / singlecopter / dualcopter
MULTITYPE_AIRPLANE = 14, // airplane / singlecopter / dualcopter (not yet properly supported)
MULTITYPE_HELI_120_CCPM = 15,
MULTITYPE_HELI_90_DEG = 16,
MULTITYPE_VTAIL4 = 17,

View File

@ -308,9 +308,11 @@ void Baro_update(void)
static void GYRO_Common(void)
{
int axis;
static int16_t previousGyroADC[3] = { 0, 0, 0 };
static int32_t g[3];
int axis;
static int16_t gyroMin[3];
static int16_t gyroMax[3];
if (calibratingG > 0) {
for (axis = 0; axis < 3; axis++) {
@ -319,11 +321,23 @@ static void GYRO_Common(void)
g[axis] = 0;
// Sum up 1000 readings
g[axis] += gyroADC[axis];
// g[axis] += (1000 - calibratingG) >> 1;
if (gyroMin[axis] > gyroADC[axis])
gyroMin[axis] = gyroADC[axis];
if (gyroMax[axis] < gyroADC[axis])
gyroMax[axis] = gyroADC[axis];
// Clear global variables for next reading
gyroADC[axis] = 0;
gyroZero[axis] = 0;
if (calibratingG == 1) {
int16_t gyroDiff = gyroMax[axis] - gyroMin[axis];
// check variance and startover if idiot was moving the model
if (gyroDiff > 10) {
calibratingG = 1000;
gyroMin[0] = gyroMin[1] = gyroMin[2] = 0;
gyroMax[0] = gyroMax[1] = gyroMax[2] = 0;
g[0] = g[1] = g[2] = 0;
continue;
}
gyroZero[axis] = g[axis] / 1000;
blinkLED(10, 15, 1);
}