Fix some BlackBox isues, remove redundant code from PID controllers.

This commit is contained in:
Michael Jakob 2015-04-12 04:46:27 +02:00
parent e7e297ad53
commit fe2f2f3053
4 changed files with 6 additions and 20 deletions

View File

@ -1164,8 +1164,8 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
} }
case FLIGHT_LOG_EVENT_GTUNE_RESULT: case FLIGHT_LOG_EVENT_GTUNE_RESULT:
blackboxWrite(data->gtuneCycleResult.gtuneAxis); blackboxWrite(data->gtuneCycleResult.gtuneAxis);
blackboxWrite(data->gtuneCycleResult.gtuneGyroAVG); blackboxWriteSignedVB(data->gtuneCycleResult.gtuneGyroAVG);
blackboxWrite(data->gtuneCycleResult.gtuneNewP); blackboxWriteS16(data->gtuneCycleResult.gtuneNewP);
break; break;
case FLIGHT_LOG_EVENT_LOGGING_RESUME: case FLIGHT_LOG_EVENT_LOGGING_RESUME:
blackboxWriteUnsignedVB(data->loggingResume.logIteration); blackboxWriteUnsignedVB(data->loggingResume.logIteration);

View File

@ -157,8 +157,8 @@ typedef struct flightLogEvent_loggingResume_t {
======= =======
typedef struct flightLogEvent_gtuneCycleResult_t { typedef struct flightLogEvent_gtuneCycleResult_t {
uint8_t gtuneAxis; uint8_t gtuneAxis;
uint32_t gtuneGyroAVG; int32_t gtuneGyroAVG;
uint8_t gtuneNewP; int16_t gtuneNewP;
} flightLogEvent_gtuneCycleResult_t; } flightLogEvent_gtuneCycleResult_t;
>>>>>>> 6f60c52 Add BlackBox recording for G-Tune >>>>>>> 6f60c52 Add BlackBox recording for G-Tune

View File

@ -159,7 +159,8 @@ void calculate_Gtune(uint8_t axis)
eventData.gtuneAxis = axis; eventData.gtuneAxis = axis;
eventData.gtuneGyroAVG = AvgGyro[axis]; eventData.gtuneGyroAVG = AvgGyro[axis];
eventData.gtuneNewP = newP; if (floatPID) eventData.gtuneNewP = newP / 10;
else eventData.gtuneNewP = newP;
blackboxLogEvent(FLIGHT_LOG_EVENT_GTUNE_RESULT, (flightLogEventData_t*)&eventData); blackboxLogEvent(FLIGHT_LOG_EVENT_GTUNE_RESULT, (flightLogEventData_t*)&eventData);
} }

View File

@ -456,11 +456,6 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control
axisPID[FD_YAW] = PTerm + ITerm; axisPID[FD_YAW] = PTerm + ITerm;
if (motorCount >= 4) { // prevent "yaw jump" during yaw correction
int16_t limit = ABS(rcCommand[FD_YAW]) + 100;
axisPID[FD_YAW] = (float)constrain((int32_t)axisPID[FD_YAW], -limit, +limit);
}
#ifdef GTUNE #ifdef GTUNE
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
calculate_Gtune(FD_YAW); calculate_Gtune(FD_YAW);
@ -594,11 +589,6 @@ static void pidMultiWiiHybrid(pidProfile_t *pidProfile, controlRateConfig_t *con
axisPID[FD_YAW] = PTerm + ITerm; axisPID[FD_YAW] = PTerm + ITerm;
if (motorCount >= 4) { // prevent "yaw jump" during yaw correction
int16_t limit = ABS(rcCommand[FD_YAW]) + 100;
axisPID[FD_YAW] = (float)constrain((int32_t)axisPID[FD_YAW], -limit, +limit);
}
#ifdef GTUNE #ifdef GTUNE
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
calculate_Gtune(FD_YAW); calculate_Gtune(FD_YAW);
@ -749,11 +739,6 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
axisPID[FD_YAW] = PTerm + ITerm; axisPID[FD_YAW] = PTerm + ITerm;
axisPID[FD_YAW] = lrintf(axisPID[FD_YAW]); // Round up result. axisPID[FD_YAW] = lrintf(axisPID[FD_YAW]); // Round up result.
if (motorCount >= 4) { // prevent "yaw jump" during yaw correction
int16_t limit = ABS(rcCommand[FD_YAW]) + 100;
axisPID[FD_YAW] = (float)constrain((int32_t)axisPID[FD_YAW], -limit, +limit);
}
#ifdef GTUNE #ifdef GTUNE
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
calculate_Gtune(FD_YAW); calculate_Gtune(FD_YAW);