From 47a4d30358d8c5b8502e14b70198dc23c399c7be Mon Sep 17 00:00:00 2001 From: "timecop@gmail.com" Date: Mon, 21 Oct 2013 00:22:33 +0000 Subject: [PATCH] fixed cli status command (thx alexk) moved mpuscale into core struct since it's not a changeable setting git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@447 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/cli.c | 4 ++-- src/mw.h | 10 +++++----- src/sensors.c | 4 ++-- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/cli.c b/src/cli.c index 0715b1c7f..0947e16bf 100644 --- a/src/cli.c +++ b/src/cli.c @@ -50,7 +50,7 @@ static const char * const featureNames[] = { // sync this with AvailableSensors enum from board.h static const char * const sensorNames[] = { - "ACC", "BARO", "MAG", "SONAR", "GPS", NULL + "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", NULL }; static const char * const accNames[] = { @@ -896,7 +896,7 @@ static void cliStatus(char *cmdline) if (sensors(SENSOR_ACC)) { printf("ACCHW: %s", accNames[accHardware]); if (accHardware == ACC_MPU6050) - printf(".%c", mcfg.mpu6050_scale ? 'o' : 'n'); + printf(".%c", core.mpu6050_scale ? 'o' : 'n'); } cliPrint("\r\n"); diff --git a/src/mw.h b/src/mw.h index 88ba2dcd7..207fe0cb7 100755 --- a/src/mw.h +++ b/src/mw.h @@ -244,7 +244,6 @@ typedef struct master_t { uint16_t gyro_cmpfm_factor; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter uint32_t gyro_smoothing_factor; // How much to smoothen with per axis (32bit value with Roll, Pitch, Yaw in bits 24, 16, 8 respectively uint8_t moron_threshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. - uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver. int16_t accZero[3]; int16_t magZero[3]; @@ -265,11 +264,11 @@ typedef struct master_t { uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable. // gps-related stuff - uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2: MTK + uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2: MTK NMEA 3: MTK Binary int8_t gps_baudrate; // GPS baudrate, -1: autodetect (NMEA only), 0: 115200, 1: 57600, 2: 38400, 3: 19200, 4: 9600 uint32_t serial_baudrate; - + uint32_t softserial_baudrate; uint8_t softserial_inverted; // use inverted softserial input and output signals @@ -286,8 +285,9 @@ typedef struct core_t { serialPort_t *gpsport; serialPort_t *telemport; serialPort_t *rcvrport; - bool useServo; - uint8_t numRCChannels; + uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver. + uint8_t numRCChannels; // number of rc channels as reported by current input driver + bool useServo; // feature SERVO_TILT or wing/airplane mixers will enable this } core_t; typedef struct flags_t { diff --git a/src/sensors.c b/src/sensors.c index ff4738b72..ed3bd94c3 100755 --- a/src/sensors.c +++ b/src/sensors.c @@ -36,7 +36,7 @@ void sensorsAutodetect(void) bool haveMpu6k = false; // Autodetect gyro hardware. We have MPU3050 or MPU6050. - if (mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &mcfg.mpu6050_scale)) { + if (mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &core.mpu6050_scale)) { // this filled up acc.* struct with init values haveMpu6k = true; } else if (l3g4200dDetect(&gyro, mcfg.gyro_lpf)) { @@ -64,7 +64,7 @@ retry: ; // fallthrough case ACC_MPU6050: // MPU6050 if (haveMpu6k) { - mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &mcfg.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct + mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &core.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct accHardware = ACC_MPU6050; if (mcfg.acc_hardware == ACC_MPU6050) break;