Browse Source

Introduce better naming consistency for some union members. remove type

prefix from a typedef.
master
Dominic Clifton 11 years ago
parent
commit
3b347fa839
  1. 4601
      obj/cleanflight_OLIMEXINO.hex
  2. 8
      src/config.c
  3. 4
      src/config_master.h
  4. 10
      src/flight_common.c
  5. 12
      src/flight_common.h
  6. 6
      src/flight_imu.c
  7. 12
      src/flight_mixer.c
  8. 10
      src/mw.c
  9. 14
      src/sensors_acceleration.c
  10. 2
      src/sensors_acceleration.h
  11. 6
      src/sensors_compass.c
  12. 2
      src/sensors_compass.h
  13. 4
      src/serial_cli.c
  14. 10
      src/serial_msp.c

4601
obj/cleanflight_OLIMEXINO.hex
File diff suppressed because it is too large
View File

8
src/config.c

@ -60,11 +60,11 @@ profile_t currentProfile; // profile config struct
static const uint8_t EEPROM_CONF_VERSION = 70;
static void resetAccelerometerTrims(int16_flightDynamicsTrims_t *accelerometerTrims)
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
{
accelerometerTrims->trims.pitch = 0;
accelerometerTrims->trims.roll = 0;
accelerometerTrims->trims.yaw = 0;
accelerometerTrims->values.pitch = 0;
accelerometerTrims->values.roll = 0;
accelerometerTrims->values.yaw = 0;
}
static void resetPidProfile(pidProfile_t *pidProfile)

4
src/config_master.h

@ -34,8 +34,8 @@ typedef struct master_t {
gyroConfig_t gyroConfig;
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
int16_flightDynamicsTrims_t accZero;
int16_flightDynamicsTrims_t magZero;
flightDynamicsTrims_t accZero;
flightDynamicsTrims_t magZero;
batteryConfig_t batteryConfig;

10
src/flight_common.c

@ -34,8 +34,8 @@ pidControllerFuncPtr pid_controller = pidMultiWii; // which pid controller are w
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims)
{
rollAndPitchTrims->trims.roll = 0;
rollAndPitchTrims->trims.pitch = 0;
rollAndPitchTrims->values.roll = 0;
rollAndPitchTrims->values.pitch = 0;
}
void resetErrorAngle(void)
@ -76,7 +76,7 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control
AngleRate = (float)((controlRateConfig->yawRate + 10) * rcCommand[YAW]) / 50.0f;
} else {
// calculate error and limit the angle to 50 degrees max inclination
errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - inclination.rawAngles[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
AngleRate = (float)((controlRateConfig->rollPitchRate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max yaw rate
if (f.HORIZON_MODE) {
@ -140,7 +140,7 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
if ((f.ANGLE_MODE || f.HORIZON_MODE) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC
// 50 degrees max inclination
errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
+max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis];
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis];
PTermACC = errorAngle * pidProfile->P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
PTermACC = constrain(PTermACC, -pidProfile->D8[PIDLEVEL] * 5, +pidProfile->D8[PIDLEVEL] * 5);
@ -203,7 +203,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
} else {
// calculate error and limit the angle to max configured inclination
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int) max_angle_inclination),
+max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; // 16 bits is ok here
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]; // 16 bits is ok here
if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
AngleRateTmp = ((int32_t)(controlRateConfig->rollPitchRate + 27) * rcCommand[axis]) >> 4;

12
src/flight_common.h

@ -69,12 +69,12 @@ typedef struct int16_flightDynamicsTrims_s {
int16_t roll;
int16_t pitch;
int16_t yaw;
} int16_flightDynamicsTrims_def_t;
} flightDynamicsTrims_def_t;
typedef union {
int16_t raw[3];
int16_flightDynamicsTrims_def_t trims;
} int16_flightDynamicsTrims_t;
flightDynamicsTrims_def_t values;
} flightDynamicsTrims_t;
typedef struct rollAndPitchTrims_s {
int16_t roll;
@ -83,7 +83,7 @@ typedef struct rollAndPitchTrims_s {
typedef union {
int16_t raw[2];
rollAndPitchTrims_t_def trims;
rollAndPitchTrims_t_def values;
} rollAndPitchTrims_t;
typedef struct rollAndPitchInclination_s {
@ -93,8 +93,8 @@ typedef struct rollAndPitchInclination_s {
} rollAndPitchInclination_t_def;
typedef union {
int16_t rawAngles[ANGLE_INDEX_COUNT];
rollAndPitchInclination_t_def angle;
int16_t raw[ANGLE_INDEX_COUNT];
rollAndPitchInclination_t_def values;
} rollAndPitchInclination_t;

6
src/flight_imu.c

@ -327,8 +327,8 @@ static void getEstimatedAttitude(void)
// Attitude of the estimated vector
anglerad[AI_ROLL] = atan2f(EstG.V.Y, EstG.V.Z);
anglerad[AI_PITCH] = atan2f(-EstG.V.X, sqrtf(EstG.V.Y * EstG.V.Y + EstG.V.Z * EstG.V.Z));
inclination.angle.rollDeciDegrees = lrintf(anglerad[AI_ROLL] * (1800.0f / M_PI));
inclination.angle.pitchDeciDegrees = lrintf(anglerad[AI_PITCH] * (1800.0f / M_PI));
inclination.values.rollDeciDegrees = lrintf(anglerad[AI_ROLL] * (1800.0f / M_PI));
inclination.values.pitchDeciDegrees = lrintf(anglerad[AI_PITCH] * (1800.0f / M_PI));
if (sensors(SENSOR_MAG))
heading = calculateHeading(&EstM);
@ -361,7 +361,7 @@ static void getEstimatedAttitude(void)
bool isThrustFacingDownwards(rollAndPitchInclination_t *inclination)
{
return abs(inclination->angle.rollDeciDegrees) < DEGREES_80_IN_DECIDEGREES && abs(inclination->angle.pitchDeciDegrees) < DEGREES_80_IN_DECIDEGREES;
return abs(inclination->values.rollDeciDegrees) < DEGREES_80_IN_DECIDEGREES && abs(inclination->values.pitchDeciDegrees) < DEGREES_80_IN_DECIDEGREES;
}
int32_t calculateBaroPid(int32_t vel_tmp, float accZ_tmp, float accZ_old)

12
src/flight_mixer.c

@ -450,8 +450,8 @@ void mixTable(void)
break;
case MULTITYPE_GIMBAL:
servo[0] = (((int32_t)servoConf[0].rate * inclination.angle.pitchDeciDegrees) / 50) + determineServoMiddleOrForwardFromChannel(0);
servo[1] = (((int32_t)servoConf[1].rate * inclination.angle.rollDeciDegrees) / 50) + determineServoMiddleOrForwardFromChannel(1);
servo[0] = (((int32_t)servoConf[0].rate * inclination.values.pitchDeciDegrees) / 50) + determineServoMiddleOrForwardFromChannel(0);
servo[1] = (((int32_t)servoConf[1].rate * inclination.values.rollDeciDegrees) / 50) + determineServoMiddleOrForwardFromChannel(1);
break;
case MULTITYPE_AIRPLANE:
@ -504,11 +504,11 @@ void mixTable(void)
if (rcOptions[BOXCAMSTAB]) {
if (gimbalConfig->gimbal_flags & GIMBAL_MIXTILT) {
servo[0] -= (-(int32_t)servoConf[0].rate) * inclination.angle.pitchDeciDegrees / 50 - (int32_t)servoConf[1].rate * inclination.angle.rollDeciDegrees / 50;
servo[1] += (-(int32_t)servoConf[0].rate) * inclination.angle.pitchDeciDegrees / 50 + (int32_t)servoConf[1].rate * inclination.angle.rollDeciDegrees / 50;
servo[0] -= (-(int32_t)servoConf[0].rate) * inclination.values.pitchDeciDegrees / 50 - (int32_t)servoConf[1].rate * inclination.values.rollDeciDegrees / 50;
servo[1] += (-(int32_t)servoConf[0].rate) * inclination.values.pitchDeciDegrees / 50 + (int32_t)servoConf[1].rate * inclination.values.rollDeciDegrees / 50;
} else {
servo[0] += (int32_t)servoConf[0].rate * inclination.angle.pitchDeciDegrees / 50;
servo[1] += (int32_t)servoConf[1].rate * inclination.angle.rollDeciDegrees / 50;
servo[0] += (int32_t)servoConf[0].rate * inclination.values.pitchDeciDegrees / 50;
servo[1] += (int32_t)servoConf[1].rate * inclination.values.rollDeciDegrees / 50;
}
}
}

10
src/mw.c

@ -226,7 +226,7 @@ void annexCode(void)
static uint32_t LEDTime;
if ((int32_t)(currentTime - LEDTime) >= 0) {
LEDTime = currentTime + 50000;
ledringState(f.ARMED, inclination.angle.pitchDeciDegrees, inclination.angle.rollDeciDegrees);
ledringState(f.ARMED, inclination.values.pitchDeciDegrees, inclination.values.rollDeciDegrees);
}
}
#endif
@ -409,16 +409,16 @@ void loop(void)
i = 0;
// Acc Trim
if (rcSticks == THR_HI + YAW_CE + PIT_HI + ROL_CE) {
currentProfile.accelerometerTrims.trims.pitch += 2;
currentProfile.accelerometerTrims.values.pitch += 2;
i = 1;
} else if (rcSticks == THR_HI + YAW_CE + PIT_LO + ROL_CE) {
currentProfile.accelerometerTrims.trims.pitch -= 2;
currentProfile.accelerometerTrims.values.pitch -= 2;
i = 1;
} else if (rcSticks == THR_HI + YAW_CE + PIT_CE + ROL_HI) {
currentProfile.accelerometerTrims.trims.roll += 2;
currentProfile.accelerometerTrims.values.roll += 2;
i = 1;
} else if (rcSticks == THR_HI + YAW_CE + PIT_CE + ROL_LO) {
currentProfile.accelerometerTrims.trims.roll -= 2;
currentProfile.accelerometerTrims.values.roll -= 2;
i = 1;
}
if (i) {

14
src/sensors_acceleration.c

@ -28,7 +28,7 @@ extern bool AccInflightCalibrationMeasurementDone;
extern bool AccInflightCalibrationSavetoEEProm;
extern bool AccInflightCalibrationActive;
static int16_flightDynamicsTrims_t *accelerationTrims;
static flightDynamicsTrims_t *accelerationTrims;
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired)
{
@ -95,8 +95,8 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
accZero_saved[FD_ROLL] = accelerationTrims->raw[FD_ROLL];
accZero_saved[FD_PITCH] = accelerationTrims->raw[FD_PITCH];
accZero_saved[FD_YAW] = accelerationTrims->raw[FD_YAW];
angleTrim_saved.trims.roll = rollAndPitchTrims->trims.roll;
angleTrim_saved.trims.pitch = rollAndPitchTrims->trims.pitch;
angleTrim_saved.values.roll = rollAndPitchTrims->values.roll;
angleTrim_saved.values.pitch = rollAndPitchTrims->values.pitch;
}
if (InflightcalibratingA > 0) {
for (axis = 0; axis < 3; axis++) {
@ -118,8 +118,8 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL];
accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH];
accelerationTrims->raw[FD_YAW] = accZero_saved[FD_YAW];
rollAndPitchTrims->trims.roll = angleTrim_saved.trims.roll;
rollAndPitchTrims->trims.pitch = angleTrim_saved.trims.pitch;
rollAndPitchTrims->values.roll = angleTrim_saved.values.roll;
rollAndPitchTrims->values.pitch = angleTrim_saved.values.pitch;
}
InflightcalibratingA--;
}
@ -137,7 +137,7 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
}
void applyAccelerationTrims(int16_flightDynamicsTrims_t *accelerationTrims)
void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims)
{
accADC[FD_ROLL] -= accelerationTrims->raw[FD_ROLL];
accADC[FD_PITCH] -= accelerationTrims->raw[FD_PITCH];
@ -160,7 +160,7 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
applyAccelerationTrims(accelerationTrims);
}
void setAccelerationTrims(int16_flightDynamicsTrims_t *accelerationTrimsToUse)
void setAccelerationTrims(flightDynamicsTrims_t *accelerationTrimsToUse)
{
accelerationTrims = accelerationTrimsToUse;
}

2
src/sensors_acceleration.h

@ -20,4 +20,4 @@ extern uint16_t acc_1G;
bool isAccelerationCalibrationComplete(void);
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims);
void setAccelerationTrims(int16_flightDynamicsTrims_t *accelerationTrimsToUse);
void setAccelerationTrims(flightDynamicsTrims_t *accelerationTrimsToUse);

6
src/sensors_compass.c

@ -33,11 +33,11 @@ void compassInit(void)
magInit = 1;
}
int compassGetADC(int16_flightDynamicsTrims_t *magZero)
int compassGetADC(flightDynamicsTrims_t *magZero)
{
static uint32_t t, tCal = 0;
static int16_flightDynamicsTrims_t magZeroTempMin;
static int16_flightDynamicsTrims_t magZeroTempMax;
static flightDynamicsTrims_t magZeroTempMin;
static flightDynamicsTrims_t magZeroTempMax;
uint32_t axis;
if ((int32_t)(currentTime - t) < 0)

2
src/sensors_compass.h

@ -2,7 +2,7 @@
#ifdef MAG
void compassInit(void);
int compassGetADC(int16_flightDynamicsTrims_t *magZero);
int compassGetADC(flightDynamicsTrims_t *magZero);
#endif
extern int16_t magADC[XYZ_AXIS_COUNT];

4
src/serial_cli.c

@ -242,8 +242,8 @@ const clivalue_t valueTable[] = {
{ "accxy_deadband", VAR_UINT8, &currentProfile.accxy_deadband, 0, 100 },
{ "accz_deadband", VAR_UINT8, &currentProfile.accz_deadband, 0, 100 },
{ "acc_unarmedcal", VAR_UINT8, &currentProfile.acc_unarmedcal, 0, 1 },
{ "acc_trim_pitch", VAR_INT16, &currentProfile.accelerometerTrims.trims.pitch, -300, 300 },
{ "acc_trim_roll", VAR_INT16, &currentProfile.accelerometerTrims.trims.roll, -300, 300 },
{ "acc_trim_pitch", VAR_INT16, &currentProfile.accelerometerTrims.values.pitch, -300, 300 },
{ "acc_trim_roll", VAR_INT16, &currentProfile.accelerometerTrims.values.roll, -300, 300 },
{ "baro_tab_size", VAR_UINT8, &currentProfile.barometerConfig.baro_sample_count, 0, BARO_SAMPLE_COUNT_MAX },
{ "baro_noise_lpf", VAR_FLOAT, &currentProfile.barometerConfig.baro_noise_lpf, 0, 1 },

10
src/serial_msp.c

@ -387,8 +387,8 @@ static void evaluateCommand(void)
rxMspFrameRecieve();
break;
case MSP_SET_ACC_TRIM:
currentProfile.accelerometerTrims.trims.pitch = read16();
currentProfile.accelerometerTrims.trims.roll = read16();
currentProfile.accelerometerTrims.values.pitch = read16();
currentProfile.accelerometerTrims.values.roll = read16();
headSerialReply(0);
break;
case MSP_SET_RAW_GPS:
@ -604,7 +604,7 @@ static void evaluateCommand(void)
case MSP_ATTITUDE:
headSerialReply(6);
for (i = 0; i < 2; i++)
serialize16(inclination.rawAngles[i]);
serialize16(inclination.raw[i]);
serialize16(heading);
break;
case MSP_ALTITUDE:
@ -775,8 +775,8 @@ static void evaluateCommand(void)
// Additional commands that are not compatible with MultiWii
case MSP_ACC_TRIM:
headSerialReply(4);
serialize16(currentProfile.accelerometerTrims.trims.pitch);
serialize16(currentProfile.accelerometerTrims.trims.roll);
serialize16(currentProfile.accelerometerTrims.values.pitch);
serialize16(currentProfile.accelerometerTrims.values.roll);
break;
case MSP_UID:
headSerialReply(12);

Loading…
Cancel
Save