mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Merge pull request #2699 from betaflight/battery-cleanup
Battery cleanup
This commit is contained in:
commit
7edb599296
84 changed files with 1872 additions and 747 deletions
2
Makefile
2
Makefile
|
@ -641,6 +641,8 @@ COMMON_SRC = \
|
|||
scheduler/scheduler.c \
|
||||
sensors/acceleration.c \
|
||||
sensors/battery.c \
|
||||
sensors/current.c \
|
||||
sensors/voltage.c \
|
||||
sensors/boardalignment.c \
|
||||
sensors/compass.c \
|
||||
sensors/gyro.c \
|
||||
|
|
|
@ -425,10 +425,10 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
#endif
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_VBAT:
|
||||
return feature(FEATURE_VBAT);
|
||||
return batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC:
|
||||
return feature(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC;
|
||||
return batteryConfig()->currentMeterSource == CURRENT_METER_ADC;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_SONAR:
|
||||
#ifdef SONAR
|
||||
|
@ -841,7 +841,7 @@ void startBlackbox(void)
|
|||
blackboxHistory[1] = &blackboxHistoryRing[1];
|
||||
blackboxHistory[2] = &blackboxHistoryRing[2];
|
||||
|
||||
vbatReference = vbatLatest;
|
||||
vbatReference = getBatteryVoltageLatest();
|
||||
|
||||
//No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
|
||||
|
||||
|
@ -1037,8 +1037,8 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
blackboxCurrent->motor[i] = motor[i];
|
||||
}
|
||||
|
||||
blackboxCurrent->vbatLatest = vbatLatest;
|
||||
blackboxCurrent->amperageLatest = amperageLatest;
|
||||
blackboxCurrent->vbatLatest = getBatteryVoltageLatest();
|
||||
blackboxCurrent->amperageLatest = getAmperageLatest();
|
||||
|
||||
#ifdef MAG
|
||||
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
|
||||
|
@ -1180,8 +1180,8 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
|
|||
}
|
||||
|
||||
#ifndef BLACKBOX_PRINT_HEADER_LINE
|
||||
#define BLACKBOX_PRINT_HEADER_LINE(x, ...) case __COUNTER__: \
|
||||
blackboxPrintfHeaderLine(x, __VA_ARGS__); \
|
||||
#define BLACKBOX_PRINT_HEADER_LINE(name, format, ...) case __COUNTER__: \
|
||||
blackboxPrintfHeaderLine(name, format, __VA_ARGS__); \
|
||||
break;
|
||||
#define BLACKBOX_PRINT_HEADER_LINE_CUSTOM(...) case __COUNTER__: \
|
||||
{__VA_ARGS__}; \
|
||||
|
@ -1201,124 +1201,123 @@ static bool blackboxWriteSysinfo()
|
|||
|
||||
const controlRateConfig_t *currentControlRateProfile = controlRateProfiles(systemConfig()->activeRateProfile);
|
||||
switch (xmitState.headerIndex) {
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
|
||||
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", systemConfig()->name);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", motorConfig()->minthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", motorConfig()->maxthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_scale:0x%x", castFloatBytesToInt(1.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("motorOutput:%d,%d", motorOutputLow,motorOutputHigh);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_1G:%u", acc.dev.acc_1G);
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware type", "%s", "Cleanflight");
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware revision", "%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware date", "%s %s", buildDate, buildTime);
|
||||
BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", systemConfig()->name);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P interval", "%d/%d", blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", motorConfig()->minthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_scale","0x%x", castFloatBytesToInt(1.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", motorOutputLow,motorOutputHigh);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc.dev.acc_1G);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
|
||||
blackboxPrintfHeaderLine("vbatscale:%u", batteryConfig()->vbatscale);
|
||||
blackboxPrintfHeaderLine("vbatscale", "%u", voltageSensorADCConfig(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale);
|
||||
} else {
|
||||
xmitState.headerIndex += 2; // Skip the next two vbat fields too
|
||||
}
|
||||
);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage:%u,%u,%u", batteryConfig()->vbatmincellvoltage,
|
||||
BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage", "%u,%u,%u", batteryConfig()->vbatmincellvoltage,
|
||||
batteryConfig()->vbatwarningcellvoltage,
|
||||
batteryConfig()->vbatmaxcellvoltage);
|
||||
BLACKBOX_PRINT_HEADER_LINE("vbatref:%u", vbatReference);
|
||||
BLACKBOX_PRINT_HEADER_LINE("vbatref", "%u", vbatReference);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
|
||||
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
|
||||
if (feature(FEATURE_CURRENT_METER)) {
|
||||
blackboxPrintfHeaderLine("currentMeter:%d,%d", batteryConfig()->currentMeterOffset, batteryConfig()->currentMeterScale);
|
||||
if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
|
||||
blackboxPrintfHeaderLine("currentSensor", "%d,%d",currentSensorADCConfig()->offset, currentSensorADCConfig()->scale);
|
||||
}
|
||||
);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE("looptime:%d", gyro.targetLooptime);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom:%d", gyroConfig()->gyro_sync_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pid_process_denom:%d", pidConfig()->pid_process_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcRate:%d", currentControlRateProfile->rcRate8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", currentControlRateProfile->rcExpo8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcYawRate:%d", currentControlRateProfile->rcYawRate8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcYawExpo:%d", currentControlRateProfile->rcYawExpo8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("thrMid:%d", currentControlRateProfile->thrMid8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("thrExpo:%d", currentControlRateProfile->thrExpo8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dynThrPID:%d", currentControlRateProfile->dynThrPID);
|
||||
BLACKBOX_PRINT_HEADER_LINE("tpa_breakpoint:%d", currentControlRateProfile->tpa_breakpoint);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rates:%d,%d,%d", currentControlRateProfile->rates[ROLL],
|
||||
BLACKBOX_PRINT_HEADER_LINE("looptime", "%d", gyro.targetLooptime);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom", "%d", gyroConfig()->gyro_sync_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pid_process_denom", "%d", pidConfig()->pid_process_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcRate", "%d", currentControlRateProfile->rcRate8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcExpo", "%d", currentControlRateProfile->rcExpo8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcYawRate", "%d", currentControlRateProfile->rcYawRate8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcYawExpo", "%d", currentControlRateProfile->rcYawExpo8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("thrMid", "%d", currentControlRateProfile->thrMid8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("thrExpo", "%d", currentControlRateProfile->thrExpo8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dynThrPID", "%d", currentControlRateProfile->dynThrPID);
|
||||
BLACKBOX_PRINT_HEADER_LINE("tpa_breakpoint", "%d", currentControlRateProfile->tpa_breakpoint);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile->rates[ROLL],
|
||||
currentControlRateProfile->rates[PITCH],
|
||||
currentControlRateProfile->rates[YAW]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rollPID:%d,%d,%d", currentPidProfile->P8[ROLL],
|
||||
BLACKBOX_PRINT_HEADER_LINE("rollPID", "%d,%d,%d", currentPidProfile->P8[ROLL],
|
||||
currentPidProfile->I8[ROLL],
|
||||
currentPidProfile->D8[ROLL]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pitchPID:%d,%d,%d", currentPidProfile->P8[PITCH],
|
||||
BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d", currentPidProfile->P8[PITCH],
|
||||
currentPidProfile->I8[PITCH],
|
||||
currentPidProfile->D8[PITCH]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yawPID:%d,%d,%d", currentPidProfile->P8[YAW],
|
||||
BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d", currentPidProfile->P8[YAW],
|
||||
currentPidProfile->I8[YAW],
|
||||
currentPidProfile->D8[YAW]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("altPID:%d,%d,%d", currentPidProfile->P8[PIDALT],
|
||||
BLACKBOX_PRINT_HEADER_LINE("altPID", "%d,%d,%d", currentPidProfile->P8[PIDALT],
|
||||
currentPidProfile->I8[PIDALT],
|
||||
currentPidProfile->D8[PIDALT]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("posPID:%d,%d,%d", currentPidProfile->P8[PIDPOS],
|
||||
BLACKBOX_PRINT_HEADER_LINE("posPID", "%d,%d,%d", currentPidProfile->P8[PIDPOS],
|
||||
currentPidProfile->I8[PIDPOS],
|
||||
currentPidProfile->D8[PIDPOS]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("posrPID:%d,%d,%d", currentPidProfile->P8[PIDPOSR],
|
||||
BLACKBOX_PRINT_HEADER_LINE("posrPID", "%d,%d,%d", currentPidProfile->P8[PIDPOSR],
|
||||
currentPidProfile->I8[PIDPOSR],
|
||||
currentPidProfile->D8[PIDPOSR]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("navrPID:%d,%d,%d", currentPidProfile->P8[PIDNAVR],
|
||||
BLACKBOX_PRINT_HEADER_LINE("navrPID", "%d,%d,%d", currentPidProfile->P8[PIDNAVR],
|
||||
currentPidProfile->I8[PIDNAVR],
|
||||
currentPidProfile->D8[PIDNAVR]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("levelPID:%d,%d,%d", currentPidProfile->P8[PIDLEVEL],
|
||||
BLACKBOX_PRINT_HEADER_LINE("levelPID", "%d,%d,%d", currentPidProfile->P8[PIDLEVEL],
|
||||
currentPidProfile->I8[PIDLEVEL],
|
||||
currentPidProfile->D8[PIDLEVEL]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("magPID:%d", currentPidProfile->P8[PIDMAG]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("velPID:%d,%d,%d", currentPidProfile->P8[PIDVEL],
|
||||
BLACKBOX_PRINT_HEADER_LINE("magPID", "%d", currentPidProfile->P8[PIDMAG]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("velPID", "%d,%d,%d", currentPidProfile->P8[PIDVEL],
|
||||
currentPidProfile->I8[PIDVEL],
|
||||
currentPidProfile->D8[PIDVEL]);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type:%d", currentPidProfile->dterm_filter_type);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", currentPidProfile->dterm_lpf_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", currentPidProfile->yaw_lpf_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz:%d", currentPidProfile->dterm_notch_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff:%d", currentPidProfile->dterm_notch_cutoff);
|
||||
BLACKBOX_PRINT_HEADER_LINE("itermWindupPointPercent:%d", currentPidProfile->itermWindupPointPercent);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", currentPidProfile->dterm_average_count);
|
||||
BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", currentPidProfile->vbatPidCompensation);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle:%d", currentPidProfile->pidAtMinThrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type", "%d", currentPidProfile->dterm_filter_type);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz", "%d", currentPidProfile->dterm_lpf_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz", "%d", currentPidProfile->yaw_lpf_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", currentPidProfile->dterm_notch_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", currentPidProfile->dterm_notch_cutoff);
|
||||
BLACKBOX_PRINT_HEADER_LINE("itermWindupPointPercent", "%d", currentPidProfile->itermWindupPointPercent);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_average_count", "%d", currentPidProfile->dterm_average_count);
|
||||
BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation", "%d", currentPidProfile->vbatPidCompensation);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle", "%d", currentPidProfile->pidAtMinThrottle);
|
||||
|
||||
// Betaflight PID controller parameters
|
||||
BLACKBOX_PRINT_HEADER_LINE("anti_gravity_threshold:%d", currentPidProfile->itermThrottleThreshold);
|
||||
BLACKBOX_PRINT_HEADER_LINE("anti_gravity_gain:%d", castFloatBytesToInt(currentPidProfile->itermAcceleratorGain));
|
||||
BLACKBOX_PRINT_HEADER_LINE("setpointRelaxRatio:%d", currentPidProfile->setpointRelaxRatio);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", currentPidProfile->dtermSetpointWeight);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", castFloatBytesToInt(currentPidProfile->yawRateAccelLimit));
|
||||
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", castFloatBytesToInt(currentPidProfile->rateAccelLimit));
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit:%d", castFloatBytesToInt(currentPidProfile->pidSumLimit));
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw:%d", castFloatBytesToInt(currentPidProfile->pidSumLimitYaw));
|
||||
BLACKBOX_PRINT_HEADER_LINE("anti_gravity_threshold", "%d", currentPidProfile->itermThrottleThreshold);
|
||||
BLACKBOX_PRINT_HEADER_LINE("anti_gravity_gain", "%d", castFloatBytesToInt(currentPidProfile->itermAcceleratorGain));
|
||||
BLACKBOX_PRINT_HEADER_LINE("setpointRelaxRatio", "%d", currentPidProfile->setpointRelaxRatio);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight", "%d", currentPidProfile->dtermSetpointWeight);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit", "%d", castFloatBytesToInt(currentPidProfile->yawRateAccelLimit));
|
||||
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit", "%d", castFloatBytesToInt(currentPidProfile->rateAccelLimit));
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", castFloatBytesToInt(currentPidProfile->pidSumLimit));
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", castFloatBytesToInt(currentPidProfile->pidSumLimitYaw));
|
||||
// End of Betaflight controller parameters
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE("deadband:%d", rcControlsConfig()->deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", rcControlsConfig()->yaw_deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", gyroConfig()->gyro_lpf);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_soft_type:%d", gyroConfig()->gyro_soft_lpf_type);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", gyroConfig()->gyro_soft_lpf_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d,%d", gyroConfig()->gyro_soft_notch_hz_1,
|
||||
BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_soft_type", "%d", gyroConfig()->gyro_soft_lpf_type);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz", "%d", gyroConfig()->gyro_soft_lpf_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1,
|
||||
gyroConfig()->gyro_soft_notch_hz_2);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1,
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1,
|
||||
gyroConfig()->gyro_soft_notch_cutoff_2);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(accelerometerConfig()->acc_lpf_hz * 100.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", accelerometerConfig()->acc_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", barometerConfig()->baro_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", compassConfig()->mag_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", armingConfig()->gyro_cal_on_first_arm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation:%d", rxConfig()->rcInterpolation);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", rxConfig()->rcInterpolationInterval);
|
||||
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", rxConfig()->airModeActivateThreshold);
|
||||
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider:%d", rxConfig()->serialrx_provider);
|
||||
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", motorConfig()->dev.useUnsyncedPwm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", motorConfig()->dev.motorPwmProtocol);
|
||||
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", motorConfig()->dev.motorPwmRate);
|
||||
BLACKBOX_PRINT_HEADER_LINE("digitalIdleOffset:%d", (int)(motorConfig()->digitalIdleOffsetPercent * 100.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("debug_mode:%d", systemConfig()->debug_mode);
|
||||
BLACKBOX_PRINT_HEADER_LINE("features:%d", featureConfig()->enabledFeatures);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz", "%d", (int)(accelerometerConfig()->acc_lpf_hz * 100.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_hardware", "%d", accelerometerConfig()->acc_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("baro_hardware", "%d", barometerConfig()->baro_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("mag_hardware", "%d", compassConfig()->mag_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm", "%d", armingConfig()->gyro_cal_on_first_arm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation", "%d", rxConfig()->rcInterpolation);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval", "%d", rxConfig()->rcInterpolationInterval);
|
||||
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle", "%d", rxConfig()->airModeActivateThreshold);
|
||||
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider", "%d", rxConfig()->serialrx_provider);
|
||||
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm", "%d", motorConfig()->dev.useUnsyncedPwm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol", "%d", motorConfig()->dev.motorPwmProtocol);
|
||||
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->dev.motorPwmRate);
|
||||
BLACKBOX_PRINT_HEADER_LINE("digitalIdleOffset", "%d", (int)(motorConfig()->digitalIdleOffsetPercent * 100.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode);
|
||||
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
|
||||
|
||||
default:
|
||||
return true;
|
||||
|
|
|
@ -125,12 +125,14 @@ int blackboxPrintf(const char *fmt, ...)
|
|||
* printf a Blackbox header line with a leading "H " and trailing "\n" added automatically. blackboxHeaderBudget is
|
||||
* decreased to account for the number of bytes written.
|
||||
*/
|
||||
void blackboxPrintfHeaderLine(const char *fmt, ...)
|
||||
void blackboxPrintfHeaderLine(const char *name, const char *fmt, ...)
|
||||
{
|
||||
va_list va;
|
||||
|
||||
blackboxWrite('H');
|
||||
blackboxWrite(' ');
|
||||
blackboxPrint(name);
|
||||
blackboxWrite(':');
|
||||
|
||||
va_start(va, fmt);
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@ void blackboxOpen(void);
|
|||
void blackboxWrite(uint8_t value);
|
||||
|
||||
int blackboxPrintf(const char *fmt, ...);
|
||||
void blackboxPrintfHeaderLine(const char *fmt, ...);
|
||||
void blackboxPrintfHeaderLine(const char *name, const char *fmt, ...);
|
||||
int blackboxPrint(const char *s);
|
||||
|
||||
void blackboxWriteUnsignedVB(uint32_t value);
|
||||
|
|
|
@ -91,14 +91,14 @@ CMS_Menu cmsx_menuRcPreview = {
|
|||
|
||||
static uint16_t motorConfig_minthrottle;
|
||||
static uint8_t motorConfig_digitalIdleOffsetPercent;
|
||||
static uint8_t batteryConfig_vbatscale;
|
||||
static uint8_t voltageSensorADCConfig_vbatscale;
|
||||
static uint8_t batteryConfig_vbatmaxcellvoltage;
|
||||
|
||||
static long cmsx_menuMiscOnEnter(void)
|
||||
{
|
||||
motorConfig_minthrottle = motorConfig()->minthrottle;
|
||||
motorConfig_digitalIdleOffsetPercent = 10 * motorConfig()->digitalIdleOffsetPercent;
|
||||
batteryConfig_vbatscale = batteryConfig()->vbatscale;
|
||||
voltageSensorADCConfig_vbatscale = voltageSensorADCConfig(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale;
|
||||
batteryConfig_vbatmaxcellvoltage = batteryConfig()->vbatmaxcellvoltage;
|
||||
return 0;
|
||||
}
|
||||
|
@ -109,7 +109,7 @@ static long cmsx_menuMiscOnExit(const OSD_Entry *self)
|
|||
|
||||
motorConfigMutable()->minthrottle = motorConfig_minthrottle;
|
||||
motorConfigMutable()->digitalIdleOffsetPercent = motorConfig_digitalIdleOffsetPercent / 10.0f;
|
||||
batteryConfigMutable()->vbatscale = batteryConfig_vbatscale;
|
||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = voltageSensorADCConfig_vbatscale;
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = batteryConfig_vbatmaxcellvoltage;
|
||||
return 0;
|
||||
}
|
||||
|
@ -118,10 +118,10 @@ static OSD_Entry menuMiscEntries[]=
|
|||
{
|
||||
{ "-- MISC --", OME_Label, NULL, NULL, 0 },
|
||||
|
||||
{ "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &motorConfig_minthrottle, 1000, 2000, 1 }, 0 },
|
||||
{ "DIGITAL IDLE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &motorConfig_digitalIdleOffsetPercent, 0, 200, 1, 100 }, 0 },
|
||||
{ "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t) { &batteryConfig_vbatscale, 1, 250, 1 }, 0 },
|
||||
{ "VBAT CLMAX", OME_UINT8, NULL, &(OSD_UINT8_t) { &batteryConfig_vbatmaxcellvoltage, 10, 50, 1 }, 0 },
|
||||
{ "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &motorConfig_minthrottle, 1000, 2000, 1 }, 0 },
|
||||
{ "DIGITAL IDLE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &motorConfig_digitalIdleOffsetPercent, 0, 200, 1, 100 }, 0 },
|
||||
{ "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t) { &voltageSensorADCConfig_vbatscale, 1, 250, 1 }, 0 },
|
||||
{ "VBAT CLMAX", OME_UINT8, NULL, &(OSD_UINT8_t) { &batteryConfig_vbatmaxcellvoltage, 10, 50, 1 }, 0 },
|
||||
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview, 0},
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0},
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
// FC configuration
|
||||
// FC configuration (defined by cleanflight v1)
|
||||
#define PG_FAILSAFE_CONFIG 1 // struct OK
|
||||
#define PG_BOARD_ALIGNMENT 2 // struct OK
|
||||
#define PG_GIMBAL_CONFIG 3 // struct OK
|
||||
|
@ -67,14 +67,24 @@
|
|||
#define PG_SPECIAL_COLOR_CONFIG 46 // part of led strip, structs OK
|
||||
#define PG_PILOT_CONFIG 47 // does not exist in betaflight
|
||||
#define PG_MSP_SERVER_CONFIG 48 // does not exist in betaflight
|
||||
#define PG_VOLTAGE_METER_CONFIG 49 // Cleanflight has voltageMeterConfig_t, betaflight has batteryConfig_t
|
||||
#define PG_AMPERAGE_METER_CONFIG 50 // Cleanflight has amperageMeterConfig_t, betaflight has batteryConfig_t
|
||||
#define PG_VOLTAGE_METER_CONFIG 49 // renamed from PG_VOLTAGE_METER_CONFIG // deprecated
|
||||
#define PG_AMPERAGE_METER_CONFIG 50 // renamed from PG_AMPERAGE_METER_CONFIG // deprecated
|
||||
#define PG_DEBUG_CONFIG 51 // does not exist in betaflight
|
||||
#define PG_SERVO_CONFIG 52
|
||||
#define PG_IBUS_TELEMETRY_CONFIG 53 // CF 1.x
|
||||
//#define PG_VTX_CONFIG 54 // CF 1.x
|
||||
|
||||
// Driver configuration
|
||||
#define PG_DRIVER_PWM_RX_CONFIG 100 // does not exist in betaflight
|
||||
#define PG_DRIVER_FLASHCHIP_CONFIG 101 // does not exist in betaflight
|
||||
|
||||
|
||||
// cleanflight v2 specific parameter group ids start at 256
|
||||
#define PG_CURRENT_SENSOR_ADC_CONFIG 256
|
||||
#define PG_CURRENT_SENSOR_VIRTUAL_CONFIG 257
|
||||
#define PG_VOLTAGE_SENSOR_ADC_CONFIG 258
|
||||
|
||||
|
||||
// betaflight specific parameter group ids start at 500
|
||||
#define PG_BETAFLIGHT_START 500
|
||||
#define PG_MODE_ACTIVATION_OPERATOR_CONFIG 500
|
||||
|
|
|
@ -43,7 +43,7 @@ typedef struct adcChannelConfig_t {
|
|||
typedef struct adcConfig_s {
|
||||
adcChannelConfig_t vbat;
|
||||
adcChannelConfig_t rssi;
|
||||
adcChannelConfig_t currentMeter;
|
||||
adcChannelConfig_t current;
|
||||
adcChannelConfig_t external1;
|
||||
} adcConfig_t;
|
||||
|
||||
|
|
|
@ -96,8 +96,8 @@ void adcInit(const adcConfig_t *config)
|
|||
adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
if (config->currentMeter.enabled) {
|
||||
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
if (config->current.enabled) {
|
||||
adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||
|
|
|
@ -125,8 +125,8 @@ void adcInit(const adcConfig_t *config)
|
|||
adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
if (config->currentMeter.enabled) {
|
||||
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
if (config->current.enabled) {
|
||||
adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||
|
|
|
@ -109,8 +109,8 @@ void adcInit(const adcConfig_t *config)
|
|||
adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
if (config->currentMeter.enabled) {
|
||||
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
if (config->current.enabled) {
|
||||
adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||
|
|
|
@ -102,8 +102,8 @@ void adcInit(const adcConfig_t *config)
|
|||
adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
if (config->currentMeter.enabled) {
|
||||
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
if (config->current.enabled) {
|
||||
adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||
|
|
|
@ -249,7 +249,7 @@ static const char * const lookupTableCurrentSensor[] = {
|
|||
};
|
||||
|
||||
static const char * const lookupTableBatterySensor[] = {
|
||||
"ADC", "ESC"
|
||||
"NONE", "ADC", "ESC"
|
||||
};
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
|
@ -339,7 +339,7 @@ static const char * const lookupTableSuperExpoYaw[] = {
|
|||
static const char * const lookupTablePwmProtocol[] = {
|
||||
"OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED",
|
||||
#ifdef USE_DSHOT
|
||||
"DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200",
|
||||
"DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200"
|
||||
#endif
|
||||
};
|
||||
|
||||
|
@ -375,8 +375,8 @@ typedef enum {
|
|||
#ifdef BLACKBOX
|
||||
TABLE_BLACKBOX_DEVICE,
|
||||
#endif
|
||||
TABLE_CURRENT_SENSOR,
|
||||
TABLE_BATTERY_SENSOR,
|
||||
TABLE_CURRENT_METER,
|
||||
TABLE_VOLTAGE_METER,
|
||||
#ifdef USE_SERVOS
|
||||
TABLE_GIMBAL_MODE,
|
||||
#endif
|
||||
|
@ -622,21 +622,27 @@ static const clivalue_t valueTable[] = {
|
|||
|
||||
// PG_BATTERY_CONFIG
|
||||
{ "bat_capacity", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryCapacity) },
|
||||
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatscale) },
|
||||
{ "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmaxcellvoltage) },
|
||||
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmincellvoltage) },
|
||||
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatwarningcellvoltage) },
|
||||
{ "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 250 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbathysteresis) },
|
||||
{ "ibat_scale", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterScale) },
|
||||
{ "ibat_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterOffset) },
|
||||
{ "mwii_ibat_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, multiwiiCurrentMeterOutput) },
|
||||
{ "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_SENSOR }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterType) },
|
||||
{ "battery_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BATTERY_SENSOR }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryMeterType) },
|
||||
{ "bat_detect_thresh", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batterynotpresentlevel) },
|
||||
{ "current_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterSource) },
|
||||
{ "battery_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, voltageMeterSource) },
|
||||
{ "bat_detect_thresh", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryNotPresentLevel) },
|
||||
{ "use_vbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useVBatAlerts) },
|
||||
{ "use_cbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useConsumptionAlerts) },
|
||||
{ "cbat_alert_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, consumptionWarningPercentage) },
|
||||
|
||||
// PG_VOLTAGE_SENSOR_ADC_CONFIG
|
||||
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX }, PG_VOLTAGE_SENSOR_ADC_CONFIG, offsetof(voltageSensorADCConfig_t, vbatscale) },
|
||||
|
||||
// PG_CURRENT_SENSOR_ADC_CONFIG
|
||||
{ "ibata_scale", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_ADC_CONFIG, offsetof(currentSensorADCConfig_t, scale) },
|
||||
{ "ibata_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_ADC_CONFIG, offsetof(currentSensorADCConfig_t, offset) },
|
||||
// PG_CURRENT_SENSOR_ADC_CONFIG
|
||||
{ "ibatv_scale", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, offsetof(currentSensorVirtualConfig_t, scale) },
|
||||
{ "ibatv_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, offsetof(currentSensorVirtualConfig_t, offset) },
|
||||
|
||||
// PG_BEEPER_DEV_CONFIG
|
||||
#ifdef BEEPER
|
||||
{ "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isInverted) },
|
||||
|
@ -910,6 +916,9 @@ static servoMixer_t customServoMixersCopy[MAX_SERVO_RULES];
|
|||
static servoParam_t servoParamsCopy[MAX_SUPPORTED_SERVOS];
|
||||
#endif
|
||||
static batteryConfig_t batteryConfigCopy;
|
||||
static voltageSensorADCConfig_t voltageSensorADCConfigCopy[MAX_VOLTAGE_SENSOR_ADC];
|
||||
static currentSensorADCConfig_t currentSensorADCConfigCopy;
|
||||
static currentSensorVirtualConfig_t currentSensorVirtualConfigCopy;
|
||||
static motorMixer_t customMotorMixerCopy[MAX_SUPPORTED_MOTORS];
|
||||
static mixerConfig_t mixerConfigCopy;
|
||||
static flight3DConfig_t flight3DConfigCopy;
|
||||
|
@ -1213,6 +1222,18 @@ static const cliCurrentAndDefaultConfig_t *getCurrentAndDefaultConfigs(pgn_t pgn
|
|||
ret.currentConfig = &batteryConfigCopy;
|
||||
ret.defaultConfig = batteryConfig();
|
||||
break;
|
||||
case PG_VOLTAGE_SENSOR_ADC_CONFIG:
|
||||
ret.currentConfig = &voltageSensorADCConfigCopy[0];
|
||||
ret.defaultConfig = voltageSensorADCConfig(0);
|
||||
break;
|
||||
case PG_CURRENT_SENSOR_ADC_CONFIG:
|
||||
ret.currentConfig = ¤tSensorADCConfigCopy;
|
||||
ret.defaultConfig = currentSensorADCConfig();
|
||||
break;
|
||||
case PG_CURRENT_SENSOR_VIRTUAL_CONFIG:
|
||||
ret.currentConfig = ¤tSensorVirtualConfigCopy;
|
||||
ret.defaultConfig = currentSensorVirtualConfig();
|
||||
break;
|
||||
case PG_SERIAL_CONFIG:
|
||||
ret.currentConfig = &serialConfigCopy;
|
||||
ret.defaultConfig = serialConfig();
|
||||
|
@ -3739,7 +3760,7 @@ static void cliStatus(char *cmdline)
|
|||
UNUSED(cmdline);
|
||||
|
||||
cliPrintf("System Uptime: %d seconds\r\n", millis() / 1000);
|
||||
cliPrintf("Voltage: %d * 0.1V (%dS battery - %s)\r\n", getVbat(), batteryCellCount, getBatteryStateString());
|
||||
cliPrintf("Voltage: %d * 0.1V (%dS battery - %s)\r\n", getBatteryVoltage(), getBatteryCellCount(), getBatteryStateString());
|
||||
|
||||
cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
|
||||
|
||||
|
@ -3800,7 +3821,7 @@ static void cliTasks(char *cmdline)
|
|||
|
||||
#ifndef MINIMAL_CLI
|
||||
if (systemConfig()->task_statistics) {
|
||||
cliPrintf("Task list rate/hz max/us avg/us maxload avgload total/ms\r\n");
|
||||
cliPrintf("Task list rate/hz max/us avg/us maxload avgload total/ms\r\n");
|
||||
} else {
|
||||
cliPrintf("Task list\r\n");
|
||||
}
|
||||
|
@ -3815,14 +3836,14 @@ static void cliTasks(char *cmdline)
|
|||
subTaskFrequency = taskInfo.latestDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
|
||||
taskFrequency = subTaskFrequency / pidConfig()->pid_process_denom;
|
||||
if (pidConfig()->pid_process_denom > 1) {
|
||||
cliPrintf("%02d - (%13s) ", taskId, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%15s) ", taskId, taskInfo.taskName);
|
||||
} else {
|
||||
taskFrequency = subTaskFrequency;
|
||||
cliPrintf("%02d - (%9s/%3s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%11s/%3s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
|
||||
}
|
||||
} else {
|
||||
taskFrequency = taskInfo.latestDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
|
||||
cliPrintf("%02d - (%13s) ", taskId, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%15s) ", taskId, taskInfo.taskName);
|
||||
}
|
||||
const int maxLoad = taskInfo.maxExecutionTime == 0 ? 0 :(taskInfo.maxExecutionTime * taskFrequency + 5000) / 1000;
|
||||
const int averageLoad = taskInfo.averageExecutionTime == 0 ? 0 : (taskInfo.averageExecutionTime * taskFrequency + 5000) / 1000;
|
||||
|
@ -3838,7 +3859,7 @@ static void cliTasks(char *cmdline)
|
|||
cliPrintf("%6d\r\n", taskFrequency);
|
||||
}
|
||||
if (taskId == TASK_GYROPID && pidConfig()->pid_process_denom > 1) {
|
||||
cliPrintf(" - (%13s) %6d\r\n", taskInfo.subTaskName, subTaskFrequency);
|
||||
cliPrintf(" - (%15s) %6d\r\n", taskInfo.subTaskName, subTaskFrequency);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -113,7 +113,7 @@ pidProfile_t *currentPidProfile;
|
|||
PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
|
||||
.enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE | FEATURE_FAILSAFE
|
||||
.enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE | FEATURE_FAILSAFE
|
||||
);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
|
||||
|
@ -195,8 +195,8 @@ void pgResetFn_adcConfig(adcConfig_t *adcConfig)
|
|||
#endif
|
||||
|
||||
#ifdef CURRENT_METER_ADC_PIN
|
||||
adcConfig->currentMeter.enabled = true;
|
||||
adcConfig->currentMeter.ioTag = IO_TAG(CURRENT_METER_ADC_PIN);
|
||||
adcConfig->current.enabled = true;
|
||||
adcConfig->current.ioTag = IO_TAG(CURRENT_METER_ADC_PIN);
|
||||
#endif
|
||||
|
||||
#ifdef RSSI_ADC_PIN
|
||||
|
@ -503,12 +503,6 @@ void createDefaultConfig(master_t *config)
|
|||
#endif
|
||||
#endif // USE_PARAMETER_GROUPS
|
||||
|
||||
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
||||
// only enable the VBAT feature by default if the board has a voltage divider otherwise
|
||||
// the user may see incorrect readings and unexpected issues with pin mappings may occur.
|
||||
intFeatureSet(FEATURE_VBAT, featuresPtr);
|
||||
#endif
|
||||
|
||||
config->version = EEPROM_CONF_VERSION;
|
||||
|
||||
// global settings
|
||||
|
@ -873,8 +867,8 @@ void validateAndFixConfig(void)
|
|||
// rssi adc needs the same ports
|
||||
featureClear(FEATURE_RSSI_ADC);
|
||||
// current meter needs the same ports
|
||||
if (batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
|
||||
batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
|
||||
}
|
||||
#endif
|
||||
// software serial needs free PWM ports
|
||||
|
@ -883,14 +877,15 @@ void validateAndFixConfig(void)
|
|||
|
||||
#ifdef USE_SOFTSPI
|
||||
if (featureConfigured(FEATURE_SOFTSPI)) {
|
||||
featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL | FEATURE_VBAT);
|
||||
featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL);
|
||||
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_NONE;
|
||||
#if defined(STM32F10X)
|
||||
featureClear(FEATURE_LED_STRIP);
|
||||
// rssi adc needs the same ports
|
||||
featureClear(FEATURE_RSSI_ADC);
|
||||
// current meter needs the same ports
|
||||
if (batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
|
||||
batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
|
||||
typedef enum {
|
||||
FEATURE_RX_PPM = 1 << 0,
|
||||
FEATURE_VBAT = 1 << 1,
|
||||
//FEATURE_VBAT = 1 << 1,
|
||||
FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
|
||||
FEATURE_RX_SERIAL = 1 << 3,
|
||||
FEATURE_MOTOR_STOP = 1 << 4,
|
||||
|
@ -44,7 +44,7 @@ typedef enum {
|
|||
FEATURE_FAILSAFE = 1 << 8,
|
||||
FEATURE_SONAR = 1 << 9,
|
||||
FEATURE_TELEMETRY = 1 << 10,
|
||||
FEATURE_CURRENT_METER = 1 << 11,
|
||||
//FEATURE_CURRENT_METER = 1 << 11,
|
||||
FEATURE_3D = 1 << 12,
|
||||
FEATURE_RX_PARALLEL_PWM = 1 << 13,
|
||||
FEATURE_RX_MSP = 1 << 14,
|
||||
|
|
|
@ -377,9 +377,9 @@ void init(void)
|
|||
#endif
|
||||
|
||||
#ifdef USE_ADC
|
||||
/* these can be removed from features! */
|
||||
adcConfigMutable()->vbat.enabled = feature(FEATURE_VBAT);
|
||||
adcConfigMutable()->currentMeter.enabled = feature(FEATURE_CURRENT_METER);
|
||||
adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC);
|
||||
adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC);
|
||||
|
||||
adcConfigMutable()->rssi.enabled = feature(FEATURE_RSSI_ADC);
|
||||
adcInit(adcConfig());
|
||||
#endif
|
||||
|
@ -556,10 +556,7 @@ void init(void)
|
|||
serialPrint(loopbackPort, "LOOPBACK\r\n");
|
||||
#endif
|
||||
|
||||
// Now that everything has powered up the voltage and cell count be determined.
|
||||
|
||||
if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
|
||||
batteryInit();
|
||||
batteryInit(); // always needs doing, regardless of features.
|
||||
|
||||
#ifdef USE_DASHBOARD
|
||||
if (feature(FEATURE_DASHBOARD)) {
|
||||
|
|
|
@ -728,13 +728,10 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
break;
|
||||
|
||||
case MSP_ANALOG:
|
||||
sbufWriteU8(dst, (uint8_t)constrain(getVbat(), 0, 255));
|
||||
sbufWriteU16(dst, (uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
|
||||
sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255));
|
||||
sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
|
||||
sbufWriteU16(dst, rssi);
|
||||
if(batteryConfig()->multiwiiCurrentMeterOutput) {
|
||||
sbufWriteU16(dst, (uint16_t)constrain(amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero
|
||||
} else
|
||||
sbufWriteU16(dst, (int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
|
||||
break;
|
||||
|
||||
case MSP_ARMING_CONFIG:
|
||||
|
@ -833,13 +830,13 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU8(dst, 0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
|
||||
sbufWriteU8(dst, 0); // gps_ubx_sbas
|
||||
#endif
|
||||
sbufWriteU8(dst, batteryConfig()->multiwiiCurrentMeterOutput);
|
||||
sbufWriteU8(dst, 0); // was multiwiiCurrentMeterOutput
|
||||
sbufWriteU8(dst, rxConfig()->rssi_channel);
|
||||
sbufWriteU8(dst, 0);
|
||||
|
||||
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
||||
|
||||
sbufWriteU8(dst, batteryConfig()->vbatscale);
|
||||
sbufWriteU8(dst, 0); // was vbatscale
|
||||
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
|
||||
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
|
||||
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
|
||||
|
@ -911,19 +908,97 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU16(dst, boardAlignment()->yawDegrees);
|
||||
break;
|
||||
|
||||
case MSP_BATTERY_STATE: {
|
||||
// battery characteristics
|
||||
sbufWriteU8(dst, (uint8_t)constrain(getBatteryCellCount(), 0, 255)); // 0 indicates battery not detected.
|
||||
sbufWriteU16(dst, batteryConfig()->batteryCapacity); // in mAh
|
||||
|
||||
// battery state
|
||||
sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255)); // in 0.1V steps
|
||||
sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
|
||||
sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
|
||||
|
||||
// battery alerts
|
||||
sbufWriteU8(dst, (uint8_t)getBatteryState());
|
||||
break;
|
||||
}
|
||||
case MSP_VOLTAGE_METERS:
|
||||
// write out id and voltage meter values, once for each meter we support
|
||||
for (int i = 0; i < supportedVoltageMeterCount; i++) {
|
||||
|
||||
voltageMeter_t meter;
|
||||
uint8_t id = (uint8_t)voltageMeterIds[i];
|
||||
voltageMeterRead(id, &meter);
|
||||
|
||||
sbufWriteU8(dst, id);
|
||||
sbufWriteU8(dst, (uint8_t)constrain(meter.filtered, 0, 255));
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_CURRENT_METERS:
|
||||
// write out id and current meter values, once for each meter we support
|
||||
for (int i = 0; i < supportedCurrentMeterCount; i++) {
|
||||
|
||||
currentMeter_t meter;
|
||||
uint8_t id = (uint8_t)currentMeterIds[i];
|
||||
currentMeterRead(id, &meter);
|
||||
|
||||
sbufWriteU8(dst, id);
|
||||
sbufWriteU16(dst, (uint16_t)constrain(meter.mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
|
||||
sbufWriteU16(dst, (uint16_t)constrain(meter.amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps (mA). Negative range is truncated to zero
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_VOLTAGE_METER_CONFIG:
|
||||
sbufWriteU8(dst, batteryConfig()->vbatscale);
|
||||
// by using a sensor type and a sub-frame length it's possible to configure any type of voltage meter,
|
||||
// e.g. an i2c/spi/can sensor or any sensor not built directly into the FC such as ESC/RX/SPort/SBus that has
|
||||
// different configuration requirements.
|
||||
BUILD_BUG_ON(VOLTAGE_SENSOR_ADC_VBAT != 0); // VOLTAGE_SENSOR_ADC_VBAT should be the first index,
|
||||
sbufWriteU8(dst, MAX_VOLTAGE_SENSOR_ADC); // voltage meters in payload
|
||||
for (int i = VOLTAGE_SENSOR_ADC_VBAT; i < MAX_VOLTAGE_SENSOR_ADC; i++) {
|
||||
sbufWriteU8(dst, voltageMeterADCtoIDMap[i]); // id of the sensor
|
||||
sbufWriteU8(dst, VOLTAGE_SENSOR_TYPE_ADC_RESISTOR_DIVIDER); // indicate the type of sensor that the next part of the payload is for
|
||||
|
||||
const uint8_t adcSensorSubframeLength = 1 + 1 + 1; // length of vbatscale, vbatresdivval, vbatresdivmultipler, in bytes
|
||||
sbufWriteU8(dst, adcSensorSubframeLength); // ADC sensor sub-frame length
|
||||
sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatscale);
|
||||
sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatresdivval);
|
||||
sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatresdivmultiplier);
|
||||
}
|
||||
// if we had any other voltage sensors, this is where we would output any needed configuration
|
||||
break;
|
||||
|
||||
case MSP_CURRENT_METER_CONFIG: {
|
||||
// the ADC and VIRTUAL sensors have the same configuration requirements, however this API reflects
|
||||
// that this situation may change and allows us to support configuration of any current sensor with
|
||||
// specialist configuration requirements.
|
||||
|
||||
sbufWriteU8(dst, 2); // current meters in payload (adc + virtual)
|
||||
|
||||
const uint8_t adcSensorSubframeLength = 1 + 1 + 2 + 2; // length of id, type, scale, offset, in bytes
|
||||
sbufWriteU8(dst, adcSensorSubframeLength);
|
||||
sbufWriteU8(dst, CURRENT_METER_ID_BATTERY_1); // the id of the sensor
|
||||
sbufWriteU8(dst, CURRENT_SENSOR_ADC); // indicate the type of sensor that the next part of the payload is for
|
||||
sbufWriteU16(dst, currentSensorADCConfig()->scale);
|
||||
sbufWriteU16(dst, currentSensorADCConfig()->offset);
|
||||
|
||||
const int8_t virtualSensorSubframeLength = 1 + 1 + 2 + 2; // length of id, type, scale, offset, in bytes
|
||||
sbufWriteU8(dst, virtualSensorSubframeLength);
|
||||
sbufWriteU8(dst, CURRENT_METER_ID_VIRTUAL_1); // the id of the sensor
|
||||
sbufWriteU8(dst, CURRENT_SENSOR_VIRTUAL); // indicate the type of sensor that the next part of the payload is for
|
||||
sbufWriteU16(dst, currentSensorVirtualConfig()->scale);
|
||||
sbufWriteU16(dst, currentSensorVirtualConfig()->offset);
|
||||
|
||||
// if we had any other current sensors, this is where we would output any needed configuration
|
||||
break;
|
||||
}
|
||||
case MSP_BATTERY_CONFIG:
|
||||
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
|
||||
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
|
||||
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
|
||||
sbufWriteU8(dst, batteryConfig()->batteryMeterType);
|
||||
break;
|
||||
|
||||
case MSP_CURRENT_METER_CONFIG:
|
||||
sbufWriteU16(dst, batteryConfig()->currentMeterScale);
|
||||
sbufWriteU16(dst, batteryConfig()->currentMeterOffset);
|
||||
sbufWriteU8(dst, batteryConfig()->currentMeterType);
|
||||
sbufWriteU16(dst, batteryConfig()->batteryCapacity);
|
||||
sbufWriteU8(dst, batteryConfig()->voltageMeterSource);
|
||||
sbufWriteU8(dst, batteryConfig()->currentMeterSource);
|
||||
break;
|
||||
|
||||
case MSP_MIXER:
|
||||
|
@ -982,8 +1057,8 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU16(dst, boardAlignment()->pitchDegrees);
|
||||
sbufWriteU16(dst, boardAlignment()->yawDegrees);
|
||||
|
||||
sbufWriteU16(dst, batteryConfig()->currentMeterScale);
|
||||
sbufWriteU16(dst, batteryConfig()->currentMeterOffset);
|
||||
sbufWriteU16(dst, 0); // was currentMeterScale, see MSP_CURRENT_METER_CONFIG
|
||||
sbufWriteU16(dst, 0); //was currentMeterOffset, see MSP_CURRENT_METER_CONFIG
|
||||
break;
|
||||
|
||||
case MSP_CF_SERIAL_CONFIG:
|
||||
|
@ -1411,13 +1486,13 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
sbufReadU8(src); // gps_baudrate
|
||||
sbufReadU8(src); // gps_ubx_sbas
|
||||
#endif
|
||||
batteryConfigMutable()->multiwiiCurrentMeterOutput = sbufReadU8(src);
|
||||
sbufReadU8(src); // legacy - was multiwiiCurrentMeterOutput
|
||||
rxConfigMutable()->rssi_channel = sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
|
||||
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
|
||||
|
||||
batteryConfigMutable()->vbatscale = sbufReadU8(src); // actual vbatscale as intended
|
||||
sbufReadU8(src); // legacy - was vbatscale
|
||||
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
|
||||
|
@ -1756,21 +1831,57 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
boardAlignmentMutable()->yawDegrees = sbufReadU16(src);
|
||||
break;
|
||||
|
||||
case MSP_SET_VOLTAGE_METER_CONFIG:
|
||||
batteryConfigMutable()->vbatscale = sbufReadU8(src); // actual vbatscale as intended
|
||||
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
|
||||
if (dataSize > 4) {
|
||||
batteryConfigMutable()->batteryMeterType = sbufReadU8(src);
|
||||
case MSP_SET_VOLTAGE_METER_CONFIG: {
|
||||
int id = sbufReadU8(src);
|
||||
|
||||
//
|
||||
// find and configure an ADC voltage sensor
|
||||
//
|
||||
int voltageSensorADCIndex;
|
||||
for (voltageSensorADCIndex = 0; voltageSensorADCIndex < MAX_VOLTAGE_SENSOR_ADC; voltageSensorADCIndex++) {
|
||||
if (id == voltageMeterADCtoIDMap[voltageSensorADCIndex]) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (voltageSensorADCIndex < MAX_VOLTAGE_SENSOR_ADC) {
|
||||
voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatscale = sbufReadU8(src);
|
||||
voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatresdivval = sbufReadU8(src);
|
||||
voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatresdivmultiplier = sbufReadU8(src);
|
||||
} else {
|
||||
// if we had any other types of voltage sensor to configure, this is where we'd do it.
|
||||
return -1;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case MSP_SET_CURRENT_METER_CONFIG:
|
||||
batteryConfigMutable()->currentMeterScale = sbufReadU16(src);
|
||||
batteryConfigMutable()->currentMeterOffset = sbufReadU16(src);
|
||||
batteryConfigMutable()->currentMeterType = sbufReadU8(src);
|
||||
case MSP_SET_CURRENT_METER_CONFIG: {
|
||||
int id = sbufReadU8(src);
|
||||
|
||||
switch (id) {
|
||||
case CURRENT_METER_ID_BATTERY_1:
|
||||
currentSensorADCConfigMutable()->scale = sbufReadU16(src);
|
||||
currentSensorADCConfigMutable()->offset = sbufReadU16(src);
|
||||
break;
|
||||
case CURRENT_METER_ID_VIRTUAL_1:
|
||||
currentSensorVirtualConfigMutable()->scale = sbufReadU16(src);
|
||||
currentSensorVirtualConfigMutable()->offset = sbufReadU16(src);
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case MSP_SET_BATTERY_CONFIG:
|
||||
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
|
||||
batteryConfigMutable()->batteryCapacity = sbufReadU16(src);
|
||||
batteryConfigMutable()->voltageMeterSource = sbufReadU8(src);
|
||||
batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
|
||||
break;
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
|
@ -1849,8 +1960,8 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
boardAlignmentMutable()->pitchDegrees = sbufReadU16(src); // board_align_pitch
|
||||
boardAlignmentMutable()->yawDegrees = sbufReadU16(src); // board_align_yaw
|
||||
|
||||
batteryConfigMutable()->currentMeterScale = sbufReadU16(src);
|
||||
batteryConfigMutable()->currentMeterOffset = sbufReadU16(src);
|
||||
sbufReadU16(src); // was currentMeterScale, see MSP_SET_CURRENT_METER_CONFIG
|
||||
sbufReadU16(src); // was currentMeterOffset see MSP_SET_CURRENT_METER_CONFIG
|
||||
break;
|
||||
|
||||
case MSP_SET_CF_SERIAL_CONFIG:
|
||||
|
|
|
@ -26,6 +26,7 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/config_profile.h"
|
||||
|
@ -88,12 +89,6 @@ void taskBstMasterProcess(timeUs_t currentTimeUs);
|
|||
#define TASK_PERIOD_MS(ms) ((ms) * 1000)
|
||||
#define TASK_PERIOD_US(us) (us)
|
||||
|
||||
/* VBAT monitoring interval (in microseconds) - 1s*/
|
||||
#define VBATINTERVAL (6 * 3500)
|
||||
/* IBat monitoring interval (in microseconds) - 6 default looptimes */
|
||||
#define IBATINTERVAL (6 * 3500)
|
||||
|
||||
|
||||
static void taskUpdateAccelerometer(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
@ -114,27 +109,17 @@ static void taskHandleSerial(timeUs_t currentTimeUs)
|
|||
mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA, mspFcProcessCommand);
|
||||
}
|
||||
|
||||
static void taskUpdateBattery(timeUs_t currentTimeUs)
|
||||
void taskBatteryAlerts(timeUs_t currentTimeUs)
|
||||
{
|
||||
#if defined(USE_ADC) || defined(USE_ESC_SENSOR)
|
||||
if (feature(FEATURE_VBAT) || feature(FEATURE_ESC_SENSOR)) {
|
||||
static uint32_t vbatLastServiced = 0;
|
||||
if (cmp32(currentTimeUs, vbatLastServiced) >= VBATINTERVAL) {
|
||||
vbatLastServiced = currentTimeUs;
|
||||
updateBattery();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_SENSOR)) {
|
||||
static uint32_t ibatLastServiced = 0;
|
||||
const int32_t ibatTimeSinceLastServiced = cmp32(currentTimeUs, ibatLastServiced);
|
||||
|
||||
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
|
||||
ibatLastServiced = currentTimeUs;
|
||||
updateCurrentMeter(ibatTimeSinceLastServiced);
|
||||
}
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
// the battery *might* fall out in flight, but if that happens the FC will likely be off too unless the user has battery backup.
|
||||
batteryUpdatePresence();
|
||||
}
|
||||
batteryUpdateStates();
|
||||
|
||||
batteryUpdateAlarms();
|
||||
}
|
||||
|
||||
static void taskUpdateRxMain(timeUs_t currentTimeUs)
|
||||
|
@ -237,7 +222,15 @@ void fcTasksInit(void)
|
|||
setTaskEnabled(TASK_ATTITUDE, sensors(SENSOR_ACC));
|
||||
setTaskEnabled(TASK_SERIAL, true);
|
||||
rescheduleTask(TASK_SERIAL, TASK_PERIOD_HZ(serialConfig()->serial_update_rate_hz));
|
||||
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || feature(FEATURE_CURRENT_METER));
|
||||
|
||||
bool useBatteryVoltage = batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE;
|
||||
setTaskEnabled(TASK_BATTERY_VOLTAGE, useBatteryVoltage);
|
||||
bool useBatteryCurrent = batteryConfig()->currentMeterSource != CURRENT_METER_NONE;
|
||||
setTaskEnabled(TASK_BATTERY_CURRENT, useBatteryCurrent);
|
||||
|
||||
bool useBatteryAlerts = batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts || feature(FEATURE_OSD);
|
||||
setTaskEnabled(TASK_BATTERY_ALERTS, (useBatteryVoltage || useBatteryCurrent) && useBatteryAlerts);
|
||||
|
||||
setTaskEnabled(TASK_RX, true);
|
||||
|
||||
setTaskEnabled(TASK_DISPATCH, dispatchIsEnabled());
|
||||
|
@ -366,13 +359,25 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
|
||||
[TASK_BATTERY] = {
|
||||
.taskName = "BATTERY",
|
||||
.taskFunc = taskUpdateBattery,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(50), // 50 Hz
|
||||
[TASK_BATTERY_ALERTS] = {
|
||||
.taskName = "BATTERY_ALERTS",
|
||||
.taskFunc = taskBatteryAlerts,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(5), // 5 Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
|
||||
[TASK_BATTERY_VOLTAGE] = {
|
||||
.taskName = "BATTERY_VOLTAGE",
|
||||
.taskFunc = batteryUpdateVoltage,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(50),
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
[TASK_BATTERY_CURRENT] = {
|
||||
.taskName = "BATTERY_CURRENT",
|
||||
.taskFunc = batteryUpdateCurrentMeter,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(50),
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#ifdef BEEPER
|
||||
[TASK_BEEPER] = {
|
||||
.taskName = "BEEPER",
|
||||
|
|
|
@ -208,7 +208,12 @@ static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
|||
*/
|
||||
void beeper(beeperMode_e mode)
|
||||
{
|
||||
if (mode == BEEPER_SILENCE || ((getBeeperOffMask() & (1 << (BEEPER_USB-1))) && (feature(FEATURE_VBAT) && (batteryCellCount == 0)))) {
|
||||
if (
|
||||
mode == BEEPER_SILENCE || (
|
||||
(getBeeperOffMask() & (1 << (BEEPER_USB - 1)))
|
||||
&& (batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE && (getBatteryCellCount() == 0))
|
||||
)
|
||||
) {
|
||||
beeperSilence();
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -452,24 +452,26 @@ void showBatteryPage(void)
|
|||
{
|
||||
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
|
||||
|
||||
if (feature(FEATURE_VBAT)) {
|
||||
tfp_sprintf(lineBuffer, "Volts: %d.%1d Cells: %d", getVbat() / 10, getVbat() % 10, batteryCellCount);
|
||||
if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE) {
|
||||
tfp_sprintf(lineBuffer, "Volts: %d.%1d Cells: %d", getBatteryVoltage() / 10, getBatteryVoltage() % 10, getBatteryCellCount());
|
||||
padLineBuffer();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(lineBuffer);
|
||||
|
||||
uint8_t batteryPercentage = calculateBatteryPercentage();
|
||||
uint8_t batteryPercentage = calculateBatteryPercentageRemaining();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, batteryPercentage);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_CURRENT_METER)) {
|
||||
tfp_sprintf(lineBuffer, "Amps: %d.%2d mAh: %d", amperage / 100, amperage % 100, mAhDrawn);
|
||||
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
|
||||
|
||||
int32_t amperage = getAmperage();
|
||||
tfp_sprintf(lineBuffer, "Amps: %d.%2d mAh: %d", amperage / 100, amperage % 100, getMAhDrawn());
|
||||
padLineBuffer();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(lineBuffer);
|
||||
|
||||
uint8_t capacityPercentage = calculateBatteryPercentage();
|
||||
uint8_t capacityPercentage = calculateBatteryPercentageRemaining();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, capacityPercentage);
|
||||
}
|
||||
|
|
|
@ -472,7 +472,7 @@ static void applyLedFixedLayers()
|
|||
|
||||
case LED_FUNCTION_BATTERY:
|
||||
color = HSV(RED);
|
||||
hOffset += scaleRange(calculateBatteryPercentage(), 0, 100, -30, 120);
|
||||
hOffset += scaleRange(calculateBatteryPercentageRemaining(), 0, 100, -30, 120);
|
||||
break;
|
||||
|
||||
case LED_FUNCTION_RSSI:
|
||||
|
@ -522,7 +522,7 @@ static void applyLedWarningLayer(bool updateNow, timeUs_t *timer)
|
|||
|
||||
if (warningFlashCounter == 0) { // update when old flags was processed
|
||||
warningFlags = 0;
|
||||
if (feature(FEATURE_VBAT) && getBatteryState() != BATTERY_OK)
|
||||
if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE && getBatteryState() != BATTERY_OK)
|
||||
warningFlags |= 1 << WARNING_LOW_BATTERY;
|
||||
if (feature(FEATURE_FAILSAFE) && failsafeIsActive())
|
||||
warningFlags |= 1 << WARNING_FAILSAFE;
|
||||
|
|
|
@ -175,6 +175,9 @@ static void osdDrawSingleElement(uint8_t item)
|
|||
|
||||
uint8_t elemPosX = OSD_X(osdConfig()->item_pos[item]);
|
||||
uint8_t elemPosY = OSD_Y(osdConfig()->item_pos[item]);
|
||||
|
||||
uint8_t elemOffsetX = 0;
|
||||
|
||||
char buff[32];
|
||||
|
||||
switch(item) {
|
||||
|
@ -192,12 +195,13 @@ static void osdDrawSingleElement(uint8_t item)
|
|||
case OSD_MAIN_BATT_VOLTAGE:
|
||||
{
|
||||
buff[0] = SYM_BATT_5;
|
||||
sprintf(buff + 1, "%d.%1dV", getVbat() / 10, getVbat() % 10);
|
||||
sprintf(buff + 1, "%d.%1dV", getBatteryVoltage() / 10, getBatteryVoltage() % 10);
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_CURRENT_DRAW:
|
||||
{
|
||||
int32_t amperage = getAmperage();
|
||||
buff[0] = SYM_AMP;
|
||||
sprintf(buff + 1, "%d.%02d", abs(amperage) / 100, abs(amperage) % 100);
|
||||
break;
|
||||
|
@ -206,7 +210,7 @@ static void osdDrawSingleElement(uint8_t item)
|
|||
case OSD_MAH_DRAWN:
|
||||
{
|
||||
buff[0] = SYM_MAH;
|
||||
sprintf(buff + 1, "%d", mAhDrawn);
|
||||
sprintf(buff + 1, "%d", getMAhDrawn());
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -401,7 +405,7 @@ static void osdDrawSingleElement(uint8_t item)
|
|||
|
||||
case OSD_POWER:
|
||||
{
|
||||
sprintf(buff, "%dW", amperage * getVbat() / 1000);
|
||||
sprintf(buff, "%dW", getAmperage() * getBatteryVoltage() / 1000);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -415,16 +419,25 @@ static void osdDrawSingleElement(uint8_t item)
|
|||
|
||||
case OSD_MAIN_BATT_WARNING:
|
||||
{
|
||||
if (getVbat() > (batteryWarningVoltage - 1))
|
||||
return;
|
||||
switch(getBatteryState()) {
|
||||
case BATTERY_WARNING:
|
||||
sprintf(buff, "LOW BATTERY");
|
||||
break;
|
||||
|
||||
sprintf(buff, "LOW VOLTAGE");
|
||||
case BATTERY_CRITICAL:
|
||||
sprintf(buff, "LAND NOW");
|
||||
elemOffsetX += 1;
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_AVG_CELL_VOLTAGE:
|
||||
{
|
||||
uint16_t cellV = getVbat() * 10 / batteryCellCount;
|
||||
uint16_t cellV = getBatteryVoltage() * 10 / getBatteryCellCount();
|
||||
buff[0] = SYM_BATT_5;
|
||||
sprintf(buff + 1, "%d.%dV", cellV / 100, cellV % 100);
|
||||
break;
|
||||
|
@ -434,7 +447,7 @@ static void osdDrawSingleElement(uint8_t item)
|
|||
return;
|
||||
}
|
||||
|
||||
displayWrite(osdDisplayPort, elemPosX, elemPosY, buff);
|
||||
displayWrite(osdDisplayPort, elemPosX + elemOffsetX, elemPosY, buff);
|
||||
}
|
||||
|
||||
void osdDrawElements(void)
|
||||
|
@ -582,14 +595,14 @@ void osdUpdateAlarms(void)
|
|||
else
|
||||
CLR_BLINK(OSD_RSSI_VALUE);
|
||||
|
||||
if (getVbat() <= (batteryWarningVoltage - 1)) {
|
||||
SET_BLINK(OSD_MAIN_BATT_VOLTAGE);
|
||||
SET_BLINK(OSD_MAIN_BATT_WARNING);
|
||||
SET_BLINK(OSD_AVG_CELL_VOLTAGE);
|
||||
} else {
|
||||
if (getBatteryState() == BATTERY_OK) {
|
||||
CLR_BLINK(OSD_MAIN_BATT_VOLTAGE);
|
||||
CLR_BLINK(OSD_MAIN_BATT_WARNING);
|
||||
CLR_BLINK(OSD_AVG_CELL_VOLTAGE);
|
||||
} else {
|
||||
SET_BLINK(OSD_MAIN_BATT_VOLTAGE);
|
||||
SET_BLINK(OSD_MAIN_BATT_WARNING);
|
||||
SET_BLINK(OSD_AVG_CELL_VOLTAGE);
|
||||
}
|
||||
|
||||
if (STATE(GPS_FIX) == 0)
|
||||
|
@ -602,7 +615,7 @@ void osdUpdateAlarms(void)
|
|||
else
|
||||
CLR_BLINK(OSD_FLYTIME);
|
||||
|
||||
if (mAhDrawn >= osdConfig()->cap_alarm)
|
||||
if (getMAhDrawn() >= osdConfig()->cap_alarm)
|
||||
SET_BLINK(OSD_MAH_DRAWN);
|
||||
else
|
||||
CLR_BLINK(OSD_MAH_DRAWN);
|
||||
|
@ -644,10 +657,10 @@ static void osdUpdateStats(void)
|
|||
if (stats.max_speed < value)
|
||||
stats.max_speed = value;
|
||||
|
||||
if (stats.min_voltage > getVbat())
|
||||
stats.min_voltage = getVbat();
|
||||
if (stats.min_voltage > getBatteryVoltage())
|
||||
stats.min_voltage = getBatteryVoltage();
|
||||
|
||||
value = amperage / 100;
|
||||
value = getAmperage() / 100;
|
||||
if (stats.max_current < value)
|
||||
stats.max_current = value;
|
||||
|
||||
|
@ -722,14 +735,14 @@ static void osdShowStats(void)
|
|||
strcat(buff, "%");
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
|
||||
if (feature(FEATURE_CURRENT_METER)) {
|
||||
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
|
||||
displayWrite(osdDisplayPort, 2, top, "MAX CURRENT :");
|
||||
itoa(stats.max_current, buff, 10);
|
||||
strcat(buff, "A");
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
|
||||
displayWrite(osdDisplayPort, 2, top, "USED MAH :");
|
||||
itoa(mAhDrawn, buff, 10);
|
||||
itoa(getMAhDrawn(), buff, 10);
|
||||
strcat(buff, "\x07");
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
}
|
||||
|
|
|
@ -426,6 +426,10 @@ void closeSerialPort(serialPort_t *serialPort)
|
|||
|
||||
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
|
||||
{
|
||||
#if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
|
||||
UNUSED(softserialEnabled);
|
||||
#endif
|
||||
|
||||
serialPortCount = SERIAL_PORT_COUNT;
|
||||
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
|
||||
|
||||
|
|
|
@ -59,7 +59,7 @@
|
|||
#define MSP_PROTOCOL_VERSION 0
|
||||
|
||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||
#define API_VERSION_MINOR 32 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
|
||||
#define API_VERSION_MINOR 33 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
|
||||
|
||||
#define API_VERSION_LENGTH 2
|
||||
|
||||
|
@ -105,6 +105,9 @@
|
|||
//
|
||||
// MSP commands for Cleanflight original features
|
||||
//
|
||||
#define MSP_BATTERY_CONFIG 32
|
||||
#define MSP_SET_BATTERY_CONFIG 33
|
||||
|
||||
#define MSP_MODE_RANGES 34 //out message Returns all mode ranges
|
||||
#define MSP_SET_MODE_RANGE 35 //in message Sets a single mode range
|
||||
|
||||
|
@ -253,6 +256,9 @@
|
|||
#define MSP_RC_DEADBAND 125 //out message deadbands for yaw alt pitch roll
|
||||
#define MSP_SENSOR_ALIGNMENT 126 //out message orientation of acc,gyro,mag
|
||||
#define MSP_LED_STRIP_MODECOLOR 127 //out message Get LED strip mode_color settings
|
||||
#define MSP_VOLTAGE_METERS 128 //out message Voltage (per meter)
|
||||
#define MSP_CURRENT_METERS 129 //out message Amperage (per meter)
|
||||
#define MSP_BATTERY_STATE 130 //out message Connected/Disconnected, Voltage, Current Used
|
||||
|
||||
#define MSP_SET_RAW_RC 200 //in message 8 rc chan
|
||||
#define MSP_SET_RAW_GPS 201 //in message fix, numsat, lat, lon, alt, speed
|
||||
|
|
|
@ -81,4 +81,4 @@ void crsfRxSendTelemetryData(void);
|
|||
struct rxConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool crsfRxInit(const struct rxConfig_s *initialRxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
bool crsfRxIsActive(void);
|
||||
bool crsfRxIsActive(void);
|
||||
|
|
|
@ -523,10 +523,10 @@ void handleJetiExBusTelemetry(void)
|
|||
}
|
||||
|
||||
if((jetiExBusRequestFrame[EXBUS_HEADER_DATA_ID] == EXBUS_EX_REQUEST) && (calcCRC16(jetiExBusRequestFrame, jetiExBusRequestFrame[EXBUS_HEADER_MSG_LEN]) == 0)) {
|
||||
jetiExSensors[EX_VOLTAGE].value = getVbat();
|
||||
jetiExSensors[EX_CURRENT].value = amperage;
|
||||
jetiExSensors[EX_VOLTAGE].value = getBatteryVoltage();
|
||||
jetiExSensors[EX_CURRENT].value = getAmperage();
|
||||
jetiExSensors[EX_ALTITUDE].value = baro.BaroAlt;
|
||||
jetiExSensors[EX_CAPACITY].value = mAhDrawn;
|
||||
jetiExSensors[EX_CAPACITY].value = getMAhDrawn();
|
||||
jetiExSensors[EX_FRAMES_LOST].value = framesLost;
|
||||
jetiExSensors[EX_TIME_DIFF].value = timeDiff;
|
||||
|
||||
|
|
|
@ -56,7 +56,9 @@ typedef enum {
|
|||
TASK_RX,
|
||||
TASK_SERIAL,
|
||||
TASK_DISPATCH,
|
||||
TASK_BATTERY,
|
||||
TASK_BATTERY_VOLTAGE,
|
||||
TASK_BATTERY_CURRENT,
|
||||
TASK_BATTERY_ALERTS,
|
||||
#ifdef BEEPER
|
||||
TASK_BEEPER,
|
||||
#endif
|
||||
|
|
|
@ -33,109 +33,107 @@
|
|||
#include "drivers/adc.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
|
||||
/**
|
||||
* terminology: meter vs sensors
|
||||
*
|
||||
* voltage and current sensors are used to collect data.
|
||||
* - e.g. voltage at an MCU ADC input pin, value from an ESC sensor.
|
||||
* sensors require very specific configuration, such as resistor values.
|
||||
* voltage and current meters are used to process and expose data collected from sensors to the rest of the system.
|
||||
* - e.g. a meter exposes normalized, and often filtered, values from a sensor.
|
||||
* meters require different or little configuration.
|
||||
* meters also have different precision concerns, and may use different units to the sensors.
|
||||
*
|
||||
*/
|
||||
|
||||
#define VBAT_LPF_FREQ 0.4f
|
||||
#define IBAT_LPF_FREQ 0.4f
|
||||
static void batteryUpdateConsumptionState(void); // temporary forward reference
|
||||
|
||||
#define VBAT_STABLE_MAX_DELTA 2
|
||||
|
||||
#define ADCVREF 3300 // in mV
|
||||
|
||||
#define MAX_ESC_BATTERY_AGE 10
|
||||
|
||||
// Battery monitoring stuff
|
||||
uint8_t batteryCellCount;
|
||||
uint8_t batteryCellCount; // Note: this can be 0 when no battery is detected or when the battery voltage sensor is missing or disabled.
|
||||
uint16_t batteryWarningVoltage;
|
||||
uint16_t batteryCriticalVoltage;
|
||||
//
|
||||
static currentMeter_t currentMeter;
|
||||
static voltageMeter_t voltageMeter;
|
||||
|
||||
uint16_t vbat = 0; // battery voltage in 0.1V steps (filtered)
|
||||
uint16_t vbatLatest = 0; // most recent unsmoothed value
|
||||
|
||||
int32_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A)
|
||||
int32_t amperageLatest = 0; // most recent value
|
||||
|
||||
int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
|
||||
|
||||
static batteryState_e vBatState;
|
||||
static batteryState_e batteryState;
|
||||
static batteryState_e voltageState;
|
||||
static batteryState_e consumptionState;
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
|
||||
|
||||
#ifndef CURRENT_METER_SCALE_DEFAULT
|
||||
#define CURRENT_METER_SCALE_DEFAULT 400 // for Allegro ACS758LCB-100U (40mV/A)
|
||||
#ifdef BOARD_HAS_CURRENT_SENSOR
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#else
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_VIRTUAL
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#else
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_NONE
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 1);
|
||||
|
||||
PG_RESET_TEMPLATE(batteryConfig_t, batteryConfig,
|
||||
.vbatscale = VBAT_SCALE_DEFAULT,
|
||||
.vbatresdivval = VBAT_RESDIVVAL_DEFAULT,
|
||||
.vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT,
|
||||
// voltage
|
||||
.vbatmaxcellvoltage = 43,
|
||||
.vbatmincellvoltage = 33,
|
||||
.vbatwarningcellvoltage = 35,
|
||||
.vbathysteresis = 1,
|
||||
.batteryMeterType = BATTERY_SENSOR_ADC,
|
||||
.currentMeterOffset = 0,
|
||||
.currentMeterScale = CURRENT_METER_SCALE_DEFAULT,
|
||||
.batteryNotPresentLevel = 55, // VBAT below 5.5 V will be ignored
|
||||
.voltageMeterSource = DEFAULT_VOLTAGE_METER_SOURCE,
|
||||
|
||||
// current
|
||||
.batteryCapacity = 0,
|
||||
.currentMeterType = CURRENT_SENSOR_ADC,
|
||||
.batterynotpresentlevel = 55, // VBAT below 5.5 V will be igonored
|
||||
.currentMeterSource = DEFAULT_VOLTAGE_METER_SOURCE,
|
||||
|
||||
// warnings / alerts
|
||||
.useVBatAlerts = true,
|
||||
.useConsumptionAlerts = false,
|
||||
.consumptionWarningPercentage = 10
|
||||
.consumptionWarningPercentage = 10,
|
||||
.vbathysteresis = 1
|
||||
);
|
||||
|
||||
static uint16_t batteryAdcToVoltage(uint16_t src)
|
||||
void batteryUpdateVoltage(timeUs_t currentTimeUs)
|
||||
{
|
||||
// calculate battery voltage based on ADC reading
|
||||
// result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V
|
||||
return ((((uint32_t)src * batteryConfig()->vbatscale * 33 + (0xFFF * 5)) / (0xFFF * batteryConfig()->vbatresdivval))/batteryConfig()->vbatresdivmultiplier);
|
||||
}
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
static void updateBatteryVoltage(void)
|
||||
{
|
||||
static biquadFilter_t vBatFilter;
|
||||
static bool vBatFilterIsInitialised;
|
||||
switch(batteryConfig()->voltageMeterSource) {
|
||||
#ifdef USE_ESC_SENSOR
|
||||
case VOLTAGE_METER_ESC:
|
||||
if (feature(FEATURE_ESC_SENSOR)) {
|
||||
voltageMeterESCRefresh();
|
||||
voltageMeterESCReadCombined(&voltageMeter);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case VOLTAGE_METER_ADC:
|
||||
voltageMeterADCRefresh();
|
||||
voltageMeterADCRead(ADC_BATTERY, &voltageMeter);
|
||||
break;
|
||||
|
||||
if (!vBatFilterIsInitialised) {
|
||||
biquadFilterInitLPF(&vBatFilter, VBAT_LPF_FREQ, 50000); //50HZ Update
|
||||
vBatFilterIsInitialised = true;
|
||||
}
|
||||
|
||||
#ifdef USE_ESC_SENSOR
|
||||
if (feature(FEATURE_ESC_SENSOR) && batteryConfig()->batteryMeterType == BATTERY_SENSOR_ESC) {
|
||||
escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED);
|
||||
vbatLatest = escData->dataAge <= MAX_ESC_BATTERY_AGE ? escData->voltage / 10 : 0;
|
||||
if (debugMode == DEBUG_BATTERY) {
|
||||
debug[0] = -1;
|
||||
}
|
||||
vbat = biquadFilterApply(&vBatFilter, vbatLatest);
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
uint16_t vBatSample = adcGetChannel(ADC_BATTERY);
|
||||
if (debugMode == DEBUG_BATTERY) {
|
||||
debug[0] = vBatSample;
|
||||
}
|
||||
vbat = batteryAdcToVoltage(biquadFilterApply(&vBatFilter, vBatSample));
|
||||
vbatLatest = batteryAdcToVoltage(vBatSample);
|
||||
default:
|
||||
case VOLTAGE_METER_NONE:
|
||||
voltageMeterReset(&voltageMeter);
|
||||
break;
|
||||
}
|
||||
|
||||
if (debugMode == DEBUG_BATTERY) {
|
||||
debug[1] = vbat;
|
||||
debug[0] = voltageMeter.unfiltered;
|
||||
debug[1] = voltageMeter.filtered;
|
||||
}
|
||||
}
|
||||
|
||||
static void updateBatteryAlert(void)
|
||||
static void updateBatteryBeeperAlert(void)
|
||||
{
|
||||
switch(getBatteryState()) {
|
||||
case BATTERY_WARNING:
|
||||
|
@ -152,75 +150,94 @@ static void updateBatteryAlert(void)
|
|||
}
|
||||
}
|
||||
|
||||
void updateBattery(void)
|
||||
void batteryUpdatePresence(void)
|
||||
{
|
||||
uint16_t vBatPrevious = vbatLatest;
|
||||
updateBatteryVoltage();
|
||||
uint16_t vBatMeasured = vbatLatest;
|
||||
static uint16_t previousVoltage = 0;
|
||||
|
||||
/* battery has just been connected*/
|
||||
if (vBatState == BATTERY_NOT_PRESENT && (ARMING_FLAG(ARMED) || (vbat > batteryConfig()->batterynotpresentlevel && ABS(vBatMeasured - vBatPrevious) <= VBAT_STABLE_MAX_DELTA))) {
|
||||
/* Actual battery state is calculated below, this is really BATTERY_PRESENT */
|
||||
vBatState = BATTERY_OK;
|
||||
bool isVoltageStable = (
|
||||
previousVoltage > 0
|
||||
&& ABS(voltageMeter.filtered - previousVoltage) <= VBAT_STABLE_MAX_DELTA
|
||||
);
|
||||
|
||||
unsigned cells = (vBatMeasured / batteryConfig()->vbatmaxcellvoltage) + 1;
|
||||
if (
|
||||
voltageState == BATTERY_NOT_PRESENT
|
||||
&& voltageMeter.filtered > batteryConfig()->batteryNotPresentLevel
|
||||
&& isVoltageStable
|
||||
) {
|
||||
/* battery has just been connected - calculate cells, warning voltages and reset state */
|
||||
|
||||
|
||||
unsigned cells = (voltageMeter.filtered / batteryConfig()->vbatmaxcellvoltage) + 1;
|
||||
if (cells > 8) {
|
||||
// something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells)
|
||||
cells = 8;
|
||||
}
|
||||
|
||||
consumptionState = voltageState = BATTERY_OK;
|
||||
batteryCellCount = cells;
|
||||
batteryWarningVoltage = batteryCellCount * batteryConfig()->vbatwarningcellvoltage;
|
||||
batteryCriticalVoltage = batteryCellCount * batteryConfig()->vbatmincellvoltage;
|
||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of batteryConfig()->batterynotpresentlevel */
|
||||
} else if (vBatState != BATTERY_NOT_PRESENT && !ARMING_FLAG(ARMED) && vbat <= batteryConfig()->batterynotpresentlevel && ABS(vBatMeasured - vBatPrevious) <= VBAT_STABLE_MAX_DELTA) {
|
||||
vBatState = BATTERY_NOT_PRESENT;
|
||||
} else if (
|
||||
voltageState != BATTERY_NOT_PRESENT
|
||||
&& voltageMeter.filtered <= batteryConfig()->batteryNotPresentLevel
|
||||
&& isVoltageStable
|
||||
) {
|
||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of batteryConfig()->batterynotpresentlevel */
|
||||
|
||||
consumptionState = voltageState = BATTERY_NOT_PRESENT;
|
||||
|
||||
batteryCellCount = 0;
|
||||
batteryWarningVoltage = 0;
|
||||
batteryCriticalVoltage = 0;
|
||||
}
|
||||
|
||||
if (debugMode == DEBUG_BATTERY) {
|
||||
debug[2] = vBatState;
|
||||
debug[2] = voltageState;
|
||||
debug[3] = batteryCellCount;
|
||||
}
|
||||
|
||||
if (batteryConfig()->useVBatAlerts) {
|
||||
switch(vBatState) {
|
||||
case BATTERY_OK:
|
||||
if (vbat <= (batteryWarningVoltage - batteryConfig()->vbathysteresis)) {
|
||||
vBatState = BATTERY_WARNING;
|
||||
}
|
||||
previousVoltage = voltageMeter.filtered; // record the current value so we can detect voltage stabilisation next the presence needs updating.
|
||||
}
|
||||
|
||||
break;
|
||||
case BATTERY_WARNING:
|
||||
if (vbat <= (batteryCriticalVoltage - batteryConfig()->vbathysteresis)) {
|
||||
vBatState = BATTERY_CRITICAL;
|
||||
} else if (vbat > batteryWarningVoltage) {
|
||||
vBatState = BATTERY_OK;
|
||||
}
|
||||
static void batteryUpdateVoltageState(void)
|
||||
{
|
||||
// alerts are currently used by beeper, osd and other subsystems
|
||||
switch(voltageState) {
|
||||
case BATTERY_OK:
|
||||
if (voltageMeter.filtered <= (batteryWarningVoltage - batteryConfig()->vbathysteresis)) {
|
||||
voltageState = BATTERY_WARNING;
|
||||
}
|
||||
break;
|
||||
|
||||
break;
|
||||
case BATTERY_CRITICAL:
|
||||
if (vbat > batteryCriticalVoltage) {
|
||||
vBatState = BATTERY_WARNING;
|
||||
}
|
||||
case BATTERY_WARNING:
|
||||
if (voltageMeter.filtered <= (batteryCriticalVoltage - batteryConfig()->vbathysteresis)) {
|
||||
voltageState = BATTERY_CRITICAL;
|
||||
} else if (voltageMeter.filtered > batteryWarningVoltage) {
|
||||
voltageState = BATTERY_OK;
|
||||
}
|
||||
break;
|
||||
|
||||
break;
|
||||
case BATTERY_NOT_PRESENT:
|
||||
break;
|
||||
}
|
||||
case BATTERY_CRITICAL:
|
||||
if (voltageMeter.filtered > batteryCriticalVoltage) {
|
||||
voltageState = BATTERY_WARNING;
|
||||
}
|
||||
break;
|
||||
|
||||
updateBatteryAlert();
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void batteryUpdateStates(void)
|
||||
{
|
||||
batteryUpdateVoltageState();
|
||||
batteryUpdateConsumptionState();
|
||||
|
||||
batteryState = MAX(voltageState, consumptionState);
|
||||
}
|
||||
|
||||
batteryState_e getBatteryState(void)
|
||||
{
|
||||
batteryState_e batteryState = BATTERY_NOT_PRESENT;
|
||||
if (vBatState != BATTERY_NOT_PRESENT) {
|
||||
batteryState = MAX(vBatState, consumptionState);
|
||||
}
|
||||
|
||||
return batteryState;
|
||||
}
|
||||
|
||||
|
@ -233,140 +250,177 @@ const char * getBatteryStateString(void)
|
|||
|
||||
void batteryInit(void)
|
||||
{
|
||||
vBatState = BATTERY_NOT_PRESENT;
|
||||
consumptionState = BATTERY_OK;
|
||||
//
|
||||
// presence
|
||||
//
|
||||
batteryState = BATTERY_NOT_PRESENT;
|
||||
batteryCellCount = 0;
|
||||
|
||||
//
|
||||
// voltage
|
||||
//
|
||||
voltageState = BATTERY_NOT_PRESENT;
|
||||
batteryWarningVoltage = 0;
|
||||
batteryCriticalVoltage = 0;
|
||||
}
|
||||
|
||||
static int32_t currentSensorToCentiamps(uint16_t src)
|
||||
{
|
||||
int32_t millivolts;
|
||||
voltageMeterReset(&voltageMeter);
|
||||
switch(batteryConfig()->voltageMeterSource) {
|
||||
case VOLTAGE_METER_ESC:
|
||||
#ifdef USE_ESC_SENSOR
|
||||
voltageMeterESCInit();
|
||||
#endif
|
||||
break;
|
||||
|
||||
millivolts = ((uint32_t)src * ADCVREF) / 4096;
|
||||
millivolts -= batteryConfig()->currentMeterOffset;
|
||||
case VOLTAGE_METER_ADC:
|
||||
voltageMeterADCInit();
|
||||
break;
|
||||
|
||||
return (millivolts * 1000) / (int32_t)batteryConfig()->currentMeterScale; // current in 0.01A steps
|
||||
}
|
||||
|
||||
static void updateBatteryCurrent(void)
|
||||
{
|
||||
static biquadFilter_t iBatFilter;
|
||||
static bool iBatFilterIsInitialised;
|
||||
|
||||
if (!iBatFilterIsInitialised) {
|
||||
biquadFilterInitLPF(&iBatFilter, IBAT_LPF_FREQ, 50000); //50HZ Update
|
||||
iBatFilterIsInitialised = true;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
//
|
||||
// current
|
||||
//
|
||||
consumptionState = BATTERY_OK;
|
||||
currentMeterReset(¤tMeter);
|
||||
switch(batteryConfig()->currentMeterSource) {
|
||||
case CURRENT_METER_ADC:
|
||||
currentMeterADCInit();
|
||||
break;
|
||||
|
||||
case CURRENT_METER_VIRTUAL:
|
||||
currentMeterVirtualInit();
|
||||
break;
|
||||
|
||||
case CURRENT_METER_ESC:
|
||||
currentMeterESCInit();
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
uint16_t iBatSample = adcGetChannel(ADC_CURRENT);
|
||||
amperageLatest = currentSensorToCentiamps(iBatSample);
|
||||
amperage = currentSensorToCentiamps(biquadFilterApply(&iBatFilter, iBatSample));
|
||||
}
|
||||
|
||||
static void updateCurrentDrawn(int32_t lastUpdateAt)
|
||||
static void batteryUpdateConsumptionState(void)
|
||||
{
|
||||
static float mAhDrawnF = 0.0f; // used to get good enough resolution
|
||||
if (batteryConfig()->useConsumptionAlerts && batteryConfig()->batteryCapacity > 0 && batteryCellCount > 0) {
|
||||
uint8_t batteryPercentageRemaining = calculateBatteryPercentageRemaining();
|
||||
|
||||
mAhDrawnF = mAhDrawnF + (amperageLatest * lastUpdateAt / (100.0f * 1000 * 3600));
|
||||
mAhDrawn = mAhDrawnF;
|
||||
}
|
||||
|
||||
void updateConsumptionWarning(void)
|
||||
{
|
||||
if (batteryConfig()->useConsumptionAlerts && batteryConfig()->batteryCapacity > 0 && getBatteryState() != BATTERY_NOT_PRESENT) {
|
||||
if (calculateBatteryPercentage() == 0) {
|
||||
vBatState = BATTERY_CRITICAL;
|
||||
} else if (calculateBatteryPercentage() <= batteryConfig()->consumptionWarningPercentage) {
|
||||
if (batteryPercentageRemaining == 0) {
|
||||
consumptionState = BATTERY_CRITICAL;
|
||||
} else if (batteryPercentageRemaining <= batteryConfig()->consumptionWarningPercentage) {
|
||||
consumptionState = BATTERY_WARNING;
|
||||
} else {
|
||||
consumptionState = BATTERY_OK;
|
||||
}
|
||||
|
||||
updateBatteryAlert();
|
||||
}
|
||||
}
|
||||
|
||||
void updateCurrentMeter(int32_t lastUpdateAt)
|
||||
void batteryUpdateCurrentMeter(timeUs_t currentTimeUs)
|
||||
{
|
||||
if (getBatteryState() != BATTERY_NOT_PRESENT) {
|
||||
switch(batteryConfig()->currentMeterType) {
|
||||
case CURRENT_SENSOR_ADC:
|
||||
updateBatteryCurrent();
|
||||
updateCurrentDrawn(lastUpdateAt);
|
||||
updateConsumptionWarning();
|
||||
break;
|
||||
case CURRENT_SENSOR_VIRTUAL:
|
||||
amperageLatest = (int32_t)batteryConfig()->currentMeterOffset;
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
const throttleStatus_e throttleStatus = calculateThrottleStatus();
|
||||
int throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000;
|
||||
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) {
|
||||
throttleOffset = 0;
|
||||
}
|
||||
int throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50);
|
||||
amperageLatest += throttleFactor * (int32_t)batteryConfig()->currentMeterScale / 1000;
|
||||
}
|
||||
amperage = amperageLatest;
|
||||
updateCurrentDrawn(lastUpdateAt);
|
||||
updateConsumptionWarning();
|
||||
break;
|
||||
case CURRENT_SENSOR_ESC:
|
||||
#ifdef USE_ESC_SENSOR
|
||||
if (feature(FEATURE_ESC_SENSOR)) {
|
||||
escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED);
|
||||
if (escData->dataAge <= MAX_ESC_BATTERY_AGE) {
|
||||
amperageLatest = escData->current;
|
||||
mAhDrawn = escData->consumption;
|
||||
} else {
|
||||
amperageLatest = 0;
|
||||
mAhDrawn = 0;
|
||||
}
|
||||
amperage = amperageLatest;
|
||||
UNUSED(currentTimeUs);
|
||||
if (batteryCellCount == 0) {
|
||||
currentMeterReset(¤tMeter);
|
||||
return;
|
||||
}
|
||||
|
||||
updateConsumptionWarning();
|
||||
}
|
||||
static uint32_t ibatLastServiced = 0;
|
||||
const int32_t lastUpdateAt = cmp32(currentTimeUs, ibatLastServiced);
|
||||
ibatLastServiced = currentTimeUs;
|
||||
|
||||
break;
|
||||
#endif
|
||||
case CURRENT_SENSOR_NONE:
|
||||
amperage = 0;
|
||||
amperageLatest = 0;
|
||||
switch(batteryConfig()->currentMeterSource) {
|
||||
case CURRENT_METER_ADC:
|
||||
currentMeterADCRefresh(lastUpdateAt);
|
||||
currentMeterADCRead(¤tMeter);
|
||||
break;
|
||||
|
||||
break;
|
||||
case CURRENT_METER_VIRTUAL: {
|
||||
throttleStatus_e throttleStatus = calculateThrottleStatus();
|
||||
bool throttleLowAndMotorStop = (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP));
|
||||
int32_t throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000;
|
||||
|
||||
currentMeterVirtualRefresh(lastUpdateAt, ARMING_FLAG(ARMED), throttleLowAndMotorStop, throttleOffset);
|
||||
currentMeterVirtualRead(¤tMeter);
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
amperage = 0;
|
||||
amperageLatest = 0;
|
||||
|
||||
case CURRENT_METER_ESC:
|
||||
#ifdef USE_ESC_SENSOR
|
||||
if (feature(FEATURE_ESC_SENSOR)) {
|
||||
currentMeterESCRefresh(lastUpdateAt);
|
||||
currentMeterESCReadCombined(¤tMeter);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
case CURRENT_METER_NONE:
|
||||
currentMeterReset(¤tMeter);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
float calculateVbatPidCompensation(void) {
|
||||
float batteryScaler = 1.0f;
|
||||
if (feature(FEATURE_VBAT) && batteryCellCount > 0) {
|
||||
if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE && batteryCellCount > 0) {
|
||||
// Up to 33% PID gain. Should be fine for 4,2to 3,3 difference
|
||||
batteryScaler = constrainf((( (float)batteryConfig()->vbatmaxcellvoltage * batteryCellCount ) / (float) vbat), 1.0f, 1.33f);
|
||||
batteryScaler = constrainf((( (float)batteryConfig()->vbatmaxcellvoltage * batteryCellCount ) / (float) voltageMeter.filtered), 1.0f, 1.33f);
|
||||
}
|
||||
return batteryScaler;
|
||||
}
|
||||
|
||||
uint8_t calculateBatteryPercentage(void)
|
||||
uint8_t calculateBatteryPercentageRemaining(void)
|
||||
{
|
||||
uint8_t batteryPercentage = 0;
|
||||
if (batteryCellCount > 0) {
|
||||
uint16_t batteryCapacity = batteryConfig()->batteryCapacity;
|
||||
|
||||
if (batteryCapacity > 0) {
|
||||
batteryPercentage = constrain(((float)batteryCapacity - mAhDrawn) * 100 / batteryCapacity, 0, 100);
|
||||
batteryPercentage = constrain(((float)batteryCapacity - currentMeter.mAhDrawn) * 100 / batteryCapacity, 0, 100);
|
||||
} else {
|
||||
batteryPercentage = constrain((((uint32_t)vbat - (batteryConfig()->vbatmincellvoltage * batteryCellCount)) * 100) / ((batteryConfig()->vbatmaxcellvoltage - batteryConfig()->vbatmincellvoltage) * batteryCellCount), 0, 100);
|
||||
batteryPercentage = constrain((((uint32_t)voltageMeter.filtered - (batteryConfig()->vbatmincellvoltage * batteryCellCount)) * 100) / ((batteryConfig()->vbatmaxcellvoltage - batteryConfig()->vbatmincellvoltage) * batteryCellCount), 0, 100);
|
||||
}
|
||||
}
|
||||
|
||||
return batteryPercentage;
|
||||
}
|
||||
|
||||
uint16_t getVbat(void)
|
||||
void batteryUpdateAlarms(void)
|
||||
{
|
||||
return vbat;
|
||||
// use the state to trigger beeper alerts
|
||||
if (batteryConfig()->useVBatAlerts) {
|
||||
updateBatteryBeeperAlert();
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltage(void)
|
||||
{
|
||||
return voltageMeter.filtered;
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltageLatest(void)
|
||||
{
|
||||
return voltageMeter.unfiltered;
|
||||
}
|
||||
|
||||
uint8_t getBatteryCellCount(void)
|
||||
{
|
||||
return batteryCellCount;
|
||||
}
|
||||
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
return currentMeter.amperage;
|
||||
}
|
||||
|
||||
int32_t getAmperageLatest(void)
|
||||
{
|
||||
return currentMeter.amperageLatest;
|
||||
}
|
||||
|
||||
int32_t getMAhDrawn(void)
|
||||
{
|
||||
return currentMeter.mAhDrawn;
|
||||
}
|
||||
|
|
|
@ -19,48 +19,29 @@
|
|||
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#ifndef VBAT_SCALE_DEFAULT
|
||||
#define VBAT_SCALE_DEFAULT 110
|
||||
#endif
|
||||
#define VBAT_RESDIVVAL_DEFAULT 10
|
||||
#define VBAT_RESDIVMULTIPLIER_DEFAULT 1
|
||||
#define VBAT_SCALE_MIN 0
|
||||
#define VBAT_SCALE_MAX 255
|
||||
|
||||
typedef enum {
|
||||
CURRENT_SENSOR_NONE = 0,
|
||||
CURRENT_SENSOR_ADC,
|
||||
CURRENT_SENSOR_VIRTUAL,
|
||||
CURRENT_SENSOR_ESC,
|
||||
CURRENT_SENSOR_MAX = CURRENT_SENSOR_ESC
|
||||
} currentSensor_e;
|
||||
|
||||
typedef enum {
|
||||
BATTERY_SENSOR_ADC = 0,
|
||||
BATTERY_SENSOR_ESC
|
||||
} batterySensor_e;
|
||||
#include "common/filter.h"
|
||||
#include "common/time.h"
|
||||
#include "sensors/current.h"
|
||||
#include "sensors/voltage.h"
|
||||
|
||||
typedef struct batteryConfig_s {
|
||||
uint8_t vbatscale; // adjust this to match battery voltage to reported value
|
||||
uint8_t vbatresdivval; // resistor divider R2 (default NAZE 10(K))
|
||||
uint8_t vbatresdivmultiplier; // multiplier for scale (e.g. 2.5:1 ratio with multiplier of 4 can use '100' instead of '25' in ratio) to get better precision
|
||||
// voltage
|
||||
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 critical alarm, in 0.1V units, default is 33 (3.3V)
|
||||
uint8_t vbatwarningcellvoltage; // warning voltage per cell, this triggers battery warning alarm, in 0.1V units, default is 35 (3.5V)
|
||||
uint8_t vbathysteresis; // hysteresis for alarm, default 1 = 0.1V
|
||||
batterySensor_e batteryMeterType; // type of battery meter uses, either ADC or ESC
|
||||
uint8_t batteryNotPresentLevel; // Below this level battery is considered as not present
|
||||
|
||||
int16_t currentMeterScale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
|
||||
int16_t currentMeterOffset; // offset of the current sensor in millivolt steps
|
||||
currentSensor_e currentMeterType; // type of current meter used, either ADC, Virtual or ESC
|
||||
voltageMeterSource_e voltageMeterSource; // source of battery voltage meter used, either ADC or ESC
|
||||
|
||||
// FIXME this doesn't belong in here since it's a concern of MSP, not of the battery code.
|
||||
uint8_t multiwiiCurrentMeterOutput; // if set to 1 output the amperage in milliamp steps instead of 0.01A steps via msp
|
||||
// current
|
||||
currentMeterSource_e currentMeterSource; // source of battery current meter used, either ADC, Virtual or ESC
|
||||
uint16_t batteryCapacity; // mAh
|
||||
uint8_t batterynotpresentlevel; // Below this level battery is considered as not present
|
||||
|
||||
// warnings / alerts
|
||||
bool useVBatAlerts; // Issue alerts based on VBat readings
|
||||
bool useConsumptionAlerts; // Issue alerts based on total power consumption
|
||||
uint8_t consumptionWarningPercentage; // Percentage of remaining capacity that should trigger a battery warning
|
||||
uint8_t vbathysteresis; // hysteresis for alarm, default 1 = 0.1V
|
||||
} batteryConfig_t;
|
||||
|
||||
PG_DECLARE(batteryConfig_t, batteryConfig);
|
||||
|
@ -72,23 +53,26 @@ typedef enum {
|
|||
BATTERY_NOT_PRESENT
|
||||
} batteryState_e;
|
||||
|
||||
extern uint16_t vbatRaw;
|
||||
extern uint16_t vbatLatest;
|
||||
extern uint8_t batteryCellCount;
|
||||
extern uint16_t batteryWarningVoltage;
|
||||
extern int32_t amperageLatest;
|
||||
extern int32_t amperage;
|
||||
extern int32_t mAhDrawn;
|
||||
void batteryInit(void);
|
||||
void batteryUpdateVoltage(timeUs_t currentTimeUs);
|
||||
void batteryUpdatePresence(void);
|
||||
|
||||
batteryState_e getBatteryState(void);
|
||||
const char * getBatteryStateString(void);
|
||||
void updateBattery(void);
|
||||
void batteryInit(void);
|
||||
|
||||
void batteryUpdateStates(void);
|
||||
void batteryUpdateAlarms(void);
|
||||
|
||||
struct rxConfig_s;
|
||||
void updateCurrentMeter(int32_t lastUpdateAt);
|
||||
int32_t currentMeterToCentiamps(uint16_t src);
|
||||
|
||||
float calculateVbatPidCompensation(void);
|
||||
uint8_t calculateBatteryPercentage(void);
|
||||
uint16_t getVbat(void);
|
||||
uint8_t calculateBatteryPercentageRemaining(void);
|
||||
uint16_t getBatteryVoltage(void);
|
||||
uint16_t getBatteryVoltageLatest(void);
|
||||
uint8_t getBatteryCellCount(void);
|
||||
|
||||
int32_t getAmperage(void);
|
||||
int32_t getAmperageLatest(void);
|
||||
int32_t getMAhDrawn(void);
|
||||
|
||||
void batteryUpdateCurrentMeter(timeUs_t currentTimeUs);
|
||||
|
|
257
src/main/sensors/current.c
Normal file
257
src/main/sensors/current.c
Normal file
|
@ -0,0 +1,257 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "stdbool.h"
|
||||
#include "stdint.h"
|
||||
#include "string.h"
|
||||
|
||||
#include <platform.h>
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "config/config_reset.h"
|
||||
|
||||
#include "sensors/current.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
|
||||
const uint8_t currentMeterIds[] = {
|
||||
CURRENT_METER_ID_BATTERY_1,
|
||||
CURRENT_METER_ID_VIRTUAL_1,
|
||||
#ifdef USE_ESC_SENSOR
|
||||
CURRENT_METER_ID_ESC_COMBINED_1,
|
||||
CURRENT_METER_ID_ESC_MOTOR_1,
|
||||
CURRENT_METER_ID_ESC_MOTOR_2,
|
||||
CURRENT_METER_ID_ESC_MOTOR_3,
|
||||
CURRENT_METER_ID_ESC_MOTOR_4,
|
||||
CURRENT_METER_ID_ESC_MOTOR_5,
|
||||
CURRENT_METER_ID_ESC_MOTOR_6,
|
||||
CURRENT_METER_ID_ESC_MOTOR_7,
|
||||
CURRENT_METER_ID_ESC_MOTOR_8,
|
||||
CURRENT_METER_ID_ESC_MOTOR_9,
|
||||
CURRENT_METER_ID_ESC_MOTOR_10,
|
||||
CURRENT_METER_ID_ESC_MOTOR_11,
|
||||
CURRENT_METER_ID_ESC_MOTOR_12,
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t supportedCurrentMeterCount = ARRAYLEN(currentMeterIds);
|
||||
|
||||
//
|
||||
// ADC/Virtual/ESC shared
|
||||
//
|
||||
|
||||
void currentMeterReset(currentMeter_t *meter)
|
||||
{
|
||||
meter->amperage = 0;
|
||||
meter->amperageLatest = 0;
|
||||
meter->mAhDrawn = 0;
|
||||
}
|
||||
|
||||
//
|
||||
// ADC/Virtual shared
|
||||
//
|
||||
|
||||
#define ADCVREF 3300 // in mV
|
||||
|
||||
#define IBAT_LPF_FREQ 0.4f
|
||||
static biquadFilter_t adciBatFilter;
|
||||
|
||||
#ifndef CURRENT_METER_SCALE_DEFAULT
|
||||
#define CURRENT_METER_SCALE_DEFAULT 400 // for Allegro ACS758LCB-100U (40mV/A)
|
||||
#endif
|
||||
|
||||
#ifndef CURRENT_METER_OFFSET_DEFAULT
|
||||
#define CURRENT_METER_OFFSET_DEFAULT 0
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(currentSensorADCConfig_t, currentSensorADCConfig, PG_CURRENT_SENSOR_ADC_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(currentSensorADCConfig_t, currentSensorADCConfig,
|
||||
.scale = CURRENT_METER_SCALE_DEFAULT,
|
||||
.offset = CURRENT_METER_OFFSET_DEFAULT,
|
||||
);
|
||||
|
||||
PG_REGISTER(currentSensorVirtualConfig_t, currentSensorVirtualConfig, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, 0);
|
||||
|
||||
static int32_t currentMeterADCToCentiamps(const uint16_t src)
|
||||
{
|
||||
|
||||
const currentSensorADCConfig_t *config = currentSensorADCConfig();
|
||||
|
||||
int32_t millivolts = ((uint32_t)src * ADCVREF) / 4096;
|
||||
millivolts -= config->offset;
|
||||
|
||||
return (millivolts * 1000) / (int32_t)config->scale; // current in 0.01A steps
|
||||
}
|
||||
|
||||
static void updateCurrentmAhDrawnState(currentMeterMAhDrawnState_t *state, int32_t amperageLatest, int32_t lastUpdateAt)
|
||||
{
|
||||
state->mAhDrawnF = state->mAhDrawnF + (amperageLatest * lastUpdateAt / (100.0f * 1000 * 3600));
|
||||
state->mAhDrawn = state->mAhDrawnF;
|
||||
}
|
||||
|
||||
//
|
||||
// ADC
|
||||
//
|
||||
|
||||
currentMeterADCState_t currentMeterADCState;
|
||||
|
||||
void currentMeterADCInit(void)
|
||||
{
|
||||
memset(¤tMeterADCState, 0, sizeof(currentMeterADCState_t));
|
||||
biquadFilterInitLPF(&adciBatFilter, IBAT_LPF_FREQ, 50000); //50HZ Update
|
||||
}
|
||||
|
||||
void currentMeterADCRefresh(int32_t lastUpdateAt)
|
||||
{
|
||||
const uint16_t iBatSample = adcGetChannel(ADC_CURRENT);
|
||||
currentMeterADCState.amperageLatest = currentMeterADCToCentiamps(iBatSample);
|
||||
currentMeterADCState.amperage = currentMeterADCToCentiamps(biquadFilterApply(&adciBatFilter, iBatSample));
|
||||
|
||||
updateCurrentmAhDrawnState(¤tMeterADCState.mahDrawnState, currentMeterADCState.amperageLatest, lastUpdateAt);
|
||||
}
|
||||
|
||||
void currentMeterADCRead(currentMeter_t *meter)
|
||||
{
|
||||
meter->amperageLatest = currentMeterADCState.amperageLatest;
|
||||
meter->amperage = currentMeterADCState.amperage;
|
||||
meter->mAhDrawn = currentMeterADCState.mahDrawnState.mAhDrawn;
|
||||
}
|
||||
|
||||
//
|
||||
// VIRTUAL
|
||||
//
|
||||
|
||||
currentSensorVirtualState_t currentMeterVirtualState;
|
||||
|
||||
void currentMeterVirtualInit(void)
|
||||
{
|
||||
memset(¤tMeterVirtualState, 0, sizeof(currentSensorVirtualState_t));
|
||||
}
|
||||
|
||||
void currentMeterVirtualRefresh(int32_t lastUpdateAt, bool armed, bool throttleLowAndMotorStop, int32_t throttleOffset)
|
||||
{
|
||||
currentMeterVirtualState.amperage = (int32_t)currentSensorVirtualConfig()->offset;
|
||||
if (armed) {
|
||||
if (throttleLowAndMotorStop) {
|
||||
throttleOffset = 0;
|
||||
}
|
||||
|
||||
int throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50); // FIXME magic number 50, 50hz?
|
||||
currentMeterVirtualState.amperage += throttleFactor * (int32_t)currentSensorVirtualConfig()->scale / 1000;
|
||||
}
|
||||
updateCurrentmAhDrawnState(¤tMeterVirtualState.mahDrawnState, currentMeterVirtualState.amperage, lastUpdateAt);
|
||||
}
|
||||
|
||||
void currentMeterVirtualRead(currentMeter_t *meter)
|
||||
{
|
||||
meter->amperageLatest = currentMeterVirtualState.amperage;
|
||||
meter->amperage = currentMeterVirtualState.amperage;
|
||||
meter->mAhDrawn = currentMeterVirtualState.mahDrawnState.mAhDrawn;
|
||||
}
|
||||
|
||||
//
|
||||
// ESC
|
||||
//
|
||||
|
||||
#ifdef USE_ESC_SENSOR
|
||||
currentMeterESCState_t currentMeterESCState;
|
||||
#endif
|
||||
|
||||
void currentMeterESCInit(void)
|
||||
{
|
||||
#ifdef USE_ESC_SENSOR
|
||||
memset(¤tMeterESCState, 0, sizeof(currentMeterESCState_t));
|
||||
#endif
|
||||
}
|
||||
|
||||
void currentMeterESCRefresh(int32_t lastUpdateAt)
|
||||
{
|
||||
UNUSED(lastUpdateAt);
|
||||
#ifdef USE_ESC_SENSOR
|
||||
escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED);
|
||||
if (escData->dataAge <= ESC_BATTERY_AGE_MAX) {
|
||||
currentMeterESCState.amperage = escData->current;
|
||||
currentMeterESCState.mAhDrawn = escData->consumption;
|
||||
} else {
|
||||
currentMeterESCState.amperage = 0;
|
||||
currentMeterESCState.mAhDrawn = 0;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void currentMeterESCReadCombined(currentMeter_t *meter)
|
||||
{
|
||||
#ifdef USE_ESC_SENSOR
|
||||
meter->amperageLatest = currentMeterESCState.amperage;
|
||||
meter->amperage = currentMeterESCState.amperage;
|
||||
meter->mAhDrawn = currentMeterESCState.mAhDrawn;
|
||||
#else
|
||||
currentMeterReset(meter);
|
||||
#endif
|
||||
}
|
||||
|
||||
void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter)
|
||||
{
|
||||
#ifndef USE_ESC_SENSOR
|
||||
UNUSED(motorNumber);
|
||||
currentMeterReset(meter);
|
||||
#else
|
||||
escSensorData_t *escData = getEscSensorData(motorNumber);
|
||||
if (escData->dataAge <= ESC_BATTERY_AGE_MAX) {
|
||||
meter->amperage = escData->current;
|
||||
meter->amperageLatest = escData->current;
|
||||
meter->mAhDrawn = escData->consumption;
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
//
|
||||
// API for current meters using IDs
|
||||
//
|
||||
// This API is used by MSP, for configuration/status.
|
||||
//
|
||||
|
||||
void currentMeterRead(currentMeterId_e id, currentMeter_t *meter)
|
||||
{
|
||||
if (id == CURRENT_METER_ID_BATTERY_1) {
|
||||
currentMeterADCRead(meter);
|
||||
} else if (id == CURRENT_METER_ID_VIRTUAL_1) {
|
||||
currentMeterVirtualRead(meter);
|
||||
}
|
||||
#ifdef USE_ESC_SENSOR
|
||||
if (id == CURRENT_METER_ID_ESC_COMBINED_1) {
|
||||
currentMeterESCReadCombined(meter);
|
||||
} else
|
||||
if (id >= CURRENT_METER_ID_ESC_MOTOR_1 && id <= CURRENT_METER_ID_ESC_MOTOR_20 ) {
|
||||
int motor = id - CURRENT_METER_ID_ESC_MOTOR_1;
|
||||
currentMeterESCReadMotor(motor, meter);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
currentMeterReset(meter);
|
||||
}
|
||||
}
|
116
src/main/sensors/current.h
Normal file
116
src/main/sensors/current.h
Normal file
|
@ -0,0 +1,116 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "current_ids.h"
|
||||
|
||||
typedef enum {
|
||||
CURRENT_METER_NONE = 0,
|
||||
CURRENT_METER_ADC,
|
||||
CURRENT_METER_VIRTUAL,
|
||||
CURRENT_METER_ESC,
|
||||
CURRENT_METER_MAX = CURRENT_METER_ESC
|
||||
} currentMeterSource_e;
|
||||
|
||||
typedef struct currentMeter_s {
|
||||
int32_t amperage; // current read by current sensor in centiampere (1/100th A)
|
||||
int32_t amperageLatest; // current read by current sensor in centiampere (1/100th A) (unfiltered)
|
||||
int32_t mAhDrawn; // milliampere hours drawn from the battery since start
|
||||
} currentMeter_t;
|
||||
|
||||
// WARNING - do not mix usage of CURRENT_SENSOR_* and CURRENT_METER_*, they are separate concerns.
|
||||
|
||||
typedef struct currentMeterMAhDrawnState_s {
|
||||
int32_t mAhDrawn; // milliampere hours drawn from the battery since start
|
||||
float mAhDrawnF;
|
||||
} currentMeterMAhDrawnState_t;
|
||||
|
||||
//
|
||||
// Sensors
|
||||
//
|
||||
|
||||
typedef enum {
|
||||
CURRENT_SENSOR_VIRTUAL = 0,
|
||||
CURRENT_SENSOR_ADC,
|
||||
CURRENT_SENSOR_ESC,
|
||||
} currentSensor_e;
|
||||
|
||||
|
||||
//
|
||||
// ADC
|
||||
//
|
||||
|
||||
typedef struct currentMeterADCState_s {
|
||||
currentMeterMAhDrawnState_t mahDrawnState;
|
||||
int32_t amperage; // current read by current sensor in centiampere (1/100th A)
|
||||
int32_t amperageLatest; // current read by current sensor in centiampere (1/100th A) (unfiltered)
|
||||
} currentMeterADCState_t;
|
||||
|
||||
typedef struct currentSensorADCConfig_s {
|
||||
int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
|
||||
uint16_t offset; // offset of the current sensor in millivolt steps
|
||||
} currentSensorADCConfig_t;
|
||||
|
||||
PG_DECLARE(currentSensorADCConfig_t, currentSensorADCConfig);
|
||||
|
||||
//
|
||||
// Virtual
|
||||
//
|
||||
|
||||
typedef struct currentMeterVirtualState_s {
|
||||
currentMeterMAhDrawnState_t mahDrawnState;
|
||||
int32_t amperage; // current read by current sensor in centiampere (1/100th A)
|
||||
} currentSensorVirtualState_t;
|
||||
|
||||
typedef struct currentSensorVirtualConfig_s {
|
||||
int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
|
||||
uint16_t offset; // offset of the current sensor in millivolt steps
|
||||
} currentSensorVirtualConfig_t;
|
||||
|
||||
PG_DECLARE(currentSensorVirtualConfig_t, currentSensorVirtualConfig);
|
||||
|
||||
//
|
||||
// ESC
|
||||
//
|
||||
|
||||
typedef struct currentMeterESCState_s {
|
||||
int32_t mAhDrawn; // milliampere hours drawn from the battery since start
|
||||
int32_t amperage; // current read by current sensor in centiampere (1/100th A)
|
||||
} currentMeterESCState_t;
|
||||
|
||||
void currentMeterReset(currentMeter_t *meter);
|
||||
|
||||
void currentMeterADCInit(void);
|
||||
void currentMeterADCRefresh(int32_t lastUpdateAt);
|
||||
void currentMeterADCRead(currentMeter_t *meter);
|
||||
|
||||
void currentMeterVirtualInit(void);
|
||||
void currentMeterVirtualRefresh(int32_t lastUpdateAt, bool armed, bool throttleLowAndMotorStop, int32_t throttleOffset);
|
||||
void currentMeterVirtualRead(currentMeter_t *meter);
|
||||
|
||||
void currentMeterESCInit(void);
|
||||
void currentMeterESCRefresh(int32_t lastUpdateAt);
|
||||
void currentMeterESCReadCombined(currentMeter_t *meter);
|
||||
void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter);
|
||||
|
||||
//
|
||||
// API for reading current meters by id.
|
||||
//
|
||||
extern const uint8_t supportedCurrentMeterCount;
|
||||
extern const uint8_t currentMeterIds[];
|
||||
void currentMeterRead(currentMeterId_e id, currentMeter_t *currentMeter);
|
69
src/main/sensors/current_ids.h
Normal file
69
src/main/sensors/current_ids.h
Normal file
|
@ -0,0 +1,69 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
//
|
||||
// fixed ids, current can be measured at many different places, these identifiers are the ones we support or would consider supporting.
|
||||
//
|
||||
|
||||
typedef enum {
|
||||
CURRENT_METER_ID_NONE = 0,
|
||||
|
||||
CURRENT_METER_ID_BATTERY_1 = 10, // 10-19 for battery meters
|
||||
CURRENT_METER_ID_BATTERY_2,
|
||||
//..
|
||||
CURRENT_METER_ID_BATTERY_10 = 19,
|
||||
|
||||
CURRENT_METER_ID_5V_1 = 20, // 20-29 for 5V meters
|
||||
CURRENT_METER_ID_5V_2,
|
||||
//..
|
||||
CURRENT_METER_ID_5V_10 = 29,
|
||||
|
||||
CURRENT_METER_ID_9V_1 = 30, // 30-39 for 9V meters
|
||||
CURRENT_METER_ID_9V_2,
|
||||
//..
|
||||
CURRENT_METER_ID_9V_10 = 39,
|
||||
|
||||
CURRENT_METER_ID_12V_1 = 40, // 40-49 for 12V meters
|
||||
CURRENT_METER_ID_12V_2,
|
||||
//..
|
||||
CURRENT_METER_ID_12V_10 = 49,
|
||||
|
||||
CURRENT_METER_ID_ESC_COMBINED_1 = 50, // 50-59 for ESC combined (it's doubtful an FC would ever expose 51-59 however)
|
||||
// ...
|
||||
CURRENT_METER_ID_ESC_COMBINED_10 = 59,
|
||||
|
||||
CURRENT_METER_ID_ESC_MOTOR_1 = 60, // 60-79 for ESC motors (20 motors)
|
||||
CURRENT_METER_ID_ESC_MOTOR_2,
|
||||
CURRENT_METER_ID_ESC_MOTOR_3,
|
||||
CURRENT_METER_ID_ESC_MOTOR_4,
|
||||
CURRENT_METER_ID_ESC_MOTOR_5,
|
||||
CURRENT_METER_ID_ESC_MOTOR_6,
|
||||
CURRENT_METER_ID_ESC_MOTOR_7,
|
||||
CURRENT_METER_ID_ESC_MOTOR_8,
|
||||
CURRENT_METER_ID_ESC_MOTOR_9,
|
||||
CURRENT_METER_ID_ESC_MOTOR_10,
|
||||
CURRENT_METER_ID_ESC_MOTOR_11,
|
||||
CURRENT_METER_ID_ESC_MOTOR_12,
|
||||
//...
|
||||
CURRENT_METER_ID_ESC_MOTOR_20 = 79,
|
||||
|
||||
CURRENT_METER_ID_VIRTUAL_1 = 80, // 80-89 for virtual meters
|
||||
CURRENT_METER_ID_VIRTUAL_2,
|
||||
|
||||
} currentMeterId_e;
|
|
@ -43,8 +43,6 @@
|
|||
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
/*
|
||||
|
|
|
@ -30,6 +30,8 @@ typedef struct {
|
|||
|
||||
#define ESC_DATA_INVALID 255
|
||||
|
||||
#define ESC_BATTERY_AGE_MAX 10
|
||||
|
||||
bool escSensorInit(void);
|
||||
void escSensorProcess(timeUs_t currentTime);
|
||||
|
||||
|
|
293
src/main/sensors/voltage.c
Normal file
293
src/main/sensors/voltage.c
Normal file
|
@ -0,0 +1,293 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "stdbool.h"
|
||||
#include "stdint.h"
|
||||
#include "string.h"
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "config/config_reset.h"
|
||||
|
||||
#include "sensors/voltage.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
|
||||
const uint8_t voltageMeterIds[] = {
|
||||
VOLTAGE_METER_ID_BATTERY_1,
|
||||
#ifdef ADC_POWER_12V
|
||||
VOLTAGE_METER_ID_12V_1,
|
||||
#endif
|
||||
#ifdef ADC_POWER_9V
|
||||
VOLTAGE_METER_ID_9V_1,
|
||||
#endif
|
||||
#ifdef ADC_POWER_5V
|
||||
VOLTAGE_METER_ID_5V_1,
|
||||
#endif
|
||||
#ifdef USE_ESC_SENSOR
|
||||
VOLTAGE_METER_ID_ESC_COMBINED_1,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_1,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_2,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_3,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_4,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_5,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_6,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_7,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_8,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_9,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_10,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_11,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_12,
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t supportedVoltageMeterCount = ARRAYLEN(voltageMeterIds);
|
||||
|
||||
|
||||
//
|
||||
// ADC/ESC shared
|
||||
//
|
||||
|
||||
void voltageMeterReset(voltageMeter_t *meter)
|
||||
{
|
||||
meter->filtered = 0;
|
||||
meter->unfiltered = 0;
|
||||
}
|
||||
//
|
||||
// ADC
|
||||
//
|
||||
|
||||
#ifndef VBAT_SCALE_DEFAULT
|
||||
#define VBAT_SCALE_DEFAULT 110
|
||||
#endif
|
||||
|
||||
#ifndef VBAT_RESDIVVAL_DEFAULT
|
||||
#define VBAT_RESDIVVAL_DEFAULT 10
|
||||
#endif
|
||||
|
||||
#ifndef VBAT_RESDIVMULTIPLIER_DEFAULT
|
||||
#define VBAT_RESDIVMULTIPLIER_DEFAULT 1
|
||||
#endif
|
||||
|
||||
typedef struct voltageMeterADCState_s {
|
||||
uint16_t voltageFiltered; // battery voltage in 0.1V steps (filtered)
|
||||
uint16_t voltageUnfiltered; // battery voltage in 0.1V steps (unfiltered)
|
||||
biquadFilter_t filter;
|
||||
} voltageMeterADCState_t;
|
||||
|
||||
extern voltageMeterADCState_t voltageMeterADCStates[MAX_VOLTAGE_SENSOR_ADC];
|
||||
|
||||
voltageMeterADCState_t voltageMeterADCStates[MAX_VOLTAGE_SENSOR_ADC];
|
||||
|
||||
voltageMeterADCState_t *getVoltageMeterADC(uint8_t index)
|
||||
{
|
||||
return &voltageMeterADCStates[index];
|
||||
}
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(voltageSensorADCConfig_t, MAX_VOLTAGE_SENSOR_ADC, voltageSensorADCConfig, PG_VOLTAGE_SENSOR_ADC_CONFIG, 0);
|
||||
|
||||
void pgResetFn_voltageSensorADCConfig(voltageSensorADCConfig_t *instance)
|
||||
{
|
||||
for (int i = 0; i < MAX_VOLTAGE_SENSOR_ADC; i++) {
|
||||
RESET_CONFIG(voltageSensorADCConfig_t, &instance[i],
|
||||
.vbatscale = VBAT_SCALE_DEFAULT,
|
||||
.vbatresdivval = VBAT_RESDIVVAL_DEFAULT,
|
||||
.vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT,
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static const uint8_t voltageMeterAdcChannelMap[] = {
|
||||
ADC_BATTERY,
|
||||
#ifdef ADC_POWER_12V
|
||||
ADC_POWER_12V,
|
||||
#endif
|
||||
#ifdef ADC_POWER_9V
|
||||
ADC_POWER_9V,
|
||||
#endif
|
||||
#ifdef ADC_POWER_5V
|
||||
ADC_POWER_5V,
|
||||
#endif
|
||||
};
|
||||
|
||||
STATIC_UNIT_TESTED uint16_t voltageAdcToVoltage(const uint16_t src, const voltageSensorADCConfig_t *config)
|
||||
{
|
||||
// calculate battery voltage based on ADC reading
|
||||
// result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 110 = 10:1 voltage divider (10k:1k) * 10 for 0.1V
|
||||
return ((((uint32_t)src * config->vbatscale * 33 + (0xFFF * 5)) / (0xFFF * config->vbatresdivval)) / config->vbatresdivmultiplier);
|
||||
}
|
||||
|
||||
void voltageMeterADCRefresh(void)
|
||||
{
|
||||
for (uint8_t i = 0; i < MAX_VOLTAGE_SENSOR_ADC && i < ARRAYLEN(voltageMeterAdcChannelMap); i++) {
|
||||
// store the battery voltage with some other recent battery voltage readings
|
||||
|
||||
voltageMeterADCState_t *state = &voltageMeterADCStates[i];
|
||||
const voltageSensorADCConfig_t *config = voltageSensorADCConfig(i);
|
||||
|
||||
uint8_t channel = voltageMeterAdcChannelMap[i];
|
||||
uint16_t rawSample = adcGetChannel(channel);
|
||||
|
||||
uint16_t filteredSample = biquadFilterApply(&state->filter, rawSample);
|
||||
|
||||
// always calculate the latest voltage, see getLatestVoltage() which does the calculation on demand.
|
||||
state->voltageFiltered = voltageAdcToVoltage(filteredSample, config);
|
||||
state->voltageUnfiltered = voltageAdcToVoltage(rawSample, config);
|
||||
}
|
||||
}
|
||||
|
||||
void voltageMeterADCRead(voltageSensorADC_e adcChannel, voltageMeter_t *voltageMeter)
|
||||
{
|
||||
voltageMeterADCState_t *state = &voltageMeterADCStates[adcChannel];
|
||||
|
||||
voltageMeter->filtered = state->voltageFiltered;
|
||||
voltageMeter->unfiltered = state->voltageUnfiltered;
|
||||
}
|
||||
|
||||
void voltageMeterADCInit(void)
|
||||
{
|
||||
for (uint8_t i = 0; i < MAX_VOLTAGE_SENSOR_ADC && i < ARRAYLEN(voltageMeterAdcChannelMap); i++) {
|
||||
// store the battery voltage with some other recent battery voltage readings
|
||||
|
||||
voltageMeterADCState_t *state = &voltageMeterADCStates[i];
|
||||
memset(state, 0, sizeof(voltageMeterADCState_t));
|
||||
|
||||
biquadFilterInitLPF(&state->filter, VBATT_LPF_FREQ, 50000);
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// ESC
|
||||
//
|
||||
|
||||
#ifdef USE_ESC_SENSOR
|
||||
typedef struct voltageMeterESCState_s {
|
||||
uint16_t voltageFiltered; // battery voltage in 0.1V steps (filtered)
|
||||
uint16_t voltageUnfiltered; // battery voltage in 0.1V steps (unfiltered)
|
||||
biquadFilter_t filter;
|
||||
} voltageMeterESCState_t;
|
||||
|
||||
static voltageMeterESCState_t voltageMeterESCState;
|
||||
#endif
|
||||
|
||||
#define VBAT_LPF_FREQ 0.4f
|
||||
|
||||
void voltageMeterESCInit(void)
|
||||
{
|
||||
#ifdef USE_ESC_SENSOR
|
||||
memset(&voltageMeterESCState, 0, sizeof(voltageMeterESCState_t));
|
||||
biquadFilterInitLPF(&voltageMeterESCState.filter, VBAT_LPF_FREQ, 50000); //50HZ Update
|
||||
#endif
|
||||
}
|
||||
|
||||
void voltageMeterESCRefresh(void)
|
||||
{
|
||||
#ifdef USE_ESC_SENSOR
|
||||
escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED);
|
||||
voltageMeterESCState.voltageUnfiltered = escData->dataAge <= ESC_BATTERY_AGE_MAX ? escData->voltage / 10 : 0;
|
||||
voltageMeterESCState.voltageFiltered = biquadFilterApply(&voltageMeterESCState.filter, voltageMeterESCState.voltageUnfiltered);
|
||||
#endif
|
||||
}
|
||||
|
||||
void voltageMeterESCReadMotor(uint8_t motorNumber, voltageMeter_t *voltageMeter)
|
||||
{
|
||||
#ifndef USE_ESC_SENSOR
|
||||
UNUSED(motorNumber);
|
||||
voltageMeterReset(voltageMeter);
|
||||
#else
|
||||
escSensorData_t *escData = getEscSensorData(motorNumber);
|
||||
|
||||
voltageMeter->unfiltered = escData->dataAge <= ESC_BATTERY_AGE_MAX ? escData->voltage / 10 : 0;
|
||||
voltageMeter->filtered = voltageMeter->unfiltered; // no filtering for ESC motors currently.
|
||||
#endif
|
||||
}
|
||||
|
||||
void voltageMeterESCReadCombined(voltageMeter_t *voltageMeter)
|
||||
{
|
||||
#ifndef USE_ESC_SENSOR
|
||||
voltageMeterReset(voltageMeter);
|
||||
#else
|
||||
voltageMeter->filtered = voltageMeterESCState.voltageFiltered;
|
||||
voltageMeter->unfiltered = voltageMeterESCState.voltageUnfiltered;
|
||||
#endif
|
||||
}
|
||||
|
||||
//
|
||||
// API for using voltage meters using IDs
|
||||
//
|
||||
// This API is used by MSP, for configuration/status.
|
||||
//
|
||||
|
||||
|
||||
// the order of these much match the indexes in voltageSensorADC_e
|
||||
const uint8_t voltageMeterADCtoIDMap[MAX_VOLTAGE_SENSOR_ADC] = {
|
||||
VOLTAGE_METER_ID_BATTERY_1,
|
||||
#ifdef ADC_POWER_12V
|
||||
VOLTAGE_METER_ID_12V_1,
|
||||
#endif
|
||||
#ifdef ADC_POWER_9V
|
||||
VOLTAGE_METER_ID_9V_1,
|
||||
#endif
|
||||
#ifdef ADC_POWER_5V
|
||||
VOLTAGE_METER_ID_5V_1,
|
||||
#endif
|
||||
};
|
||||
|
||||
void voltageMeterRead(voltageMeterId_e id, voltageMeter_t *meter)
|
||||
{
|
||||
if (id == VOLTAGE_METER_ID_BATTERY_1) {
|
||||
voltageMeterADCRead(VOLTAGE_SENSOR_ADC_VBAT, meter);
|
||||
} else
|
||||
#ifdef ADC_POWER_12V
|
||||
if (id == VOLTAGE_METER_ID_12V_1) {
|
||||
voltageMeterADCRead(VOLTAGE_SENSOR_ADC_12V, meter);
|
||||
} else
|
||||
#endif
|
||||
#ifdef ADC_POWER_9V
|
||||
if (id == VOLTAGE_METER_ID_9V_1) {
|
||||
voltageMeterADCRead(VOLTAGE_SENSOR_ADC_9V, meter);
|
||||
} else
|
||||
#endif
|
||||
#ifdef ADC_POWER_5V
|
||||
if (id == VOLTAGE_METER_ID_5V_1) {
|
||||
voltageMeterADCRead(VOLTAGE_SENSOR_ADC_5V, meter);
|
||||
} else
|
||||
#endif
|
||||
#ifdef USE_ESC_SENSOR
|
||||
if (id == VOLTAGE_METER_ID_ESC_COMBINED_1) {
|
||||
voltageMeterESCReadCombined(meter);
|
||||
} else
|
||||
if (id >= VOLTAGE_METER_ID_ESC_MOTOR_1 && id <= VOLTAGE_METER_ID_ESC_MOTOR_20 ) {
|
||||
int motor = id - VOLTAGE_METER_ID_ESC_MOTOR_1;
|
||||
voltageMeterESCReadMotor(motor, meter);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
voltageMeterReset(meter);
|
||||
}
|
||||
}
|
101
src/main/sensors/voltage.h
Normal file
101
src/main/sensors/voltage.h
Normal file
|
@ -0,0 +1,101 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "voltage_ids.h"
|
||||
|
||||
//
|
||||
// meters
|
||||
//
|
||||
|
||||
typedef enum {
|
||||
VOLTAGE_METER_NONE = 0,
|
||||
VOLTAGE_METER_ADC,
|
||||
VOLTAGE_METER_ESC
|
||||
} voltageMeterSource_e;
|
||||
|
||||
// WARNING - do not mix usage of VOLTAGE_METER_* and VOLTAGE_SENSOR_*, they are separate concerns.
|
||||
|
||||
typedef struct voltageMeter_s {
|
||||
uint16_t filtered; // voltage in 0.1V steps
|
||||
uint16_t unfiltered; // voltage in 0.1V steps
|
||||
} voltageMeter_t;
|
||||
|
||||
|
||||
//
|
||||
// sensors
|
||||
//
|
||||
|
||||
typedef enum {
|
||||
VOLTAGE_SENSOR_TYPE_ADC_RESISTOR_DIVIDER = 0,
|
||||
VOLTAGE_SENSOR_TYPE_ESC
|
||||
} voltageSensorType_e;
|
||||
|
||||
|
||||
//
|
||||
// adc sensors
|
||||
//
|
||||
|
||||
#define VBAT_SCALE_MIN 0
|
||||
#define VBAT_SCALE_MAX 255
|
||||
|
||||
#define VBATT_LPF_FREQ 1.0f
|
||||
|
||||
#ifndef MAX_VOLTAGE_SENSOR_ADC
|
||||
#define MAX_VOLTAGE_SENSOR_ADC 1 // VBAT - some boards have external, 12V, 9V and 5V meters.
|
||||
#endif
|
||||
|
||||
typedef enum {
|
||||
VOLTAGE_SENSOR_ADC_VBAT = 0,
|
||||
VOLTAGE_SENSOR_ADC_12V = 1,
|
||||
VOLTAGE_SENSOR_ADC_9V = 2,
|
||||
VOLTAGE_SENSOR_ADC_5V = 3
|
||||
} voltageSensorADC_e; // see also voltageMeterADCtoIDMap
|
||||
|
||||
|
||||
typedef struct voltageSensorADCConfig_s {
|
||||
uint8_t vbatscale; // adjust this to match battery voltage to reported value
|
||||
uint8_t vbatresdivval; // resistor divider R2 (default NAZE 10(K))
|
||||
uint8_t vbatresdivmultiplier; // multiplier for scale (e.g. 2.5:1 ratio with multiplier of 4 can use '100' instead of '25' in ratio) to get better precision
|
||||
} voltageSensorADCConfig_t;
|
||||
|
||||
PG_DECLARE_ARRAY(voltageSensorADCConfig_t, MAX_VOLTAGE_SENSOR_ADC, voltageSensorADCConfig);
|
||||
|
||||
//
|
||||
// Main API
|
||||
//
|
||||
void voltageMeterReset(voltageMeter_t *voltageMeter);
|
||||
|
||||
void voltageMeterADCInit(void);
|
||||
void voltageMeterADCRefresh(void);
|
||||
void voltageMeterADCRead(voltageSensorADC_e adcChannel, voltageMeter_t *voltageMeter);
|
||||
|
||||
void voltageMeterESCInit(void);
|
||||
void voltageMeterESCRefresh(void);
|
||||
void voltageMeterESCReadCombined(voltageMeter_t *voltageMeter);
|
||||
void voltageMeterESCReadMotor(uint8_t motor, voltageMeter_t *voltageMeter);
|
||||
|
||||
|
||||
//
|
||||
// API for reading/configuring current meters by id.
|
||||
//
|
||||
extern const uint8_t voltageMeterADCtoIDMap[MAX_VOLTAGE_SENSOR_ADC];
|
||||
|
||||
extern const uint8_t supportedVoltageMeterCount;
|
||||
extern const uint8_t voltageMeterIds[];
|
||||
void voltageMeterRead(voltageMeterId_e id, voltageMeter_t *voltageMeter);
|
71
src/main/sensors/voltage_ids.h
Normal file
71
src/main/sensors/voltage_ids.h
Normal file
|
@ -0,0 +1,71 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
//
|
||||
// fixed ids, voltage can be measured at many different places, these identifiers are the ones we support or would consider supporting.
|
||||
//
|
||||
|
||||
typedef enum {
|
||||
VOLTAGE_METER_ID_NONE = 0,
|
||||
|
||||
VOLTAGE_METER_ID_BATTERY_1 = 10, // 10-19 for battery meters
|
||||
VOLTAGE_METER_ID_BATTERY_2,
|
||||
//..
|
||||
VOLTAGE_METER_ID_BATTERY_10 = 19,
|
||||
|
||||
VOLTAGE_METER_ID_5V_1 = 20, // 20-29 for 5V meters
|
||||
VOLTAGE_METER_ID_5V_2,
|
||||
//..
|
||||
VOLTAGE_METER_ID_5V_10 = 29,
|
||||
|
||||
VOLTAGE_METER_ID_9V_1 = 30, // 30-39 for 9V meters
|
||||
VOLTAGE_METER_ID_9V_2,
|
||||
//..
|
||||
VOLTAGE_METER_ID_9V_10 = 39,
|
||||
|
||||
VOLTAGE_METER_ID_12V_1 = 40, // 40-49 for 12V meters
|
||||
VOLTAGE_METER_ID_12V_2,
|
||||
//..
|
||||
VOLTAGE_METER_ID_12V_10 = 49,
|
||||
|
||||
VOLTAGE_METER_ID_ESC_COMBINED_1 = 50, // 50-59 for ESC combined (it's doubtful an FC would ever expose 51-59 however)
|
||||
// ...
|
||||
VOLTAGE_METER_ID_ESC_COMBINED_10 = 59,
|
||||
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_1 = 60, // 60-79 for ESC motors (20 motors)
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_2,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_3,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_4,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_5,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_6,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_7,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_8,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_9,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_10,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_11,
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_12,
|
||||
//...
|
||||
VOLTAGE_METER_ID_ESC_MOTOR_20 = 79,
|
||||
|
||||
VOLTAGE_METER_ID_CELL_1 = 80, // 80-119 for cell meters (40 cells)
|
||||
VOLTAGE_METER_ID_CELL_2,
|
||||
//...
|
||||
VOLTAGE_METER_ID_CELL_40 = 119,
|
||||
|
||||
} voltageMeterId_e;
|
|
@ -83,7 +83,6 @@
|
|||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
|
||||
#define DEFAULT_FEATURES FEATURE_VBAT
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
|
|
@ -44,9 +44,6 @@
|
|||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
#define CURRENTOFFSET 2500 // ACS712/714-30A - 0A = 2.5V
|
||||
#define CURRENTSCALE -667 // ACS712/714-30A - 66.666 mV/A inverted mode
|
||||
|
||||
#ifdef BRUSHED_MOTORS_PWM_RATE
|
||||
#undef BRUSHED_MOTORS_PWM_RATE
|
||||
#endif
|
||||
|
@ -56,8 +53,6 @@
|
|||
// alternative defaults settings for AlienFlight targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
batteryConfigMutable()->currentMeterOffset = CURRENTOFFSET;
|
||||
batteryConfigMutable()->currentMeterScale = CURRENTSCALE;
|
||||
compassConfigMutable()->mag_hardware = MAG_NONE; // disabled by default
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
|
@ -74,7 +69,9 @@ void targetConfiguration(void)
|
|||
rxConfigMutable()->sbus_inversion = 0;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
featureSet(FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY);
|
||||
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
|
||||
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;
|
||||
featureSet(FEATURE_TELEMETRY);
|
||||
}
|
||||
|
||||
pidProfilesMutable(0)->P8[FD_ROLL] = 53;
|
||||
|
|
|
@ -145,11 +145,15 @@
|
|||
|
||||
#define USE_ADC
|
||||
//#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
//#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC4
|
||||
#define EXTERNAL1_ADC_GPIO_PIN PC5
|
||||
|
||||
#define CURRENT_METER_OFFSET_DEFAULT 2500 // ACS712/714-30A - 0A = 2.5V
|
||||
#define CURRENT_METER_SCALE_DEFAULT -667 // ACS712/714-30A - 66.666 mV/A inverted mode
|
||||
|
||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
||||
|
||||
#define BINDPLUG_PIN PB2
|
||||
|
|
|
@ -43,9 +43,6 @@
|
|||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
#define CURRENTOFFSET 2500 // ACS712/714-30A - 0A = 2.5V
|
||||
#define CURRENTSCALE -667 // ACS712/714-30A - 66.666 mV/A inverted mode
|
||||
|
||||
#ifdef BRUSHED_MOTORS_PWM_RATE
|
||||
#undef BRUSHED_MOTORS_PWM_RATE
|
||||
#endif
|
||||
|
@ -55,8 +52,6 @@
|
|||
// alternative defaults settings for AlienFlight targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
batteryConfigMutable()->currentMeterOffset = CURRENTOFFSET;
|
||||
batteryConfigMutable()->currentMeterScale = CURRENTSCALE;
|
||||
compassConfigMutable()->mag_hardware = MAG_NONE; // disabled by default
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
|
@ -73,7 +68,9 @@ void targetConfiguration(void)
|
|||
rxConfigMutable()->sbus_inversion = 0;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
featureSet(FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY);
|
||||
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
|
||||
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;
|
||||
featureSet(FEATURE_TELEMETRY);
|
||||
}
|
||||
|
||||
pidProfilesMutable(0)->P8[FD_ROLL] = 53;
|
||||
|
|
|
@ -156,10 +156,14 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC4
|
||||
|
||||
#define CURRENT_METER_OFFSET_DEFAULT 2500 // ACS712/714-30A - 0A = 2.5V
|
||||
#define CURRENT_METER_SCALE_DEFAULT -667 // ACS712/714-30A - 66.666 mV/A inverted mode
|
||||
|
||||
// LED strip configuration.
|
||||
#define LED_STRIP
|
||||
|
||||
|
|
|
@ -1,32 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef TARGET_CONFIG
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
batteryConfigMutable()->currentMeterScale = 220;
|
||||
}
|
||||
#endif
|
|
@ -21,7 +21,6 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "BFF3"
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
#define TARGET_CONFIG
|
||||
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
@ -112,19 +111,22 @@
|
|||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define CURRENT_METER_ADC_PIN PA5
|
||||
#define RSSI_ADC_PIN PB2
|
||||
|
||||
#define CURRENT_METER_SCALE_DEFAULT 200
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define SBUS_TELEMETRY_UART SERIAL_PORT_USART1
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_OSD)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_TELEMETRY | FEATURE_OSD)
|
||||
|
||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
||||
|
||||
|
|
|
@ -78,7 +78,7 @@
|
|||
#define BST_PROTOCOL_VERSION 0
|
||||
|
||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||
#define API_VERSION_MINOR 12 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
#define API_VERSION_MINOR 13 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
|
||||
#define API_VERSION_LENGTH 2
|
||||
|
||||
|
@ -120,6 +120,9 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
|||
//
|
||||
// MSP commands for Cleanflight original features
|
||||
//
|
||||
#define BST_BATTERY_CONFIG 32
|
||||
#define BST_SET_BATTERY_CONFIG 33
|
||||
|
||||
#define BST_MODE_RANGES 34 //out message Returns all mode ranges
|
||||
#define BST_SET_MODE_RANGE 35 //in message Sets a single mode range
|
||||
|
||||
|
@ -674,13 +677,10 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
#endif
|
||||
break;
|
||||
case BST_ANALOG:
|
||||
bstWrite8((uint8_t)constrain(getVbat(), 0, 255));
|
||||
bstWrite16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
|
||||
bstWrite8((uint8_t)constrain(getBatteryVoltage(), 0, 255));
|
||||
bstWrite16((uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
|
||||
bstWrite16(rssi);
|
||||
if(batteryConfig()->multiwiiCurrentMeterOutput) {
|
||||
bstWrite16((uint16_t)constrain(amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero
|
||||
} else
|
||||
bstWrite16((int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
bstWrite16((int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
break;
|
||||
case BST_ARMING_CONFIG:
|
||||
bstWrite8(armingConfig()->auto_disarm_delay);
|
||||
|
@ -767,13 +767,13 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
|
||||
bstWrite8(0); // gps_ubx_sbas
|
||||
#endif
|
||||
bstWrite8(batteryConfig()->multiwiiCurrentMeterOutput);
|
||||
bstWrite8(0); // legacy - was multiwiiCurrentMeterOutput);
|
||||
bstWrite8(rxConfig()->rssi_channel);
|
||||
bstWrite8(0);
|
||||
|
||||
bstWrite16(compassConfig()->mag_declination / 10);
|
||||
|
||||
bstWrite8(batteryConfig()->vbatscale);
|
||||
bstWrite8(voltageSensorADCConfig(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale);
|
||||
bstWrite8(batteryConfig()->vbatmincellvoltage);
|
||||
bstWrite8(batteryConfig()->vbatmaxcellvoltage);
|
||||
bstWrite8(batteryConfig()->vbatwarningcellvoltage);
|
||||
|
@ -855,17 +855,18 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
bstWrite16(boardAlignment()->yawDegrees);
|
||||
break;
|
||||
|
||||
|
||||
case BST_VOLTAGE_METER_CONFIG:
|
||||
bstWrite8(batteryConfig()->vbatscale);
|
||||
bstWrite8(voltageSensorADCConfig(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale);
|
||||
bstWrite8(batteryConfig()->vbatmincellvoltage);
|
||||
bstWrite8(batteryConfig()->vbatmaxcellvoltage);
|
||||
bstWrite8(batteryConfig()->vbatwarningcellvoltage);
|
||||
break;
|
||||
|
||||
case BST_CURRENT_METER_CONFIG:
|
||||
bstWrite16(batteryConfig()->currentMeterScale);
|
||||
bstWrite16(batteryConfig()->currentMeterOffset);
|
||||
bstWrite8(batteryConfig()->currentMeterType);
|
||||
bstWrite16(currentSensorADCConfig()->scale);
|
||||
bstWrite16(currentSensorADCConfig()->offset);
|
||||
bstWrite8(batteryConfig()->currentMeterSource);
|
||||
bstWrite16(batteryConfig()->batteryCapacity);
|
||||
break;
|
||||
|
||||
|
@ -916,8 +917,8 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
bstWrite16(boardAlignment()->pitchDegrees);
|
||||
bstWrite16(boardAlignment()->yawDegrees);
|
||||
|
||||
bstWrite16(batteryConfig()->currentMeterScale);
|
||||
bstWrite16(batteryConfig()->currentMeterOffset);
|
||||
bstWrite16(currentSensorADCConfig()->scale);
|
||||
bstWrite16(currentSensorADCConfig()->offset);
|
||||
break;
|
||||
|
||||
case BST_CF_SERIAL_CONFIG:
|
||||
|
@ -1128,13 +1129,13 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
bstRead8(); // gps_baudrate
|
||||
bstRead8(); // gps_ubx_sbas
|
||||
#endif
|
||||
batteryConfigMutable()->multiwiiCurrentMeterOutput = bstRead8();
|
||||
bstRead8(); // legacy - was multiwiiCurrentMeterOutput
|
||||
rxConfigMutable()->rssi_channel = bstRead8();
|
||||
bstRead8();
|
||||
|
||||
compassConfigMutable()->mag_declination = bstRead16() * 10;
|
||||
|
||||
batteryConfigMutable()->vbatscale = bstRead8(); // actual vbatscale as intended
|
||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = bstRead8(); // actual vbatscale as intended
|
||||
batteryConfigMutable()->vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = bstRead8(); // vbatlevel_warn2 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatwarningcellvoltage = bstRead8(); // vbatlevel when buzzer starts to alert
|
||||
|
@ -1266,15 +1267,15 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
boardAlignmentMutable()->yawDegrees = bstRead16();
|
||||
break;
|
||||
case BST_SET_VOLTAGE_METER_CONFIG:
|
||||
batteryConfigMutable()->vbatscale = bstRead8(); // actual vbatscale as intended
|
||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = bstRead8(); // actual vbatscale as intended
|
||||
batteryConfigMutable()->vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = bstRead8(); // vbatlevel_warn2 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatwarningcellvoltage = bstRead8(); // vbatlevel when buzzer starts to alert
|
||||
break;
|
||||
case BST_SET_CURRENT_METER_CONFIG:
|
||||
batteryConfigMutable()->currentMeterScale = bstRead16();
|
||||
batteryConfigMutable()->currentMeterOffset = bstRead16();
|
||||
batteryConfigMutable()->currentMeterType = bstRead8();
|
||||
currentSensorADCConfigMutable()->scale = bstRead16();
|
||||
currentSensorADCConfigMutable()->offset = bstRead16();
|
||||
batteryConfigMutable()->currentMeterSource = bstRead8();
|
||||
batteryConfigMutable()->batteryCapacity = bstRead16();
|
||||
break;
|
||||
|
||||
|
@ -1338,8 +1339,8 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
boardAlignmentMutable()->pitchDegrees = bstRead16(); // board_align_pitch
|
||||
boardAlignmentMutable()->yawDegrees = bstRead16(); // board_align_yaw
|
||||
|
||||
batteryConfigMutable()->currentMeterScale = bstRead16();
|
||||
batteryConfigMutable()->currentMeterOffset = bstRead16();
|
||||
currentSensorADCConfigMutable()->scale = bstRead16();
|
||||
currentSensorADCConfigMutable()->offset = bstRead16();
|
||||
break;
|
||||
case BST_SET_CF_SERIAL_CONFIG:
|
||||
{
|
||||
|
|
|
@ -117,7 +117,7 @@
|
|||
#define RSSI_ADC_PIN PC2
|
||||
#define EXTERNAL1_ADC_PIN PC3
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_FAILSAFE | FEATURE_AIRMODE | FEATURE_LED_STRIP)
|
||||
#define DEFAULT_FEATURES (FEATURE_FAILSAFE | FEATURE_AIRMODE | FEATURE_LED_STRIP)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
|
|
@ -94,7 +94,6 @@
|
|||
|
||||
#undef LED_STRIP
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
|
|
@ -141,7 +141,7 @@
|
|||
|
||||
#undef LED_STRIP
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
||||
|
|
|
@ -127,7 +127,7 @@
|
|||
#define RSSI_ADC_PIN PC1
|
||||
|
||||
// *************** FEATURES ************************
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX | FEATURE_VTX)
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_BLACKBOX | FEATURE_VTX)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART3
|
||||
|
|
|
@ -166,7 +166,7 @@
|
|||
#define RSSI_ADC_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC3
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
||||
|
|
|
@ -89,7 +89,7 @@
|
|||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
||||
|
|
|
@ -95,7 +95,6 @@
|
|||
#define CURRENT_METER_ADC_PIN PA2
|
||||
//#define RSSI_ADC_PIN PB2
|
||||
|
||||
#define DEFAULT_FEATURES FEATURE_VBAT
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
|
|
@ -119,7 +119,7 @@
|
|||
#define RSSI_ADC_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC3
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_OSD)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_OSD)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
||||
|
|
|
@ -29,17 +29,13 @@
|
|||
#include "io/osd.h"
|
||||
|
||||
#define VBAT_SCALE 113
|
||||
#define CURRENT_SCALE 1000
|
||||
#define CURRENT_OFFSET 0
|
||||
|
||||
#define OSD_POS(x,y) (x | (y << 5))
|
||||
|
||||
#ifdef TARGET_CONFIG
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
batteryConfigMutable()->vbatscale = VBAT_SCALE;
|
||||
batteryConfigMutable()->currentMeterScale = CURRENT_SCALE;
|
||||
batteryConfigMutable()->currentMeterOffset = CURRENT_OFFSET;
|
||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = VBAT_SCALE;
|
||||
barometerConfigMutable()->baro_hardware = 0;
|
||||
compassConfigMutable()->mag_hardware = 0;
|
||||
osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1) | VISIBLE_FLAG;
|
||||
|
|
|
@ -86,12 +86,16 @@
|
|||
#define OSD_CH_SWITCH PC5
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define VBAT_ADC_PIN PC3
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
#define RSSI_ADC_PIN PC0
|
||||
|
||||
#define CURRENT_METER_SCALE_DEFAULT 1000
|
||||
#define CURRENT_METER_OFFSET_DEFAULT 0
|
||||
|
||||
#define USE_VCP
|
||||
//#define VBUS_SENSING_PIN PA9
|
||||
|
||||
|
@ -144,7 +148,7 @@
|
|||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define RX_CHANNELS_TAER
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD)
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD)
|
||||
|
||||
#define LED_STRIP
|
||||
|
||||
|
|
|
@ -39,15 +39,16 @@
|
|||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#define VBAT_SCALE 100
|
||||
|
||||
// alternative defaults settings for MULTIFLITEPICO targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
compassConfigMutable()->mag_hardware = MAG_NONE; // disabled by default
|
||||
|
||||
batteryConfigMutable()->vbatscale = 100;
|
||||
batteryConfigMutable()->vbatresdivval = 15;
|
||||
batteryConfigMutable()->vbatresdivmultiplier = 4;
|
||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = VBAT_SCALE;
|
||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatresdivval = 15;
|
||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatresdivmultiplier = 4;
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = 44;
|
||||
batteryConfigMutable()->vbatmincellvoltage = 32;
|
||||
batteryConfigMutable()->vbatwarningcellvoltage = 33;
|
||||
|
|
|
@ -116,8 +116,8 @@
|
|||
|
||||
//#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP|FEATURE_VBAT)
|
||||
#define BRUSHED_MOTORS
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#define SERIALRX_UART SERIAL_PORT_USART3
|
||||
|
|
|
@ -18,6 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
#undef TELEMETRY_IBUS //no space left
|
||||
#undef TELEMETRY_HOTT //no space left
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "OMNI" // https://en.wikipedia.org/wiki/Omnibus
|
||||
|
||||
|
@ -145,7 +146,8 @@
|
|||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
||||
#define USE_ADC
|
||||
//#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define VBAT_ADC_PIN PA0
|
||||
#define CURRENT_METER_ADC_PIN PA1
|
||||
#define ADC_INSTANCE ADC1
|
||||
|
@ -159,7 +161,7 @@
|
|||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_OSD)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_OSD)
|
||||
|
||||
#define BUTTONS
|
||||
#define BUTTON_A_PIN PB1
|
||||
|
|
0
src/main/target/OMNIBUSF4/CL_RACINGF4.mk
Normal file
0
src/main/target/OMNIBUSF4/CL_RACINGF4.mk
Normal file
|
@ -25,8 +25,10 @@
|
|||
#include "drivers/timer_def.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
#ifdef OMNIBUSF4SD
|
||||
#if defined(CL_RACINGF4)
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_PWM | TIM_USE_PPM, TIMER_OUTPUT_NONE, 0), // PPM
|
||||
#else
|
||||
#if defined(OMNIBUSF4SD)
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S2_IN
|
||||
#else
|
||||
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, TIMER_OUTPUT_NONE, 0), // PPM
|
||||
|
@ -36,13 +38,14 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S4_IN
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S5_IN
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S6_IN
|
||||
|
||||
#endif // CL_RACINGF4
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S1_OUT D1_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S2_OUT D1_ST2
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 1), // S3_OUT D1_ST6
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S4_OUT D1_ST1
|
||||
|
||||
#ifdef OMNIBUSF4SD
|
||||
#if defined(CL_RACINGF4)
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), // S5_OUT
|
||||
#elif defined(OMNIBUSF4SD)
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S5_OUT
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), // S6_OUT
|
||||
#else
|
||||
|
|
|
@ -15,21 +15,26 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef OMNIBUSF4SD
|
||||
#if defined(CL_RACINGF4)
|
||||
#define TARGET_BOARD_IDENTIFIER "CLR4"
|
||||
#elif defined(OMNIBUSF4SD)
|
||||
#define TARGET_BOARD_IDENTIFIER "OBSD"
|
||||
#else
|
||||
#define TARGET_BOARD_IDENTIFIER "OBF4"
|
||||
#endif
|
||||
|
||||
#if defined(CL_RACINGF4)
|
||||
#define USBD_PRODUCT_STRING "CL_RACINGF4"
|
||||
#else
|
||||
#define USBD_PRODUCT_STRING "OmnibusF4"
|
||||
#endif
|
||||
|
||||
#ifdef OPBL
|
||||
#define USBD_SERIALNUMBER_STRING "0x8020000"
|
||||
#endif
|
||||
|
||||
|
||||
#define LED0 PB5
|
||||
//#define LED1 PB4
|
||||
|
||||
#define BEEPER PB4
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
|
@ -44,12 +49,15 @@
|
|||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
|
||||
#ifdef OMNIBUSF4SD
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
#if defined(CL_RACINGF4)
|
||||
#define GYRO_MPU6000_ALIGN CW0_DEG
|
||||
#define ACC_MPU6000_ALIGN CW0_DEG
|
||||
#elif defined(OMNIBUSF4SD)
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
#else
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||
#endif
|
||||
|
||||
// MPU6000 interrupts
|
||||
|
@ -66,11 +74,11 @@
|
|||
|
||||
#define BARO
|
||||
#define USE_BARO_MS5611
|
||||
#ifdef OMNIBUSF4SD
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_SPI_BMP280
|
||||
#define BMP280_SPI_INSTANCE SPI3
|
||||
#define BMP280_CS_PIN PB3 // v1
|
||||
#if defined(OMNIBUSF4SD)
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_SPI_BMP280
|
||||
#define BMP280_SPI_INSTANCE SPI3
|
||||
#define BMP280_CS_PIN PB3 // v1
|
||||
#endif
|
||||
|
||||
#define OSD
|
||||
|
@ -80,32 +88,32 @@
|
|||
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
|
||||
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
||||
|
||||
#ifdef OMNIBUSF4SD
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI2
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
|
||||
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||
#else
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define M25P16_CS_PIN SPI3_NSS_PIN
|
||||
#define M25P16_SPI_INSTANCE SPI3
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#if defined(OMNIBUSF4SD) || defined(CL_RACINGF4)
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI2
|
||||
#if defined(OMNIBUSF4SD)
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#endif
|
||||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
|
||||
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||
#else
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define M25P16_CS_PIN SPI3_NSS_PIN
|
||||
#define M25P16_SPI_INSTANCE SPI3
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#endif // OMNIBUSF4
|
||||
|
||||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PC5
|
||||
|
@ -123,28 +131,35 @@
|
|||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#if defined(CL_RACINGF4)
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PA1
|
||||
#define UART4_TX_PIN PA0
|
||||
|
||||
#define SERIAL_PORT_COUNT 5 //VCP, USART1, USART3,USART4, USART6,
|
||||
#else
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
|
||||
#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART3, USART6, SOFTSERIAL x 2
|
||||
#endif
|
||||
|
||||
#define USE_ESCSERIAL
|
||||
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||
|
||||
#define USE_SPI
|
||||
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#ifdef OMNIBUSF4SD
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
#if defined(OMNIBUSF4SD) || defined(CL_RACINGF4)
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
#endif
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#ifdef OMNIBUSF4SD
|
||||
#if defined(OMNIBUSF4SD) || defined(CL_RACINGF4)
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#else
|
||||
#define SPI3_NSS_PIN PB3
|
||||
|
@ -156,17 +171,22 @@
|
|||
#define USE_ADC
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#if defined(CL_RACINGF4)
|
||||
#define RSSI_ADC_PIN PC3
|
||||
#else
|
||||
//#define RSSI_ADC_PIN PA0
|
||||
#endif
|
||||
|
||||
#define USE_ESC_SENSOR
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)
|
||||
|
||||
#define AVOID_UART1_FOR_PWM_PPM
|
||||
#if defined(CL_RACINGF4)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_TELEMETRY | FEATURE_OSD )
|
||||
#else
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_OSD)
|
||||
#endif
|
||||
|
||||
#define SPEKTRUM_BIND_PIN UART1_RX_PIN
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
|
||||
|
|
|
@ -1,5 +1,10 @@
|
|||
F405_TARGETS += $(TARGET)
|
||||
|
||||
ifeq ($(TARGET), CL_RACINGF4)
|
||||
FEATURES = VCP SDCARD
|
||||
else
|
||||
FEATURES += VCP ONBOARDFLASH
|
||||
endif
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro_spi_mpu6000.c \
|
||||
|
|
|
@ -1,32 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef TARGET_CONFIG
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
batteryConfigMutable()->currentMeterScale = 125;
|
||||
}
|
||||
#endif
|
|
@ -20,7 +20,6 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV Piko BLX
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
#define TARGET_CONFIG
|
||||
|
||||
#define LED0 PB9
|
||||
#define LED1 PB5
|
||||
|
@ -76,6 +75,8 @@
|
|||
#define CURRENT_METER_ADC_PIN PB2
|
||||
#define VBAT_ADC_PIN PA5
|
||||
|
||||
#define CURRENT_METER_SCALE_DEFAULT 125
|
||||
|
||||
#define TRANSPONDER
|
||||
#define TRANSPONDER_GPIO GPIOA
|
||||
#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
|
|
@ -105,7 +105,7 @@
|
|||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_VBAT | FEATURE_RSSI_ADC | FEATURE_OSD)
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_RSSI_ADC | FEATURE_OSD)
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -102,7 +102,6 @@
|
|||
#define CURRENT_METER_ADC_PIN PB2
|
||||
#define RSSI_ADC_PIN PA6
|
||||
|
||||
#define DEFAULT_FEATURES FEATURE_VBAT
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
|
|
|
@ -28,6 +28,5 @@
|
|||
void targetConfiguration(void)
|
||||
{
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = 45;
|
||||
batteryConfigMutable()->vbatscale = VBAT_SCALE_DEFAULT;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -89,7 +89,7 @@
|
|||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
||||
|
|
|
@ -164,6 +164,7 @@
|
|||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
|
@ -181,7 +182,7 @@
|
|||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_TELEMETRY)
|
||||
|
||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
||||
|
||||
|
|
|
@ -132,6 +132,7 @@
|
|||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define RSSI_ADC_PIN PB2
|
||||
|
@ -148,7 +149,7 @@
|
|||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_TELEMETRY)
|
||||
|
||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
||||
|
||||
|
|
|
@ -136,6 +136,8 @@
|
|||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define VBAT_ADC_PIN PC1
|
||||
|
@ -158,7 +160,7 @@
|
|||
#define OSD
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_OSD)
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_TELEMETRY)
|
||||
|
||||
#define BUTTONS
|
||||
#define BUTTON_A_PIN PD2
|
||||
|
|
|
@ -36,26 +36,15 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#define TARGET_CPU_VOLTAGE 3.0
|
||||
|
||||
// set default settings to match our target
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
batteryConfigMutable()->currentMeterOffset = 0;
|
||||
// we use an ina139, RL=0.005, Rs=30000
|
||||
// V/A = (0.005 * 0.001 * 30000) * I
|
||||
// rescale to 1/10th mV / A -> * 1000 * 10
|
||||
// we use 3.0V as cpu and adc voltage -> rescale by 3.0/3.3
|
||||
batteryConfigMutable()->currentMeterScale = (0.005 * 0.001 * 30000) * 1000 * 10 * (TARGET_CPU_VOLTAGE / 3.3);
|
||||
|
||||
// we use the same uart for frsky telemetry and SBUS, both non inverted
|
||||
// use the same uart for frsky telemetry and SBUS, both non inverted
|
||||
const int index = findSerialPortIndexByIdentifier(SBUS_TELEMETRY_UART);
|
||||
serialConfigMutable()->portConfigs[index].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
||||
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
rxConfigMutable()->sbus_inversion = 0;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
|
||||
featureSet(FEATURE_CURRENT_METER | FEATURE_VBAT);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -94,11 +94,21 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define VBAT_ADC_PIN PB1
|
||||
#define CURRENT_METER_ADC_PIN PB0
|
||||
#define ADC_INSTANCE ADC3
|
||||
#define VBAT_SCALE_DEFAULT 100
|
||||
|
||||
#define CURRENT_TARGET_CPU_VOLTAGE 3.0
|
||||
|
||||
// board uses an ina139, RL=0.005, Rs=30000
|
||||
// V/A = (0.005 * 0.001 * 30000) * I
|
||||
// rescale to 1/10th mV / A -> * 1000 * 10
|
||||
// use 3.0V as cpu and adc voltage -> rescale by 3.0/3.3
|
||||
#define CURRENT_METER_SCALE_DEFAULT (0.005 * 0.001 * 30000) * 1000 * 10 * (CURRENT_TARGET_CPU_VOLTAGE / 3.3)
|
||||
#define CURRENT_METER_OFFSET_DEFAULT 0
|
||||
|
||||
#define WS2811_PIN PA8
|
||||
#define WS2811_TIMER TIM1
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
|
@ -107,7 +117,7 @@
|
|||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_TELEMETRY)
|
||||
#define TARGET_CONFIG
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -159,7 +159,7 @@
|
|||
|
||||
#undef LED_STRIP
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_FEATURES (FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
||||
|
|
|
@ -174,7 +174,7 @@ void crsfFrameBatterySensor(sbuf_t *dst)
|
|||
// use sbufWrite since CRC does not include frame length
|
||||
sbufWriteU8(dst, CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC);
|
||||
crsfSerialize8(dst, CRSF_FRAMETYPE_BATTERY_SENSOR);
|
||||
crsfSerialize16(dst, getVbat()); // vbat is in units of 0.1V
|
||||
crsfSerialize16(dst, getBatteryVoltage()); // vbat is in units of 0.1V
|
||||
#ifdef CLEANFLIGHT
|
||||
const amperageMeter_t *amperageMeter = getAmperageMeter(batteryConfig()->amperageMeterSource);
|
||||
const int16_t amperage = constrain(amperageMeter->amperage, -0x8000, 0x7FFF) / 10; // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
|
@ -182,9 +182,9 @@ void crsfFrameBatterySensor(sbuf_t *dst)
|
|||
const uint32_t batteryCapacity = batteryConfig()->batteryCapacity;
|
||||
const uint8_t batteryRemainingPercentage = batteryCapacityRemainingPercentage();
|
||||
#else
|
||||
crsfSerialize16(dst, amperage / 10);
|
||||
crsfSerialize16(dst, getAmperage() / 10);
|
||||
const uint32_t batteryCapacity = batteryConfig()->batteryCapacity;
|
||||
const uint8_t batteryRemainingPercentage = calculateBatteryPercentage();
|
||||
const uint8_t batteryRemainingPercentage = calculateBatteryPercentageRemaining();
|
||||
#endif
|
||||
crsfSerialize8(dst, (batteryCapacity >> 16));
|
||||
crsfSerialize8(dst, (batteryCapacity >> 8));
|
||||
|
|
|
@ -371,6 +371,7 @@ static void sendVoltage(void)
|
|||
uint32_t cellVoltage;
|
||||
uint16_t payload;
|
||||
|
||||
uint8_t cellCount = getBatteryCellCount();
|
||||
/*
|
||||
* Format for Voltage Data for single cells is like this:
|
||||
*
|
||||
|
@ -382,7 +383,7 @@ static void sendVoltage(void)
|
|||
* The actual value sent for cell voltage has resolution of 0.002 volts
|
||||
* Since vbat has resolution of 0.1 volts it has to be multiplied by 50
|
||||
*/
|
||||
cellVoltage = ((uint32_t)getVbat() * 100 + batteryCellCount) / (batteryCellCount * 2);
|
||||
cellVoltage = ((uint32_t)getBatteryVoltage() * 100 + cellCount) / (cellCount * 2);
|
||||
|
||||
// Cell number is at bit 9-12
|
||||
payload = (currentCell << 4);
|
||||
|
@ -397,7 +398,7 @@ static void sendVoltage(void)
|
|||
serialize16(payload);
|
||||
|
||||
currentCell++;
|
||||
currentCell %= batteryCellCount;
|
||||
currentCell %= cellCount;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -405,17 +406,18 @@ static void sendVoltage(void)
|
|||
*/
|
||||
static void sendVoltageAmp(void)
|
||||
{
|
||||
uint16_t batteryVoltage = getBatteryVoltage();
|
||||
if (telemetryConfig()->frsky_vfas_precision == FRSKY_VFAS_PRECISION_HIGH) {
|
||||
/*
|
||||
* Use new ID 0x39 to send voltage directly in 0.1 volts resolution
|
||||
*/
|
||||
sendDataHead(ID_VOLTAGE_AMP);
|
||||
serialize16(getVbat());
|
||||
serialize16(batteryVoltage);
|
||||
} else {
|
||||
uint16_t voltage = (getVbat() * 110) / 21;
|
||||
uint16_t voltage = (batteryVoltage * 110) / 21;
|
||||
uint16_t vfasVoltage;
|
||||
if (telemetryConfig()->frsky_vfas_cell_voltage) {
|
||||
vfasVoltage = voltage / batteryCellCount;
|
||||
vfasVoltage = voltage / getBatteryCellCount();
|
||||
} else {
|
||||
vfasVoltage = voltage;
|
||||
}
|
||||
|
@ -429,7 +431,7 @@ static void sendVoltageAmp(void)
|
|||
static void sendAmperage(void)
|
||||
{
|
||||
sendDataHead(ID_CURRENT);
|
||||
serialize16((uint16_t)(amperage / 10));
|
||||
serialize16((uint16_t)(getAmperage() / 10));
|
||||
}
|
||||
|
||||
static void sendFuelLevel(void)
|
||||
|
@ -437,9 +439,9 @@ static void sendFuelLevel(void)
|
|||
sendDataHead(ID_FUEL_LEVEL);
|
||||
|
||||
if (batteryConfig()->batteryCapacity > 0) {
|
||||
serialize16((uint16_t)calculateBatteryPercentage());
|
||||
serialize16((uint16_t)calculateBatteryPercentageRemaining());
|
||||
} else {
|
||||
serialize16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF));
|
||||
serialize16((uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -537,7 +539,7 @@ void handleFrSkyTelemetry(void)
|
|||
sendTemperature1();
|
||||
sendThrottleOrBatterySizeAsRpm();
|
||||
|
||||
if ((feature(FEATURE_VBAT) || feature(FEATURE_ESC_SENSOR)) && batteryCellCount > 0) {
|
||||
if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE && getBatteryCellCount() > 0) {
|
||||
sendVoltage();
|
||||
sendVoltageAmp();
|
||||
sendAmperage();
|
||||
|
|
|
@ -247,24 +247,24 @@ static inline void updateAlarmBatteryStatus(HOTT_EAM_MSG_t *hottEAMMessage)
|
|||
|
||||
static inline void hottEAMUpdateBattery(HOTT_EAM_MSG_t *hottEAMMessage)
|
||||
{
|
||||
hottEAMMessage->main_voltage_L = getVbat() & 0xFF;
|
||||
hottEAMMessage->main_voltage_H = getVbat() >> 8;
|
||||
hottEAMMessage->batt1_voltage_L = getVbat() & 0xFF;
|
||||
hottEAMMessage->batt1_voltage_H = getVbat() >> 8;
|
||||
hottEAMMessage->main_voltage_L = getBatteryVoltage() & 0xFF;
|
||||
hottEAMMessage->main_voltage_H = getBatteryVoltage() >> 8;
|
||||
hottEAMMessage->batt1_voltage_L = getBatteryVoltage() & 0xFF;
|
||||
hottEAMMessage->batt1_voltage_H = getBatteryVoltage() >> 8;
|
||||
|
||||
updateAlarmBatteryStatus(hottEAMMessage);
|
||||
}
|
||||
|
||||
static inline void hottEAMUpdateCurrentMeter(HOTT_EAM_MSG_t *hottEAMMessage)
|
||||
{
|
||||
int32_t amp = amperage / 10;
|
||||
int32_t amp = getAmperage() / 10;
|
||||
hottEAMMessage->current_L = amp & 0xFF;
|
||||
hottEAMMessage->current_H = amp >> 8;
|
||||
}
|
||||
|
||||
static inline void hottEAMUpdateBatteryDrawnCapacity(HOTT_EAM_MSG_t *hottEAMMessage)
|
||||
{
|
||||
int32_t mAh = mAhDrawn / 10;
|
||||
int32_t mAh = getMAhDrawn() / 10;
|
||||
hottEAMMessage->batt_cap_L = mAh & 0xFF;
|
||||
hottEAMMessage->batt_cap_H = mAh >> 8;
|
||||
}
|
||||
|
|
|
@ -125,9 +125,9 @@ static uint8_t dispatchMeasurementReply(ibusAddress_t address)
|
|||
|
||||
switch (sensorAddressTypeLookup[address - ibusBaseAddress]) {
|
||||
case IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE:
|
||||
value = getVbat() * 10;
|
||||
value = getBatteryVoltage() * 10;
|
||||
if (telemetryConfig()->report_cell_voltage) {
|
||||
value /= batteryCellCount;
|
||||
value /= getBatteryCellCount();
|
||||
}
|
||||
return sendIbusMeasurement(address, value);
|
||||
|
||||
|
|
|
@ -190,7 +190,7 @@ static void ltm_sframe(void)
|
|||
if (failsafeIsActive())
|
||||
lt_statemode |= 2;
|
||||
ltm_initialise_packet('S');
|
||||
ltm_serialise_16(getVbat() * 100); //vbat converted to mv
|
||||
ltm_serialise_16(getBatteryVoltage() * 100); //vbat converted to mv
|
||||
ltm_serialise_16(0); // current, not implemented
|
||||
ltm_serialise_8((uint8_t)((rssi * 254) / 1023)); // scaled RSSI (uchar)
|
||||
ltm_serialise_8(0); // no airspeed
|
||||
|
|
|
@ -223,11 +223,11 @@ void mavlinkSendSystemStatus(void)
|
|||
// load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
|
||||
0,
|
||||
// voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
|
||||
feature(FEATURE_VBAT) ? getVbat() * 100 : 0,
|
||||
(batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE) ? getBatteryVoltage() * 100 : 0,
|
||||
// current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
|
||||
feature(FEATURE_VBAT) ? amperage : -1,
|
||||
(batteryConfig()->currentMeterSource != CURRENT_METER_NONE) ? getAmperage() : -1,
|
||||
// battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
|
||||
feature(FEATURE_VBAT) ? calculateBatteryPercentage() : 100,
|
||||
(batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE) ? calculateBatteryPercentageRemaining() : 100,
|
||||
// drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
|
||||
0,
|
||||
// errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
|
||||
|
|
|
@ -618,20 +618,20 @@ void handleSmartPortTelemetry(void)
|
|||
break;
|
||||
#endif
|
||||
case FSSP_DATAID_VFAS :
|
||||
if (feature(FEATURE_VBAT) && batteryCellCount > 0) {
|
||||
if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE && getBatteryCellCount() > 0) {
|
||||
uint16_t vfasVoltage;
|
||||
if (telemetryConfig()->frsky_vfas_cell_voltage) {
|
||||
vfasVoltage = getVbat() / batteryCellCount;
|
||||
vfasVoltage = getBatteryVoltage() / getBatteryCellCount();
|
||||
} else {
|
||||
vfasVoltage = getVbat();
|
||||
vfasVoltage = getBatteryVoltage();
|
||||
}
|
||||
smartPortSendPackage(id, vfasVoltage * 10); // given in 0.1V, convert to volts
|
||||
smartPortHasRequest = 0;
|
||||
}
|
||||
break;
|
||||
case FSSP_DATAID_CURRENT :
|
||||
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_SENSOR)) {
|
||||
smartPortSendPackage(id, amperage / 10); // given in 10mA steps, unknown requested unit
|
||||
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
|
||||
smartPortSendPackage(id, getAmperage() / 10); // given in 10mA steps, unknown requested unit
|
||||
smartPortHasRequest = 0;
|
||||
}
|
||||
break;
|
||||
|
@ -643,8 +643,8 @@ void handleSmartPortTelemetry(void)
|
|||
}
|
||||
break;
|
||||
case FSSP_DATAID_FUEL :
|
||||
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_SENSOR)) {
|
||||
smartPortSendPackage(id, mAhDrawn); // given in mAh, unknown requested unit
|
||||
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
|
||||
smartPortSendPackage(id, getMAhDrawn()); // given in mAh, unknown requested unit
|
||||
smartPortHasRequest = 0;
|
||||
}
|
||||
break;
|
||||
|
@ -791,8 +791,8 @@ void handleSmartPortTelemetry(void)
|
|||
break;
|
||||
#endif
|
||||
case FSSP_DATAID_A4 :
|
||||
if (feature(FEATURE_VBAT) && batteryCellCount > 0) {
|
||||
smartPortSendPackage(id, getVbat() * 10 / batteryCellCount ); // given in 0.1V, convert to volts
|
||||
if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE && getBatteryCellCount() > 0) {
|
||||
smartPortSendPackage(id, getBatteryVoltage() * 10 / getBatteryCellCount()); // given in 0.1V, convert to volts
|
||||
smartPortHasRequest = 0;
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -161,7 +161,7 @@ void srxlFrameRpm(sbuf_t *dst)
|
|||
srxlSerialize8(dst, SRXL_FRAMETYPE_TELE_RPM);
|
||||
srxlSerialize8(dst, SRXL_FRAMETYPE_SID);
|
||||
srxlSerialize16(dst, 0xFFFF); // pulse leading edges
|
||||
srxlSerialize16(dst, getVbat() * 10); // vbat is in units of 0.1V
|
||||
srxlSerialize16(dst, getBatteryVoltage() * 10); // vbat is in units of 0.1V
|
||||
srxlSerialize16(dst, 0x7FFF); // temperature
|
||||
srxlSerialize8(dst, 0xFF); // dbmA
|
||||
srxlSerialize8(dst, 0xFF); // dbmB
|
||||
|
@ -200,9 +200,9 @@ void srxlFramePowerBox(sbuf_t *dst)
|
|||
{
|
||||
srxlSerialize8(dst, SRXL_FRAMETYPE_POWERBOX);
|
||||
srxlSerialize8(dst, SRXL_FRAMETYPE_SID);
|
||||
srxlSerialize16(dst, getVbat() * 10); // vbat is in units of 0.1V - vbat1
|
||||
srxlSerialize16(dst, getVbat() * 10); // vbat is in units of 0.1V - vbat2
|
||||
srxlSerialize16(dst, amperage / 10);
|
||||
srxlSerialize16(dst, getBatteryVoltage() * 10); // vbat is in units of 0.1V - vbat1
|
||||
srxlSerialize16(dst, getBatteryVoltage() * 10); // vbat is in units of 0.1V - vbat2
|
||||
srxlSerialize16(dst, getAmperage() / 10);
|
||||
srxlSerialize16(dst, 0xFFFF);
|
||||
|
||||
srxlSerialize16(dst, 0xFFFF); // spare
|
||||
|
|
|
@ -54,7 +54,10 @@ extern "C" {
|
|||
#include "telemetry/telemetry.h"
|
||||
|
||||
bool airMode;
|
||||
uint16_t vbat;
|
||||
|
||||
uint16_t testBatteryVoltage = 0;
|
||||
int32_t testAmperage = 0;
|
||||
|
||||
serialPort_t *telemetrySharedPort;
|
||||
PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
|
||||
PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
|
||||
|
@ -138,7 +141,7 @@ TEST(TelemetryCrsfTest, TestBattery)
|
|||
{
|
||||
uint8_t frame[CRSF_FRAME_SIZE_MAX];
|
||||
|
||||
vbat = 0; // 0.1V units
|
||||
testBatteryVoltage = 0; // 0.1V units
|
||||
int frameLen = getCrsfFrame(frame, CRSF_FRAME_BATTERY_SENSOR);
|
||||
EXPECT_EQ(CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
|
||||
EXPECT_EQ(CRSF_ADDRESS_BROADCAST, frame[0]); // address
|
||||
|
@ -154,8 +157,8 @@ TEST(TelemetryCrsfTest, TestBattery)
|
|||
EXPECT_EQ(67, remaining);
|
||||
EXPECT_EQ(crfsCrc(frame, frameLen), frame[11]);
|
||||
|
||||
vbat = 33; // 3.3V = 3300 mv
|
||||
amperage = 2960; // = 29.60A = 29600mA - amperage is in 0.01A steps
|
||||
testBatteryVoltage = 33; // 3.3V = 3300 mv
|
||||
testAmperage = 2960; // = 29.60A = 29600mA - amperage is in 0.01A steps
|
||||
batteryConfigMutable()->batteryCapacity = 1234;
|
||||
frameLen = getCrsfFrame(frame, CRSF_FRAME_BATTERY_SENSOR);
|
||||
voltage = frame[3] << 8 | frame[4]; // mV * 100
|
||||
|
@ -283,9 +286,6 @@ uint16_t GPS_altitude; // altitude in m
|
|||
uint16_t GPS_speed; // speed in 0.1m/s
|
||||
uint16_t GPS_ground_course = 0; // degrees * 10
|
||||
|
||||
int32_t amperage;
|
||||
int32_t mAhDrawn;
|
||||
|
||||
void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
|
||||
|
||||
uint32_t micros(void) {return 0;}
|
||||
|
@ -308,11 +308,23 @@ bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return true;}
|
|||
|
||||
portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e) {return PORTSHARING_NOT_SHARED;}
|
||||
|
||||
uint8_t batteryCapacityRemainingPercentage(void) {return 67;}
|
||||
uint8_t calculateBatteryCapacityRemainingPercentage(void) {return 67;}
|
||||
uint8_t calculateBatteryPercentage(void) {return 67;}
|
||||
batteryState_e getBatteryState(void) {return BATTERY_OK;}
|
||||
bool isAirmodeActive(void) {return airMode;}
|
||||
uint16_t getVbat(void) { return vbat; }
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
return testAmperage;
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltage(void) {
|
||||
return testBatteryVoltage;
|
||||
}
|
||||
|
||||
batteryState_e getBatteryState(void) {
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
uint8_t calculateBatteryPercentageRemaining(void) {
|
||||
return 67;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -51,6 +51,11 @@ extern "C" {
|
|||
#include "telemetry/hott.h"
|
||||
|
||||
PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
|
||||
|
||||
uint16_t testBatteryVoltage = 0;
|
||||
int32_t testAmperage = 0;
|
||||
int32_t testMAhDrawn = 0;
|
||||
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
|
@ -172,10 +177,7 @@ uint16_t GPS_speed; // speed in 0.1m/s
|
|||
uint16_t GPS_distanceToHome; // distance to home point in meters
|
||||
uint16_t GPS_altitude; // altitude in 0.1m
|
||||
int16_t GPS_directionToHome; // direction to home or hol point in degrees
|
||||
uint16_t vbat;
|
||||
|
||||
int32_t amperage;
|
||||
int32_t mAhDrawn;
|
||||
|
||||
uint32_t fixedMillis = 0;
|
||||
|
||||
|
@ -264,8 +266,17 @@ batteryState_e getBatteryState(void)
|
|||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
uint16_t getVbat(void)
|
||||
uint16_t getBatteryVoltage(void)
|
||||
{
|
||||
return vbat;
|
||||
return testBatteryVoltage;
|
||||
}
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
return testAmperage;
|
||||
}
|
||||
|
||||
int32_t getMAhDrawn(void) {
|
||||
return testMAhDrawn;
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -37,7 +37,7 @@ extern "C" {
|
|||
|
||||
|
||||
extern "C" {
|
||||
uint8_t batteryCellCount = 3;
|
||||
uint8_t testBatteryCellCount =3;
|
||||
int16_t rcCommand[4] = {0, 0, 0, 0};
|
||||
telemetryConfig_t telemetryConfig_System;
|
||||
}
|
||||
|
@ -62,6 +62,16 @@ typedef struct serialPortStub_s {
|
|||
} serialPortStub_t;
|
||||
|
||||
|
||||
static uint16_t testBatteryVoltage = 100;
|
||||
uint16_t getBatteryVoltage(void)
|
||||
{
|
||||
return testBatteryVoltage;
|
||||
}
|
||||
|
||||
uint8_t getBatteryCellCount(void) {
|
||||
return testBatteryCellCount;
|
||||
}
|
||||
|
||||
static serialPortStub_t serialWriteStub;
|
||||
static serialPortStub_t serialReadStub;
|
||||
|
||||
|
@ -367,7 +377,7 @@ TEST_F(IbusTelemteryProtocolUnitTest, Test_IbusRespondToGetMeasurementVbattZero)
|
|||
{
|
||||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0 volts
|
||||
vbat = 0;
|
||||
testBatteryVoltage = 0;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x00\x00\x58\xFF", 6);
|
||||
}
|
||||
|
||||
|
@ -377,14 +387,14 @@ TEST_F(IbusTelemteryProtocolUnitTest, Test_IbusRespondToGetMeasurementVbattCellV
|
|||
|
||||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
batteryCellCount = 3;
|
||||
vbat = 30;
|
||||
testBatteryCellCount =3;
|
||||
testBatteryVoltage = 30;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x64\x00\xf4\xFe", 6);
|
||||
|
||||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
batteryCellCount = 1;
|
||||
vbat = 10;
|
||||
testBatteryCellCount =1;
|
||||
testBatteryVoltage = 10;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x64\x00\xf4\xFe", 6);
|
||||
}
|
||||
|
||||
|
@ -394,14 +404,14 @@ TEST_F(IbusTelemteryProtocolUnitTest, Test_IbusRespondToGetMeasurementVbattPackV
|
|||
|
||||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
batteryCellCount = 3;
|
||||
vbat = 10;
|
||||
testBatteryCellCount =3;
|
||||
testBatteryVoltage = 10;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x64\x00\xf4\xFe", 6);
|
||||
|
||||
//Given ibus command: Sensor at address 1, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
batteryCellCount = 1;
|
||||
vbat = 10;
|
||||
testBatteryCellCount =1;
|
||||
testBatteryVoltage = 10;
|
||||
checkResponseToCommand("\x04\xA1\x5a\xff", 4, "\x06\xA1\x64\x00\xf4\xFe", 6);
|
||||
}
|
||||
|
||||
|
@ -488,8 +498,8 @@ TEST_F(IbusTelemteryProtocolUnitTestDaisyChained, Test_IbusRespondToGetMeasureme
|
|||
{
|
||||
//Given ibus command: Sensor at address 3, please send your measurement
|
||||
//then we respond with: I'm reading 0.1 volts
|
||||
batteryCellCount = 1;
|
||||
vbat = 10;
|
||||
testBatteryCellCount = 1;
|
||||
testBatteryVoltage = 10;
|
||||
checkResponseToCommand("\x04\xA3\x58\xff", 4, "\x06\xA3\x64\x00\xf2\xfe", 6);
|
||||
|
||||
//Given ibus command: Sensor at address 4, please send your measurement
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue