Merge remote-tracking branch 'bf/master' into FishDrone

This commit is contained in:
linjieqiang 2016-12-12 14:49:52 +08:00
commit baadf03117
261 changed files with 3667 additions and 2825 deletions

View File

@ -506,6 +506,7 @@ COMMON_SRC = \
drivers/serial.c \
drivers/serial_uart.c \
drivers/sound_beeper.c \
drivers/stack_check.c \
drivers/system.c \
drivers/timer.c \
fc/config.c \
@ -756,7 +757,11 @@ ifeq ($(DEBUG),GDB)
OPTIMIZE = -O0
LTO_FLAGS = $(OPTIMIZE)
else
ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
OPTIMIZE = -Os
else
OPTIMIZE = -Ofast
endif
LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
endif
@ -826,6 +831,9 @@ CLEAN_ARTIFACTS := $(TARGET_BIN)
CLEAN_ARTIFACTS += $(TARGET_HEX)
CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
# Make sure build date and revision is updated on every incremental build
$(OBJECT_DIR)/$(TARGET)/build/version.o : $(TARGET_SRC)
# List of buildable ELF files and their object dependencies.
# It would be nice to compute these lists, but that seems to be just beyond make.

View File

@ -18,6 +18,7 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <math.h>
#include "platform.h"
@ -349,7 +350,7 @@ bool blackboxMayEditConfig()
}
static bool blackboxIsOnlyLoggingIntraframes() {
return masterConfig.blackboxConfig.rate_num == 1 && masterConfig.blackboxConfig.rate_denom == 32;
return blackboxConfig()->rate_num == 1 && blackboxConfig()->rate_denom == 32;
}
static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
@ -369,7 +370,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
return masterConfig.mixerConfig.mixerMode == MIXER_TRI || masterConfig.mixerConfig.mixerMode == MIXER_CUSTOM_TRI;
return mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI;
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
@ -394,7 +395,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
return feature(FEATURE_VBAT);
case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC:
return feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC;
return feature(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC;
case FLIGHT_LOG_FIELD_CONDITION_SONAR:
#ifdef SONAR
@ -404,10 +405,10 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
#endif
case FLIGHT_LOG_FIELD_CONDITION_RSSI:
return masterConfig.rxConfig.rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
return rxConfig()->rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
return masterConfig.blackboxConfig.rate_num < masterConfig.blackboxConfig.rate_denom;
return blackboxConfig()->rate_num < blackboxConfig()->rate_denom;
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
return false;
@ -495,7 +496,7 @@ static void writeIntraframe(void)
* Write the throttle separately from the rest of the RC data so we can apply a predictor to it.
* Throttle lies in range [minthrottle..maxthrottle]:
*/
blackboxWriteUnsignedVB(blackboxCurrent->rcCommand[THROTTLE] - masterConfig.motorConfig.minthrottle);
blackboxWriteUnsignedVB(blackboxCurrent->rcCommand[THROTTLE] - motorConfig()->minthrottle);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
/*
@ -539,7 +540,7 @@ static void writeIntraframe(void)
blackboxWriteSigned16VBArray(blackboxCurrent->debug, 4);
//Motors can be below minthrottle when disarmed, but that doesn't happen much
blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - masterConfig.motorConfig.minthrottle);
blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - motorConfig()->minthrottle);
//Motors tend to be similar to each other so use the first motor's value as a predictor of the others
for (x = 1; x < motorCount; x++) {
@ -758,22 +759,22 @@ static void validateBlackboxConfig()
{
int div;
if (masterConfig.blackboxConfig.rate_num == 0 || masterConfig.blackboxConfig.rate_denom == 0
|| masterConfig.blackboxConfig.rate_num >= masterConfig.blackboxConfig.rate_denom) {
masterConfig.blackboxConfig.rate_num = 1;
masterConfig.blackboxConfig.rate_denom = 1;
if (blackboxConfig()->rate_num == 0 || blackboxConfig()->rate_denom == 0
|| blackboxConfig()->rate_num >= blackboxConfig()->rate_denom) {
blackboxConfig()->rate_num = 1;
blackboxConfig()->rate_denom = 1;
} else {
/* Reduce the fraction the user entered as much as possible (makes the recorded/skipped frame pattern repeat
* itself more frequently)
*/
div = gcd(masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
div = gcd(blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
masterConfig.blackboxConfig.rate_num /= div;
masterConfig.blackboxConfig.rate_denom /= div;
blackboxConfig()->rate_num /= div;
blackboxConfig()->rate_denom /= div;
}
// If we've chosen an unsupported device, change the device to serial
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
#endif
@ -785,7 +786,7 @@ static void validateBlackboxConfig()
break;
default:
masterConfig.blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
blackboxConfig()->device = BLACKBOX_DEVICE_SERIAL;
}
}
@ -867,7 +868,7 @@ bool startedLoggingInTestMode = false;
void startInTestMode(void)
{
if(!startedLoggingInTestMode) {
if (masterConfig.blackboxConfig.device == BLACKBOX_DEVICE_SERIAL) {
if (blackboxConfig()->device == BLACKBOX_DEVICE_SERIAL) {
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
if (sharedBlackboxAndMspPort) {
return; // When in test mode, we cannot share the MSP and serial logger port!
@ -898,13 +899,13 @@ bool inMotorTestMode(void) {
static uint32_t resetTime = 0;
uint16_t inactiveMotorCommand;
if (feature(FEATURE_3D)) {
inactiveMotorCommand = masterConfig.flight3DConfig.neutral3d;
inactiveMotorCommand = flight3DConfig()->neutral3d;
#ifdef USE_DSHOT
} else if (isMotorProtocolDshot()) {
inactiveMotorCommand = DSHOT_DISARM_COMMAND;
#endif
} else {
inactiveMotorCommand = masterConfig.motorConfig.mincommand;
inactiveMotorCommand = motorConfig()->mincommand;
}
int i;
@ -937,7 +938,7 @@ static void writeGPSHomeFrame()
gpsHistory.GPS_home[1] = GPS_home[1];
}
static void writeGPSFrame(uint32_t currentTime)
static void writeGPSFrame(timeUs_t currentTimeUs)
{
blackboxWrite('G');
@ -949,7 +950,7 @@ static void writeGPSFrame(uint32_t currentTime)
*/
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME)) {
// Predict the time of the last frame in the main log
blackboxWriteUnsignedVB(currentTime - blackboxHistory[1]->time);
blackboxWriteUnsignedVB(currentTimeUs - blackboxHistory[1]->time);
}
blackboxWriteUnsignedVB(GPS_numSat);
@ -968,12 +969,12 @@ static void writeGPSFrame(uint32_t currentTime)
/**
* Fill the current state of the blackbox using values read from the flight controller
*/
static void loadMainState(uint32_t currentTime)
static void loadMainState(timeUs_t currentTimeUs)
{
blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
int i;
blackboxCurrent->time = currentTime;
blackboxCurrent->time = currentTimeUs;
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->axisPID_P[i] = axisPID_P[i];
@ -990,11 +991,11 @@ static void loadMainState(uint32_t currentTime)
}
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->gyroADC[i] = gyroADC[i];
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
}
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->accSmooth[i] = accSmooth[i];
blackboxCurrent->accSmooth[i] = acc.accSmooth[i];
}
for (i = 0; i < 4; i++) {
@ -1010,12 +1011,12 @@ static void loadMainState(uint32_t currentTime)
#ifdef MAG
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->magADC[i] = magADC[i];
blackboxCurrent->magADC[i] = mag.magADC[i];
}
#endif
#ifdef BARO
blackboxCurrent->BaroAlt = BaroAlt;
blackboxCurrent->BaroAlt = baro.BaroAlt;
#endif
#ifdef SONAR
@ -1172,34 +1173,34 @@ static bool blackboxWriteSysinfo()
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", masterConfig.name);
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.motorConfig.minthrottle);
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.motorConfig.maxthrottle);
BLACKBOX_PRINT_HEADER_LINE("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
BLACKBOX_PRINT_HEADER_LINE("acc_1G:%u", acc.acc_1G);
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(gyro.dev.scale));
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", masterConfig.batteryConfig.vbatscale);
blackboxPrintfHeaderLine("vbatscale:%u", batteryConfig()->vbatscale);
} else {
xmitState.headerIndex += 2; // Skip the next two vbat fields too
}
);
BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage,
masterConfig.batteryConfig.vbatwarningcellvoltage,
masterConfig.batteryConfig.vbatmaxcellvoltage);
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_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", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale);
blackboxPrintfHeaderLine("currentMeter:%d,%d", batteryConfig()->currentMeterOffset, batteryConfig()->currentMeterScale);
}
);
BLACKBOX_PRINT_HEADER_LINE("looptime:%d", gyro.targetLooptime);
BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom:%d", masterConfig.gyroConfig.gyro_sync_denom);
BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom:%d", gyroConfig()->gyro_sync_denom);
BLACKBOX_PRINT_HEADER_LINE("pid_process_denom:%d", masterConfig.pid_process_denom);
BLACKBOX_PRINT_HEADER_LINE("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcRate8);
BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8);
@ -1260,27 +1261,27 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rateAccelLimit);
// End of Betaflight controller parameters
BLACKBOX_PRINT_HEADER_LINE("deadband:%d", masterConfig.rcControlsConfig.deadband);
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyroConfig.gyro_lpf);
BLACKBOX_PRINT_HEADER_LINE("gyro_soft_type:%d", masterConfig.gyroConfig.gyro_soft_lpf_type);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", masterConfig.gyroConfig.gyro_soft_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d,%d", masterConfig.gyroConfig.gyro_soft_notch_hz_1,
masterConfig.gyroConfig.gyro_soft_notch_hz_2);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d,%d", masterConfig.gyroConfig.gyro_soft_notch_cutoff_1,
masterConfig.gyroConfig.gyro_soft_notch_cutoff_2);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.sensorSelectionConfig.acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.sensorSelectionConfig.baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.sensorSelectionConfig.mag_hardware);
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.armingConfig.gyro_cal_on_first_arm);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation:%d", masterConfig.rxConfig.rcInterpolation);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", masterConfig.rxConfig.rcInterpolationInterval);
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold);
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider:%d", masterConfig.rxConfig.serialrx_provider);
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", masterConfig.motorConfig.useUnsyncedPwm);
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", masterConfig.motorConfig.motorPwmProtocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", masterConfig.motorConfig.motorPwmRate);
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,
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()->useUnsyncedPwm);
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", motorConfig()->motorPwmProtocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", motorConfig()->motorPwmRate);
BLACKBOX_PRINT_HEADER_LINE("debug_mode:%d", masterConfig.debug_mode);
BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures);
@ -1376,10 +1377,10 @@ static void blackboxCheckAndLogFlightMode()
*/
static bool blackboxShouldLogPFrame(uint32_t pFrameIndex)
{
/* Adding a magic shift of "masterConfig.blackboxConfig.rate_num - 1" in here creates a better spread of
/* Adding a magic shift of "blackboxConfig()->rate_num - 1" in here creates a better spread of
* recorded / skipped frames when the I frame's position is considered:
*/
return (pFrameIndex + masterConfig.blackboxConfig.rate_num - 1) % masterConfig.blackboxConfig.rate_denom < masterConfig.blackboxConfig.rate_num;
return (pFrameIndex + blackboxConfig()->rate_num - 1) % blackboxConfig()->rate_denom < blackboxConfig()->rate_num;
}
static bool blackboxShouldLogIFrame() {
@ -1400,7 +1401,7 @@ static void blackboxAdvanceIterationTimers()
}
// Called once every FC loop in order to log the current state
static void blackboxLogIteration(uint32_t currentTime)
static void blackboxLogIteration(timeUs_t currentTimeUs)
{
// Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames
if (blackboxShouldLogIFrame()) {
@ -1410,7 +1411,7 @@ static void blackboxLogIteration(uint32_t currentTime)
*/
writeSlowFrameIfNeeded(blackboxIsOnlyLoggingIntraframes());
loadMainState(currentTime);
loadMainState(currentTimeUs);
writeIntraframe();
} else {
blackboxCheckAndLogArmingBeep();
@ -1423,7 +1424,7 @@ static void blackboxLogIteration(uint32_t currentTime)
*/
writeSlowFrameIfNeeded(true);
loadMainState(currentTime);
loadMainState(currentTimeUs);
writeInterframe();
}
#ifdef GPS
@ -1439,11 +1440,11 @@ static void blackboxLogIteration(uint32_t currentTime)
|| (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) {
writeGPSHomeFrame();
writeGPSFrame(currentTime);
writeGPSFrame(currentTimeUs);
} else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0]
|| GPS_coord[1] != gpsHistory.GPS_coord[1]) {
//We could check for velocity changes as well but I doubt it changes independent of position
writeGPSFrame(currentTime);
writeGPSFrame(currentTimeUs);
}
}
#endif
@ -1456,7 +1457,7 @@ static void blackboxLogIteration(uint32_t currentTime)
/**
* Call each flight loop iteration to perform blackbox logging.
*/
void handleBlackbox(uint32_t currentTime)
void handleBlackbox(timeUs_t currentTimeUs)
{
int i;
@ -1548,12 +1549,12 @@ void handleBlackbox(uint32_t currentTime)
flightLogEvent_loggingResume_t resume;
resume.logIteration = blackboxIteration;
resume.currentTime = currentTime;
resume.currentTime = currentTimeUs;
blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume);
blackboxSetState(BLACKBOX_STATE_RUNNING);
blackboxLogIteration(currentTime);
blackboxLogIteration(currentTimeUs);
}
// Keep the logging timers ticking so our log iteration continues to advance
@ -1565,7 +1566,7 @@ void handleBlackbox(uint32_t currentTime)
if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX) && !startedLoggingInTestMode) {
blackboxSetState(BLACKBOX_STATE_PAUSED);
} else {
blackboxLogIteration(currentTime);
blackboxLogIteration(currentTimeUs);
}
blackboxAdvanceIterationTimers();
@ -1595,7 +1596,7 @@ void handleBlackbox(uint32_t currentTime)
if (startedLoggingInTestMode) startedLoggingInTestMode = false;
} else { // Only log in test mode if there is room!
if(masterConfig.blackboxConfig.on_motor_test) {
if(blackboxConfig()->on_motor_test) {
// Handle Motor Test Mode
if(inMotorTestMode()) {
if(blackboxState==BLACKBOX_STATE_STOPPED)

View File

@ -19,6 +19,8 @@
#include "blackbox/blackbox_fielddefs.h"
#include "common/time.h"
typedef struct blackboxConfig_s {
uint8_t rate_num;
uint8_t rate_denom;
@ -29,7 +31,7 @@ typedef struct blackboxConfig_s {
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data);
void initBlackbox(void);
void handleBlackbox(uint32_t currentTime);
void handleBlackbox(timeUs_t currentTimeUs);
void startBlackbox(void);
void finishBlackbox(void);

View File

@ -65,7 +65,7 @@ static struct {
void blackboxWrite(uint8_t value)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
flashfsWriteByte(value); // Write byte asynchronously
@ -137,7 +137,7 @@ int blackboxPrint(const char *s)
int length;
const uint8_t *pos;
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
@ -479,7 +479,7 @@ void blackboxWriteFloat(float value)
*/
void blackboxDeviceFlush(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_FLASHFS
/*
* This is our only output device which requires us to call flush() in order for it to write anything. The other
@ -502,7 +502,7 @@ void blackboxDeviceFlush(void)
*/
bool blackboxDeviceFlushForce(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
// Nothing to speed up flushing on serial, as serial is continuously being drained out of its buffer
return isSerialTransmitBufferEmpty(blackboxPort);
@ -530,7 +530,7 @@ bool blackboxDeviceFlushForce(void)
*/
bool blackboxDeviceOpen(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
{
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX);
@ -604,7 +604,7 @@ bool blackboxDeviceOpen(void)
*/
void blackboxDeviceClose(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
// Since the serial port could be shared with other processes, we have to give it back here
closeSerialPort(blackboxPort);
@ -748,7 +748,7 @@ static bool blackboxSDCardBeginLog()
*/
bool blackboxDeviceBeginLog(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
return blackboxSDCardBeginLog();
@ -772,7 +772,7 @@ bool blackboxDeviceEndLog(bool retainLog)
(void) retainLog;
#endif
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
// Keep retrying until the close operation queues
@ -794,7 +794,7 @@ bool blackboxDeviceEndLog(bool retainLog)
bool isBlackboxDeviceFull(void)
{
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
return false;
@ -821,7 +821,7 @@ void blackboxReplenishHeaderBudget()
{
int32_t freeSpace;
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
freeSpace = serialTxBytesFree(blackboxPort);
break;
@ -867,7 +867,7 @@ blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
}
// Handle failure:
switch (masterConfig.blackboxConfig.device) {
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_SERIAL:
/*
* One byte of the tx buffer isn't available for user data (due to its circular list implementation),

View File

@ -27,7 +27,6 @@ typedef enum BlackboxDevice {
BLACKBOX_DEVICE_SDCARD = 2,
#endif
BLACKBOX_DEVICE_END
} BlackboxDevice;
typedef enum {

View File

@ -60,5 +60,7 @@ typedef enum {
DEBUG_DTERM_FILTER,
DEBUG_ANGLERATE,
DEBUG_ESC_TELEMETRY,
DEBUG_SCHEDULER,
DEBUG_STACK,
DEBUG_COUNT
} debugType_e;

View File

@ -897,16 +897,16 @@ static void cmsUpdate(uint32_t currentTimeUs)
lastCalledMs = currentTimeMs;
}
void cmsHandler(uint32_t currentTime)
void cmsHandler(timeUs_t currentTimeUs)
{
if (cmsDeviceCount < 0)
return;
static uint32_t lastCalled = 0;
static timeUs_t lastCalledUs = 0;
if (currentTime >= lastCalled + CMS_UPDATE_INTERVAL_US) {
lastCalled = currentTime;
cmsUpdate(currentTime);
if (currentTimeUs >= lastCalledUs + CMS_UPDATE_INTERVAL_US) {
lastCalledUs = currentTimeUs;
cmsUpdate(currentTimeUs);
}
}

View File

@ -2,12 +2,14 @@
#include "drivers/display.h"
#include "common/time.h"
// Device management
bool cmsDisplayPortRegister(displayPort_t *pDisplay);
// For main.c and scheduler
void cmsInit(void);
void cmsHandler(uint32_t currentTime);
void cmsHandler(timeUs_t currentTimeUs);
long cmsMenuChange(displayPort_t *pPort, const void *ptr);
long cmsMenuExit(displayPort_t *pPort, const void *ptr);

View File

@ -90,7 +90,7 @@ static OSD_Entry cmsx_menuBlackboxEntries[] =
{
{ "-- BLACKBOX --", OME_Label, NULL, NULL, 0},
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureBlackbox, 0 },
{ "RATE DENOM", OME_UINT8, NULL, &(OSD_UINT8_t){ &masterConfig.blackboxConfig.rate_denom,1,32,1 }, 0 },
{ "RATE DENOM", OME_UINT8, NULL, &(OSD_UINT8_t){ &blackboxConfig()->rate_denom,1,32,1 }, 0 },
#ifdef USE_FLASHFS
{ "ERASE FLASH", OME_Funcall, cmsx_EraseFlash, NULL, 0 },

View File

@ -130,6 +130,7 @@ static long cmsx_PidWriteback(const OSD_Entry *self)
masterConfig.profile[profileIndex].pidProfile.I8[i] = tempPid[i][1];
masterConfig.profile[profileIndex].pidProfile.D8[i] = tempPid[i][2];
}
pidInitConfig(&currentProfile->pidProfile);
return 0;
}
@ -248,6 +249,7 @@ static long cmsx_profileOtherOnExit(const OSD_Entry *self)
masterConfig.profile[profileIndex].pidProfile.dtermSetpointWeight = cmsx_dtermSetpointWeight;
masterConfig.profile[profileIndex].pidProfile.setpointRelaxRatio = cmsx_setpointRelaxRatio;
pidInitConfig(&currentProfile->pidProfile);
masterConfig.profile[profileIndex].pidProfile.P8[PIDLEVEL] = cmsx_angleStrength;
masterConfig.profile[profileIndex].pidProfile.I8[PIDLEVEL] = cmsx_horizonStrength;
@ -282,11 +284,11 @@ static OSD_Entry cmsx_menuFilterGlobalEntries[] =
{
{ "-- FILTER GLB --", OME_Label, NULL, NULL, 0 },
{ "GYRO LPF", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.gyroConfig.gyro_soft_lpf_hz, 0, 255, 1 }, 0 },
{ "GYRO NF1", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyroConfig.gyro_soft_notch_hz_1, 0, 500, 1 }, 0 },
{ "GYRO NF1C", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyroConfig.gyro_soft_notch_cutoff_1, 0, 500, 1 }, 0 },
{ "GYRO NF2", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyroConfig.gyro_soft_notch_hz_2, 0, 500, 1 }, 0 },
{ "GYRO NF2C", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyroConfig.gyro_soft_notch_cutoff_2, 0, 500, 1 }, 0 },
{ "GYRO LPF", OME_UINT8, NULL, &(OSD_UINT8_t) { &gyroConfig()->gyro_soft_lpf_hz, 0, 255, 1 }, 0 },
{ "GYRO NF1", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig()->gyro_soft_notch_hz_1, 0, 500, 1 }, 0 },
{ "GYRO NF1C", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig()->gyro_soft_notch_cutoff_1, 0, 500, 1 }, 0 },
{ "GYRO NF2", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig()->gyro_soft_notch_hz_2, 0, 500, 1 }, 0 },
{ "GYRO NF2C", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig()->gyro_soft_notch_cutoff_2, 0, 500, 1 }, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }

View File

@ -83,9 +83,9 @@ static OSD_Entry menuMiscEntries[]=
{
{ "-- MISC --", OME_Label, NULL, NULL, 0 },
{ "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &masterConfig.motorConfig.minthrottle, 1000, 2000, 1 }, 0 },
{ "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.batteryConfig.vbatscale, 1, 250, 1 }, 0 },
{ "VBAT CLMAX", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50, 1 }, 0 },
{ "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &motorConfig()->minthrottle, 1000, 2000, 1 }, 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 },
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview, 0},
{ "BACK", OME_Back, NULL, NULL, 0},

View File

@ -33,10 +33,10 @@
#if defined(OSD) && defined(CMS)
OSD_UINT8_t entryAlarmRssi = {&masterConfig.osdProfile.rssi_alarm, 5, 90, 5};
OSD_UINT16_t entryAlarmCapacity = {&masterConfig.osdProfile.cap_alarm, 50, 30000, 50};
OSD_UINT16_t enryAlarmFlyTime = {&masterConfig.osdProfile.time_alarm, 1, 200, 1};
OSD_UINT16_t entryAlarmAltitude = {&masterConfig.osdProfile.alt_alarm, 1, 200, 1};
OSD_UINT8_t entryAlarmRssi = {&osdProfile()->rssi_alarm, 5, 90, 5};
OSD_UINT16_t entryAlarmCapacity = {&osdProfile()->cap_alarm, 50, 30000, 50};
OSD_UINT16_t enryAlarmFlyTime = {&osdProfile()->time_alarm, 1, 200, 1};
OSD_UINT16_t entryAlarmAltitude = {&osdProfile()->alt_alarm, 1, 200, 1};
OSD_Entry cmsx_menuAlarmsEntries[] =
{
@ -61,25 +61,25 @@ CMS_Menu cmsx_menuAlarms = {
OSD_Entry menuOsdActiveElemsEntries[] =
{
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], 0},
{"MAIN BATTERY", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"HORIZON", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], 0},
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], 0},
{"UPTIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ONTIME], 0},
{"FLY TIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYTIME], 0},
{"FLY MODE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], 0},
{"NAME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], 0},
{"THROTTLE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], 0},
{"RSSI", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_RSSI_VALUE], 0},
{"MAIN BATTERY", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"HORIZON", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ARTIFICIAL_HORIZON], 0},
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_HORIZON_SIDEBARS], 0},
{"UPTIME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ONTIME], 0},
{"FLY TIME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_FLYTIME], 0},
{"FLY MODE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_FLYMODE], 0},
{"NAME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_CRAFT_NAME], 0},
{"THROTTLE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_THROTTLE_POS], 0},
#ifdef VTX
{"VTX CHAN", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL]},
{"VTX CHAN", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_VTX_CHANNEL]},
#endif // VTX
{"CURRENT (A)", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], 0},
{"USED MAH", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], 0},
{"CURRENT (A)", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_CURRENT_DRAW], 0},
{"USED MAH", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_MAH_DRAWN], 0},
#ifdef GPS
{"GPS SPEED", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], 0},
{"GPS SATS.", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], 0},
{"GPS SPEED", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_GPS_SPEED], 0},
{"GPS SATS.", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_GPS_SATS], 0},
#endif // GPS
{"ALTITUDE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], 0},
{"ALTITUDE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ALTITUDE], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};

View File

@ -36,7 +36,7 @@ typedef enum {
typedef enum {
AI_ROLL = 0,
AI_PITCH,
AI_PITCH
} angle_index_t;
#define ANGLE_INDEX_COUNT 2

View File

@ -15,6 +15,8 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef STM32F10X
#define MAX_FIR_DENOISE_WINDOW_SIZE 60
#else

37
src/main/common/time.h Normal file
View File

@ -0,0 +1,37 @@
/*
* 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 <stdint.h>
#include "platform.h"
// time difference, 32 bits always sufficient
typedef int32_t timeDelta_t;
// millisecond time
typedef uint32_t timeMs_t ;
// microsecond time
#ifdef USE_64BIT_TIME
typedef uint64_t timeUs_t;
#define TIMEUS_MAX UINT64_MAX
#else
typedef uint32_t timeUs_t;
#define TIMEUS_MAX UINT32_MAX
#endif
static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); }

View File

@ -31,9 +31,9 @@ void uli2a(unsigned long int num, unsigned int base, int uc, char *bf)
while (d != 0) {
int dgt = num / d;
*bf++ = dgt + (dgt < 10 ? '0' : (uc ? 'A' : 'a') - 10);
*bf++ = dgt + (dgt < 10 ? '0' : (uc ? 'A' : 'a') - 10);
// Next digit
// Next digit
num %= d;
d /= base;
}
@ -60,9 +60,9 @@ void ui2a(unsigned int num, unsigned int base, int uc, char *bf)
while (d != 0) {
int dgt = num / d;
*bf++ = dgt + (dgt < 10 ? '0' : (uc ? 'A' : 'a') - 10);
*bf++ = dgt + (dgt < 10 ? '0' : (uc ? 'A' : 'a') - 10);
// Next digit
// Next digit
num %= d;
d /= base;
}

View File

@ -17,7 +17,7 @@
#pragma once
#define EEPROM_CONF_VERSION 146
#define EEPROM_CONF_VERSION 147
void initEEPROM(void);
void writeEEPROM();

View File

@ -61,6 +61,41 @@
#include "sensors/battery.h"
#include "sensors/compass.h"
#define motorConfig(x) (&masterConfig.motorConfig)
#define flight3DConfig(x) (&masterConfig.flight3DConfig)
#define servoConfig(x) (&masterConfig.servoConfig)
#define servoMixerConfig(x) (&masterConfig.servoMixerConfig)
#define gimbalConfig(x) (&masterConfig.gimbalConfig)
#define boardAlignment(x) (&masterConfig.boardAlignment)
#define imuConfig(x) (&masterConfig.imuConfig)
#define gyroConfig(x) (&masterConfig.gyroConfig)
#define compassConfig(x) (&masterConfig.compassConfig)
#define accelerometerConfig(x) (&masterConfig.accelerometerConfig)
#define barometerConfig(x) (&masterConfig.barometerConfig)
#define throttleCorrectionConfig(x) (&masterConfig.throttleCorrectionConfig)
#define batteryConfig(x) (&masterConfig.batteryConfig)
#define rcControlsConfig(x) (&masterConfig.rcControlsConfig)
#define gpsProfile(x) (&masterConfig.gpsProfile)
#define gpsConfig(x) (&masterConfig.gpsConfig)
#define rxConfig(x) (&masterConfig.rxConfig)
#define armingConfig(x) (&masterConfig.armingConfig)
#define mixerConfig(x) (&masterConfig.mixerConfig)
#define airplaneConfig(x) (&masterConfig.airplaneConfig)
#define failsafeConfig(x) (&masterConfig.failsafeConfig)
#define serialConfig(x) (&masterConfig.serialConfig)
#define telemetryConfig(x) (&masterConfig.telemetryConfig)
#define ppmConfig(x) (&masterConfig.ppmConfig)
#define pwmConfig(x) (&masterConfig.pwmConfig)
#define adcConfig(x) (&masterConfig.adcConfig)
#define beeperConfig(x) (&masterConfig.beeperConfig)
#define sonarConfig(x) (&masterConfig.sonarConfig)
#define ledStripConfig(x) (&masterConfig.ledStripConfig)
#define osdProfile(x) (&masterConfig.osdProfile)
#define vcdProfile(x) (&masterConfig.vcdProfile)
#define sdcardConfig(x) (&masterConfig.sdcardConfig)
#define blackboxConfig(x) (&masterConfig.blackboxConfig)
// System-wide
typedef struct master_s {
uint8_t version;
@ -84,16 +119,12 @@ typedef struct master_s {
gimbalConfig_t gimbalConfig;
#endif
// global sensor-related stuff
sensorSelectionConfig_t sensorSelectionConfig;
sensorAlignmentConfig_t sensorAlignmentConfig;
boardAlignment_t boardAlignment;
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes.
imuConfig_t imuConfig;
uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
@ -102,15 +133,12 @@ typedef struct master_s {
gyroConfig_t gyroConfig;
compassConfig_t compassConfig;
rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
accelerometerConfig_t accelerometerConfig;
uint16_t acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
accDeadband_t accDeadband;
barometerConfig_t barometerConfig;
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
throttleCorrectionConfig_t throttleCorrectionConfig;
batteryConfig_t batteryConfig;
// Radio/ESC-related configuration
@ -121,9 +149,6 @@ typedef struct master_s {
gpsConfig_t gpsConfig;
#endif
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
sensorTrims_t sensorTrims;
rxConfig_t rxConfig;
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
@ -140,7 +165,7 @@ typedef struct master_s {
#ifdef USE_PPM
ppmConfig_t ppmConfig;
#endif
#ifdef USE_PWM
pwmConfig_t pwmConfig;
#endif
@ -177,7 +202,7 @@ typedef struct master_s {
#ifdef USE_MAX7456
vcdProfile_t vcdProfile;
#endif
#ifdef USE_SDCARD
sdcardConfig_t sdcardConfig;
#endif

View File

@ -22,7 +22,7 @@ typedef uint16_t pgn_t;
// parameter group registry flags
typedef enum {
PGRF_NONE = 0,
PGRF_CLASSIFICATON_BIT = (1 << 0),
PGRF_CLASSIFICATON_BIT = (1 << 0)
} pgRegistryFlags_e;
typedef enum {
@ -30,7 +30,7 @@ typedef enum {
PGR_PGN_VERSION_MASK = 0xf000,
PGR_SIZE_MASK = 0x0fff,
PGR_SIZE_SYSTEM_FLAG = 0x0000, // documentary
PGR_SIZE_PROFILE_FLAG = 0x8000, // start using flags from the top bit down
PGR_SIZE_PROFILE_FLAG = 0x8000 // start using flags from the top bit down
} pgRegistryInternal_e;
// function that resets a single parameter group instance

View File

@ -30,54 +30,54 @@
#define PG_CONTROL_RATE_PROFILES 12 // struct OK, needs to be split out of rc_controls.h into rate_profile.h
#define PG_SERIAL_CONFIG 13 // struct OK
#define PG_PID_PROFILE 14 // struct OK, CF differences
#define PG_GTUNE_CONFIG 15
#define PG_ARMING_CONFIG 16
#define PG_TRANSPONDER_CONFIG 17
#define PG_SYSTEM_CONFIG 18
#define PG_FEATURE_CONFIG 19
#define PG_MIXER_CONFIG 20
#define PG_SERVO_MIXER 21
#define PG_IMU_CONFIG 22
#define PG_PROFILE_SELECTION 23
#define PG_RX_CONFIG 24
#define PG_RC_CONTROLS_CONFIG 25
#define PG_MOTOR_3D_CONFIG 26
#define PG_LED_STRIP_CONFIG 27
#define PG_COLOR_CONFIG 28
#define PG_AIRPLANE_ALT_HOLD_CONFIG 29
#define PG_GPS_CONFIG 30
#define PG_TELEMETRY_CONFIG 31
#define PG_FRSKY_TELEMETRY_CONFIG 32
#define PG_HOTT_TELEMETRY_CONFIG 33
#define PG_NAVIGATION_CONFIG 34
#define PG_ACCELEROMETER_CONFIG 35
#define PG_RATE_PROFILE_SELECTION 36
#define PG_ADJUSTMENT_PROFILE 37
#define PG_BAROMETER_CONFIG 38
#define PG_GTUNE_CONFIG 15 // is GTUNE still being used?
#define PG_ARMING_CONFIG 16 // structs OK, CF naming differences
#define PG_TRANSPONDER_CONFIG 17 // struct OK
#define PG_SYSTEM_CONFIG 18 // just has i2c_highspeed
#define PG_FEATURE_CONFIG 19 // just has enabledFeatures
#define PG_MIXER_CONFIG 20 // Cleanflight has single struct mixerConfig_t, betaflight has mixerConfig_t and servoMixerConfig_t
#define PG_SERVO_MIXER 21 // Cleanflight has servoParam_t for each servo, betaflight has single servoParam_t
#define PG_IMU_CONFIG 22 // Cleanflight has imuConfig_t, betaflight has imuRuntimeConfig_t with additional parameters
#define PG_PROFILE_SELECTION 23 // just contains current_profile_index
#define PG_RX_CONFIG 24 // betaflight rxConfig_t contains different values
#define PG_RC_CONTROLS_CONFIG 25 // Cleanflight has more parameters in rcControlsConfig_t
#define PG_MOTOR_3D_CONFIG 26 // Cleanflight has motor3DConfig_t, betaflight has flight3DConfig_t with more parameters
#define PG_LED_STRIP_CONFIG 27 // structs OK
#define PG_COLOR_CONFIG 28 // part of led strip, structs OK
#define PG_AIRPLANE_ALT_HOLD_CONFIG 29 // struct OK
#define PG_GPS_CONFIG 30 // struct OK
#define PG_TELEMETRY_CONFIG 31 // betaflight has more and different data in telemetryConfig_t
#define PG_FRSKY_TELEMETRY_CONFIG 32 // Cleanflight has split data out of PG_TELEMETRY_CONFIG
#define PG_HOTT_TELEMETRY_CONFIG 33 // Cleanflight has split data out of PG_TELEMETRY_CONFIG
#define PG_NAVIGATION_CONFIG 34 // structs OK
#define PG_ACCELEROMETER_CONFIG 35 // no accelerometerConfig_t in betaflight
#define PG_RATE_PROFILE_SELECTION 36 // part of profile in betaflight
#define PG_ADJUSTMENT_PROFILE 37 // array needs to be made into struct
#define PG_BAROMETER_CONFIG 38 // structs OK
#define PG_THROTTLE_CORRECTION_CONFIG 39
#define PG_COMPASS_CONFIGURATION 40
#define PG_MODE_ACTIVATION_PROFILE 41
#define PG_COMPASS_CONFIGURATION 40 // structs OK
#define PG_MODE_ACTIVATION_PROFILE 41 // array needs to be made into struct
#define PG_SERVO_PROFILE 42
#define PG_FAILSAFE_CHANNEL_CONFIG 43
#define PG_CHANNEL_RANGE_CONFIG 44
#define PG_MODE_COLOR_CONFIG 45
#define PG_SPECIAL_COLOR_CONFIG 46
#define PG_PILOT_CONFIG 47
#define PG_MSP_SERVER_CONFIG 48
#define PG_VOLTAGE_METER_CONFIG 49
#define PG_AMPERAGE_METER_CONFIG 50
#define PG_FAILSAFE_CHANNEL_CONFIG 43 // structs OK
#define PG_CHANNEL_RANGE_CONFIG 44 // structs OK
#define PG_MODE_COLOR_CONFIG 45 // part of led strip, structs OK
#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
// Driver configuration
#define PG_DRIVER_PWM_RX_CONFIG 100
#define PG_DRIVER_FLASHCHIP_CONFIG 101
#define PG_DRIVER_PWM_RX_CONFIG 100 // does not exist in betaflight
#define PG_DRIVER_FLASHCHIP_CONFIG 101 // does not exist in betaflight
// OSD configuration (subject to change)
#define PG_OSD_FONT_CONFIG 32768
#define PG_OSD_VIDEO_CONFIG 32769
#define PG_OSD_ELEMENT_CONFIG 32770
#define PG_OSD_FONT_CONFIG 2047
#define PG_OSD_VIDEO_CONFIG 2046
#define PG_OSD_ELEMENT_CONFIG 2045
#define PG_RESERVED_FOR_TESTING_1 65533
#define PG_RESERVED_FOR_TESTING_2 65534
#define PG_RESERVED_FOR_TESTING_3 65535
// 4095 is currently the highest number that can be used for a PGN due to the top 4 bits of the 16 bit value being reserved for the version when the PG is stored in an EEPROM.
#define PG_RESERVED_FOR_TESTING_1 4095
#define PG_RESERVED_FOR_TESTING_2 4094
#define PG_RESERVED_FOR_TESTING_3 4093

View File

@ -17,6 +17,7 @@
#pragma once
#include "common/axis.h"
#include "drivers/sensor.h"
#ifndef MPU_I2C_INSTANCE
@ -32,18 +33,22 @@
#define GYRO_LPF_5HZ 6
#define GYRO_LPF_NONE 7
typedef struct gyro_s {
typedef struct gyroDev_s {
sensorGyroInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
sensorGyroReadFuncPtr read; // read 3 axis data function
sensorReadFuncPtr temperature; // read temperature if available
sensorInterruptFuncPtr intStatus;
sensorGyroInterruptStatusFuncPtr intStatus;
float scale; // scalefactor
uint32_t targetLooptime;
} gyro_t;
volatile bool dataReady;
uint16_t lpf;
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
sensor_align_e gyroAlign;
} gyroDev_t;
typedef struct acc_s {
typedef struct accDev_s {
sensorAccInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
uint16_t acc_1G;
char revisionCode; // a revision code for the sensor, if known
} acc_t;
sensor_align_e accAlign;
} accDev_t;

View File

@ -56,16 +56,16 @@
#define ADXL345_RANGE_16G 0x03
#define ADXL345_FIFO_STREAM 0x80
static void adxl345Init(acc_t *acc);
static void adxl345Init(accDev_t *acc);
static bool adxl345Read(int16_t *accelData);
static bool useFifo = false;
bool adxl345Detect(drv_adxl345_config_t *init, acc_t *acc)
bool adxl345Detect(drv_adxl345_config_t *init, accDev_t *acc)
{
uint8_t sig = 0;
bool ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
if (!ack || sig != 0xE5)
return false;
@ -77,7 +77,7 @@ bool adxl345Detect(drv_adxl345_config_t *init, acc_t *acc)
return true;
}
static void adxl345Init(acc_t *acc)
static void adxl345Init(accDev_t *acc)
{
if (useFifo) {
uint8_t fifoDepth = 16;

View File

@ -22,4 +22,4 @@ typedef struct drv_adxl345_config_s {
uint16_t dataRate;
} drv_adxl345_config_t;
bool adxl345Detect(drv_adxl345_config_t *init, acc_t *acc);
bool adxl345Detect(drv_adxl345_config_t *init, accDev_t *acc);

View File

@ -32,10 +32,10 @@
#define BMA280_PMU_BW 0x10
#define BMA280_PMU_RANGE 0x0F
static void bma280Init(acc_t *acc);
static void bma280Init(accDev_t *acc);
static bool bma280Read(int16_t *accelData);
bool bma280Detect(acc_t *acc)
bool bma280Detect(accDev_t *acc)
{
uint8_t sig = 0;
bool ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
@ -48,7 +48,7 @@ bool bma280Detect(acc_t *acc)
return true;
}
static void bma280Init(acc_t *acc)
static void bma280Init(accDev_t *acc)
{
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW

View File

@ -17,4 +17,4 @@
#pragma once
bool bma280Detect(acc_t *acc);
bool bma280Detect(accDev_t *acc);

View File

@ -0,0 +1,110 @@
/*
* 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"
#include "common/axis.h"
#include "common/utils.h"
#include "accgyro.h"
#include "accgyro_fake.h"
#ifdef USE_FAKE_GYRO
static int16_t fakeGyroADC[XYZ_AXIS_COUNT];
static void fakeGyroInit(gyroDev_t *gyro)
{
UNUSED(gyro);
}
void fakeGyroSet(int16_t x, int16_t y, int16_t z)
{
fakeGyroADC[X] = x;
fakeGyroADC[Y] = y;
fakeGyroADC[Z] = z;
}
static bool fakeGyroRead(gyroDev_t *gyro)
{
gyro->gyroADCRaw[X] = fakeGyroADC[X];
gyro->gyroADCRaw[Y] = fakeGyroADC[Y];
gyro->gyroADCRaw[Z] = fakeGyroADC[Z];
return true;
}
static bool fakeGyroReadTemperature(int16_t *tempData)
{
UNUSED(tempData);
return true;
}
static bool fakeGyroInitStatus(gyroDev_t *gyro)
{
UNUSED(gyro);
return true;
}
bool fakeGyroDetect(gyroDev_t *gyro)
{
gyro->init = fakeGyroInit;
gyro->intStatus = fakeGyroInitStatus;
gyro->read = fakeGyroRead;
gyro->temperature = fakeGyroReadTemperature;
gyro->scale = 1.0f;
return true;
}
#endif // USE_FAKE_GYRO
#ifdef USE_FAKE_ACC
static int16_t fakeAccData[XYZ_AXIS_COUNT];
static void fakeAccInit(accDev_t *acc)
{
UNUSED(acc);
}
void fakeAccSet(int16_t x, int16_t y, int16_t z)
{
fakeAccData[X] = x;
fakeAccData[Y] = y;
fakeAccData[Z] = z;
}
static bool fakeAccRead(int16_t *accData)
{
accData[X] = fakeAccData[X];
accData[Y] = fakeAccData[Y];
accData[Z] = fakeAccData[Z];
return true;
}
bool fakeAccDetect(accDev_t *acc)
{
acc->init = fakeAccInit;
acc->read = fakeAccRead;
acc->revisionCode = 0;
return true;
}
#endif // USE_FAKE_ACC

View File

@ -0,0 +1,26 @@
/*
* 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
struct accDev_s;
bool fakeAccDetect(struct accDev_s *acc);
void fakeAccSet(int16_t x, int16_t y, int16_t z);
struct gyroDev_s;
bool fakeGyroDetect(struct gyroDev_s *gyro);
void fakeGyroSet(int16_t x, int16_t y, int16_t z);

View File

@ -54,10 +54,10 @@
#define L3G4200D_DLPF_78HZ 0x80
#define L3G4200D_DLPF_93HZ 0xC0
static void l3g4200dInit(uint8_t lpf);
static bool l3g4200dRead(int16_t *gyroADC);
static void l3g4200dInit(gyroDev_t *gyro);
static bool l3g4200dRead(gyroDev_t *gyro);
bool l3g4200dDetect(gyro_t *gyro)
bool l3g4200dDetect(gyroDev_t *gyro)
{
uint8_t deviceid;
@ -76,13 +76,13 @@ bool l3g4200dDetect(gyro_t *gyro)
return true;
}
static void l3g4200dInit(uint8_t lpf)
static void l3g4200dInit(gyroDev_t *gyro)
{
bool ack;
uint8_t mpuLowPassFilter = L3G4200D_DLPF_32HZ;
switch (lpf) {
switch (gyro->lpf) {
default:
case 32:
mpuLowPassFilter = L3G4200D_DLPF_32HZ;
@ -109,7 +109,7 @@ static void l3g4200dInit(uint8_t lpf)
}
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
static bool l3g4200dRead(int16_t *gyroADC)
static bool l3g4200dRead(gyroDev_t *gyro)
{
uint8_t buf[6];
@ -117,9 +117,9 @@ static bool l3g4200dRead(int16_t *gyroADC)
return false;
}
gyroADC[X] = (int16_t)((buf[0] << 8) | buf[1]);
gyroADC[Y] = (int16_t)((buf[2] << 8) | buf[3]);
gyroADC[Z] = (int16_t)((buf[4] << 8) | buf[5]);
gyro->gyroADCRaw[X] = (int16_t)((buf[0] << 8) | buf[1]);
gyro->gyroADCRaw[Y] = (int16_t)((buf[2] << 8) | buf[3]);
gyro->gyroADCRaw[Z] = (int16_t)((buf[4] << 8) | buf[5]);
return true;
}

View File

@ -17,4 +17,4 @@
#pragma once
bool l3g4200dDetect(gyro_t *gyro);
bool l3g4200dDetect(gyroDev_t *gyro);

View File

@ -84,9 +84,9 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx)
spiSetDivisor(L3GD20_SPI, SPI_CLOCK_STANDARD);
}
void l3gd20GyroInit(uint8_t lpf)
void l3gd20GyroInit(gyroDev_t *gyro)
{
UNUSED(lpf); // FIXME use it!
UNUSED(gyro); // FIXME use it!
l3gd20SpiInit(L3GD20_SPI);
@ -120,7 +120,7 @@ void l3gd20GyroInit(uint8_t lpf)
delay(100);
}
static bool l3gd20GyroRead(int16_t *gyroADC)
static bool l3gd20GyroRead(gyroDev_t *gyro)
{
uint8_t buf[6];
@ -134,9 +134,9 @@ static bool l3gd20GyroRead(int16_t *gyroADC)
DISABLE_L3GD20;
gyroADC[0] = (int16_t)((buf[0] << 8) | buf[1]);
gyroADC[1] = (int16_t)((buf[2] << 8) | buf[3]);
gyroADC[2] = (int16_t)((buf[4] << 8) | buf[5]);
gyro->gyroADCRaw[0] = (int16_t)((buf[0] << 8) | buf[1]);
gyro->gyroADCRaw[1] = (int16_t)((buf[2] << 8) | buf[3]);
gyro->gyroADCRaw[2] = (int16_t)((buf[4] << 8) | buf[5]);
#if 0
debug[0] = (int16_t)((buf[1] << 8) | buf[0]);
@ -150,7 +150,7 @@ static bool l3gd20GyroRead(int16_t *gyroADC)
// Page 9 in datasheet, So - Sensitivity, Full Scale = 2000, 70 mdps/digit
#define L3GD20_GYRO_SCALE_FACTOR 0.07f
bool l3gd20Detect(gyro_t *gyro)
bool l3gd20Detect(gyroDev_t *gyro)
{
gyro->init = l3gd20GyroInit;
gyro->read = l3gd20GyroRead;

View File

@ -17,4 +17,4 @@
#pragma once
bool l3gd20Detect(gyro_t *gyro);
bool l3gd20Detect(gyroDev_t *gyro);

View File

@ -115,7 +115,7 @@ int32_t accelSummedSamples100Hz[3];
int32_t accelSummedSamples500Hz[3];
void lsm303dlhcAccInit(acc_t *acc)
void lsm303dlhcAccInit(accDev_t *acc)
{
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT);
@ -157,7 +157,7 @@ static bool lsm303dlhcAccRead(int16_t *gyroADC)
return true;
}
bool lsm303dlhcAccDetect(acc_t *acc)
bool lsm303dlhcAccDetect(accDev_t *acc)
{
bool ack;
uint8_t status;

View File

@ -195,10 +195,10 @@ typedef struct {
/** @defgroup Acc_Full_Scale_Selection
* @{
*/
#define LSM303DLHC_FULLSCALE_2G ((uint8_t)0x00) /*!< ±2 g */
#define LSM303DLHC_FULLSCALE_4G ((uint8_t)0x10) /*!< ±4 g */
#define LSM303DLHC_FULLSCALE_8G ((uint8_t)0x20) /*!< ±8 g */
#define LSM303DLHC_FULLSCALE_16G ((uint8_t)0x30) /*!< ±16 g */
#define LSM303DLHC_FULLSCALE_2G ((uint8_t)0x00) /*!< +/-2 g */
#define LSM303DLHC_FULLSCALE_4G ((uint8_t)0x10) /*!< +/-4 g */
#define LSM303DLHC_FULLSCALE_8G ((uint8_t)0x20) /*!< +/-8 g */
#define LSM303DLHC_FULLSCALE_16G ((uint8_t)0x30) /*!< +/-16 g */
/**
* @}
*/
@ -388,13 +388,13 @@ typedef struct {
/** @defgroup Mag_Full_Scale
* @{
*/
#define LSM303DLHC_FS_1_3_GA ((uint8_t) 0x20) /*!< Full scale = ±1.3 Gauss */
#define LSM303DLHC_FS_1_9_GA ((uint8_t) 0x40) /*!< Full scale = ±1.9 Gauss */
#define LSM303DLHC_FS_2_5_GA ((uint8_t) 0x60) /*!< Full scale = ±2.5 Gauss */
#define LSM303DLHC_FS_4_0_GA ((uint8_t) 0x80) /*!< Full scale = ±4.0 Gauss */
#define LSM303DLHC_FS_4_7_GA ((uint8_t) 0xA0) /*!< Full scale = ±4.7 Gauss */
#define LSM303DLHC_FS_5_6_GA ((uint8_t) 0xC0) /*!< Full scale = ±5.6 Gauss */
#define LSM303DLHC_FS_8_1_GA ((uint8_t) 0xE0) /*!< Full scale = ±8.1 Gauss */
#define LSM303DLHC_FS_1_3_GA ((uint8_t) 0x20) /*!< Full scale = +/-1.3 Gauss */
#define LSM303DLHC_FS_1_9_GA ((uint8_t) 0x40) /*!< Full scale = +/-1.9 Gauss */
#define LSM303DLHC_FS_2_5_GA ((uint8_t) 0x60) /*!< Full scale = +/-2.5 Gauss */
#define LSM303DLHC_FS_4_0_GA ((uint8_t) 0x80) /*!< Full scale = +/-4.0 Gauss */
#define LSM303DLHC_FS_4_7_GA ((uint8_t) 0xA0) /*!< Full scale = +/-4.7 Gauss */
#define LSM303DLHC_FS_5_6_GA ((uint8_t) 0xC0) /*!< Full scale = +/-5.6 Gauss */
#define LSM303DLHC_FS_8_1_GA ((uint8_t) 0xE0) /*!< Full scale = +/-8.1 Gauss */
/**
* @}
*/
@ -438,5 +438,5 @@ typedef struct {
#define LSM303DLHC_TEMPSENSOR_DISABLE ((uint8_t) 0x00) /*!< Temp sensor Disable */
bool lsm303dlhcAccDetect(acc_t *acc);
bool lsm303dlhcAccDetect(accDev_t *acc);

View File

@ -81,10 +81,10 @@
static uint8_t device_id;
static void mma8452Init(acc_t *acc);
static void mma8452Init(accDev_t *acc);
static bool mma8452Read(int16_t *accelData);
bool mma8452Detect(acc_t *acc)
bool mma8452Detect(accDev_t *acc)
{
uint8_t sig = 0;
bool ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
@ -113,7 +113,7 @@ static inline void mma8451ConfigureInterrupt(void)
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2
}
static void mma8452Init(acc_t *acc)
static void mma8452Init(accDev_t *acc)
{
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG1, 0); // Put device in standby to configure stuff

View File

@ -17,4 +17,4 @@
#pragma once
bool mma8452Detect(acc_t *acc);
bool mma8452Detect(accDev_t *acc);

View File

@ -25,7 +25,9 @@
#include "build/build_config.h"
#include "build/debug.h"
#include "common/filter.h"
#include "common/maths.h"
#include "common/utils.h"
#include "nvic.h"
@ -52,8 +54,6 @@ static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data);
static void mpu6050FindRevision(void);
static volatile bool mpuDataReady;
#ifdef USE_SPI
static bool detectSPISensorsAndUpdateDetectionResult(void);
#endif
@ -221,12 +221,22 @@ static void mpu6050FindRevision(void)
}
}
extiCallbackRec_t mpuIntCallbackRec;
typedef struct mpuIntRec_s {
extiCallbackRec_t exti;
gyroDev_t *gyro;
} mpuIntRec_t;
void mpuIntExtiHandler(extiCallbackRec_t *cb)
mpuIntRec_t mpuIntRec;
/*
* Gyro interrupt service routine
*/
#if defined(MPU_INT_EXTI)
static void mpuIntExtiHandler(extiCallbackRec_t *cb)
{
UNUSED(cb);
mpuDataReady = true;
mpuIntRec_t *rec = container_of(cb, mpuIntRec_t, exti);
gyroDev_t *gyro = rec->gyro;
gyro->dataReady = true;
#ifdef DEBUG_MPU_DATA_READY_INTERRUPT
static uint32_t lastCalledAt = 0;
@ -236,17 +246,18 @@ void mpuIntExtiHandler(extiCallbackRec_t *cb)
lastCalledAt = now;
#endif
}
#endif
void mpuIntExtiInit(void)
static void mpuIntExtiInit(gyroDev_t *gyro)
{
mpuIntRec.gyro = gyro;
#if defined(MPU_INT_EXTI)
static bool mpuExtiInitDone = false;
if (mpuExtiInitDone || !mpuIntExtiConfig) {
return;
}
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag);
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
@ -258,20 +269,20 @@ void mpuIntExtiInit(void)
#if defined (STM32F7)
IOInit(mpuIntIO, OWNER_MPU_EXTI, 0);
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
EXTIHandlerInit(&mpuIntRec.exti, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &mpuIntRec.exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
#else
IOInit(mpuIntIO, OWNER_MPU_EXTI, 0);
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
EXTIHandlerInit(&mpuIntRec.exti, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &mpuIntRec.exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(mpuIntIO, true);
#endif
#endif
mpuExtiInitDone = true;
#endif
}
static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data)
@ -302,28 +313,33 @@ bool mpuAccRead(int16_t *accData)
return true;
}
bool mpuGyroRead(int16_t *gyroADC)
bool mpuGyroRead(gyroDev_t *gyro)
{
uint8_t data[6];
bool ack = mpuConfiguration.read(mpuConfiguration.gyroReadXRegister, 6, data);
const bool ack = mpuConfiguration.read(mpuConfiguration.gyroReadXRegister, 6, data);
if (!ack) {
return false;
}
gyroADC[0] = (int16_t)((data[0] << 8) | data[1]);
gyroADC[1] = (int16_t)((data[2] << 8) | data[3]);
gyroADC[2] = (int16_t)((data[4] << 8) | data[5]);
gyro->gyroADCRaw[X] = (int16_t)((data[0] << 8) | data[1]);
gyro->gyroADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]);
gyro->gyroADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]);
return true;
}
bool checkMPUDataReady(void)
void mpuGyroInit(gyroDev_t *gyro)
{
mpuIntExtiInit(gyro);
}
bool checkMPUDataReady(gyroDev_t* gyro)
{
bool ret;
if (mpuDataReady) {
if (gyro->dataReady) {
ret = true;
mpuDataReady= false;
gyro->dataReady= false;
} else {
ret = false;
}

View File

@ -17,7 +17,6 @@
#pragma once
#include "io_types.h"
#include "exti.h"
// MPU6050
@ -185,8 +184,9 @@ typedef struct mpuDetectionResult_s {
extern mpuDetectionResult_t mpuDetectionResult;
void configureMPUDataReadyInterruptHandling(void);
void mpuIntExtiInit(void);
struct gyroDev_s;
void mpuGyroInit(struct gyroDev_s *gyro);
bool mpuAccRead(int16_t *accData);
bool mpuGyroRead(int16_t *gyroADC);
bool mpuGyroRead(struct gyroDev_s *gyro);
mpuDetectionResult_t *detectMpu(const extiConfig_t *configToUse);
bool checkMPUDataReady(void);
bool checkMPUDataReady(struct gyroDev_s *gyro);

View File

@ -46,10 +46,10 @@
#define MPU3050_USER_RESET 0x01
#define MPU3050_CLK_SEL_PLL_GX 0x01
static void mpu3050Init(uint8_t lpf);
static void mpu3050Init(gyroDev_t *gyro);
static bool mpu3050ReadTemp(int16_t *tempData);
bool mpu3050Detect(gyro_t *gyro)
bool mpu3050Detect(gyroDev_t *gyro)
{
if (mpuDetectionResult.sensor != MPU_3050) {
return false;
@ -65,7 +65,7 @@ bool mpu3050Detect(gyro_t *gyro)
return true;
}
static void mpu3050Init(uint8_t lpf)
static void mpu3050Init(gyroDev_t *gyro)
{
bool ack;
@ -75,7 +75,7 @@ static void mpu3050Init(uint8_t lpf)
if (!ack)
failureMode(FAILURE_ACC_INIT);
mpuConfiguration.write(MPU3050_DLPF_FS_SYNC, MPU3050_FS_SEL_2000DPS | lpf);
mpuConfiguration.write(MPU3050_DLPF_FS_SYNC, MPU3050_FS_SEL_2000DPS | gyro->lpf);
mpuConfiguration.write(MPU3050_INT_CFG, 0);
mpuConfiguration.write(MPU3050_USER_CTRL, MPU3050_USER_RESET);
mpuConfiguration.write(MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);

View File

@ -26,4 +26,4 @@
#define MPU3050_USER_CTRL 0x3D
#define MPU3050_PWR_MGM 0x3E
bool mpu3050Detect(gyro_t *gyro);
bool mpu3050Detect(gyroDev_t *gyro);

View File

@ -50,10 +50,10 @@
#define MPU6050_SMPLRT_DIV 0 // 8000Hz
static void mpu6050AccInit(acc_t *acc);
static void mpu6050GyroInit(uint8_t lpf);
static void mpu6050AccInit(accDev_t *acc);
static void mpu6050GyroInit(gyroDev_t *gyro);
bool mpu6050AccDetect(acc_t *acc)
bool mpu6050AccDetect(accDev_t *acc)
{
if (mpuDetectionResult.sensor != MPU_60x0) {
return false;
@ -66,7 +66,7 @@ bool mpu6050AccDetect(acc_t *acc)
return true;
}
bool mpu6050GyroDetect(gyro_t *gyro)
bool mpu6050GyroDetect(gyroDev_t *gyro)
{
if (mpuDetectionResult.sensor != MPU_60x0) {
return false;
@ -81,10 +81,8 @@ bool mpu6050GyroDetect(gyro_t *gyro)
return true;
}
static void mpu6050AccInit(acc_t *acc)
static void mpu6050AccInit(accDev_t *acc)
{
mpuIntExtiInit();
switch (mpuDetectionResult.resolution) {
case MPU_HALF_RESOLUTION:
acc->acc_1G = 256 * 4;
@ -95,16 +93,16 @@ static void mpu6050AccInit(acc_t *acc)
}
}
static void mpu6050GyroInit(uint8_t lpf)
static void mpu6050GyroInit(gyroDev_t *gyro)
{
mpuIntExtiInit();
mpuGyroInit(gyro);
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
delay(100);
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure
mpuConfiguration.write(MPU_RA_CONFIG, lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
mpuConfiguration.write(MPU_RA_CONFIG, gyro->lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec
// ACC Init stuff.

View File

@ -17,5 +17,5 @@
#pragma once
bool mpu6050AccDetect(acc_t *acc);
bool mpu6050GyroDetect(gyro_t *gyro);
bool mpu6050AccDetect(accDev_t *acc);
bool mpu6050GyroDetect(gyroDev_t *gyro);

View File

@ -34,7 +34,7 @@
#include "accgyro_mpu.h"
#include "accgyro_mpu6500.h"
bool mpu6500AccDetect(acc_t *acc)
bool mpu6500AccDetect(accDev_t *acc)
{
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
return false;
@ -46,7 +46,7 @@ bool mpu6500AccDetect(acc_t *acc)
return true;
}
bool mpu6500GyroDetect(gyro_t *gyro)
bool mpu6500GyroDetect(gyroDev_t *gyro)
{
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
return false;
@ -62,16 +62,14 @@ bool mpu6500GyroDetect(gyro_t *gyro)
return true;
}
void mpu6500AccInit(acc_t *acc)
void mpu6500AccInit(accDev_t *acc)
{
mpuIntExtiInit();
acc->acc_1G = 512 * 4;
}
void mpu6500GyroInit(uint8_t lpf)
void mpu6500GyroInit(gyroDev_t *gyro)
{
mpuIntExtiInit();
mpuGyroInit(gyro);
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET);
delay(100);
@ -85,7 +83,7 @@ void mpu6500GyroInit(uint8_t lpf)
delay(15);
mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3);
delay(15);
mpuConfiguration.write(MPU_RA_CONFIG, lpf);
mpuConfiguration.write(MPU_RA_CONFIG, gyro->lpf);
delay(15);
mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); // Get Divider Drops
delay(100);

View File

@ -28,8 +28,8 @@
#define MPU6500_BIT_I2C_IF_DIS (1 << 4)
#define MPU6500_BIT_RAW_RDY_EN (0x01)
bool mpu6500AccDetect(acc_t *acc);
bool mpu6500GyroDetect(gyro_t *gyro);
bool mpu6500AccDetect(accDev_t *acc);
bool mpu6500GyroDetect(gyroDev_t *gyro);
void mpu6500AccInit(acc_t *acc);
void mpu6500GyroInit(uint8_t lpf);
void mpu6500AccInit(accDev_t *acc);
void mpu6500GyroInit(gyroDev_t *gyro);

View File

@ -107,7 +107,7 @@ bool icm20689SpiDetect(void)
}
bool icm20689SpiAccDetect(acc_t *acc)
bool icm20689SpiAccDetect(accDev_t *acc)
{
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
return false;
@ -119,7 +119,7 @@ bool icm20689SpiAccDetect(acc_t *acc)
return true;
}
bool icm20689SpiGyroDetect(gyro_t *gyro)
bool icm20689SpiGyroDetect(gyroDev_t *gyro)
{
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
return false;
@ -135,16 +135,14 @@ bool icm20689SpiGyroDetect(gyro_t *gyro)
return true;
}
void icm20689AccInit(acc_t *acc)
void icm20689AccInit(accDev_t *acc)
{
mpuIntExtiInit();
acc->acc_1G = 512 * 4;
}
void icm20689GyroInit(uint8_t lpf)
void icm20689GyroInit(gyroDev_t *gyro)
{
mpuIntExtiInit();
mpuGyroInit(gyro);
spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
@ -160,7 +158,7 @@ void icm20689GyroInit(uint8_t lpf)
delay(15);
mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3);
delay(15);
mpuConfiguration.write(MPU_RA_CONFIG, lpf);
mpuConfiguration.write(MPU_RA_CONFIG, gyro->lpf);
delay(15);
mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); // Get Divider Drops
delay(100);

View File

@ -19,16 +19,16 @@
#define ICM20689_WHO_AM_I_CONST (0x98)
#define ICM20689_BIT_RESET (0x80)
bool icm20689AccDetect(acc_t *acc);
bool icm20689GyroDetect(gyro_t *gyro);
bool icm20689AccDetect(accDev_t *acc);
bool icm20689GyroDetect(gyroDev_t *gyro);
void icm20689AccInit(acc_t *acc);
void icm20689GyroInit(uint8_t lpf);
void icm20689AccInit(accDev_t *acc);
void icm20689GyroInit(gyroDev_t *gyro);
bool icm20689SpiDetect(void);
bool icm20689SpiAccDetect(acc_t *acc);
bool icm20689SpiGyroDetect(gyro_t *gyro);
bool icm20689SpiAccDetect(accDev_t *acc);
bool icm20689SpiGyroDetect(gyroDev_t *gyro);
bool icm20689WriteRegister(uint8_t reg, uint8_t data);
bool icm20689ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);
bool icm20689ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);

View File

@ -124,32 +124,29 @@ bool mpu6000ReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
return true;
}
void mpu6000SpiGyroInit(uint8_t lpf)
void mpu6000SpiGyroInit(gyroDev_t *gyro)
{
mpuIntExtiInit();
mpuGyroInit(gyro);
mpu6000AccAndGyroInit();
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
// Accel and Gyro DLPF Setting
mpu6000WriteRegister(MPU6000_CONFIG, lpf);
mpu6000WriteRegister(MPU6000_CONFIG, gyro->lpf);
delayMicroseconds(1);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); // 18 MHz SPI clock
int16_t data[3];
mpuGyroRead(data);
mpuGyroRead(gyro);
if (((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) {
if (((int8_t)gyro->gyroADCRaw[1]) == -1 && ((int8_t)gyro->gyroADCRaw[0]) == -1) {
failureMode(FAILURE_GYRO_INIT_FAILED);
}
}
void mpu6000SpiAccInit(acc_t *acc)
void mpu6000SpiAccInit(accDev_t *acc)
{
mpuIntExtiInit();
acc->acc_1G = 512 * 4;
}
@ -257,7 +254,7 @@ static void mpu6000AccAndGyroInit(void)
mpuSpi6000InitDone = true;
}
bool mpu6000SpiAccDetect(acc_t *acc)
bool mpu6000SpiAccDetect(accDev_t *acc)
{
if (mpuDetectionResult.sensor != MPU_60x0_SPI) {
return false;
@ -269,7 +266,7 @@ bool mpu6000SpiAccDetect(acc_t *acc)
return true;
}
bool mpu6000SpiGyroDetect(gyro_t *gyro)
bool mpu6000SpiGyroDetect(gyroDev_t *gyro)
{
if (mpuDetectionResult.sensor != MPU_60x0_SPI) {
return false;

View File

@ -17,8 +17,8 @@
bool mpu6000SpiDetect(void);
bool mpu6000SpiAccDetect(acc_t *acc);
bool mpu6000SpiGyroDetect(gyro_t *gyro);
bool mpu6000SpiAccDetect(accDev_t *acc);
bool mpu6000SpiGyroDetect(gyroDev_t *gyro);
bool mpu6000WriteRegister(uint8_t reg, uint8_t data);
bool mpu6000ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);

View File

@ -94,17 +94,17 @@ bool mpu6500SpiDetect(void)
return false;
}
void mpu6500SpiAccInit(acc_t *acc)
void mpu6500SpiAccInit(accDev_t *acc)
{
mpu6500AccInit(acc);
}
void mpu6500SpiGyroInit(uint8_t lpf)
void mpu6500SpiGyroInit(gyroDev_t *gyro)
{
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_SLOW);
delayMicroseconds(1);
mpu6500GyroInit(lpf);
mpu6500GyroInit(gyro);
// Disable Primary I2C Interface
mpu6500WriteRegister(MPU_RA_USER_CTRL, MPU6500_BIT_I2C_IF_DIS);
@ -114,7 +114,7 @@ void mpu6500SpiGyroInit(uint8_t lpf)
delayMicroseconds(1);
}
bool mpu6500SpiAccDetect(acc_t *acc)
bool mpu6500SpiAccDetect(accDev_t *acc)
{
if (mpuDetectionResult.sensor != MPU_65xx_SPI) {
return false;
@ -126,7 +126,7 @@ bool mpu6500SpiAccDetect(acc_t *acc)
return true;
}
bool mpu6500SpiGyroDetect(gyro_t *gyro)
bool mpu6500SpiGyroDetect(gyroDev_t *gyro)
{
if (mpuDetectionResult.sensor != MPU_65xx_SPI) {
return false;

View File

@ -19,11 +19,11 @@
bool mpu6500SpiDetect(void);
void mpu6500SpiAccInit(acc_t *acc);
void mpu6500SpiGyroInit(uint8_t lpf);
void mpu6500SpiAccInit(accDev_t *acc);
void mpu6500SpiGyroInit(gyroDev_t *gyro);
bool mpu6500SpiAccDetect(acc_t *acc);
bool mpu6500SpiGyroDetect(gyro_t *gyro);
bool mpu6500SpiAccDetect(accDev_t *acc);
bool mpu6500SpiGyroDetect(gyroDev_t *gyro);
bool mpu6500WriteRegister(uint8_t reg, uint8_t data);
bool mpu6500ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);

View File

@ -96,31 +96,26 @@ bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
return true;
}
void mpu9250SpiGyroInit(uint8_t lpf)
void mpu9250SpiGyroInit(gyroDev_t *gyro)
{
(void)(lpf);
mpuGyroInit(gyro);
mpuIntExtiInit();
mpu9250AccAndGyroInit(lpf);
mpu9250AccAndGyroInit(gyro->lpf);
spiResetErrorCounter(MPU9250_SPI_INSTANCE);
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); //high speed now that we don't need to write to the slow registers
int16_t data[3];
mpuGyroRead(data);
mpuGyroRead(gyro);
if ((((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) || spiGetErrorCounter(MPU9250_SPI_INSTANCE) != 0) {
if ((((int8_t)gyro->gyroADCRaw[1]) == -1 && ((int8_t)gyro->gyroADCRaw[0]) == -1) || spiGetErrorCounter(MPU9250_SPI_INSTANCE) != 0) {
spiResetErrorCounter(MPU9250_SPI_INSTANCE);
failureMode(FAILURE_GYRO_INIT_FAILED);
}
}
void mpu9250SpiAccInit(acc_t *acc)
void mpu9250SpiAccInit(accDev_t *acc)
{
mpuIntExtiInit();
acc->acc_1G = 512 * 8;
}
@ -214,7 +209,7 @@ bool mpu9250SpiDetect(void)
return true;
}
bool mpu9250SpiAccDetect(acc_t *acc)
bool mpu9250SpiAccDetect(accDev_t *acc)
{
if (mpuDetectionResult.sensor != MPU_9250_SPI) {
return false;
@ -226,7 +221,7 @@ bool mpu9250SpiAccDetect(acc_t *acc)
return true;
}
bool mpu9250SpiGyroDetect(gyro_t *gyro)
bool mpu9250SpiGyroDetect(gyroDev_t *gyro)
{
if (mpuDetectionResult.sensor != MPU_9250_SPI) {
return false;

View File

@ -27,8 +27,8 @@ void mpu9250ResetGyro(void);
bool mpu9250SpiDetect(void);
bool mpu9250SpiAccDetect(acc_t *acc);
bool mpu9250SpiGyroDetect(gyro_t *gyro);
bool mpu9250SpiAccDetect(accDev_t *acc);
bool mpu9250SpiGyroDetect(gyroDev_t *gyro);
bool mpu9250WriteRegister(uint8_t reg, uint8_t data);
bool verifympu9250WriteRegister(uint8_t reg, uint8_t data);

View File

@ -21,14 +21,12 @@
typedef enum {
ADC_BATTERY = 0,
ADC_RSSI = 1,
ADC_CURRENT = 1,
ADC_EXTERNAL1 = 2,
ADC_CURRENT = 3,
ADC_CHANNEL_MAX = ADC_CURRENT
ADC_RSSI = 3,
ADC_CHANNEL_COUNT
} AdcChannel;
#define ADC_CHANNEL_COUNT (ADC_CHANNEL_MAX + 1)
typedef struct adc_config_s {
ioTag_t tag;
uint8_t adcChannel; // ADC1_INxx channel number

View File

@ -31,16 +31,9 @@
typedef enum ADCDevice {
ADCINVALID = -1,
ADCDEV_1 = 0,
#if defined(STM32F3)
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
ADCDEV_2,
ADCDEV_3,
ADCDEV_MAX = ADCDEV_3,
#elif defined(STM32F4) || defined(STM32F7)
ADCDEV_2,
ADCDEV_3,
ADCDEV_MAX = ADCDEV_3,
#else
ADCDEV_MAX = ADCDEV_1,
ADCDEV_3
#endif
} ADCDevice;

View File

@ -119,7 +119,7 @@ void adcInit(adcConfig_t *config)
adcOperatingConfig[i].sampleTime = ADC_SampleTime_239Cycles5;
adcOperatingConfig[i].enabled = true;
}
if (!adcActive) {
return;
}

View File

@ -128,7 +128,7 @@ void adcInit(adcConfig_t *config)
if (config->currentMeter.enabled) {
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
}
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
if (device == ADCINVALID)
return;
@ -155,7 +155,7 @@ void adcInit(adcConfig_t *config)
if (!adcActive) {
return;
}
if ((device == ADCDEV_1) || (device == ADCDEV_2)) {
// enable clock for ADC1+2
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz

View File

@ -136,7 +136,7 @@ void adcInit(adcConfig_t *config)
if (!adcActive) {
return;
}
RCC_ClockCmd(adc.rccADC, ENABLE);
dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0);

View File

@ -20,7 +20,7 @@
typedef void (*baroOpFuncPtr)(void); // baro start operation
typedef void (*baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature)
typedef struct baro_s {
typedef struct baroDev_s {
uint16_t ut_delay;
uint16_t up_delay;
baroOpFuncPtr start_ut;
@ -28,7 +28,7 @@ typedef struct baro_s {
baroOpFuncPtr start_up;
baroOpFuncPtr get_up;
baroCalculateFuncPtr calculate;
} baro_t;
} baroDev_t;
#ifndef BARO_I2C_INSTANCE
#define BARO_I2C_INSTANCE I2C_DEVICE

View File

@ -154,7 +154,7 @@ void bmp085Disable(const bmp085Config_t *config)
BMP085_OFF;
}
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
{
uint8_t data;
bool ack;

View File

@ -17,12 +17,14 @@
#pragma once
#include "io_types.h"
typedef struct bmp085Config_s {
ioTag_t xclrIO;
ioTag_t eocIO;
} bmp085Config_t;
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro);
bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro);
void bmp085Disable(const bmp085Config_t *config);
#if defined(BARO_EOC_GPIO)

View File

@ -65,7 +65,7 @@ static void bmp280_get_up(void);
#endif
STATIC_UNIT_TESTED void bmp280_calculate(int32_t *pressure, int32_t *temperature);
bool bmp280Detect(baro_t *baro)
bool bmp280Detect(baroDev_t *baro)
{
if (bmp280InitDone)
return true;

View File

@ -56,5 +56,5 @@
#define T_SETUP_PRESSURE_MAX (10)
// 10/16 = 0.625 ms
bool bmp280Detect(baro_t *baro);
bool bmp280Detect(baroDev_t *baro);

View File

@ -0,0 +1,70 @@
/*
* 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 USE_FAKE_BARO
#include "barometer.h"
#include "barometer_fake.h"
static int32_t fakePressure;
static int32_t fakeTemperature;
static void fakeBaroStartGet(void)
{
}
static void fakeBaroCalculate(int32_t *pressure, int32_t *temperature)
{
if (pressure)
*pressure = fakePressure;
if (temperature)
*temperature = fakeTemperature;
}
void fakeBaroSet(int32_t pressure, int32_t temperature)
{
fakePressure = pressure;
fakeTemperature = temperature;
}
bool fakeBaroDetect(baroDev_t *baro)
{
fakePressure = 101325; // pressure in Pa (0m MSL)
fakeTemperature = 2500; // temperature in 0.01 C = 25 deg
// these are dummy as temperature is measured as part of pressure
baro->ut_delay = 10000;
baro->get_ut = fakeBaroStartGet;
baro->start_ut = fakeBaroStartGet;
// only _up part is executed, and gets both temperature and pressure
baro->up_delay = 10000;
baro->start_up = fakeBaroStartGet;
baro->get_up = fakeBaroStartGet;
baro->calculate = fakeBaroCalculate;
return true;
}
#endif // USE_FAKE_BARO

View File

@ -0,0 +1,23 @@
/*
* 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
struct baroDev_s;
bool fakeBaroDetect(struct baroDev_s *baro);
void fakeBaroSet(int32_t pressure, int32_t temperature);

View File

@ -59,7 +59,7 @@ STATIC_UNIT_TESTED uint32_t ms5611_up; // static result of pressure measurement
STATIC_UNIT_TESTED uint16_t ms5611_c[PROM_NB]; // on-chip ROM
static uint8_t ms5611_osr = CMD_ADC_4096;
bool ms5611Detect(baro_t *baro)
bool ms5611Detect(baroDev_t *baro)
{
uint8_t sig;
int i;

View File

@ -17,4 +17,4 @@
#pragma once
bool ms5611Detect(baro_t *baro);
bool ms5611Detect(baroDev_t *baro);

View File

@ -34,7 +34,7 @@ typedef enum I2CDevice {
I2CDEV_2,
I2CDEV_3,
I2CDEV_4,
I2CDEV_MAX = I2CDEV_4,
I2CDEV_COUNT
} I2CDevice;
typedef struct i2cDevice_s {

View File

@ -80,7 +80,7 @@ static i2cDevice_t i2cHardwareMap[] = {
typedef struct{
I2C_HandleTypeDef Handle;
}i2cHandle_t;
static i2cHandle_t i2cHandle[I2CDEV_MAX+1];
static i2cHandle_t i2cHandle[I2CDEV_COUNT];
void I2C1_ER_IRQHandler(void)
{

View File

@ -126,6 +126,7 @@ void spiInitDevice(SPIDevice device)
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);
if (spi->nss) {
IOInit(IOGetByTag(spi->nss), OWNER_SPI_CS, RESOURCE_INDEX(device));
IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af);
}
#endif
@ -135,6 +136,7 @@ void spiInitDevice(SPIDevice device)
IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG);
if (spi->nss) {
IOInit(IOGetByTag(spi->nss), OWNER_SPI_CS, RESOURCE_INDEX(device));
IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG);
}
#endif

View File

@ -46,17 +46,17 @@ typedef enum {
SPI_CLOCK_SLOW = 128, //00.65625 MHz
SPI_CLOCK_STANDARD = 8, //10.50000 MHz
SPI_CLOCK_FAST = 4, //21.00000 MHz
SPI_CLOCK_ULTRAFAST = 2, //42.00000 MHz
SPI_CLOCK_ULTRAFAST = 2 //42.00000 MHz
#elif defined(STM32F7)
SPI_CLOCK_SLOW = 256, //00.42188 MHz
SPI_CLOCK_STANDARD = 16, //06.57500 MHz
SPI_CLOCK_FAST = 4, //27.00000 MHz
SPI_CLOCK_ULTRAFAST = 2, //54.00000 MHz
SPI_CLOCK_ULTRAFAST = 2 //54.00000 MHz
#else
SPI_CLOCK_SLOW = 128, //00.56250 MHz
SPI_CLOCK_STANDARD = 4, //09.00000 MHz
SPI_CLOCK_FAST = 2, //18.00000 MHz
SPI_CLOCK_ULTRAFAST = 2, //18.00000 MHz
SPI_CLOCK_ULTRAFAST = 2 //18.00000 MHz
#endif
} SPIClockDivider_e;
@ -65,8 +65,7 @@ typedef enum SPIDevice {
SPIDEV_1 = 0,
SPIDEV_2,
SPIDEV_3,
SPIDEV_4,
SPIDEV_MAX = SPIDEV_4,
SPIDEV_4
} SPIDevice;
typedef struct SPIDevice_s {

View File

@ -20,8 +20,7 @@
#include "io_types.h"
typedef enum softSPIDevice {
SOFT_SPIDEV_1 = 0,
SOFT_SPIDEV_MAX = SOFT_SPIDEV_1,
SOFT_SPIDEV_1 = 0
} softSPIDevice_e;
typedef struct softSPIDevice_s {

View File

@ -19,10 +19,11 @@
#include "sensor.h"
typedef struct mag_s {
typedef struct magDev_s {
sensorInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
} mag_t;
sensor_align_e magAlign;
} magDev_t;
#ifndef MAG_I2C_INSTANCE
#define MAG_I2C_INSTANCE I2C_DEVICE

View File

@ -42,6 +42,9 @@
#include "accgyro_spi_mpu9250.h"
#include "compass_ak8963.h"
void ak8963Init(void);
bool ak8963Read(int16_t *magData);
// This sensor is available in MPU-9250.
// AK8963, mag sensor address
@ -188,7 +191,7 @@ bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
}
#endif
bool ak8963Detect(mag_t *mag)
bool ak8963Detect(magDev_t *mag)
{
uint8_t sig = 0;

View File

@ -17,6 +17,4 @@
#pragma once
bool ak8963Detect(mag_t *mag);
void ak8963Init(void);
bool ak8963Read(int16_t *magData);
bool ak8963Detect(magDev_t *mag);

View File

@ -37,6 +37,9 @@
#include "compass_ak8975.h"
void ak8975Init(void);
bool ak8975Read(int16_t *magData);
// This sensor is available in MPU-9150.
// AK8975, mag sensor address
@ -57,7 +60,7 @@
#define AK8975_MAG_REG_CNTL 0x0a
#define AK8975_MAG_REG_ASCT 0x0c // self test
bool ak8975Detect(mag_t *mag)
bool ak8975Detect(magDev_t *mag)
{
uint8_t sig = 0;
bool ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);

View File

@ -17,6 +17,4 @@
#pragma once
bool ak8975Detect(mag_t *mag);
void ak8975Init(void);
bool ak8975Read(int16_t *magData);
bool ak8975Detect(magDev_t *mag);

View File

@ -0,0 +1,65 @@
/*
* 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 USE_FAKE_MAG
#include "build/build_config.h"
#include "common/axis.h"
#include "compass.h"
#include "compass_fake.h"
static int16_t fakeMagData[XYZ_AXIS_COUNT];
static void fakeMagInit(void)
{
// initially point north
fakeMagData[X] = 4096;
fakeMagData[Y] = 0;
fakeMagData[Z] = 0;
}
void fakeMagSet(int16_t x, int16_t y, int16_t z)
{
fakeMagData[X] = x;
fakeMagData[Y] = y;
fakeMagData[Z] = z;
}
static bool fakeMagRead(int16_t *magData)
{
magData[X] = fakeMagData[X];
magData[Y] = fakeMagData[Y];
magData[Z] = fakeMagData[Z];
return true;
}
bool fakeMagDetect(magDev_t *mag)
{
mag->init = fakeMagInit;
mag->read = fakeMagRead;
return true;
}
#endif // USE_FAKE_MAG

View File

@ -0,0 +1,22 @@
/*
* 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
struct magDev_s;
bool fakeMagDetect(struct magDev_s *mag);
void fakeMagSet(int16_t x, int16_t y, int16_t z);

View File

@ -41,6 +41,9 @@
#include "compass_hmc5883l.h"
void hmc5883lInit(void);
bool hmc5883lRead(int16_t *magData);
//#define DEBUG_MAG_DATA_READY_INTERRUPT
// HMC5883L, default address 0x1E
@ -167,13 +170,13 @@ static void hmc5883lConfigureDataReadyInterruptHandling(void)
#endif
}
bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
{
hmc5883Config = hmc5883ConfigToUse;
uint8_t sig = 0;
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
if (!ack || sig != 'H')
return false;

View File

@ -23,6 +23,4 @@ typedef struct hmc5883Config_s {
ioTag_t intTag;
} hmc5883Config_t;
bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse);
void hmc5883lInit(void);
bool hmc5883lRead(int16_t *magData);
bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse);

View File

@ -16,11 +16,11 @@
static uint8_t mpuDividerDrops;
bool gyroSyncCheckUpdate(const gyro_t *gyro)
bool gyroSyncCheckUpdate(gyroDev_t *gyro)
{
if (!gyro->intStatus)
return false;
return gyro->intStatus();
return gyro->intStatus(gyro);
}
uint32_t gyroSetSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator)

View File

@ -5,7 +5,8 @@
* Author: borisb
*/
struct gyro_s;
bool gyroSyncCheckUpdate(const struct gyro_s *gyro);
struct gyroDev_s;
bool gyroSyncCheckUpdate(struct gyroDev_s *gyro);
uint8_t gyroMPU6xxxGetDividerDrops(void);
uint32_t gyroSetSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator);

View File

@ -50,6 +50,8 @@ uint16_t IO_Pin(IO_t io);
#define IO_GPIOBYTAG(tag) IO_GPIO(IOGetByTag(tag))
#define IO_PINBYTAG(tag) IO_Pin(IOGetByTag(tag))
#define IO_GPIOPortIdxByTag(tag) DEFIO_TAG_GPIOID(tag)
#define IO_GPIOPinIdxByTag(tag) DEFIO_TAG_PIN(tag)
uint32_t IO_EXTI_Line(IO_t io);
ioRec_t *IO_Rec(IO_t io);

View File

@ -64,9 +64,7 @@ static void pwmOutConfig(pwmOutputPort_t *port, const timerHardware_t *timerHard
configTimeBase(timerHardware->tim, period, mhz);
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output);
if (timerHardware->output & TIMER_OUTPUT_ENABLED) {
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
}
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
TIM_Cmd(timerHardware->tim, ENABLE);
port->ccr = timerChCCR(timerHardware);

View File

@ -63,11 +63,7 @@ static void pwmOutConfig(pwmOutputPort_t *port, const timerHardware_t *timerHard
configTimeBase(timerHardware->tim, period, mhz);
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output);
if (timerHardware->output & TIMER_OUTPUT_ENABLED) {
HAL_TIM_PWM_Start(Handle, timerHardware->channel);
} else {
HAL_TIM_PWM_Stop(Handle, timerHardware->channel);
}
HAL_TIM_PWM_Start(Handle, timerHardware->channel);
HAL_TIM_Base_Start(Handle);
switch (timerHardware->channel) {
@ -221,7 +217,7 @@ void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t mot
break;
}
const timerHardware_t *timerHardware = timerGetByTag(tag, TIMER_OUTPUT_ENABLED);
const timerHardware_t *timerHardware = timerGetByTag(tag, TIM_USE_ANY);
if (timerHardware == NULL) {
/* flag failure and disable ability to arm */
@ -280,7 +276,7 @@ void servoInit(const servoConfig_t *servoConfig)
IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_INDEX(servoIndex));
//IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP);
const timerHardware_t *timer = timerGetByTag(tag, TIMER_OUTPUT_ENABLED);
const timerHardware_t *timer = timerGetByTag(tag, TIM_USE_ANY);
IOConfigGPIOAF(servos[servoIndex].io, IOCFG_AF_PP, timer->alternateFunction);
if (timer == NULL) {

View File

@ -74,7 +74,7 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
if (!motor->timerHardware->dmaChannel) {
return;
}
uint16_t packet = (value << 1) | (motor->requestTelemetry ? 1 : 0);
motor->requestTelemetry = false; // reset telemetry request to make sure it's triggered only once in a row

View File

@ -72,7 +72,7 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
if (!motor->timerHardware->dmaStream) {
return;
}
uint16_t packet = (value << 1) | (motor->requestTelemetry ? 1 : 0);
motor->requestTelemetry = false; // reset telemetry request to make sure it's triggered only once in a row

View File

@ -55,7 +55,7 @@ void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
typedef enum {
INPUT_MODE_PPM,
INPUT_MODE_PWM,
INPUT_MODE_PWM
} pwmInputMode_t;
typedef struct {
@ -103,7 +103,6 @@ typedef struct ppmDevice_s {
ppmDevice_t ppmDev;
#define PPM_IN_MIN_SYNC_PULSE_US 2700 // microseconds
#define PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds
#define PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds
@ -111,7 +110,6 @@ ppmDevice_t ppmDev;
#define PPM_IN_MIN_NUM_CHANNELS 4
#define PPM_IN_MAX_NUM_CHANNELS PWM_PORTS_OR_PPM_CAPTURE_COUNT
bool isPPMDataBeingReceived(void)
{
return (ppmFrameCount != lastPPMFrameCount);
@ -364,17 +362,15 @@ void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
TIM_ICInit(tim, &TIM_ICInitStructure);
}
#endif
void pwmRxInit(const pwmConfig_t *pwmConfig)
{
for (int channel = 0; channel < PWM_INPUT_PORT_COUNT; channel++) {
pwmInputPort_t *port = &pwmInputPorts[channel];
const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel], TIM_USE_PWM);
const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel], TIM_USE_ANY);
if (!timer) {
/* TODO: maybe fail here if not enough channels? */
@ -444,7 +440,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol)
pwmInputPort_t *port = &pwmInputPorts[FIRST_PWM_PORT];
const timerHardware_t *timer = timerGetByTag(ppmConfig->ioTag, TIM_USE_PPM);
const timerHardware_t *timer = timerGetByTag(ppmConfig->ioTag, TIM_USE_ANY);
if (!timer) {
/* TODO: fail here? */
return;

View File

@ -7,7 +7,7 @@ enum rcc_reg {
RCC_AHB,
RCC_APB2,
RCC_APB1,
RCC_AHB1,
RCC_AHB1
};
#define RCC_ENCODE(reg, mask) (((reg) << 5) | LOG2_32BIT(mask))

View File

@ -106,7 +106,7 @@ enum {
NRF24L01_1D_FEATURE_EN_DPL = 2,
NRF24L01_1D_FEATURE_EN_ACK_PAY = 1,
NRF24L01_1D_FEATURE_EN_DYN_ACK = 0,
NRF24L01_1D_FEATURE_EN_DYN_ACK = 0
};
// Pre-shifted and combined bits
@ -162,7 +162,7 @@ enum {
NRF24L01_06_RF_SETUP_RF_PWR_n6dbm = 0x04,
NRF24L01_06_RF_SETUP_RF_PWR_0dbm = 0x06,
NRF24L01_1C_DYNPD_ALL_PIPES = 0x3F,
NRF24L01_1C_DYNPD_ALL_PIPES = 0x3F
};
// Pipes

View File

@ -20,7 +20,7 @@
typedef enum {
RX_SPI_SOFTSPI,
RX_SPI_HARDSPI,
RX_SPI_HARDSPI
} rx_spi_type_e;
#define RX_SPI_MAX_PAYLOAD_SIZE 32

View File

@ -67,7 +67,7 @@ typedef enum {
SDCARD_STATE_SENDING_WRITE,
SDCARD_STATE_WAITING_FOR_WRITE,
SDCARD_STATE_WRITING_MULTIPLE_BLOCKS,
SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE,
SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE
} sdcardState_e;
typedef struct sdcard_t {
@ -352,7 +352,7 @@ static bool sdcard_readOCRRegister(uint32_t *result)
typedef enum {
SDCARD_RECEIVE_SUCCESS,
SDCARD_RECEIVE_BLOCK_IN_PROGRESS,
SDCARD_RECEIVE_ERROR,
SDCARD_RECEIVE_ERROR
} sdcardReceiveBlockStatus_e;
/**

View File

@ -43,7 +43,7 @@ typedef struct sdcardMetadata_s {
typedef enum {
SDCARD_BLOCK_OPERATION_READ,
SDCARD_BLOCK_OPERATION_WRITE,
SDCARD_BLOCK_OPERATION_ERASE,
SDCARD_BLOCK_OPERATION_ERASE
} sdcardBlockOperation_e;
typedef enum {

View File

@ -17,9 +17,24 @@
#pragma once
struct acc_s;
typedef enum {
ALIGN_DEFAULT = 0, // driver-provided alignment
CW0_DEG = 1,
CW90_DEG = 2,
CW180_DEG = 3,
CW270_DEG = 4,
CW0_DEG_FLIP = 5,
CW90_DEG_FLIP = 6,
CW180_DEG_FLIP = 7,
CW270_DEG_FLIP = 8
} sensor_align_e;
struct accDev_s;
typedef void (*sensorInitFuncPtr)(void); // sensor init prototype
typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
typedef void (*sensorAccInitFuncPtr)(struct acc_s *acc); // sensor init prototype
typedef void (*sensorGyroInitFuncPtr)(uint8_t lpf); // gyro sensor init prototype
typedef bool (*sensorInterruptFuncPtr)(void); // sensor Interrupt Data Ready
typedef void (*sensorAccInitFuncPtr)(struct accDev_s *acc); // sensor init prototype
struct gyroDev_s;
typedef void (*sensorGyroInitFuncPtr)(struct gyroDev_s *gyro);
typedef bool (*sensorGyroReadFuncPtr)(struct gyroDev_s *gyro);
typedef bool (*sensorGyroInterruptStatusFuncPtr)(struct gyroDev_s *gyro);
typedef bool (*sensorInterruptFuncPtr)(void);

View File

@ -24,7 +24,7 @@
typedef enum {
BAUDRATE_NORMAL = 19200,
BAUDRATE_KISS = 38400,
BAUDRATE_CASTLE = 18880,
BAUDRATE_CASTLE = 18880
} escBaudRate_e;
typedef enum {
@ -32,7 +32,7 @@ typedef enum {
PROTOCOL_BLHELI = 1,
PROTOCOL_KISS = 2,
PROTOCOL_KISSALL = 3,
PROTOCOL_CASTLE = 4,
PROTOCOL_CASTLE = 4
} escProtocol_e;
#if defined(USE_ESCSERIAL)
@ -119,7 +119,7 @@ static void escSerialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polari
void setTxSignalEsc(escSerial_t *escSerial, uint8_t state)
{
if((escSerial->mode == PROTOCOL_KISSALL))
if(escSerial->mode == PROTOCOL_KISSALL)
{
for (volatile uint8_t i = 0; i < escSerial->outputCount; i++) {
uint8_t state_temp = state;

View File

@ -415,7 +415,7 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
}
if (mode & MODE_RX) {
if (mode & MODE_RX) {
IOInit(rx, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
}

View File

@ -0,0 +1,99 @@
/*
* 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/debug.h"
#include "common/utils.h"
#include "drivers/stack_check.h"
#define STACK_FILL_CHAR 0xa5
extern char _estack; // end of stack, declared in .LD file
extern char _Min_Stack_Size; // declared in .LD file
/*
* The ARM processor uses a full descending stack. This means the stack pointer holds the address
* of the last stacked item in memory. When the processor pushes a new item onto the stack,
* it decrements the stack pointer and then writes the item to the new memory location.
*
*
* RAM layout is generally as below, although some targets vary
*
* F1 Boards
* RAM is origin 0x20000000 length 20K that is:
* 0x20000000 to 0x20005000
*
* F3 Boards
* RAM is origin 0x20000000 length 40K that is:
* 0x20000000 to 0x2000a000
*
* F4 Boards
* RAM is origin 0x20000000 length 128K that is:
* 0x20000000 to 0x20020000
*
*/
#ifdef STACK_CHECK
static uint32_t usedStackSize;
void taskStackCheck(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
char * const stackHighMem = &_estack;
const uint32_t stackSize = (uint32_t)&_Min_Stack_Size;
char * const stackLowMem = stackHighMem - stackSize;
const char * const stackCurrent = (char *)&stackLowMem;
char *p;
for (p = stackLowMem; p < stackCurrent; ++p) {
if (*p != STACK_FILL_CHAR) {
break;
}
}
usedStackSize = (uint32_t)stackHighMem - (uint32_t)p;
DEBUG_SET(DEBUG_STACK, 0, (uint32_t)stackHighMem & 0xffff);
DEBUG_SET(DEBUG_STACK, 1, (uint32_t)stackLowMem & 0xffff);
DEBUG_SET(DEBUG_STACK, 2, (uint32_t)stackCurrent & 0xffff);
DEBUG_SET(DEBUG_STACK, 3, (uint32_t)p & 0xffff);
}
uint32_t stackUsedSize(void)
{
return usedStackSize;
}
#endif
uint32_t stackTotalSize(void)
{
return (uint32_t)&_Min_Stack_Size;
}
uint32_t stackHighMem(void)
{
return (uint32_t)&_estack;
}

25
src/main/drivers/stack_check.h Executable file
View File

@ -0,0 +1,25 @@
/*
* 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 "common/time.h"
void taskStackCheck(timeUs_t currentTimeUs);
uint32_t stackUsedSize(void);
uint32_t stackTotalSize(void);
uint32_t stackHighMem(void);

View File

@ -155,7 +155,7 @@ void systemInit(void)
//SystemClock_Config();
// Configure NVIC preempt/priority groups
//NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITY_GROUPING);
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;

View File

@ -108,8 +108,9 @@ typedef struct timerHardware_s {
typedef enum {
TIMER_OUTPUT_NONE = 0x00,
TIMER_INPUT_ENABLED = 0x00,
TIMER_OUTPUT_ENABLED = 0x01,
TIMER_INPUT_ENABLED = 0x01, /* TODO: remove this */
TIMER_OUTPUT_ENABLED = 0x01, /* TODO: remove this */
TIMER_OUTPUT_STANDARD = 0x01,
TIMER_OUTPUT_INVERTED = 0x02,
TIMER_OUTPUT_N_CHANNEL = 0x04
} timerFlag_e;

View File

@ -1,12 +1,19 @@
/*
modified version of StdPeriph function is located here.
TODO - what license does apply here?
original file was lincesed under MCD-ST Liberty SW License Agreement V2
http://www.st.com/software_license_agreement_liberty_v2
*/
#include <stdbool.h>
#include <stdint.h>
* 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 "platform.h"
@ -42,59 +49,3 @@ uint8_t timerClockDivisor(TIM_TypeDef *tim)
UNUSED(tim);
return 1;
}
/**
* @brief Selects the TIM Output Compare Mode.
* @note This function does NOT disable the selected channel before changing the Output
* Compare Mode.
* @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral.
* @param TIM_Channel: specifies the TIM Channel
* This parameter can be one of the following values:
* @arg TIM_Channel_1: TIM Channel 1
* @arg TIM_Channel_2: TIM Channel 2
* @arg TIM_Channel_3: TIM Channel 3
* @arg TIM_Channel_4: TIM Channel 4
* @param TIM_OCMode: specifies the TIM Output Compare Mode.
* This parameter can be one of the following values:
* @arg TIM_OCMode_Timing
* @arg TIM_OCMode_Active
* @arg TIM_OCMode_Toggle
* @arg TIM_OCMode_PWM1
* @arg TIM_OCMode_PWM2
* @arg TIM_ForcedAction_Active
* @arg TIM_ForcedAction_InActive
* @retval None
*/
#define CCMR_Offset ((uint16_t)0x0018)
void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
{
uint32_t tmp = 0;
/* Check the parameters */
assert_param(IS_TIM_LIST8_PERIPH(TIMx));
assert_param(IS_TIM_CHANNEL(TIM_Channel));
assert_param(IS_TIM_OCM(TIM_OCMode));
tmp = (uint32_t) TIMx;
tmp += CCMR_Offset;
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) {
tmp += (TIM_Channel>>1);
/* Reset the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M);
/* Configure the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp |= TIM_OCMode;
} else {
tmp += (uint16_t)(TIM_Channel - (uint16_t)4) >> (uint16_t)1;
/* Reset the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M);
/* Configure the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8);
}
}

Some files were not shown because too many files have changed in this diff Show More