merge upstream into sirinfpv branch
This commit is contained in:
commit
a1a71d68ac
74
Makefile
74
Makefile
|
@ -28,6 +28,10 @@ OPBL ?=no
|
|||
# Debugger optons, must be empty or GDB
|
||||
DEBUG ?=
|
||||
|
||||
# Insert the debugging hardfault debugger
|
||||
# releases should not be built with this flag as it does not disable pwm output
|
||||
DEBUG_HARDFAULTS ?=
|
||||
|
||||
# Serial port/Device for flashing
|
||||
SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found)
|
||||
|
||||
|
@ -42,7 +46,7 @@ FORKNAME = betaflight
|
|||
|
||||
CC3D_TARGETS = CC3D CC3D_OPBL
|
||||
|
||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SIRINFPV
|
||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO DOGE SIRINFPV
|
||||
|
||||
# Valid targets for OP VCP support
|
||||
VCP_VALID_TARGETS = $(CC3D_TARGETS)
|
||||
|
@ -52,10 +56,17 @@ OPBL_VALID_TARGETS = CC3D_OPBL
|
|||
|
||||
64K_TARGETS = CJMCU
|
||||
128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
|
||||
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SIRINFPV
|
||||
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE SIRINFPV
|
||||
|
||||
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SIRINFPV
|
||||
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SIRINFPV
|
||||
|
||||
# note that there is no hardfault debugging startup file assembly handler for other platforms
|
||||
ifeq ($(DEBUG_HARDFAULTS),F3)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S
|
||||
else
|
||||
STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
|
||||
endif
|
||||
|
||||
# Configure default flash sizes for the targets
|
||||
ifeq ($(FLASH_SIZE),)
|
||||
|
@ -303,7 +314,9 @@ COMMON_SRC = build_config.c \
|
|||
io/rc_controls.c \
|
||||
io/rc_curves.c \
|
||||
io/serial.c \
|
||||
io/serial_1wire.c \
|
||||
io/serial_4way.c \
|
||||
io/serial_4way_avrootloader.c \
|
||||
io/serial_4way_stk500v2.c \
|
||||
io/serial_cli.c \
|
||||
io/serial_msp.c \
|
||||
io/statusindicator.c \
|
||||
|
@ -352,7 +365,8 @@ VCP_SRC = \
|
|||
vcp/usb_istr.c \
|
||||
vcp/usb_prop.c \
|
||||
vcp/usb_pwr.c \
|
||||
drivers/serial_usb_vcp.c
|
||||
drivers/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
NAZE_SRC = startup_stm32f10x_md_gcc.S \
|
||||
drivers/accgyro_adxl345.c \
|
||||
|
@ -531,8 +545,8 @@ CC3D_SRC = \
|
|||
$(COMMON_SRC) \
|
||||
$(VCP_SRC)
|
||||
|
||||
STM32F30x_COMMON_SRC = \
|
||||
startup_stm32f30x_md_gcc.S \
|
||||
|
||||
STM32F30x_COMMON_SRC += \
|
||||
drivers/adc.c \
|
||||
drivers/adc_stm32f30x.c \
|
||||
drivers/bus_i2c_stm32f30x.c \
|
||||
|
@ -561,7 +575,6 @@ STM32F3DISCOVERY_COMMON_SRC = \
|
|||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/accgyro_l3gd20.c \
|
||||
drivers/accgyro_l3gd20.c \
|
||||
drivers/accgyro_lsm303dlhc.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
$(VCP_SRC)
|
||||
|
@ -596,9 +609,11 @@ COLIBRI_RACE_SRC = \
|
|||
drivers/bus_bst_stm32f30x.c \
|
||||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6000.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_ak8963.c \
|
||||
drivers/compass_ak8975.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
|
@ -621,6 +636,20 @@ LUX_RACE_SRC = \
|
|||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC) \
|
||||
$(VCP_SRC)
|
||||
|
||||
DOGE_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/barometer_spi_bmp280.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/serial_usb_vcp.c \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC) \
|
||||
$(VCP_SRC)
|
||||
|
||||
SPARKY_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
|
@ -705,6 +734,28 @@ IRCFUSIONF3_SRC = \
|
|||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC)
|
||||
|
||||
SPRACINGF3EVO_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/compass_ak8963.c \
|
||||
drivers/display_ug2864hsweg01.h \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/serial_usb_vcp.c \
|
||||
drivers/sdcard.c \
|
||||
drivers/sdcard_standard.c \
|
||||
drivers/transponder_ir.c \
|
||||
drivers/transponder_ir_stm32f30x.c \
|
||||
io/asyncfatfs/asyncfatfs.c \
|
||||
io/asyncfatfs/fat_standard.c \
|
||||
io/transponder_ir.c \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC) \
|
||||
$(VCP_SRC)
|
||||
|
||||
MOTOLAB_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/accgyro_mpu.c \
|
||||
|
@ -794,7 +845,7 @@ endif
|
|||
|
||||
DEBUG_FLAGS = -ggdb3 -DDEBUG
|
||||
|
||||
CFLAGS = $(ARCH_FLAGS) \
|
||||
CFLAGS += $(ARCH_FLAGS) \
|
||||
$(LTO_FLAGS) \
|
||||
$(addprefix -D,$(OPTIONS)) \
|
||||
$(addprefix -I,$(INCLUDE_DIRS)) \
|
||||
|
@ -857,11 +908,8 @@ TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(
|
|||
TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
|
||||
|
||||
|
||||
ifeq ($(OPBL),yes)
|
||||
CLEAN_ARTIFACTS := $(TARGET_BIN)
|
||||
else
|
||||
CLEAN_ARTIFACTS := $(TARGET_HEX)
|
||||
endif
|
||||
CLEAN_ARTIFACTS += $(TARGET_HEX)
|
||||
CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
|
||||
|
||||
# List of buildable ELF files and their object dependencies.
|
||||
|
|
|
@ -6,6 +6,7 @@ targets=("PUBLISHMETA=True" \
|
|||
"TARGET=COLIBRI_RACE" \
|
||||
"TARGET=LUX_RACE" \
|
||||
"TARGET=SPRACINGF3" \
|
||||
"TARGET=SPRACINGF3EVO" \
|
||||
"TARGET=SPRACINGF3MINI" \
|
||||
"TARGET=NAZE" \
|
||||
"TARGET=AFROMINI" \
|
||||
|
@ -14,7 +15,8 @@ targets=("PUBLISHMETA=True" \
|
|||
"TARGET=MOTOLAB" \
|
||||
"TARGET=IRCFUSIONF3" \
|
||||
"TARGET=ALIENFLIGHTF1" \
|
||||
"TARGET=ALIENFLIGHTF3")
|
||||
"TARGET=ALIENFLIGHTF3" \
|
||||
"TARGET=DOGE")
|
||||
|
||||
#fake a travis build environment
|
||||
export TRAVIS_BUILD_NUMBER=$(date +%s)
|
||||
|
@ -24,6 +26,9 @@ export TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/simulated}
|
|||
for target in "${targets[@]}"
|
||||
do
|
||||
unset RUNTESTS PUBLISHMETA TARGET
|
||||
echo
|
||||
echo
|
||||
echo "BUILDING '$target'"
|
||||
eval "export $target"
|
||||
make -f Makefile clean
|
||||
./.travis.sh
|
||||
|
|
|
@ -308,7 +308,7 @@ typedef struct blackboxGpsState_s {
|
|||
|
||||
// This data is updated really infrequently:
|
||||
typedef struct blackboxSlowState_s {
|
||||
uint16_t flightModeFlags;
|
||||
uint32_t flightModeFlags; // extend this data size (from uint16_t)
|
||||
uint8_t stateFlags;
|
||||
uint8_t failsafePhase;
|
||||
bool rxSignalReceived;
|
||||
|
@ -324,9 +324,17 @@ extern uint32_t currentTime;
|
|||
//From rx.c:
|
||||
extern uint16_t rssi;
|
||||
|
||||
//From gyro.c
|
||||
extern uint32_t targetLooptime;
|
||||
|
||||
//From rc_controls.c
|
||||
extern uint32_t rcModeActivationMask;
|
||||
|
||||
static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
|
||||
|
||||
static uint32_t blackboxLastArmingBeep = 0;
|
||||
static uint32_t blackboxLastFlightModeFlags = 0; // New event tracking of flight modes
|
||||
|
||||
|
||||
static struct {
|
||||
uint32_t headerIndex;
|
||||
|
@ -402,11 +410,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {
|
||||
return currentProfile->pidProfile.D_f[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
|
||||
} else {
|
||||
return currentProfile->pidProfile.D8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
|
||||
}
|
||||
return currentProfile->pidProfile.D8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_MAG:
|
||||
#ifdef MAG
|
||||
|
@ -739,7 +743,7 @@ static void writeSlowFrame(void)
|
|||
*/
|
||||
static void loadSlowState(blackboxSlowState_t *slow)
|
||||
{
|
||||
slow->flightModeFlags = flightModeFlags;
|
||||
slow->flightModeFlags = rcModeActivationMask; //was flightModeFlags;
|
||||
slow->stateFlags = stateFlags;
|
||||
slow->failsafePhase = failsafePhase();
|
||||
slow->rxSignalReceived = rxIsReceivingSignal();
|
||||
|
@ -862,6 +866,8 @@ void startBlackbox(void)
|
|||
* it finally plays the beep for this arming event.
|
||||
*/
|
||||
blackboxLastArmingBeep = getArmingBeepTimeMicros();
|
||||
blackboxLastFlightModeFlags = rcModeActivationMask; // record startup status
|
||||
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE);
|
||||
}
|
||||
|
@ -1128,7 +1134,7 @@ static bool blackboxWriteSysinfo()
|
|||
blackboxPrintfHeaderLine("Firmware type:Cleanflight");
|
||||
break;
|
||||
case 1:
|
||||
blackboxPrintfHeaderLine("Firmware revision:%s", shortGitRevision);
|
||||
blackboxPrintfHeaderLine("Firmware revision:Betaflight %s (%s)", FC_VERSION_STRING, shortGitRevision);
|
||||
break;
|
||||
case 2:
|
||||
blackboxPrintfHeaderLine("Firmware date:%s %s", buildDate, buildTime);
|
||||
|
@ -1171,6 +1177,165 @@ static bool blackboxWriteSysinfo()
|
|||
blackboxPrintfHeaderLine("currentMeter:%d,%d", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale);
|
||||
}
|
||||
break;
|
||||
case 13:
|
||||
blackboxPrintfHeaderLine("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8);
|
||||
break;
|
||||
case 14:
|
||||
blackboxPrintfHeaderLine("rcYawExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawExpo8);
|
||||
break;
|
||||
case 15:
|
||||
blackboxPrintfHeaderLine("thrMid:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrMid8);
|
||||
break;
|
||||
case 16:
|
||||
blackboxPrintfHeaderLine("thrExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrExpo8);
|
||||
break;
|
||||
case 17:
|
||||
blackboxPrintfHeaderLine("dynThrPID:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].dynThrPID);
|
||||
break;
|
||||
case 18:
|
||||
blackboxPrintfHeaderLine("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint);
|
||||
break;
|
||||
case 19:
|
||||
blackboxPrintfHeaderLine("superExpoFactor:%d", masterConfig.rxConfig.superExpoFactor);
|
||||
break;
|
||||
case 20:
|
||||
blackboxPrintfHeaderLine("rates:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[ROLL],
|
||||
masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[PITCH],
|
||||
masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[YAW]);
|
||||
break;
|
||||
case 21:
|
||||
blackboxPrintfHeaderLine("looptime:%d", targetLooptime);
|
||||
break;
|
||||
case 22:
|
||||
blackboxPrintfHeaderLine("pidController:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidController);
|
||||
break;
|
||||
case 23:
|
||||
blackboxPrintfHeaderLine("rollPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[ROLL],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[ROLL],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[ROLL]);
|
||||
break;
|
||||
case 24:
|
||||
blackboxPrintfHeaderLine("pitchPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PITCH],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PITCH],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PITCH]);
|
||||
break;
|
||||
case 25:
|
||||
blackboxPrintfHeaderLine("yawPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[YAW],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[YAW],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[YAW]);
|
||||
break;
|
||||
case 26:
|
||||
blackboxPrintfHeaderLine("altPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDALT],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDALT],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDALT]);
|
||||
break;
|
||||
case 27:
|
||||
blackboxPrintfHeaderLine("posPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOS],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOS],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOS]);
|
||||
break;
|
||||
case 28:
|
||||
blackboxPrintfHeaderLine("posrPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOSR],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOSR],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOSR]);
|
||||
break;
|
||||
case 29:
|
||||
blackboxPrintfHeaderLine("navrPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDNAVR],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDNAVR],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDNAVR]);
|
||||
break;
|
||||
case 30:
|
||||
blackboxPrintfHeaderLine("levelPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL]);
|
||||
break;
|
||||
case 31:
|
||||
blackboxPrintfHeaderLine("magPID:%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDMAG]);
|
||||
break;
|
||||
case 32:
|
||||
blackboxPrintfHeaderLine("velPID:%d,%d,%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL],
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]);
|
||||
break;
|
||||
case 33:
|
||||
blackboxPrintfHeaderLine("yaw_p_limit:%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit);
|
||||
break;
|
||||
case 34:
|
||||
blackboxPrintfHeaderLine("yaw_lpf_hz:%d",
|
||||
(int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f));
|
||||
break;
|
||||
case 35:
|
||||
blackboxPrintfHeaderLine("dterm_average_count:%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count);
|
||||
break;
|
||||
case 36:
|
||||
blackboxPrintfHeaderLine("dterm_differentiator:%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_differentiator);
|
||||
break;
|
||||
case 37:
|
||||
blackboxPrintfHeaderLine("rollPitchItermResetRate:%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermResetRate);
|
||||
break;
|
||||
case 38:
|
||||
blackboxPrintfHeaderLine("yawItermResetRate:%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermResetRate);
|
||||
break;
|
||||
case 39:
|
||||
blackboxPrintfHeaderLine("dterm_lpf_hz:%d",
|
||||
(int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f));
|
||||
break;
|
||||
case 40:
|
||||
blackboxPrintfHeaderLine("H_sensitivity:%d",
|
||||
masterConfig.profile[masterConfig.current_profile_index].pidProfile.H_sensitivity);
|
||||
break;
|
||||
case 41:
|
||||
blackboxPrintfHeaderLine("deadband:%d", masterConfig.rcControlsConfig.deadband);
|
||||
break;
|
||||
case 42:
|
||||
blackboxPrintfHeaderLine("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband);
|
||||
break;
|
||||
case 43:
|
||||
blackboxPrintfHeaderLine("gyro_lpf:%d", masterConfig.gyro_lpf);
|
||||
break;
|
||||
case 44:
|
||||
blackboxPrintfHeaderLine("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f));
|
||||
break;
|
||||
case 45:
|
||||
blackboxPrintfHeaderLine("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f));
|
||||
break;
|
||||
case 46:
|
||||
blackboxPrintfHeaderLine("acc_hardware:%d", masterConfig.acc_hardware);
|
||||
break;
|
||||
case 47:
|
||||
blackboxPrintfHeaderLine("baro_hardware:%d", masterConfig.baro_hardware);
|
||||
break;
|
||||
case 48:
|
||||
blackboxPrintfHeaderLine("mag_hardware:%d", masterConfig.mag_hardware);
|
||||
break;
|
||||
case 49:
|
||||
blackboxPrintfHeaderLine("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm);
|
||||
break;
|
||||
case 50:
|
||||
blackboxPrintfHeaderLine("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation);
|
||||
break;
|
||||
case 51:
|
||||
blackboxPrintfHeaderLine("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing);
|
||||
break;
|
||||
case 52:
|
||||
blackboxPrintfHeaderLine("features:%d", masterConfig.enabledFeatures);
|
||||
break;
|
||||
default:
|
||||
return true;
|
||||
}
|
||||
|
@ -1198,6 +1363,10 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
|
|||
case FLIGHT_LOG_EVENT_SYNC_BEEP:
|
||||
blackboxWriteUnsignedVB(data->syncBeep.time);
|
||||
break;
|
||||
case FLIGHT_LOG_EVENT_FLIGHTMODE: // New flightmode flags write
|
||||
blackboxWriteUnsignedVB(data->flightMode.flags);
|
||||
blackboxWriteUnsignedVB(data->flightMode.lastFlags);
|
||||
break;
|
||||
case FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT:
|
||||
if (data->inflightAdjustment.floatFlag) {
|
||||
blackboxWrite(data->inflightAdjustment.adjustmentFunction + FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT_FUNCTION_FLOAT_VALUE_FLAG);
|
||||
|
@ -1238,6 +1407,21 @@ static void blackboxCheckAndLogArmingBeep()
|
|||
}
|
||||
}
|
||||
|
||||
/* monitor the flight mode event status and trigger an event record if the state changes */
|
||||
static void blackboxCheckAndLogFlightMode()
|
||||
{
|
||||
flightLogEvent_flightMode_t eventData; // Add new data for current flight mode flags
|
||||
|
||||
// Use != so that we can still detect a change if the counter wraps
|
||||
if (rcModeActivationMask != blackboxLastFlightModeFlags) {
|
||||
eventData.lastFlags = blackboxLastFlightModeFlags;
|
||||
blackboxLastFlightModeFlags = rcModeActivationMask;
|
||||
eventData.flags = rcModeActivationMask;
|
||||
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_FLIGHTMODE, (flightLogEventData_t *) &eventData);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control
|
||||
* the portion of logged loop iterations.
|
||||
|
@ -1282,6 +1466,7 @@ static void blackboxLogIteration()
|
|||
writeIntraframe();
|
||||
} else {
|
||||
blackboxCheckAndLogArmingBeep();
|
||||
blackboxCheckAndLogFlightMode(); // Check for FlightMode status change event
|
||||
|
||||
if (blackboxShouldLogPFrame(blackboxPFrameIndex)) {
|
||||
/*
|
||||
|
@ -1476,5 +1661,5 @@ void initBlackbox(void)
|
|||
blackboxSetState(BLACKBOX_STATE_DISABLED);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -106,6 +106,7 @@ typedef enum FlightLogEvent {
|
|||
FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT = 13,
|
||||
FLIGHT_LOG_EVENT_LOGGING_RESUME = 14,
|
||||
FLIGHT_LOG_EVENT_GTUNE_RESULT = 20,
|
||||
FLIGHT_LOG_EVENT_FLIGHTMODE = 30, // Add new event type for flight mode status.
|
||||
FLIGHT_LOG_EVENT_LOG_END = 255
|
||||
} FlightLogEvent;
|
||||
|
||||
|
@ -113,6 +114,11 @@ typedef struct flightLogEvent_syncBeep_s {
|
|||
uint32_t time;
|
||||
} flightLogEvent_syncBeep_t;
|
||||
|
||||
typedef struct flightLogEvent_flightMode_s { // New Event Data type
|
||||
uint32_t flags;
|
||||
uint32_t lastFlags;
|
||||
} flightLogEvent_flightMode_t;
|
||||
|
||||
typedef struct flightLogEvent_inflightAdjustment_s {
|
||||
uint8_t adjustmentFunction;
|
||||
bool floatFlag;
|
||||
|
@ -135,6 +141,7 @@ typedef struct flightLogEvent_gtuneCycleResult_s {
|
|||
|
||||
typedef union flightLogEventData_u {
|
||||
flightLogEvent_syncBeep_t syncBeep;
|
||||
flightLogEvent_flightMode_t flightMode; // New event data
|
||||
flightLogEvent_inflightAdjustment_t inflightAdjustment;
|
||||
flightLogEvent_loggingResume_t loggingResume;
|
||||
flightLogEvent_gtuneCycleResult_t gtuneCycleResult;
|
||||
|
|
|
@ -96,3 +96,26 @@ float applyBiQuadFilter(float sample, biquad_t *state)
|
|||
|
||||
return result;
|
||||
}
|
||||
|
||||
int32_t filterApplyAverage(int32_t input, uint8_t averageCount, int32_t averageState[DELTA_MAX_SAMPLES]) {
|
||||
int count;
|
||||
int32_t averageSum = 0;
|
||||
|
||||
for (count = averageCount-1; count > 0; count--) averageState[count] = averageState[count-1];
|
||||
averageState[0] = input;
|
||||
for (count = 0; count < averageCount; count++) averageSum += averageState[count];
|
||||
|
||||
return averageSum / averageCount;
|
||||
}
|
||||
|
||||
float filterApplyAveragef(float input, uint8_t averageCount, float averageState[DELTA_MAX_SAMPLES]) {
|
||||
int count;
|
||||
float averageSum = 0.0f;
|
||||
|
||||
for (count = averageCount-1; count > 0; count--) averageState[count] = averageState[count-1];
|
||||
averageState[0] = input;
|
||||
for (count = 0; count < averageCount; count++) averageSum += averageState[count];
|
||||
|
||||
return averageSum / averageCount;
|
||||
}
|
||||
|
||||
|
|
|
@ -15,6 +15,8 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define DELTA_MAX_SAMPLES 12
|
||||
|
||||
typedef struct filterStatePt1_s {
|
||||
float state;
|
||||
float RC;
|
||||
|
@ -29,4 +31,6 @@ typedef struct biquad_s {
|
|||
|
||||
float applyBiQuadFilter(float sample, biquad_t *state);
|
||||
float filterApplyPt1(float input, filterStatePt1_t *filter, float f_cut, float dt);
|
||||
int32_t filterApplyAverage(int32_t input, uint8_t averageCount, int32_t averageState[DELTA_MAX_SAMPLES]);
|
||||
float filterApplyAveragef(float input, uint8_t averageCount, float averageState[DELTA_MAX_SAMPLES]);
|
||||
void BiQuadNewLpf(float filterCutFreq, biquad_t *newState, uint32_t refreshRate);
|
||||
|
|
|
@ -144,6 +144,11 @@ char *itoa(int i, char *a, int base)
|
|||
|
||||
#endif
|
||||
|
||||
/* Note: the floatString must be at least 13 bytes long to cover all cases.
|
||||
* This includes up to 10 digits (32 bit ints can hold numbers up to 10
|
||||
* digits long) + the decimal point + negative sign or space + null
|
||||
* terminator.
|
||||
*/
|
||||
char *ftoa(float x, char *floatString)
|
||||
{
|
||||
int32_t value;
|
||||
|
|
|
@ -21,7 +21,17 @@ void li2a(long num, char *bf);
|
|||
void ui2a(unsigned int num, unsigned int base, int uc, char *bf);
|
||||
void i2a(int num, char *bf);
|
||||
char a2i(char ch, const char **src, int base, int *nump);
|
||||
|
||||
/* Simple conversion of a float to a string. Will display completely
|
||||
* inaccurate results for floats larger than about 2.15E6 (2^31 / 1000)
|
||||
* (same thing for negative values < -2.15E6).
|
||||
* Will always display 3 decimals, so anything smaller than 1E-3 will
|
||||
* not be displayed.
|
||||
* The floatString will be filled in with the result and will be
|
||||
* returned. It must be at least 13 bytes in length to cover all cases!
|
||||
*/
|
||||
char *ftoa(float x, char *floatString);
|
||||
|
||||
float fastA2F(const char *p);
|
||||
|
||||
#ifndef HAVE_ITOA_FUNCTION
|
||||
|
|
|
@ -135,7 +135,7 @@ static uint32_t activeFeaturesLatch = 0;
|
|||
static uint8_t currentControlRateProfileIndex = 0;
|
||||
controlRateConfig_t *currentControlRateProfile;
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 129;
|
||||
static const uint8_t EEPROM_CONF_VERSION = 133;
|
||||
|
||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||
{
|
||||
|
@ -148,14 +148,14 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
{
|
||||
pidProfile->pidController = 1;
|
||||
|
||||
pidProfile->P8[ROLL] = 42;
|
||||
pidProfile->I8[ROLL] = 40;
|
||||
pidProfile->P8[ROLL] = 45;
|
||||
pidProfile->I8[ROLL] = 30;
|
||||
pidProfile->D8[ROLL] = 18;
|
||||
pidProfile->P8[PITCH] = 54;
|
||||
pidProfile->I8[PITCH] = 40;
|
||||
pidProfile->D8[PITCH] = 22;
|
||||
pidProfile->P8[PITCH] = 45;
|
||||
pidProfile->I8[PITCH] = 30;
|
||||
pidProfile->D8[PITCH] = 18;
|
||||
pidProfile->P8[YAW] = 90;
|
||||
pidProfile->I8[YAW] = 50;
|
||||
pidProfile->I8[YAW] = 40;
|
||||
pidProfile->D8[YAW] = 0;
|
||||
pidProfile->P8[PIDALT] = 50;
|
||||
pidProfile->I8[PIDALT] = 0;
|
||||
|
@ -169,31 +169,23 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
|
||||
pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
|
||||
pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
|
||||
pidProfile->P8[PIDLEVEL] = 30;
|
||||
pidProfile->I8[PIDLEVEL] = 30;
|
||||
pidProfile->P8[PIDLEVEL] = 50;
|
||||
pidProfile->I8[PIDLEVEL] = 50;
|
||||
pidProfile->D8[PIDLEVEL] = 100;
|
||||
pidProfile->P8[PIDMAG] = 40;
|
||||
pidProfile->P8[PIDVEL] = 120;
|
||||
pidProfile->I8[PIDVEL] = 45;
|
||||
pidProfile->D8[PIDVEL] = 1;
|
||||
pidProfile->P8[PIDVEL] = 55;
|
||||
pidProfile->I8[PIDVEL] = 55;
|
||||
pidProfile->D8[PIDVEL] = 75;
|
||||
|
||||
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
|
||||
pidProfile->dterm_average_count = 4;
|
||||
pidProfile->dterm_lpf_hz = 0; // filtering ON by default
|
||||
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
|
||||
pidProfile->yaw_lpf_hz = 70.0f;
|
||||
pidProfile->dterm_differentiator = 1;
|
||||
pidProfile->rollPitchItermResetRate = 200;
|
||||
pidProfile->rollPitchItermResetAlways = 0;
|
||||
pidProfile->yawItermResetRate = 50;
|
||||
pidProfile->dterm_lpf_hz = 70.0f; // filtering ON by default
|
||||
|
||||
pidProfile->P_f[ROLL] = 1.1f;
|
||||
pidProfile->I_f[ROLL] = 0.4f;
|
||||
pidProfile->D_f[ROLL] = 0.01f;
|
||||
pidProfile->P_f[PITCH] = 1.4f;
|
||||
pidProfile->I_f[PITCH] = 0.4f;
|
||||
pidProfile->D_f[PITCH] = 0.01f;
|
||||
pidProfile->P_f[YAW] = 2.5f;
|
||||
pidProfile->I_f[YAW] = 0.4f;
|
||||
pidProfile->D_f[YAW] = 0.00f;
|
||||
pidProfile->A_level = 4.0f;
|
||||
pidProfile->H_level = 4.0f;
|
||||
pidProfile->H_sensitivity = 75;
|
||||
pidProfile->H_sensitivity = 75; // TODO - Cleanup during next EEPROM changes
|
||||
|
||||
#ifdef GTUNE
|
||||
pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
|
||||
|
@ -273,6 +265,7 @@ void resetBatteryConfig(batteryConfig_t *batteryConfig)
|
|||
batteryConfig->vbatmaxcellvoltage = 43;
|
||||
batteryConfig->vbatmincellvoltage = 33;
|
||||
batteryConfig->vbatwarningcellvoltage = 35;
|
||||
batteryConfig->vbathysteresis = 1;
|
||||
batteryConfig->vbatPidCompensation = 0;
|
||||
batteryConfig->currentMeterOffset = 0;
|
||||
batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
|
||||
|
@ -313,7 +306,7 @@ void resetSerialConfig(serialConfig_t *serialConfig)
|
|||
|
||||
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
|
||||
controlRateConfig->rcRate8 = 100;
|
||||
controlRateConfig->rcExpo8 = 70;
|
||||
controlRateConfig->rcExpo8 = 60;
|
||||
controlRateConfig->thrMid8 = 50;
|
||||
controlRateConfig->thrExpo8 = 0;
|
||||
controlRateConfig->dynThrPID = 0;
|
||||
|
@ -321,7 +314,7 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
|
|||
controlRateConfig->tpa_breakpoint = 1500;
|
||||
|
||||
for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
|
||||
controlRateConfig->rates[axis] = 0;
|
||||
controlRateConfig->rates[axis] = 50;
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -388,7 +381,7 @@ static void resetConf(void)
|
|||
masterConfig.version = EEPROM_CONF_VERSION;
|
||||
masterConfig.mixerMode = MIXER_QUADX;
|
||||
featureClearAll();
|
||||
#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE)
|
||||
#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE)
|
||||
featureSet(FEATURE_RX_PPM);
|
||||
#endif
|
||||
|
||||
|
@ -434,7 +427,7 @@ static void resetConf(void)
|
|||
masterConfig.dcm_ki = 0; // 0.003 * 10000
|
||||
masterConfig.gyro_lpf = 0; // 256HZ default
|
||||
masterConfig.gyro_sync_denom = 8;
|
||||
masterConfig.gyro_soft_lpf_hz = 60;
|
||||
masterConfig.gyro_soft_lpf_hz = 80.0f;
|
||||
|
||||
masterConfig.pid_process_denom = 1;
|
||||
|
||||
|
@ -466,7 +459,7 @@ static void resetConf(void)
|
|||
masterConfig.rxConfig.spektrum_sat_bind = 0;
|
||||
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
masterConfig.rxConfig.midrc = 1500;
|
||||
masterConfig.rxConfig.mincheck = 1040;
|
||||
masterConfig.rxConfig.mincheck = 1080;
|
||||
masterConfig.rxConfig.maxcheck = 1900;
|
||||
masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
|
||||
masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
|
||||
|
@ -483,8 +476,9 @@ static void resetConf(void)
|
|||
masterConfig.rxConfig.rcSmoothing = 0;
|
||||
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
|
||||
masterConfig.rxConfig.max_aux_channel = 6;
|
||||
masterConfig.rxConfig.acroPlusFactor = 30;
|
||||
masterConfig.rxConfig.acroPlusOffset = 40;
|
||||
masterConfig.rxConfig.superExpoFactor = 30;
|
||||
masterConfig.rxConfig.superExpoFactorYaw = 30;
|
||||
masterConfig.rxConfig.superExpoYawMode = 0;
|
||||
|
||||
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
|
||||
|
||||
|
@ -625,6 +619,13 @@ static void resetConf(void)
|
|||
featureSet(FEATURE_FAILSAFE);
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3EVO
|
||||
featureSet(FEATURE_TRANSPONDER);
|
||||
featureSet(FEATURE_RSSI_ADC);
|
||||
featureSet(FEATURE_CURRENT_METER);
|
||||
featureSet(FEATURE_TELEMETRY);
|
||||
#endif
|
||||
|
||||
// alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
|
||||
#ifdef ALIENFLIGHT
|
||||
featureSet(FEATURE_RX_SERIAL);
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#define MPU6500_WHO_AM_I_CONST (0x70)
|
||||
#define MPU9250_WHO_AM_I_CONST (0x71)
|
||||
#define ICM20608G_WHO_AM_I_CONST (0xAF)
|
||||
|
||||
#define MPU6500_BIT_RESET (0x80)
|
||||
|
||||
|
|
|
@ -132,6 +132,8 @@ void mpu6000SpiGyroInit(uint8_t lpf)
|
|||
mpu6000WriteRegister(MPU6000_CONFIG, lpf);
|
||||
delayMicroseconds(1);
|
||||
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
|
||||
|
||||
int16_t data[3];
|
||||
mpuGyroRead(data);
|
||||
|
||||
|
|
|
@ -107,7 +107,7 @@ bool mpu6500SpiDetect(void)
|
|||
|
||||
mpu6500ReadRegister(MPU_RA_WHO_AM_I, 1, &tmp);
|
||||
|
||||
if (tmp == MPU6500_WHO_AM_I_CONST || tmp == MPU9250_WHO_AM_I_CONST) {
|
||||
if (tmp == MPU6500_WHO_AM_I_CONST || tmp == MPU9250_WHO_AM_I_CONST || tmp == ICM20608G_WHO_AM_I_CONST) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -28,50 +28,12 @@
|
|||
#include "bus_i2c.h"
|
||||
|
||||
#include "barometer_bmp280.h"
|
||||
#include "barometer_spi_bmp280.h"
|
||||
|
||||
#ifdef BARO
|
||||
|
||||
// BMP280, address 0x76
|
||||
|
||||
#define BMP280_I2C_ADDR (0x76)
|
||||
#define BMP280_DEFAULT_CHIP_ID (0x58)
|
||||
|
||||
#define BMP280_CHIP_ID_REG (0xD0) /* Chip ID Register */
|
||||
#define BMP280_RST_REG (0xE0) /* Softreset Register */
|
||||
#define BMP280_STAT_REG (0xF3) /* Status Register */
|
||||
#define BMP280_CTRL_MEAS_REG (0xF4) /* Ctrl Measure Register */
|
||||
#define BMP280_CONFIG_REG (0xF5) /* Configuration Register */
|
||||
#define BMP280_PRESSURE_MSB_REG (0xF7) /* Pressure MSB Register */
|
||||
#define BMP280_PRESSURE_LSB_REG (0xF8) /* Pressure LSB Register */
|
||||
#define BMP280_PRESSURE_XLSB_REG (0xF9) /* Pressure XLSB Register */
|
||||
#define BMP280_TEMPERATURE_MSB_REG (0xFA) /* Temperature MSB Reg */
|
||||
#define BMP280_TEMPERATURE_LSB_REG (0xFB) /* Temperature LSB Reg */
|
||||
#define BMP280_TEMPERATURE_XLSB_REG (0xFC) /* Temperature XLSB Reg */
|
||||
#define BMP280_FORCED_MODE (0x01)
|
||||
|
||||
#define BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG (0x88)
|
||||
#define BMP280_PRESSURE_TEMPERATURE_CALIB_DATA_LENGTH (24)
|
||||
#define BMP280_DATA_FRAME_SIZE (6)
|
||||
|
||||
#define BMP280_OVERSAMP_SKIPPED (0x00)
|
||||
#define BMP280_OVERSAMP_1X (0x01)
|
||||
#define BMP280_OVERSAMP_2X (0x02)
|
||||
#define BMP280_OVERSAMP_4X (0x03)
|
||||
#define BMP280_OVERSAMP_8X (0x04)
|
||||
#define BMP280_OVERSAMP_16X (0x05)
|
||||
|
||||
// configure pressure and temperature oversampling, forced sampling mode
|
||||
#define BMP280_PRESSURE_OSR (BMP280_OVERSAMP_8X)
|
||||
#define BMP280_TEMPERATURE_OSR (BMP280_OVERSAMP_1X)
|
||||
#define BMP280_MODE (BMP280_PRESSURE_OSR << 2 | BMP280_TEMPERATURE_OSR << 5 | BMP280_FORCED_MODE)
|
||||
|
||||
#define T_INIT_MAX (20)
|
||||
// 20/16 = 1.25 ms
|
||||
#define T_MEASURE_PER_OSRS_MAX (37)
|
||||
// 37/16 = 2.3125 ms
|
||||
#define T_SETUP_PRESSURE_MAX (10)
|
||||
// 10/16 = 0.625 ms
|
||||
|
||||
typedef struct bmp280_calib_param_s {
|
||||
uint16_t dig_T1; /* calibration T1 data */
|
||||
int16_t dig_T2; /* calibration T2 data */
|
||||
|
@ -92,13 +54,15 @@ static uint8_t bmp280_chip_id = 0;
|
|||
static bool bmp280InitDone = false;
|
||||
STATIC_UNIT_TESTED bmp280_calib_param_t bmp280_cal;
|
||||
// uncompensated pressure and temperature
|
||||
STATIC_UNIT_TESTED int32_t bmp280_up = 0;
|
||||
STATIC_UNIT_TESTED int32_t bmp280_ut = 0;
|
||||
int32_t bmp280_up = 0;
|
||||
int32_t bmp280_ut = 0;
|
||||
|
||||
static void bmp280_start_ut(void);
|
||||
static void bmp280_get_ut(void);
|
||||
#ifndef USE_BARO_SPI_BMP280
|
||||
static void bmp280_start_up(void);
|
||||
static void bmp280_get_up(void);
|
||||
#endif
|
||||
STATIC_UNIT_TESTED void bmp280_calculate(int32_t *pressure, int32_t *temperature);
|
||||
|
||||
bool bmp280Detect(baro_t *baro)
|
||||
|
@ -108,6 +72,17 @@ bool bmp280Detect(baro_t *baro)
|
|||
|
||||
delay(20);
|
||||
|
||||
#ifdef USE_BARO_SPI_BMP280
|
||||
bmp280SpiInit();
|
||||
bmp280ReadRegister(BMP280_CHIP_ID_REG, 1, &bmp280_chip_id);
|
||||
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID)
|
||||
return false;
|
||||
|
||||
// read calibration
|
||||
bmp280ReadRegister(BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
|
||||
// set oversampling + power mode (forced), and start sampling
|
||||
bmp280WriteRegister(BMP280_CTRL_MEAS_REG, BMP280_MODE);
|
||||
#else
|
||||
i2cRead(BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
|
||||
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID)
|
||||
return false;
|
||||
|
@ -116,6 +91,7 @@ bool bmp280Detect(baro_t *baro)
|
|||
i2cRead(BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
|
||||
// set oversampling + power mode (forced), and start sampling
|
||||
i2cWrite(BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
|
||||
#endif
|
||||
|
||||
bmp280InitDone = true;
|
||||
|
||||
|
@ -126,8 +102,13 @@ bool bmp280Detect(baro_t *baro)
|
|||
|
||||
// only _up part is executed, and gets both temperature and pressure
|
||||
baro->up_delay = ((T_INIT_MAX + T_MEASURE_PER_OSRS_MAX * (((1 << BMP280_TEMPERATURE_OSR) >> 1) + ((1 << BMP280_PRESSURE_OSR) >> 1)) + (BMP280_PRESSURE_OSR ? T_SETUP_PRESSURE_MAX : 0) + 15) / 16) * 1000;
|
||||
#ifdef USE_BARO_SPI_BMP280
|
||||
baro->start_up = bmp280_spi_start_up;
|
||||
baro->get_up = bmp280_spi_get_up;
|
||||
#else
|
||||
baro->start_up = bmp280_start_up;
|
||||
baro->get_up = bmp280_get_up;
|
||||
#endif
|
||||
baro->calculate = bmp280_calculate;
|
||||
|
||||
return true;
|
||||
|
@ -143,6 +124,7 @@ static void bmp280_get_ut(void)
|
|||
// dummy
|
||||
}
|
||||
|
||||
#ifndef USE_BARO_SPI_BMP280
|
||||
static void bmp280_start_up(void)
|
||||
{
|
||||
// start measurement
|
||||
|
@ -159,6 +141,7 @@ static void bmp280_get_up(void)
|
|||
bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4));
|
||||
bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4));
|
||||
}
|
||||
#endif
|
||||
|
||||
// Returns temperature in DegC, resolution is 0.01 DegC. Output value of "5123" equals 51.23 DegC
|
||||
// t_fine carries fine temperature as global value
|
||||
|
|
|
@ -17,5 +17,44 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define BMP280_I2C_ADDR (0x76)
|
||||
#define BMP280_DEFAULT_CHIP_ID (0x58)
|
||||
|
||||
#define BMP280_CHIP_ID_REG (0xD0) /* Chip ID Register */
|
||||
#define BMP280_RST_REG (0xE0) /* Softreset Register */
|
||||
#define BMP280_STAT_REG (0xF3) /* Status Register */
|
||||
#define BMP280_CTRL_MEAS_REG (0xF4) /* Ctrl Measure Register */
|
||||
#define BMP280_CONFIG_REG (0xF5) /* Configuration Register */
|
||||
#define BMP280_PRESSURE_MSB_REG (0xF7) /* Pressure MSB Register */
|
||||
#define BMP280_PRESSURE_LSB_REG (0xF8) /* Pressure LSB Register */
|
||||
#define BMP280_PRESSURE_XLSB_REG (0xF9) /* Pressure XLSB Register */
|
||||
#define BMP280_TEMPERATURE_MSB_REG (0xFA) /* Temperature MSB Reg */
|
||||
#define BMP280_TEMPERATURE_LSB_REG (0xFB) /* Temperature LSB Reg */
|
||||
#define BMP280_TEMPERATURE_XLSB_REG (0xFC) /* Temperature XLSB Reg */
|
||||
#define BMP280_FORCED_MODE (0x01)
|
||||
|
||||
#define BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG (0x88)
|
||||
#define BMP280_PRESSURE_TEMPERATURE_CALIB_DATA_LENGTH (24)
|
||||
#define BMP280_DATA_FRAME_SIZE (6)
|
||||
|
||||
#define BMP280_OVERSAMP_SKIPPED (0x00)
|
||||
#define BMP280_OVERSAMP_1X (0x01)
|
||||
#define BMP280_OVERSAMP_2X (0x02)
|
||||
#define BMP280_OVERSAMP_4X (0x03)
|
||||
#define BMP280_OVERSAMP_8X (0x04)
|
||||
#define BMP280_OVERSAMP_16X (0x05)
|
||||
|
||||
// configure pressure and temperature oversampling, forced sampling mode
|
||||
#define BMP280_PRESSURE_OSR (BMP280_OVERSAMP_8X)
|
||||
#define BMP280_TEMPERATURE_OSR (BMP280_OVERSAMP_1X)
|
||||
#define BMP280_MODE (BMP280_PRESSURE_OSR << 2 | BMP280_TEMPERATURE_OSR << 5 | BMP280_FORCED_MODE)
|
||||
|
||||
#define T_INIT_MAX (20)
|
||||
// 20/16 = 1.25 ms
|
||||
#define T_MEASURE_PER_OSRS_MAX (37)
|
||||
// 37/16 = 2.3125 ms
|
||||
#define T_SETUP_PRESSURE_MAX (10)
|
||||
// 10/16 = 0.625 ms
|
||||
|
||||
bool bmp280Detect(baro_t *baro);
|
||||
|
||||
|
|
|
@ -0,0 +1,110 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight 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.
|
||||
*
|
||||
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "bus_spi.h"
|
||||
|
||||
#include "barometer.h"
|
||||
#include "barometer_bmp280.h"
|
||||
|
||||
#define DISABLE_BMP280 GPIO_SetBits(BMP280_CS_GPIO, BMP280_CS_PIN)
|
||||
#define ENABLE_BMP280 GPIO_ResetBits(BMP280_CS_GPIO, BMP280_CS_PIN)
|
||||
|
||||
extern int32_t bmp280_up;
|
||||
extern int32_t bmp280_ut;
|
||||
|
||||
bool bmp280WriteRegister(uint8_t reg, uint8_t data)
|
||||
{
|
||||
ENABLE_BMP280;
|
||||
spiTransferByte(BMP280_SPI_INSTANCE, reg & 0x7F);
|
||||
spiTransferByte(BMP280_SPI_INSTANCE, data);
|
||||
DISABLE_BMP280;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool bmp280ReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
|
||||
{
|
||||
ENABLE_BMP280;
|
||||
spiTransferByte(BMP280_SPI_INSTANCE, reg | 0x80); // read transaction
|
||||
spiTransfer(BMP280_SPI_INSTANCE, data, NULL, length);
|
||||
DISABLE_BMP280;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void bmp280SpiInit(void)
|
||||
{
|
||||
static bool hardwareInitialised = false;
|
||||
|
||||
if (hardwareInitialised) {
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef STM32F303
|
||||
RCC_AHBPeriphClockCmd(BMP280_CS_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = BMP280_CS_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_Init(BMP280_CS_GPIO, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X
|
||||
RCC_APB2PeriphClockCmd(BMP280_CS_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
|
||||
gpio_config_t gpio;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpio.pin = BMP280_CS_PIN;
|
||||
gpio.speed = Speed_50MHz;
|
||||
gpioInit(BMP280_CS_GPIO, &gpio);
|
||||
#endif
|
||||
|
||||
GPIO_SetBits(BMP280_CS_GPIO, BMP280_CS_PIN);
|
||||
|
||||
spiSetDivisor(BMP280_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
|
||||
|
||||
hardwareInitialised = true;
|
||||
}
|
||||
|
||||
void bmp280_spi_start_up(void)
|
||||
{
|
||||
// start measurement
|
||||
// set oversampling + power mode (forced), and start sampling
|
||||
bmp280WriteRegister(BMP280_CTRL_MEAS_REG, BMP280_MODE);
|
||||
}
|
||||
|
||||
void bmp280_spi_get_up(void)
|
||||
{
|
||||
uint8_t data[BMP280_DATA_FRAME_SIZE];
|
||||
|
||||
// read data from sensor
|
||||
bmp280ReadRegister(BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
|
||||
bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4));
|
||||
bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4));
|
||||
}
|
|
@ -0,0 +1,24 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight 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.
|
||||
*
|
||||
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
void bmp280SpiInit(void);
|
||||
bool bmp280ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);
|
||||
bool bmp280WriteRegister(uint8_t reg, uint8_t data);
|
||||
void bmp280_spi_start_up(void);
|
||||
void bmp280_spi_get_up(void);
|
|
@ -32,6 +32,8 @@
|
|||
#define CROSSFIRE_RSSI_FRAME_ID 0x14
|
||||
#define CLEANFLIGHT_MODE_FRAME_ID 0x20
|
||||
|
||||
#define DATA_BUFFER_SIZE 64
|
||||
|
||||
typedef enum BSTDevice {
|
||||
BSTDEV_1,
|
||||
BSTDEV_2,
|
||||
|
@ -39,6 +41,7 @@ typedef enum BSTDevice {
|
|||
} BSTDevice;
|
||||
|
||||
void bstInit(BSTDevice index);
|
||||
uint32_t bstTimeoutUserCallback(void);
|
||||
uint16_t bstGetErrorCounter(void);
|
||||
|
||||
bool bstWriteBusy(void);
|
||||
|
@ -47,7 +50,6 @@ bool bstSlaveRead(uint8_t* buf);
|
|||
bool bstSlaveWrite(uint8_t* data);
|
||||
|
||||
void bstMasterWriteLoop(void);
|
||||
void bstMasterReadLoop(void);
|
||||
|
||||
void crc8Cal(uint8_t data_in);
|
||||
|
||||
|
|
|
@ -12,6 +12,7 @@
|
|||
|
||||
#include <build_config.h>
|
||||
|
||||
#include "nvic.h"
|
||||
#include "bus_bst.h"
|
||||
|
||||
|
||||
|
@ -45,8 +46,6 @@
|
|||
#define BST2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||
#endif
|
||||
|
||||
static uint32_t bstTimeout;
|
||||
|
||||
static volatile uint16_t bst1ErrorCount = 0;
|
||||
static volatile uint16_t bst2ErrorCount = 0;
|
||||
|
||||
|
@ -59,101 +58,219 @@ volatile bool coreProReady = false;
|
|||
// BST TimeoutUserCallback
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
uint32_t bstTimeoutUserCallback(I2C_TypeDef *BSTx)
|
||||
uint8_t dataBuffer[DATA_BUFFER_SIZE] = {0};
|
||||
uint8_t dataBufferPointer = 0;
|
||||
uint8_t bstWriteDataLen = 0;
|
||||
|
||||
uint32_t micros(void);
|
||||
|
||||
uint8_t writeData[DATA_BUFFER_SIZE] = {0};
|
||||
uint8_t currentWriteBufferPointer = 0;
|
||||
bool receiverAddress = false;
|
||||
|
||||
uint8_t readData[DATA_BUFFER_SIZE] = {0};
|
||||
uint8_t bufferPointer = 0;
|
||||
|
||||
void bstProcessInCommand(void);
|
||||
void I2C_EV_IRQHandler()
|
||||
{
|
||||
if (BSTx == I2C1) {
|
||||
bst1ErrorCount++;
|
||||
} else {
|
||||
bst2ErrorCount++;
|
||||
}
|
||||
I2C_SoftwareResetCmd(BSTx);
|
||||
return false;
|
||||
if(I2C_GetITStatus(BSTx, I2C_IT_ADDR)) {
|
||||
CRC8 = 0;
|
||||
if(I2C_GetTransferDirection(BSTx) == I2C_Direction_Receiver) {
|
||||
currentWriteBufferPointer = 0;
|
||||
receiverAddress = true;
|
||||
I2C_SendData(BSTx, (uint8_t) writeData[currentWriteBufferPointer++]);
|
||||
I2C_ITConfig(BSTx, I2C_IT_TXI, ENABLE);
|
||||
} else {
|
||||
readData[0] = I2C_GetAddressMatched(BSTx);
|
||||
bufferPointer = 1;
|
||||
}
|
||||
I2C_ClearITPendingBit(BSTx, I2C_IT_ADDR);
|
||||
} else if(I2C_GetITStatus(BSTx, I2C_IT_RXNE)) {
|
||||
uint8_t data = I2C_ReceiveData(BSTx);
|
||||
readData[bufferPointer] = data;
|
||||
if(bufferPointer > 1) {
|
||||
if(readData[1]+1 == bufferPointer) {
|
||||
crc8Cal(0);
|
||||
bstProcessInCommand();
|
||||
} else {
|
||||
crc8Cal(data);
|
||||
}
|
||||
}
|
||||
bufferPointer++;
|
||||
I2C_ClearITPendingBit(BSTx, I2C_IT_RXNE);
|
||||
} else if(I2C_GetITStatus(BSTx, I2C_IT_TXIS)) {
|
||||
if(receiverAddress) {
|
||||
if(currentWriteBufferPointer > 0) {
|
||||
if(writeData[0] == currentWriteBufferPointer) {
|
||||
receiverAddress = false;
|
||||
crc8Cal(0);
|
||||
I2C_SendData(BSTx, (uint8_t) CRC8);
|
||||
I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE);
|
||||
} else {
|
||||
crc8Cal((uint8_t) writeData[currentWriteBufferPointer]);
|
||||
I2C_SendData(BSTx, (uint8_t) writeData[currentWriteBufferPointer++]);
|
||||
}
|
||||
}
|
||||
} else if(bstWriteDataLen) {
|
||||
I2C_SendData(BSTx, (uint8_t) dataBuffer[dataBufferPointer]);
|
||||
if(bstWriteDataLen > 1)
|
||||
dataBufferPointer++;
|
||||
if(dataBufferPointer == bstWriteDataLen) {
|
||||
I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE);
|
||||
dataBufferPointer = 0;
|
||||
bstWriteDataLen = 0;
|
||||
}
|
||||
} else {
|
||||
}
|
||||
I2C_ClearITPendingBit(BSTx, I2C_IT_TXIS);
|
||||
} else if(I2C_GetITStatus(BSTx, I2C_IT_NACKF)) {
|
||||
if(receiverAddress) {
|
||||
receiverAddress = false;
|
||||
I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE);
|
||||
}
|
||||
I2C_ClearITPendingBit(BSTx, I2C_IT_NACKF);
|
||||
} else if(I2C_GetITStatus(BSTx, I2C_IT_STOPF)) {
|
||||
if(bstWriteDataLen && dataBufferPointer == bstWriteDataLen) {
|
||||
dataBufferPointer = 0;
|
||||
bstWriteDataLen = 0;
|
||||
}
|
||||
I2C_ClearITPendingBit(BSTx, I2C_IT_STOPF);
|
||||
} else if(I2C_GetITStatus(BSTx, I2C_IT_BERR)
|
||||
|| I2C_GetITStatus(BSTx, I2C_IT_ARLO)
|
||||
|| I2C_GetITStatus(BSTx, I2C_IT_OVR)) {
|
||||
bstTimeoutUserCallback();
|
||||
I2C_ClearITPendingBit(BSTx, I2C_IT_BERR | I2C_IT_ARLO | I2C_IT_OVR);
|
||||
}
|
||||
}
|
||||
|
||||
void I2C1_EV_IRQHandler()
|
||||
{
|
||||
I2C_EV_IRQHandler();
|
||||
}
|
||||
|
||||
void I2C2_EV_IRQHandler()
|
||||
{
|
||||
I2C_EV_IRQHandler();
|
||||
}
|
||||
|
||||
uint32_t bstTimeoutUserCallback()
|
||||
{
|
||||
if (BSTx == I2C1) {
|
||||
bst1ErrorCount++;
|
||||
} else {
|
||||
bst2ErrorCount++;
|
||||
}
|
||||
I2C_GenerateSTOP(BSTx, ENABLE);
|
||||
receiverAddress = false;
|
||||
dataBufferPointer = 0;
|
||||
bstWriteDataLen = 0;
|
||||
I2C_ITConfig(BSTx, I2C_IT_TXI, DISABLE);
|
||||
I2C_SoftwareResetCmd(BSTx);
|
||||
return false;
|
||||
}
|
||||
|
||||
void bstInitPort(I2C_TypeDef *BSTx/*, uint8_t Address*/)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
I2C_InitTypeDef BST_InitStructure;
|
||||
NVIC_InitTypeDef nvic;
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
I2C_InitTypeDef BST_InitStructure;
|
||||
|
||||
if (BSTx == I2C1) {
|
||||
RCC_AHBPeriphClockCmd(BST1_SCL_CLK_SOURCE | BST1_SDA_CLK_SOURCE, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
|
||||
RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK);
|
||||
if(BSTx == I2C1) {
|
||||
RCC_AHBPeriphClockCmd(BST1_SCL_CLK_SOURCE | BST1_SDA_CLK_SOURCE, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
|
||||
RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK);
|
||||
|
||||
GPIO_PinAFConfig(BST1_SCL_GPIO, BST1_SCL_PIN_SOURCE, BST1_SCL_GPIO_AF);
|
||||
GPIO_PinAFConfig(BST1_SDA_GPIO, BST1_SDA_PIN_SOURCE, BST1_SDA_GPIO_AF);
|
||||
GPIO_PinAFConfig(BST1_SCL_GPIO, BST1_SCL_PIN_SOURCE, BST1_SCL_GPIO_AF);
|
||||
GPIO_PinAFConfig(BST1_SDA_GPIO, BST1_SDA_PIN_SOURCE, BST1_SDA_GPIO_AF);
|
||||
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
I2C_StructInit(&BST_InitStructure);
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
I2C_StructInit(&BST_InitStructure);
|
||||
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = BST1_SCL_PIN;
|
||||
GPIO_Init(BST1_SCL_GPIO, &GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = BST1_SCL_PIN;
|
||||
GPIO_Init(BST1_SCL_GPIO, &GPIO_InitStructure);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = BST1_SDA_PIN;
|
||||
GPIO_Init(BST1_SDA_GPIO, &GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = BST1_SDA_PIN;
|
||||
GPIO_Init(BST1_SDA_GPIO, &GPIO_InitStructure);
|
||||
|
||||
I2C_StructInit(&BST_InitStructure);
|
||||
I2C_StructInit(&BST_InitStructure);
|
||||
|
||||
BST_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
||||
BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
|
||||
BST_InitStructure.I2C_DigitalFilter = 0x00;
|
||||
BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC;
|
||||
//BST_InitStructure.I2C_OwnAddress1 = PNP_PRO_GPS;
|
||||
//BST_InitStructure.I2C_OwnAddress1 = Address;
|
||||
BST_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
BST_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
||||
BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
|
||||
BST_InitStructure.I2C_DigitalFilter = 0x00;
|
||||
BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC;
|
||||
BST_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
|
||||
I2C_Init(I2C1, &BST_InitStructure);
|
||||
I2C_Init(I2C1, &BST_InitStructure);
|
||||
|
||||
I2C_Cmd(I2C1, ENABLE);
|
||||
}
|
||||
I2C_GeneralCallCmd(I2C1, ENABLE);
|
||||
|
||||
if (BSTx == I2C2) {
|
||||
RCC_AHBPeriphClockCmd(BST2_SCL_CLK_SOURCE | BST2_SDA_CLK_SOURCE, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
|
||||
RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK);
|
||||
nvic.NVIC_IRQChannel = I2C1_EV_IRQn;
|
||||
nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BST_READ_DATA);
|
||||
nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BST_READ_DATA);
|
||||
nvic.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&nvic);
|
||||
|
||||
GPIO_PinAFConfig(BST2_SCL_GPIO, BST2_SCL_PIN_SOURCE, BST2_SCL_GPIO_AF);
|
||||
GPIO_PinAFConfig(BST2_SDA_GPIO, BST2_SDA_PIN_SOURCE, BST2_SDA_GPIO_AF);
|
||||
I2C_ITConfig(I2C1, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE);
|
||||
|
||||
I2C_Cmd(I2C1, ENABLE);
|
||||
}
|
||||
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
I2C_StructInit(&BST_InitStructure);
|
||||
if(BSTx == I2C2) {
|
||||
RCC_AHBPeriphClockCmd(BST2_SCL_CLK_SOURCE | BST2_SDA_CLK_SOURCE, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
|
||||
RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK);
|
||||
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_PinAFConfig(BST2_SCL_GPIO, BST2_SCL_PIN_SOURCE, BST2_SCL_GPIO_AF);
|
||||
GPIO_PinAFConfig(BST2_SDA_GPIO, BST2_SDA_PIN_SOURCE, BST2_SDA_GPIO_AF);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = BST2_SCL_PIN;
|
||||
GPIO_Init(BST2_SCL_GPIO, &GPIO_InitStructure);
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
I2C_StructInit(&BST_InitStructure);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = BST2_SDA_PIN;
|
||||
GPIO_Init(BST2_SDA_GPIO, &GPIO_InitStructure);
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
I2C_StructInit(&BST_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = BST2_SCL_PIN;
|
||||
GPIO_Init(BST2_SCL_GPIO, &GPIO_InitStructure);
|
||||
|
||||
BST_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
||||
BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
|
||||
BST_InitStructure.I2C_DigitalFilter = 0x00;
|
||||
BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC;
|
||||
//BST_InitStructure.I2C_OwnAddress1 = PNP_PRO_GPS;
|
||||
//BST_InitStructure.I2C_OwnAddress1 = Address;
|
||||
BST_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
GPIO_InitStructure.GPIO_Pin = BST2_SDA_PIN;
|
||||
GPIO_Init(BST2_SDA_GPIO, &GPIO_InitStructure);
|
||||
|
||||
I2C_Init(I2C2, &BST_InitStructure);
|
||||
I2C_StructInit(&BST_InitStructure);
|
||||
|
||||
I2C_Cmd(I2C2, ENABLE);
|
||||
}
|
||||
BST_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
||||
BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
|
||||
BST_InitStructure.I2C_DigitalFilter = 0x00;
|
||||
BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC;
|
||||
BST_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
|
||||
I2C_Init(I2C2, &BST_InitStructure);
|
||||
|
||||
I2C_GeneralCallCmd(I2C2, ENABLE);
|
||||
|
||||
nvic.NVIC_IRQChannel = I2C2_EV_IRQn;
|
||||
nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BST_READ_DATA);
|
||||
nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BST_READ_DATA);
|
||||
nvic.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&nvic);
|
||||
|
||||
I2C_ITConfig(I2C2, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE);
|
||||
|
||||
I2C_Cmd(I2C2, ENABLE);
|
||||
}
|
||||
}
|
||||
|
||||
void bstInit(BSTDevice index)
|
||||
|
@ -163,8 +280,6 @@ void bstInit(BSTDevice index)
|
|||
} else {
|
||||
BSTx = I2C2;
|
||||
}
|
||||
//bstInitPort(BSTx, PNP_PRO_GPS);
|
||||
//bstInitPort(BSTx, CLEANFLIGHT_FC);
|
||||
bstInitPort(BSTx);
|
||||
}
|
||||
|
||||
|
@ -179,9 +294,6 @@ uint16_t bstGetErrorCounter(void)
|
|||
}
|
||||
|
||||
/*************************************************************************************************/
|
||||
uint8_t dataBuffer[64] = {0};
|
||||
uint8_t bufferPointer = 0;
|
||||
uint8_t bstWriteDataLen = 0;
|
||||
|
||||
bool bstWriteBusy(void)
|
||||
{
|
||||
|
@ -195,7 +307,7 @@ bool bstMasterWrite(uint8_t* data)
|
|||
{
|
||||
if(bstWriteDataLen==0) {
|
||||
CRC8 = 0;
|
||||
bufferPointer = 0;
|
||||
dataBufferPointer = 0;
|
||||
dataBuffer[0] = *data;
|
||||
dataBuffer[1] = *(data+1);
|
||||
bstWriteDataLen = dataBuffer[1] + 2;
|
||||
|
@ -213,163 +325,27 @@ bool bstMasterWrite(uint8_t* data)
|
|||
return false;
|
||||
}
|
||||
|
||||
bool bstSlaveRead(uint8_t* buf) {
|
||||
if(I2C_GetAddressMatched(BSTx)==CLEANFLIGHT_FC && I2C_GetTransferDirection(BSTx) == I2C_Direction_Transmitter) {
|
||||
//if(I2C_GetTransferDirection(BSTx) == I2C_Direction_Transmitter) {
|
||||
uint8_t len = 0;
|
||||
CRC8 = 0;
|
||||
I2C_ClearFlag(BSTx, I2C_FLAG_ADDR);
|
||||
|
||||
/* Wait until RXNE flag is set */
|
||||
bstTimeout = BST_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(BSTx, I2C_ISR_RXNE) == RESET) {
|
||||
if ((bstTimeout--) == 0) {
|
||||
return bstTimeoutUserCallback(BSTx);
|
||||
}
|
||||
}
|
||||
len = I2C_ReceiveData(BSTx);
|
||||
*buf = len;
|
||||
buf++;
|
||||
while (len) {
|
||||
/* Wait until RXNE flag is set */
|
||||
bstTimeout = BST_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(BSTx, I2C_ISR_RXNE) == RESET) {
|
||||
if ((bstTimeout--) == 0) {
|
||||
return bstTimeoutUserCallback(BSTx);
|
||||
}
|
||||
}
|
||||
/* Read data from RXDR */
|
||||
*buf = I2C_ReceiveData(BSTx);
|
||||
if(len == 1)
|
||||
crc8Cal(0);
|
||||
else
|
||||
crc8Cal((uint8_t)*buf);
|
||||
|
||||
/* Point to the next location where the byte read will be saved */
|
||||
buf++;
|
||||
|
||||
/* Decrement the read bytes counter */
|
||||
len--;
|
||||
}
|
||||
/* If all operations OK */
|
||||
return true;
|
||||
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool bstSlaveWrite(uint8_t* data) {
|
||||
bstTimeout = BST_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(BSTx, I2C_ISR_ADDR) == RESET) {
|
||||
if ((bstTimeout--) == 0) {
|
||||
return bstTimeoutUserCallback(BSTx);
|
||||
}
|
||||
}
|
||||
if(I2C_GetAddressMatched(BSTx)==CLEANFLIGHT_FC && I2C_GetTransferDirection(BSTx) == I2C_Direction_Receiver) {
|
||||
//if(I2C_GetTransferDirection(BSTx) == I2C_Direction_Receiver) {
|
||||
uint8_t len = 0;
|
||||
CRC8 = 0;
|
||||
I2C_ClearFlag(BSTx, I2C_FLAG_ADDR);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
bstTimeout = BST_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((bstTimeout--) == 0) {
|
||||
return bstTimeoutUserCallback(BSTx);
|
||||
}
|
||||
}
|
||||
len = *data;
|
||||
data++;
|
||||
I2C_SendData(BSTx, (uint8_t) len);
|
||||
while(len) {
|
||||
/* Wait until TXIS flag is set */
|
||||
bstTimeout = BST_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((bstTimeout--) == 0) {
|
||||
return bstTimeoutUserCallback(BSTx);
|
||||
}
|
||||
}
|
||||
if(len == 1) {
|
||||
crc8Cal(0);
|
||||
I2C_SendData(BSTx, (uint8_t) CRC8);
|
||||
} else {
|
||||
crc8Cal((uint8_t)*data);
|
||||
I2C_SendData(BSTx, (uint8_t)*data);
|
||||
}
|
||||
/* Point to the next location where the byte read will be saved */
|
||||
data++;
|
||||
|
||||
/* Decrement the read bytes counter */
|
||||
len--;
|
||||
}
|
||||
/* Wait until TXIS flag is set */
|
||||
bstTimeout = BST_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((bstTimeout--) == 0) {
|
||||
return bstTimeoutUserCallback(BSTx);
|
||||
}
|
||||
}
|
||||
/* If all operations OK */
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/*************************************************************************************************/
|
||||
|
||||
uint32_t bstMasterWriteTimeout = 0;
|
||||
void bstMasterWriteLoop(void)
|
||||
{
|
||||
while(bstWriteDataLen) {
|
||||
if(bufferPointer == 0) {
|
||||
bool scl_set = false;
|
||||
if(BSTx == I2C1)
|
||||
scl_set = BST1_SCL_GPIO->IDR&BST1_SCL_PIN;
|
||||
else
|
||||
scl_set = BST2_SCL_GPIO->IDR&BST2_SCL_PIN;
|
||||
|
||||
if(I2C_GetFlagStatus(BSTx, I2C_ISR_BUSY)==RESET && scl_set) {
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(BSTx, dataBuffer[bufferPointer], 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
|
||||
bstMasterWriteTimeout = micros();
|
||||
bufferPointer++;
|
||||
}
|
||||
} else if(bufferPointer == 1) {
|
||||
if(I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS)==SET) {
|
||||
/* Send Register len */
|
||||
I2C_SendData(BSTx, (uint8_t) dataBuffer[bufferPointer]);
|
||||
bstMasterWriteTimeout = micros();
|
||||
} else if(I2C_GetFlagStatus(BSTx, I2C_ISR_TCR)==SET) {
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(BSTx, dataBuffer[bufferPointer-1], dataBuffer[bufferPointer], I2C_AutoEnd_Mode, I2C_No_StartStop);
|
||||
bstMasterWriteTimeout = micros();
|
||||
bufferPointer++;
|
||||
}
|
||||
} else if(bufferPointer == bstWriteDataLen) {
|
||||
if(I2C_GetFlagStatus(BSTx, I2C_ISR_STOPF)==SET) {
|
||||
I2C_ClearFlag(BSTx, I2C_ICR_STOPCF);
|
||||
bstWriteDataLen = 0;
|
||||
bufferPointer = 0;
|
||||
}
|
||||
} else {
|
||||
if(I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS)==SET) {
|
||||
I2C_SendData(BSTx, (uint8_t) dataBuffer[bufferPointer]);
|
||||
bstMasterWriteTimeout = micros();
|
||||
bufferPointer++;
|
||||
}
|
||||
}
|
||||
uint32_t currentTime = micros();
|
||||
if(currentTime>bstMasterWriteTimeout+5000) {
|
||||
I2C_SoftwareResetCmd(BSTx);
|
||||
bstWriteDataLen = 0;
|
||||
bufferPointer = 0;
|
||||
static uint32_t bstMasterWriteTimeout = 0;
|
||||
uint32_t currentTime = micros();
|
||||
if(bstWriteDataLen && dataBufferPointer==0) {
|
||||
bool scl_set = false;
|
||||
if(BSTx == I2C1)
|
||||
scl_set = BST1_SCL_GPIO->IDR&BST1_SCL_PIN;
|
||||
else
|
||||
scl_set = BST2_SCL_GPIO->IDR&BST2_SCL_PIN;
|
||||
if(I2C_GetFlagStatus(BSTx, I2C_FLAG_BUSY)==RESET && scl_set) {
|
||||
I2C_TransferHandling(BSTx, dataBuffer[dataBufferPointer], dataBuffer[dataBufferPointer+1]+1, I2C_AutoEnd_Mode, I2C_Generate_Start_Write);
|
||||
I2C_ITConfig(BSTx, I2C_IT_TXI, ENABLE);
|
||||
dataBufferPointer = 1;
|
||||
bstMasterWriteTimeout = micros();
|
||||
}
|
||||
} else if(currentTime>bstMasterWriteTimeout+BST_SHORT_TIMEOUT) {
|
||||
bstTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
void bstMasterReadLoop(void)
|
||||
{
|
||||
}
|
||||
/*************************************************************************************************/
|
||||
void crc8Cal(uint8_t data_in)
|
||||
{
|
||||
|
|
|
@ -24,6 +24,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
|
@ -69,6 +71,7 @@
|
|||
#define READ_FLAG 0x80
|
||||
|
||||
#define STATUS1_DATA_READY 0x01
|
||||
#define STATUS1_DATA_OVERRUN 0x02
|
||||
|
||||
#define STATUS2_DATA_ERROR 0x02
|
||||
#define STATUS2_MAG_SENSOR_OVERFLOW 0x03
|
||||
|
@ -91,6 +94,14 @@ typedef struct ak8963Configuration_s {
|
|||
ak8963Configuration_t ak8963config;
|
||||
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
||||
|
||||
// FIXME pretend we have real MPU9250 support
|
||||
#ifdef MPU6500_SPI_INSTANCE
|
||||
#define MPU9250_SPI_INSTANCE
|
||||
#define verifympu9250WriteRegister mpu6500WriteRegister
|
||||
#define mpu9250WriteRegister mpu6500WriteRegister
|
||||
#define mpu9250ReadRegister mpu6500ReadRegister
|
||||
#endif
|
||||
|
||||
#ifdef USE_SPI
|
||||
bool ak8963SPIRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
|
||||
{
|
||||
|
@ -114,6 +125,77 @@ bool ak8963SPIWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3EVO
|
||||
|
||||
typedef struct queuedReadState_s {
|
||||
bool waiting;
|
||||
uint8_t len;
|
||||
uint32_t readStartedAt; // time read was queued in micros.
|
||||
} queuedReadState_t;
|
||||
|
||||
static queuedReadState_t queuedRead = { false, 0, 0};
|
||||
|
||||
bool ak8963SPIStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
|
||||
{
|
||||
if (queuedRead.waiting) {
|
||||
return false;
|
||||
}
|
||||
|
||||
queuedRead.len = len_;
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
||||
|
||||
queuedRead.readStartedAt = micros();
|
||||
queuedRead.waiting = true;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static uint32_t ak8963SPIQueuedReadTimeRemaining(void)
|
||||
{
|
||||
if (!queuedRead.waiting) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t timeSinceStarted = micros() - queuedRead.readStartedAt;
|
||||
|
||||
int32_t timeRemaining = 8000 - timeSinceStarted;
|
||||
|
||||
if (timeRemaining < 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return timeRemaining;
|
||||
}
|
||||
|
||||
bool ak8963SPICompleteRead(uint8_t *buf)
|
||||
{
|
||||
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
|
||||
|
||||
if (timeRemaining > 0) {
|
||||
delayMicroseconds(timeRemaining);
|
||||
}
|
||||
|
||||
queuedRead.waiting = false;
|
||||
|
||||
mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, queuedRead.len, buf); // read I2C buffer
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2C
|
||||
bool c_i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data) {
|
||||
return i2cWrite(addr_, reg_, data);
|
||||
}
|
||||
|
||||
bool c_i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) {
|
||||
return i2cRead(addr_, reg_, len, buf);
|
||||
}
|
||||
#endif
|
||||
|
||||
bool ak8963Detect(mag_t *mag)
|
||||
{
|
||||
bool ack = false;
|
||||
|
@ -187,26 +269,106 @@ void ak8963Init()
|
|||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
||||
|
||||
// Trigger first measurement
|
||||
#ifdef SPRACINGF3EVO
|
||||
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
|
||||
#else
|
||||
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
||||
#endif
|
||||
}
|
||||
|
||||
typedef enum {
|
||||
CHECK_STATUS = 0,
|
||||
WAITING_FOR_STATUS,
|
||||
WAITING_FOR_DATA
|
||||
} ak8963ReadState_e;
|
||||
|
||||
bool ak8963Read(int16_t *magData)
|
||||
{
|
||||
bool ack;
|
||||
uint8_t status;
|
||||
uint8_t buf[6];
|
||||
uint8_t buf[7];
|
||||
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
|
||||
#ifdef SPRACINGF3EVO
|
||||
|
||||
// we currently need a different approach on the SPRacingF3EVO which has an MPU9250 connected via SPI.
|
||||
// we cannot use the ak8963SPIRead() method, it is to slow and blocks for far too long.
|
||||
|
||||
static ak8963ReadState_e state = CHECK_STATUS;
|
||||
|
||||
bool retry = true;
|
||||
|
||||
restart:
|
||||
switch (state) {
|
||||
case CHECK_STATUS:
|
||||
ak8963SPIStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1);
|
||||
state++;
|
||||
return false;
|
||||
|
||||
case WAITING_FOR_STATUS: {
|
||||
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
|
||||
if (timeRemaining) {
|
||||
return false;
|
||||
}
|
||||
|
||||
ack = ak8963SPICompleteRead(&buf[0]);
|
||||
|
||||
uint8_t status = buf[0];
|
||||
|
||||
if (!ack || ((status & STATUS1_DATA_READY) == 0 && (status & STATUS1_DATA_OVERRUN) == 0)) {
|
||||
// too early. queue the status read again
|
||||
state = CHECK_STATUS;
|
||||
if (retry) {
|
||||
retry = false;
|
||||
goto restart;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
// read the 6 bytes of data and the status2 register
|
||||
ak8963SPIStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7);
|
||||
|
||||
state++;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
case WAITING_FOR_DATA: {
|
||||
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
|
||||
if (timeRemaining) {
|
||||
return false;
|
||||
}
|
||||
|
||||
ack = ak8963SPICompleteRead(&buf[0]);
|
||||
|
||||
uint8_t status2 = buf[6];
|
||||
if (!ack || (status2 & STATUS2_DATA_ERROR) || (status2 & STATUS2_MAG_SENSOR_OVERFLOW)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
magData[X] = -(int16_t)(buf[1] << 8 | buf[0]) * magGain[X];
|
||||
magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
|
||||
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
|
||||
|
||||
state = CHECK_STATUS;
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
#else
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &buf[0]);
|
||||
|
||||
uint8_t status = buf[0];
|
||||
|
||||
if (!ack || (status & STATUS1_DATA_READY) == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, sizeof(buf), buf);
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7, &buf[0]);
|
||||
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
||||
|
||||
if (!ack || (status & STATUS2_DATA_ERROR) || (status & STATUS2_MAG_SENSOR_OVERFLOW)) {
|
||||
uint8_t status2 = buf[6];
|
||||
if (!ack || (status2 & STATUS2_DATA_ERROR) || (status2 & STATUS2_MAG_SENSOR_OVERFLOW)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -215,4 +377,5 @@ bool ak8963Read(int16_t *magData)
|
|||
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
|
||||
|
||||
return ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -32,7 +32,8 @@ static uint8_t mpuDividerDrops;
|
|||
bool getMpuDataStatus(gyro_t *gyro)
|
||||
{
|
||||
bool mpuDataStatus;
|
||||
|
||||
if (!gyro->intStatus)
|
||||
return false;
|
||||
gyro->intStatus(&mpuDataStatus);
|
||||
return mpuDataStatus;
|
||||
}
|
||||
|
|
|
@ -8,6 +8,7 @@
|
|||
#define NVIC_PRIO_TIMER NVIC_BUILD_PRIORITY(1, 1)
|
||||
#define NVIC_PRIO_BARO_EXT NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
||||
#define NVIC_PRIO_WS2811_DMA NVIC_BUILD_PRIORITY(1, 2) // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?)
|
||||
#define NVIC_PRIO_BST_READ_DATA NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
||||
#define NVIC_PRIO_TRANSPONDER_DMA NVIC_BUILD_PRIORITY(3, 0)
|
||||
#define NVIC_PRIO_SERIALUART1_TXDMA NVIC_BUILD_PRIORITY(1, 1)
|
||||
#define NVIC_PRIO_SERIALUART1_RXDMA NVIC_BUILD_PRIORITY(1, 1)
|
||||
|
|
|
@ -479,6 +479,67 @@ static const uint16_t airPWM[] = {
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3EVO
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t multiPWM[] = {
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPWM[] = {
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(MOTOLAB)
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
@ -578,6 +639,60 @@ static const uint16_t airPWM[] = {
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef DOGE
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t multiPWM[] = {
|
||||
// prevent crashing, but do nothing
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPWM[] = {
|
||||
// prevent crashing, but do nothing
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(SIRINFPV)
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
|
|
|
@ -50,6 +50,7 @@ static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
|
|||
|
||||
static uint8_t allocatedOutputPortCount = 0;
|
||||
|
||||
static bool pwmMotorsEnabled = true;
|
||||
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value)
|
||||
{
|
||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
|
@ -158,12 +159,12 @@ static void pwmWriteOneshot42(uint8_t index, uint16_t value)
|
|||
|
||||
static void pwmWriteMultiShot(uint8_t index, uint16_t value)
|
||||
{
|
||||
*motors[index]->ccr = (uint16_t)((float)(value-1000) / 4.1666f)+ 60;
|
||||
*motors[index]->ccr = 60001 * (value - 1000) / 250000 + 60;
|
||||
}
|
||||
|
||||
void pwmWriteMotor(uint8_t index, uint16_t value)
|
||||
{
|
||||
if (motors[index] && index < MAX_MOTORS)
|
||||
if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled)
|
||||
motors[index]->pwmWritePtr(index, value);
|
||||
}
|
||||
|
||||
|
@ -177,6 +178,16 @@ void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
|
|||
}
|
||||
}
|
||||
|
||||
void pwmDisableMotors(void)
|
||||
{
|
||||
pwmMotorsEnabled = false;
|
||||
}
|
||||
|
||||
void pwmEnableMotors(void)
|
||||
{
|
||||
pwmMotorsEnabled = true;
|
||||
}
|
||||
|
||||
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
|
||||
{
|
||||
uint8_t index;
|
||||
|
|
|
@ -24,3 +24,5 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount);
|
|||
void pwmWriteServo(uint8_t index, uint16_t value);
|
||||
|
||||
bool isMotorBrushed(uint16_t motorPwmRate);
|
||||
void pwmDisableMotors(void);
|
||||
void pwmEnableMotors(void);
|
||||
|
|
|
@ -183,3 +183,9 @@ serialPort_t *usbVcpOpen(void)
|
|||
|
||||
return (serialPort_t *)s;
|
||||
}
|
||||
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
|
||||
return CDC_BaudRate();
|
||||
}
|
||||
|
|
|
@ -30,3 +30,4 @@ typedef struct {
|
|||
} vcpPort_t;
|
||||
|
||||
serialPort_t *usbVcpOpen(void);
|
||||
uint32_t usbVcpGetBaudRate(serialPort_t *instance);
|
||||
|
|
|
@ -141,6 +141,30 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef DOGE
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6}, // PWM1 - PA8
|
||||
|
||||
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2}, // PWM2 - PB8
|
||||
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2}, // PWM3 - PB9
|
||||
|
||||
{ TIM2, GPIOA, Pin_10, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_10}, // PMW4 - PA10
|
||||
{ TIM2, GPIOA, Pin_9, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_10}, // PWM5 - PA9
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // PWM6 - PA0
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM7 - PA1
|
||||
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource0, GPIO_AF_2}, // PWM8 - PB1
|
||||
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource1, GPIO_AF_2}, // PWM9 - PB0
|
||||
};
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))
|
||||
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
|
||||
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15)
|
||||
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CHEBUZZF3
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// INPUTS CH1-8
|
||||
|
@ -298,6 +322,36 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3EVO)
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// PPM / UART2 RX
|
||||
{ TIM8, GPIOA, Pin_15, TIM_Channel_1, TIM8_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource15, GPIO_AF_2}, // PPM
|
||||
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // PWM1
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM2
|
||||
{ TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PWM3
|
||||
{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM4
|
||||
{ TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM5
|
||||
{ TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2}, // PWM6
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM7
|
||||
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM8
|
||||
|
||||
// UART3 RX/TX
|
||||
{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
|
||||
{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
|
||||
|
||||
// IR / LED Strip Pad
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO_TIMER / LED_STRIP
|
||||
};
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15))
|
||||
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
|
||||
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM15)
|
||||
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(MOTOLAB)
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 - PA4 - *TIM3_CH2
|
||||
|
|
|
@ -748,35 +748,6 @@ STATIC_UNIT_TESTED void servoMixer(void)
|
|||
|
||||
#endif
|
||||
|
||||
void acroPlusApply(void) {
|
||||
int axis;
|
||||
|
||||
for (axis = 0; axis < 2; axis++) {
|
||||
int16_t factor;
|
||||
fix12_t wowFactor;
|
||||
int16_t rcCommandDeflection = constrain(rcCommand[axis], -500, 500); // Limit stick input to 500 (rcCommand 100)
|
||||
int16_t acroPlusStickOffset = rxConfig->acroPlusOffset * 5;
|
||||
int16_t motorRange = escAndServoConfig->maxthrottle - escAndServoConfig->minthrottle;
|
||||
if (feature(FEATURE_3D)) motorRange = (motorRange - (flight3DConfig->deadband3d_high - flight3DConfig->deadband3d_low)) / 2;
|
||||
|
||||
/* acro plus factor handling */
|
||||
if (rxConfig->acroPlusFactor && ABS(rcCommandDeflection) > acroPlusStickOffset + 10) {
|
||||
if (rcCommandDeflection > 0) {
|
||||
rcCommandDeflection -= acroPlusStickOffset;
|
||||
} else {
|
||||
rcCommandDeflection += acroPlusStickOffset;
|
||||
}
|
||||
wowFactor = qConstruct(ABS(rcCommandDeflection) * rxConfig->acroPlusFactor / 100, 500);
|
||||
factor = qMultiply(wowFactor, (rcCommandDeflection * motorRange) / 500);
|
||||
wowFactor = Q12 - wowFactor;
|
||||
} else {
|
||||
wowFactor = Q12;
|
||||
factor = 0;
|
||||
}
|
||||
axisPID[axis] = factor + qMultiply(wowFactor, axisPID[axis]);
|
||||
}
|
||||
}
|
||||
|
||||
void mixTable(void)
|
||||
{
|
||||
uint32_t i;
|
||||
|
@ -785,10 +756,6 @@ void mixTable(void)
|
|||
|
||||
bool isFailsafeActive = failsafeIsActive(); // TODO - Find out if failsafe checks are really needed here in mixer code
|
||||
|
||||
if (IS_RC_MODE_ACTIVE(BOXACROPLUS)) {
|
||||
acroPlusApply();
|
||||
}
|
||||
|
||||
if (motorCount >= 4 && mixerConfig->yaw_jump_prevention_limit < YAW_JUMP_PREVENTION_LIMIT_HIGH) {
|
||||
// prevent "yaw jump" during yaw correction
|
||||
axisPID[YAW] = constrain(axisPID[YAW], -mixerConfig->yaw_jump_prevention_limit - ABS(rcCommand[YAW]), mixerConfig->yaw_jump_prevention_limit + ABS(rcCommand[YAW]));
|
||||
|
|
|
@ -58,10 +58,8 @@ int16_t axisPID[3];
|
|||
int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
||||
#endif
|
||||
|
||||
#define DELTA_MAX_SAMPLES 12
|
||||
|
||||
// PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction
|
||||
uint8_t dynP8[3], dynI8[3], dynD8[3], PIDweight[3];
|
||||
uint8_t PIDweight[3];
|
||||
|
||||
static int32_t errorGyroI[3], errorGyroILimit[3];
|
||||
static float errorGyroIf[3], errorGyroIfLimit[3];
|
||||
|
@ -81,6 +79,20 @@ void setTargetPidLooptime(uint8_t pidProcessDenom) {
|
|||
targetPidLooptime = targetLooptime * pidProcessDenom;
|
||||
}
|
||||
|
||||
float calculateExpoPlus(int axis, rxConfig_t *rxConfig) {
|
||||
float propFactor;
|
||||
float superExpoFactor;
|
||||
|
||||
if (axis == YAW && !rxConfig->superExpoYawMode) {
|
||||
propFactor = 1.0f;
|
||||
} else {
|
||||
superExpoFactor = (axis == YAW) ? rxConfig->superExpoFactorYaw : rxConfig->superExpoFactor;
|
||||
propFactor = 1.0f - ((superExpoFactor / 100.0f) * (ABS(rcCommand[axis]) / 500.0f));
|
||||
}
|
||||
|
||||
return propFactor;
|
||||
}
|
||||
|
||||
void pidResetErrorAngle(void)
|
||||
{
|
||||
errorAngleI[ROLL] = 0;
|
||||
|
@ -107,54 +119,34 @@ void pidResetErrorGyroState(uint8_t resetOption)
|
|||
}
|
||||
}
|
||||
|
||||
void scaleItermToRcInput(int axis, pidProfile_t *pidProfile) {
|
||||
float rcCommandReflection = (float)rcCommand[axis] / 500.0f;
|
||||
static float iTermScaler[3] = {1.0f, 1.0f, 1.0f};
|
||||
static float antiWindUpIncrement = 0;
|
||||
float getdT (void) {
|
||||
static float dT;
|
||||
if (!dT) dT = (float)targetPidLooptime * 0.000001f;
|
||||
|
||||
if (!antiWindUpIncrement) antiWindUpIncrement = (0.001 / 500) * targetPidLooptime; // Calculate increment for 500ms period
|
||||
|
||||
if (ABS(rcCommandReflection) > 0.7f && (!flightModeFlags)) { /* scaling should not happen in level modes */
|
||||
/* Reset Iterm on high stick inputs. No scaling necessary here */
|
||||
iTermScaler[axis] = 0.0f;
|
||||
errorGyroI[axis] = 0;
|
||||
errorGyroIf[axis] = 0.0f;
|
||||
} else {
|
||||
/* Prevent rapid windup during acro recoveries. Slowly enable Iterm for period of 500ms */
|
||||
if (iTermScaler[axis] < 1) {
|
||||
iTermScaler[axis] = constrainf(iTermScaler[axis] + antiWindUpIncrement, 0.0f, 1.0f);
|
||||
if (pidProfile->pidController != PID_CONTROLLER_LUX_FLOAT) {
|
||||
errorGyroI[axis] *= iTermScaler[axis];
|
||||
} else {
|
||||
errorGyroIf[axis] *= iTermScaler[axis];
|
||||
}
|
||||
}
|
||||
}
|
||||
return dT;
|
||||
}
|
||||
|
||||
const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
|
||||
|
||||
static biquad_t deltaBiQuadState[3];
|
||||
static bool deltaStateIsSet;
|
||||
static filterStatePt1_t deltaFilterState[3];
|
||||
static filterStatePt1_t yawFilterState;
|
||||
|
||||
static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
float RateError, AngleRate, gyroRate;
|
||||
float ITerm,PTerm,DTerm;
|
||||
static float lastErrorForDelta[3];
|
||||
static float previousDelta[3][DELTA_MAX_SAMPLES];
|
||||
static float previousAverageDelta[3];
|
||||
float delta, deltaSum;
|
||||
int axis, deltaCount;
|
||||
static float lastRate[3][PID_LAST_RATE_COUNT];
|
||||
float delta;
|
||||
int axis;
|
||||
float horizonLevelStrength = 1;
|
||||
|
||||
float dT = (float)targetPidLooptime * 0.000001f;
|
||||
float tpaFactor = PIDweight[0] / 100.0f; // tpa is now float
|
||||
|
||||
if (!deltaStateIsSet && pidProfile->dterm_lpf_hz) {
|
||||
for (axis = 0; axis < 3; axis++) BiQuadNewLpf(pidProfile->dterm_lpf_hz, &deltaBiQuadState[axis], targetPidLooptime);
|
||||
deltaStateIsSet = true;
|
||||
}
|
||||
// Scaling factors for Pids to match rewrite and use same defaults
|
||||
static const float luxPTermScale = 1.0f / 128;
|
||||
static const float luxITermScale = 1000000.0f / 0x1000000;
|
||||
static const float luxDTermScale = (0.000001f * (float)0xFFFF) / 508;
|
||||
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
// Figure out the raw stick positions
|
||||
|
@ -163,10 +155,10 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
const int32_t mostDeflectedPos = MAX(stickPosAil, stickPosEle);
|
||||
// Progressively turn off the horizon self level strength as the stick is banged over
|
||||
horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection
|
||||
if(pidProfile->H_sensitivity == 0){
|
||||
if(pidProfile->D8[PIDLEVEL] == 0){
|
||||
horizonLevelStrength = 0;
|
||||
} else {
|
||||
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->H_sensitivity)) + 1, 0, 1);
|
||||
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->D8[PIDLEVEL])) + 1, 0, 1);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -176,31 +168,31 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
|
||||
if (axis == FD_YAW) {
|
||||
// YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate
|
||||
AngleRate = (float)((rate + 10) * rcCommand[YAW]) / 50.0f;
|
||||
AngleRate = (float)((rate + 47) * rcCommand[YAW]) / 32.0f;
|
||||
} else {
|
||||
// ACRO mode, control is GYRO based, direct sticks control is applied to rate PID
|
||||
AngleRate = (float)((rate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max roll/pitch rate
|
||||
AngleRate = (float)((rate + 27) * rcCommand[axis]) / 16.0f; // 200dps to 1200dps max roll/pitch rate
|
||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
|
||||
// calculate error angle and limit the angle to the max inclination
|
||||
#ifdef GPS
|
||||
const float errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
const float errorAngle = (constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]); // 16 bits is ok here
|
||||
#else
|
||||
const float errorAngle = (constrain(rcCommand[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
const float errorAngle = (constrain(2 * rcCommand[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]); // 16 bits is ok here
|
||||
#endif
|
||||
if (FLIGHT_MODE(ANGLE_MODE)) {
|
||||
// ANGLE mode - control is angle based, so control loop is needed
|
||||
AngleRate = errorAngle * pidProfile->A_level;
|
||||
AngleRate = errorAngle * pidProfile->P8[PIDLEVEL] / 16.0f;
|
||||
} else {
|
||||
// HORIZON mode - direct sticks control is applied to rate PID
|
||||
// mix up angle error to desired AngleRate to add a little auto-level feel
|
||||
AngleRate += errorAngle * pidProfile->H_level * horizonLevelStrength;
|
||||
AngleRate += errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 16.0f;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
gyroRate = gyroADC[axis] * gyro.scale; // gyro output scaled to dps
|
||||
gyroRate = gyroADC[axis] / 4.0f; // gyro output scaled to rewrite scale
|
||||
|
||||
// --------low-level gyro-based PID. ----------
|
||||
// Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
|
||||
|
@ -208,10 +200,12 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
// multiplication of rcCommand corresponds to changing the sticks scaling here
|
||||
RateError = AngleRate - gyroRate;
|
||||
|
||||
if (lowThrottlePidReduction) RateError /= 4;
|
||||
|
||||
// -----calculate P component
|
||||
PTerm = RateError * pidProfile->P_f[axis] * PIDweight[axis] / 100;
|
||||
if ((IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) {
|
||||
PTerm = (luxPTermScale * pidProfile->P8[axis] * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig));
|
||||
} else {
|
||||
PTerm = luxPTermScale * RateError * pidProfile->P8[axis] * tpaFactor;
|
||||
}
|
||||
|
||||
// Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply
|
||||
if((motorCount >= 4 && pidProfile->yaw_p_limit) && axis == YAW) {
|
||||
|
@ -219,15 +213,20 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
}
|
||||
|
||||
// -----calculate I component.
|
||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + RateError * dT * pidProfile->I_f[axis] * 10, -250.0f, 250.0f);
|
||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + luxITermScale * RateError * getdT() * pidProfile->I8[axis], -250.0f, 250.0f);
|
||||
|
||||
if (IS_RC_MODE_ACTIVE(BOXAIRMODE) || IS_RC_MODE_ACTIVE(BOXACROPLUS)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXACROPLUS)) scaleItermToRcInput(axis, pidProfile);
|
||||
if (antiWindupProtection || motorLimitReached) {
|
||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis], -errorGyroIfLimit[axis], errorGyroIfLimit[axis]);
|
||||
} else {
|
||||
errorGyroIfLimit[axis] = ABS(errorGyroIf[axis]);
|
||||
}
|
||||
if ((pidProfile->rollPitchItermResetAlways || IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) && axis != YAW) {
|
||||
if (ABS(gyroRate / 4.1f) >= pidProfile->rollPitchItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -ITERM_RESET_THRESHOLD, ITERM_RESET_THRESHOLD);
|
||||
}
|
||||
|
||||
if (axis == YAW) {
|
||||
if (ABS(gyroRate / 4.1f) >= pidProfile->yawItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -ITERM_RESET_THRESHOLD_YAW, ITERM_RESET_THRESHOLD_YAW);
|
||||
}
|
||||
|
||||
if (antiWindupProtection || motorLimitReached) {
|
||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis], -errorGyroIfLimit[axis], errorGyroIfLimit[axis]);
|
||||
} else {
|
||||
errorGyroIfLimit[axis] = ABS(errorGyroIf[axis]);
|
||||
}
|
||||
|
||||
// limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
|
||||
|
@ -235,36 +234,38 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
ITerm = errorGyroIf[axis];
|
||||
|
||||
//-----calculate D-term
|
||||
if (pidProfile->deltaMethod == DELTA_FROM_ERROR) {
|
||||
delta = RateError - lastErrorForDelta[axis];
|
||||
lastErrorForDelta[axis] = RateError;
|
||||
if (axis == YAW) {
|
||||
if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT());
|
||||
DTerm = 0;
|
||||
} else {
|
||||
delta = -(gyroRate - lastErrorForDelta[axis]); // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
|
||||
lastErrorForDelta[axis] = gyroRate;
|
||||
if (pidProfile->dterm_differentiator) {
|
||||
// Calculate derivative using noise-robust differentiator without time delay (one-sided or forward filters)
|
||||
// by Pavel Holoborodko, see http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
|
||||
// N=5: h[0] = 3/8, h[-1] = 1/2, h[-2] = -1/2, h[-3] = -3/4, h[-4] = 1/8, h[-5] = 1/4
|
||||
delta = -(3*gyroRate + 4*lastRate[axis][0] - 4*lastRate[axis][1] - 6*lastRate[axis][2] + 1*lastRate[axis][3] + 2*lastRate[axis][4]) / 8;
|
||||
for (int i = PID_LAST_RATE_COUNT - 1; i > 0; i--) {
|
||||
lastRate[axis][i] = lastRate[axis][i-1];
|
||||
}
|
||||
} else {
|
||||
// When DTerm low pass filter disabled apply moving average to reduce noise
|
||||
delta = -(gyroRate - lastRate[axis][0]);
|
||||
}
|
||||
|
||||
lastRate[axis][0] = gyroRate;
|
||||
|
||||
// Divide delta by targetLooptime to get differential (ie dr/dt)
|
||||
delta *= (1.0f / getdT());
|
||||
|
||||
// Filter delta
|
||||
if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1(delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT());
|
||||
|
||||
DTerm = constrainf(luxDTermScale * delta * (float)pidProfile->D8[axis] * tpaFactor, -300.0f, 300.0f);
|
||||
}
|
||||
|
||||
// Correct difference by cycle time. Cycle time is jittery (can be different 2 times), so calculated difference
|
||||
// would be scaled by different dt each time. Division by dT fixes that.
|
||||
delta *= (1.0f / dT);
|
||||
|
||||
if (deltaStateIsSet) {
|
||||
delta = applyBiQuadFilter(delta, &deltaBiQuadState[axis]);
|
||||
} else {
|
||||
// Apply moving average
|
||||
deltaSum = 0;
|
||||
for (deltaCount = pidProfile->dterm_average_count-1; deltaCount > 0; deltaCount--) previousDelta[axis][deltaCount] = previousDelta[axis][deltaCount-1];
|
||||
previousDelta[axis][0] = delta;
|
||||
for (deltaCount = 0; deltaCount < pidProfile->dterm_average_count; deltaCount++) deltaSum += previousDelta[axis][deltaCount];
|
||||
delta = ((deltaSum / pidProfile->dterm_average_count) + previousAverageDelta[axis]) / 2; // Keep same original scaling + double pass averaging
|
||||
previousAverageDelta[axis] = delta;
|
||||
}
|
||||
|
||||
DTerm = constrainf(delta * pidProfile->D_f[axis] * PIDweight[axis] / 100, -300.0f, 300.0f);
|
||||
|
||||
// -----calculate total PID output
|
||||
axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -1000, 1000);
|
||||
|
||||
if (lowThrottlePidReduction) axisPID[axis] /= 4;
|
||||
if (lowThrottlePidReduction) axisPID[axis] /= 3;
|
||||
|
||||
#ifdef GTUNE
|
||||
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
|
||||
|
@ -280,181 +281,18 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
}
|
||||
}
|
||||
|
||||
static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||
rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
|
||||
int axis, deltaCount, prop = 0;
|
||||
int32_t rc, error, errorAngle, delta, gyroError;
|
||||
int32_t PTerm, ITerm, PTermACC, ITermACC, DTerm;
|
||||
static int16_t lastErrorForDelta[2];
|
||||
static int32_t previousDelta[2][DELTA_MAX_SAMPLES];
|
||||
static int32_t previousAverageDelta[2];
|
||||
|
||||
if (!deltaStateIsSet && pidProfile->dterm_lpf_hz) {
|
||||
for (axis = 0; axis < 2; axis++) BiQuadNewLpf(pidProfile->dterm_lpf_hz, &deltaBiQuadState[axis], targetPidLooptime);
|
||||
deltaStateIsSet = true;
|
||||
}
|
||||
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
prop = MIN(MAX(ABS(rcCommand[PITCH]), ABS(rcCommand[ROLL])), 512);
|
||||
}
|
||||
|
||||
// PITCH & ROLL
|
||||
for (axis = 0; axis < 2; axis++) {
|
||||
|
||||
rc = rcCommand[axis] << 1;
|
||||
|
||||
if (lowThrottlePidReduction) rc /= 4;
|
||||
|
||||
gyroError = gyroADC[axis] / 4;
|
||||
|
||||
error = rc - gyroError;
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis] + ((error * (uint16_t)targetPidLooptime) >> 11) , -16000, +16000); // WindUp 16 bits is ok here
|
||||
|
||||
if (ABS(gyroADC[axis]) > (640 * 4)) {
|
||||
errorGyroI[axis] = 0;
|
||||
}
|
||||
|
||||
// Anti windup protection
|
||||
if (IS_RC_MODE_ACTIVE(BOXAIRMODE) || IS_RC_MODE_ACTIVE(BOXACROPLUS)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXACROPLUS)) scaleItermToRcInput(axis, pidProfile);
|
||||
if (antiWindupProtection || motorLimitReached) {
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis], -errorGyroILimit[axis], errorGyroILimit[axis]);
|
||||
} else {
|
||||
errorGyroILimit[axis] = ABS(errorGyroI[axis]);
|
||||
}
|
||||
}
|
||||
|
||||
ITerm = (errorGyroI[axis] >> 7) * pidProfile->I8[axis] >> 6; // 16 bits is ok here 16000/125 = 128 ; 128*250 = 32000
|
||||
|
||||
PTerm = (int32_t)rc * pidProfile->P8[axis] >> 6;
|
||||
|
||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { // axis relying on ACC
|
||||
// 50 degrees max inclination
|
||||
#ifdef GPS
|
||||
errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis];
|
||||
#else
|
||||
errorAngle = constrain(2 * rcCommand[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis];
|
||||
#endif
|
||||
|
||||
errorAngleI[axis] = constrain(errorAngleI[axis] + errorAngle, -10000, +10000); // WindUp //16 bits is ok here
|
||||
|
||||
PTermACC = ((int32_t)errorAngle * pidProfile->P8[PIDLEVEL]) >> 7; // 32 bits is needed for calculation: errorAngle*P8 could exceed 32768 16 bits is ok for result
|
||||
|
||||
int16_t limit = pidProfile->D8[PIDLEVEL] * 5;
|
||||
PTermACC = constrain(PTermACC, -limit, +limit);
|
||||
|
||||
ITermACC = ((int32_t)errorAngleI[axis] * pidProfile->I8[PIDLEVEL]) >> 12; // 32 bits is needed for calculation:10000*I8 could exceed 32768 16 bits is ok for result
|
||||
|
||||
ITerm = ITermACC + ((ITerm - ITermACC) * prop >> 9);
|
||||
PTerm = PTermACC + ((PTerm - PTermACC) * prop >> 9);
|
||||
}
|
||||
|
||||
PTerm -= ((int32_t)gyroError * dynP8[axis]) >> 6; // 32 bits is needed for calculation
|
||||
|
||||
//-----calculate D-term based on the configured approach (delta from measurement or deltafromError)
|
||||
if (pidProfile->deltaMethod == DELTA_FROM_ERROR) {
|
||||
delta = error - lastErrorForDelta[axis];
|
||||
lastErrorForDelta[axis] = error;
|
||||
} else { /* Delta from measurement */
|
||||
delta = -(gyroError - lastErrorForDelta[axis]);
|
||||
lastErrorForDelta[axis] = gyroError;
|
||||
}
|
||||
|
||||
// Scale delta to looptime
|
||||
delta = (delta * ((uint16_t) 0xFFFF)) / ((uint16_t)targetPidLooptime << 5);
|
||||
|
||||
if (deltaStateIsSet) {
|
||||
DTerm = lrintf(applyBiQuadFilter((float) delta, &deltaBiQuadState[axis])) * 3; // Keep same scaling as unfiltered delta
|
||||
} else {
|
||||
// Apply moving average
|
||||
DTerm = 0;
|
||||
for (deltaCount = pidProfile->dterm_average_count-1; deltaCount > 0; deltaCount--) previousDelta[axis][deltaCount] = previousDelta[axis][deltaCount-1];
|
||||
previousDelta[axis][0] = delta;
|
||||
for (deltaCount = 0; deltaCount < pidProfile->dterm_average_count; deltaCount++) DTerm += previousDelta[axis][deltaCount];
|
||||
DTerm = (((DTerm / pidProfile->dterm_average_count) << 1) + previousAverageDelta[axis]) >> 1; // Keep same original scaling + double pass averaging
|
||||
previousAverageDelta[axis] = DTerm;
|
||||
}
|
||||
|
||||
DTerm = ((int32_t)DTerm * dynD8[axis]) >> 5; // 32 bits is needed for calculation
|
||||
|
||||
axisPID[axis] = PTerm + ITerm + DTerm;
|
||||
|
||||
if (lowThrottlePidReduction) axisPID[axis] /= 4;
|
||||
|
||||
#ifdef GTUNE
|
||||
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
|
||||
calculate_Gtune(axis);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
axisPID_P[axis] = PTerm;
|
||||
axisPID_I[axis] = ITerm;
|
||||
axisPID_D[axis] = DTerm;
|
||||
#endif
|
||||
}
|
||||
|
||||
//YAW
|
||||
rc = (int32_t)rcCommand[FD_YAW] * (2 * controlRateConfig->rates[FD_YAW] + 30) >> 5;
|
||||
#ifdef ALIENWII32
|
||||
error = rc - gyroADC[FD_YAW];
|
||||
#else
|
||||
error = rc - (gyroADC[FD_YAW] / 4);
|
||||
#endif
|
||||
errorGyroI[FD_YAW] += (int32_t)error * pidProfile->I8[FD_YAW];
|
||||
errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW], 2 - ((int32_t)1 << 28), -2 + ((int32_t)1 << 28));
|
||||
if (ABS(rc) > 50) errorGyroI[FD_YAW] = 0;
|
||||
|
||||
PTerm = (int32_t)error * pidProfile->P8[FD_YAW] >> 6; // TODO: Bitwise shift on a signed integer is not recommended
|
||||
|
||||
// Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply
|
||||
if(motorCount >= 4 && pidProfile->yaw_p_limit < YAW_P_LIMIT_MAX) {
|
||||
PTerm = constrain(PTerm, -pidProfile->yaw_p_limit, pidProfile->yaw_p_limit);
|
||||
}
|
||||
|
||||
ITerm = constrain((int16_t)(errorGyroI[FD_YAW] >> 13), -GYRO_I_MAX, +GYRO_I_MAX);
|
||||
|
||||
axisPID[FD_YAW] = PTerm + ITerm;
|
||||
|
||||
if (lowThrottlePidReduction) axisPID[FD_YAW] /= 4;
|
||||
|
||||
#ifdef GTUNE
|
||||
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
|
||||
calculate_Gtune(FD_YAW);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
axisPID_P[FD_YAW] = PTerm;
|
||||
axisPID_I[FD_YAW] = ITerm;
|
||||
axisPID_D[FD_YAW] = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||
rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
|
||||
int axis, deltaCount;
|
||||
int32_t PTerm, ITerm, DTerm, delta, deltaSum;
|
||||
static int32_t lastErrorForDelta[3] = { 0, 0, 0 };
|
||||
static int32_t previousDelta[3][DELTA_MAX_SAMPLES];
|
||||
static int32_t previousAverageDelta[3];
|
||||
int axis;
|
||||
int32_t PTerm, ITerm, DTerm, delta;
|
||||
static int32_t lastRate[3][PID_LAST_RATE_COUNT];
|
||||
int32_t AngleRateTmp, RateError, gyroRate;
|
||||
|
||||
int8_t horizonLevelStrength = 100;
|
||||
|
||||
if (!deltaStateIsSet && pidProfile->dterm_lpf_hz) {
|
||||
for (axis = 0; axis < 3; axis++) BiQuadNewLpf(pidProfile->dterm_lpf_hz, &deltaBiQuadState[axis], targetPidLooptime);
|
||||
deltaStateIsSet = true;
|
||||
}
|
||||
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
// Figure out the raw stick positions
|
||||
const int32_t stickPosAil = ABS(getRcStickDeflection(FD_ROLL, rxConfig->midrc));
|
||||
|
@ -474,7 +312,7 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co
|
|||
// -----Get the desired angle rate depending on flight mode
|
||||
if (axis == FD_YAW) {
|
||||
// YAW is always gyro-controlled (MAG correction is applied to rcCommand)
|
||||
AngleRateTmp = ((int32_t)(rate + 27) * rcCommand[YAW]) >> 5;
|
||||
AngleRateTmp = ((int32_t)(rate + 47) * rcCommand[YAW]) >> 5;
|
||||
} else {
|
||||
AngleRateTmp = ((int32_t)(rate + 27) * rcCommand[axis]) >> 4;
|
||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
|
||||
|
@ -504,10 +342,12 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co
|
|||
gyroRate = gyroADC[axis] / 4;
|
||||
RateError = AngleRateTmp - gyroRate;
|
||||
|
||||
if (lowThrottlePidReduction) RateError /= 4;
|
||||
|
||||
// -----calculate P component
|
||||
PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7;
|
||||
if ((IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) {
|
||||
PTerm = (pidProfile->P8[axis] * PIDweight[axis] / 100) * (AngleRateTmp - (int32_t)(gyroRate * calculateExpoPlus(axis, rxConfig))) >> 7;
|
||||
} else {
|
||||
PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7;
|
||||
}
|
||||
|
||||
// Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply
|
||||
if((motorCount >= 4 && pidProfile->yaw_p_limit) && axis == YAW) {
|
||||
|
@ -525,48 +365,55 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co
|
|||
// I coefficient (I8) moved before integration to make limiting independent from PID settings
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13);
|
||||
|
||||
if (IS_RC_MODE_ACTIVE(BOXAIRMODE) || IS_RC_MODE_ACTIVE(BOXACROPLUS)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXACROPLUS)) scaleItermToRcInput(axis, pidProfile);
|
||||
if (antiWindupProtection || motorLimitReached) {
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis], -errorGyroILimit[axis], errorGyroILimit[axis]);
|
||||
} else {
|
||||
errorGyroILimit[axis] = ABS(errorGyroI[axis]);
|
||||
}
|
||||
if ((pidProfile->rollPitchItermResetAlways || IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) && axis != YAW) {
|
||||
if (ABS(gyroRate *10 / 41) >= pidProfile->rollPitchItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], -ITERM_RESET_THRESHOLD, ITERM_RESET_THRESHOLD);
|
||||
}
|
||||
|
||||
if (axis == YAW) {
|
||||
if (ABS(gyroRate * 10 / 41) >= pidProfile->yawItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], -ITERM_RESET_THRESHOLD_YAW, ITERM_RESET_THRESHOLD_YAW);
|
||||
}
|
||||
|
||||
if (antiWindupProtection || motorLimitReached) {
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis], -errorGyroILimit[axis], errorGyroILimit[axis]);
|
||||
} else {
|
||||
errorGyroILimit[axis] = ABS(errorGyroI[axis]);
|
||||
}
|
||||
|
||||
ITerm = errorGyroI[axis] >> 13;
|
||||
|
||||
//-----calculate D-term
|
||||
if (pidProfile->deltaMethod == DELTA_FROM_ERROR) {
|
||||
delta = RateError - lastErrorForDelta[axis]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
|
||||
lastErrorForDelta[axis] = RateError;
|
||||
if (axis == YAW) {
|
||||
if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT());
|
||||
DTerm = 0;
|
||||
} else {
|
||||
delta = -(gyroRate - lastErrorForDelta[axis]); // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
|
||||
lastErrorForDelta[axis] = gyroRate;
|
||||
}
|
||||
|
||||
// Correct difference by cycle time. Cycle time is jittery (can be different 2 times), so calculated difference
|
||||
// would be scaled by different dt each time. Division by dT fixes that.
|
||||
delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 6;
|
||||
if (pidProfile->dterm_differentiator) {
|
||||
// Calculate derivative using noise-robust differentiator without time delay (one-sided or forward filters)
|
||||
// by Pavel Holoborodko, see http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
|
||||
// N=5: h[0] = 3/8, h[-1] = 1/2, h[-2] = -1/2, h[-3] = -3/4, h[-4] = 1/8, h[-5] = 1/4
|
||||
delta = -(3*gyroRate + 4*lastRate[axis][0] - 4*lastRate[axis][1] - 6*lastRate[axis][2] + 1*lastRate[axis][3] + 2*lastRate[axis][4]) / 8;
|
||||
for (int i = PID_LAST_RATE_COUNT - 1; i > 0; i--) {
|
||||
lastRate[axis][i] = lastRate[axis][i-1];
|
||||
}
|
||||
} else {
|
||||
// When DTerm low pass filter disabled apply moving average to reduce noise
|
||||
delta = -(gyroRate - lastRate[axis][0]);
|
||||
}
|
||||
|
||||
if (deltaStateIsSet) {
|
||||
delta = lrintf(applyBiQuadFilter((float) delta, &deltaBiQuadState[axis])) * 3; // Keep same scaling as unfiltered delta
|
||||
} else {
|
||||
// Apply moving average
|
||||
deltaSum = 0;
|
||||
for (deltaCount = pidProfile->dterm_average_count -1; deltaCount > 0; deltaCount--) previousDelta[axis][deltaCount] = previousDelta[axis][deltaCount-1];
|
||||
previousDelta[axis][0] = delta;
|
||||
for (deltaCount = 0; deltaCount < pidProfile->dterm_average_count; deltaCount++) deltaSum += previousDelta[axis][deltaCount];
|
||||
delta = (((deltaSum / pidProfile->dterm_average_count) << 1) + previousAverageDelta[axis]) >> 1; // Keep same original scaling + double pass averaging
|
||||
previousAverageDelta[axis] = delta;
|
||||
}
|
||||
lastRate[axis][0] = gyroRate;
|
||||
|
||||
DTerm = (delta * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;
|
||||
// Divide delta by targetLooptime to get differential (ie dr/dt)
|
||||
delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 5;
|
||||
|
||||
// Filter delta
|
||||
if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1((float)delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT());
|
||||
|
||||
DTerm = (delta * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;
|
||||
}
|
||||
|
||||
// -----calculate total PID output
|
||||
axisPID[axis] = PTerm + ITerm + DTerm;
|
||||
|
||||
if (lowThrottlePidReduction) axisPID[axis] /= 4;
|
||||
if (lowThrottlePidReduction) axisPID[axis] /= 3;
|
||||
|
||||
#ifdef GTUNE
|
||||
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
|
||||
|
@ -591,9 +438,6 @@ void pidSetController(pidControllerType_e type)
|
|||
break;
|
||||
case PID_CONTROLLER_LUX_FLOAT:
|
||||
pid_controller = pidLuxFloat;
|
||||
break;
|
||||
case PID_CONTROLLER_MW23:
|
||||
pid_controller = pidMultiWii23;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -20,7 +20,11 @@
|
|||
|
||||
#define GYRO_I_MAX 256 // Gyro I limiter
|
||||
#define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter
|
||||
#define YAW_P_LIMIT_MAX 300 // Maximum value for yaw P limiter
|
||||
#define YAW_P_LIMIT_MAX 400 // Maximum value for yaw P limiter
|
||||
|
||||
#define PID_LAST_RATE_COUNT 7
|
||||
#define ITERM_RESET_THRESHOLD 20
|
||||
#define ITERM_RESET_THRESHOLD_YAW 10
|
||||
|
||||
typedef enum {
|
||||
PIDROLL,
|
||||
|
@ -37,8 +41,7 @@ typedef enum {
|
|||
} pidIndex_e;
|
||||
|
||||
typedef enum {
|
||||
PID_CONTROLLER_MW23,
|
||||
PID_CONTROLLER_MWREWRITE,
|
||||
PID_CONTROLLER_MWREWRITE = 1,
|
||||
PID_CONTROLLER_LUX_FLOAT,
|
||||
PID_COUNT
|
||||
} pidControllerType_e;
|
||||
|
@ -54,6 +57,12 @@ typedef enum {
|
|||
RESET_ITERM_AND_REDUCE_PID
|
||||
} pidErrorResetOption_e;
|
||||
|
||||
typedef enum {
|
||||
SUPEREXPO_YAW_OFF = 0,
|
||||
SUPEREXPO_YAW_ON,
|
||||
SUPEREXPO_YAW_ALWAYS
|
||||
} pidSuperExpoYaw_e;
|
||||
|
||||
#define IS_PID_CONTROLLER_FP_BASED(pidController) (pidController == 2)
|
||||
|
||||
typedef struct pidProfile_s {
|
||||
|
@ -63,17 +72,16 @@ typedef struct pidProfile_s {
|
|||
uint8_t I8[PID_ITEM_COUNT];
|
||||
uint8_t D8[PID_ITEM_COUNT];
|
||||
|
||||
float P_f[3]; // float p i and d factors for lux float pid controller
|
||||
float I_f[3];
|
||||
float D_f[3];
|
||||
float A_level;
|
||||
float H_level;
|
||||
uint8_t H_sensitivity;
|
||||
|
||||
float dterm_lpf_hz; // Delta Filter in hz
|
||||
uint8_t deltaMethod; // Alternative delta Calculation
|
||||
float yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy
|
||||
uint16_t rollPitchItermResetRate; // Experimental threshold for resetting iterm for pitch and roll on certain rates
|
||||
uint8_t rollPitchItermResetAlways; // Reset Iterm also without SUPER EXPO
|
||||
uint16_t yawItermResetRate; // Experimental threshold for resetting iterm for yaw on certain rates
|
||||
uint16_t yaw_p_limit;
|
||||
uint8_t dterm_average_count; // Configurable delta count for dterm
|
||||
uint8_t dterm_differentiator;
|
||||
|
||||
#ifdef GTUNE
|
||||
uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune
|
||||
|
|
|
@ -290,7 +290,6 @@ static const char pidnames[] =
|
|||
"MAG;"
|
||||
"VEL;";
|
||||
|
||||
#define DATA_BUFFER_SIZE 64
|
||||
#define BOARD_IDENTIFIER_LENGTH 4
|
||||
|
||||
typedef struct box_e {
|
||||
|
@ -332,8 +331,8 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
|
|||
{ CHECKBOX_ITEM_COUNT, NULL, 0xFF }
|
||||
};
|
||||
|
||||
uint8_t readData[DATA_BUFFER_SIZE];
|
||||
uint8_t writeData[DATA_BUFFER_SIZE];
|
||||
extern uint8_t readData[DATA_BUFFER_SIZE];
|
||||
extern uint8_t writeData[DATA_BUFFER_SIZE];
|
||||
|
||||
/*************************************************************************************************/
|
||||
uint8_t writeBufferPointer = 1;
|
||||
|
@ -354,7 +353,12 @@ static void bstWrite32(uint32_t data)
|
|||
bstWrite16((uint16_t)(data >> 16));
|
||||
}
|
||||
|
||||
uint8_t readBufferPointer = 3;
|
||||
uint8_t readBufferPointer = 4;
|
||||
static uint8_t bstCurrentAddress(void)
|
||||
{
|
||||
return readData[0];
|
||||
}
|
||||
|
||||
static uint8_t bstRead8(void)
|
||||
{
|
||||
return readData[readBufferPointer++] & 0xff;
|
||||
|
@ -376,12 +380,12 @@ static uint32_t bstRead32(void)
|
|||
|
||||
static uint8_t bstReadDataSize(void)
|
||||
{
|
||||
return readData[0]-4;
|
||||
return readData[1]-5;
|
||||
}
|
||||
|
||||
static uint8_t bstReadCRC(void)
|
||||
{
|
||||
return readData[readData[0]];
|
||||
return readData[readData[1]+1];
|
||||
}
|
||||
|
||||
static void s_struct(uint8_t *cb, uint8_t siz)
|
||||
|
@ -495,6 +499,7 @@ static void bstWriteDataflashReadReply(uint32_t address, uint8_t size)
|
|||
|
||||
/*************************************************************************************************/
|
||||
#define BST_USB_COMMANDS 0x0A
|
||||
#define BST_GENERAL_HEARTBEAT 0x0B
|
||||
#define BST_USB_DEVICE_INFO_REQUEST 0x04 //Handshake
|
||||
#define BST_USB_DEVICE_INFO_FRAME 0x05 //Handshake
|
||||
#define BST_READ_COMMANDS 0x26
|
||||
|
@ -695,29 +700,10 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
bstWrite8(currentControlRateProfile->rcYawExpo8);
|
||||
break;
|
||||
case BST_PID:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid
|
||||
for (i = 0; i < 3; i++) {
|
||||
bstWrite8(constrain(lrintf(currentProfile->pidProfile.P_f[i] * 10.0f), 0, 250));
|
||||
bstWrite8(constrain(lrintf(currentProfile->pidProfile.I_f[i] * 100.0f), 0, 250));
|
||||
bstWrite8(constrain(lrintf(currentProfile->pidProfile.D_f[i] * 1000.0f), 0, 100));
|
||||
}
|
||||
for (i = 3; i < PID_ITEM_COUNT; i++) {
|
||||
if (i == PIDLEVEL) {
|
||||
bstWrite8(constrain(lrintf(currentProfile->pidProfile.A_level * 10.0f), 0, 250));
|
||||
bstWrite8(constrain(lrintf(currentProfile->pidProfile.H_level * 10.0f), 0, 250));
|
||||
bstWrite8(constrain(lrintf(currentProfile->pidProfile.H_sensitivity), 0, 250));
|
||||
} else {
|
||||
bstWrite8(currentProfile->pidProfile.P8[i]);
|
||||
bstWrite8(currentProfile->pidProfile.I8[i]);
|
||||
bstWrite8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
bstWrite8(currentProfile->pidProfile.P8[i]);
|
||||
bstWrite8(currentProfile->pidProfile.I8[i]);
|
||||
bstWrite8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
bstWrite8(currentProfile->pidProfile.P8[i]);
|
||||
bstWrite8(currentProfile->pidProfile.I8[i]);
|
||||
bstWrite8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
break;
|
||||
case BST_PIDNAMES:
|
||||
|
@ -999,7 +985,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
|||
// we do not know how to handle the (valid) message, indicate error BST
|
||||
return false;
|
||||
}
|
||||
bstSlaveWrite(writeData);
|
||||
//bstSlaveWrite(writeData);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -1061,30 +1047,11 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
pidSetController(currentProfile->pidProfile.pidController);
|
||||
break;
|
||||
case BST_SET_PID:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {
|
||||
for (i = 0; i < 3; i++) {
|
||||
currentProfile->pidProfile.P_f[i] = (float)bstRead8() / 10.0f;
|
||||
currentProfile->pidProfile.I_f[i] = (float)bstRead8() / 100.0f;
|
||||
currentProfile->pidProfile.D_f[i] = (float)bstRead8() / 1000.0f;
|
||||
}
|
||||
for (i = 3; i < PID_ITEM_COUNT; i++) {
|
||||
if (i == PIDLEVEL) {
|
||||
currentProfile->pidProfile.A_level = (float)bstRead8() / 10.0f;
|
||||
currentProfile->pidProfile.H_level = (float)bstRead8() / 10.0f;
|
||||
currentProfile->pidProfile.H_sensitivity = bstRead8();
|
||||
} else {
|
||||
currentProfile->pidProfile.P8[i] = bstRead8();
|
||||
currentProfile->pidProfile.I8[i] = bstRead8();
|
||||
currentProfile->pidProfile.D8[i] = bstRead8();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
currentProfile->pidProfile.P8[i] = bstRead8();
|
||||
currentProfile->pidProfile.I8[i] = bstRead8();
|
||||
currentProfile->pidProfile.D8[i] = bstRead8();
|
||||
}
|
||||
}
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
currentProfile->pidProfile.P8[i] = bstRead8();
|
||||
currentProfile->pidProfile.I8[i] = bstRead8();
|
||||
currentProfile->pidProfile.D8[i] = bstRead8();
|
||||
}
|
||||
break;
|
||||
case BST_SET_MODE_RANGE:
|
||||
i = bstRead8();
|
||||
|
@ -1236,7 +1203,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
if (ARMING_FLAG(ARMED)) {
|
||||
ret = BST_FAILED;
|
||||
bstWrite8(ret);
|
||||
bstSlaveWrite(writeData);
|
||||
//bstSlaveWrite(writeData);
|
||||
return ret;
|
||||
}
|
||||
writeEEPROM();
|
||||
|
@ -1465,7 +1432,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
|||
ret = BST_FAILED;
|
||||
}
|
||||
bstWrite8(ret);
|
||||
bstSlaveWrite(writeData);
|
||||
//bstSlaveWrite(writeData);
|
||||
if(ret == BST_FAILED)
|
||||
return false;
|
||||
return true;
|
||||
|
@ -1482,18 +1449,19 @@ static bool bstSlaveUSBCommandFeedback(/*uint8_t bstFeedback*/)
|
|||
bstWrite8(FC_VERSION_MINOR); //Firmware ID
|
||||
bstWrite8(0x00);
|
||||
bstWrite8(0x00);
|
||||
bstSlaveWrite(writeData);
|
||||
//bstSlaveWrite(writeData);
|
||||
return true;
|
||||
}
|
||||
|
||||
/*************************************************************************************************/
|
||||
bool slaveModeOn = false;
|
||||
static void bstSlaveProcessInCommand(void)
|
||||
#define BST_RESET_TIME 1.2*1000*1000 //micro-seconds
|
||||
uint32_t resetBstTimer = 0;
|
||||
bool needResetCheck = true;
|
||||
|
||||
void bstProcessInCommand(void)
|
||||
{
|
||||
if(bstSlaveRead(readData)) {
|
||||
slaveModeOn = true;
|
||||
readBufferPointer = 1;
|
||||
//Check if the CRC match
|
||||
readBufferPointer = 2;
|
||||
if(bstCurrentAddress() == CLEANFLIGHT_FC) {
|
||||
if(bstReadCRC() == CRC8 && bstRead8()==BST_USB_COMMANDS) {
|
||||
uint8_t i;
|
||||
writeBufferPointer = 1;
|
||||
|
@ -1519,8 +1487,23 @@ static void bstSlaveProcessInCommand(void)
|
|||
break;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
slaveModeOn = false;
|
||||
} else if(bstCurrentAddress() == 0x00) {
|
||||
if(bstReadCRC() == CRC8 && bstRead8()==BST_GENERAL_HEARTBEAT) {
|
||||
resetBstTimer = micros();
|
||||
needResetCheck = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void resetBstChecker(void)
|
||||
{
|
||||
if(needResetCheck) {
|
||||
uint32_t currentTimer = micros();
|
||||
if(currentTimer >= (resetBstTimer + BST_RESET_TIME))
|
||||
{
|
||||
bstTimeoutUserCallback();
|
||||
needResetCheck = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1555,26 +1538,13 @@ void taskBstMasterProcess(void)
|
|||
if(sensors(SENSOR_GPS) && !bstWriteBusy())
|
||||
writeGpsPositionPrameToBST();
|
||||
}
|
||||
}
|
||||
|
||||
void taskBstCheckCommand(void)
|
||||
{
|
||||
//Check if the BST input command available to out address
|
||||
bstSlaveProcessInCommand();
|
||||
|
||||
bstMasterWriteLoop();
|
||||
if (isRebootScheduled) {
|
||||
stopMotors();
|
||||
handleOneshotFeatureChangeOnRestart();
|
||||
systemReset();
|
||||
}
|
||||
}
|
||||
|
||||
void bstMasterWriteLoop(void);
|
||||
void taskBstReadWrite(void)
|
||||
{
|
||||
taskBstCheckCommand();
|
||||
if(!slaveModeOn)
|
||||
bstMasterWriteLoop();
|
||||
resetBstChecker();
|
||||
}
|
||||
|
||||
/*************************************************************************************************/
|
||||
|
|
|
@ -19,13 +19,10 @@
|
|||
|
||||
#include "drivers/bus_bst.h"
|
||||
|
||||
void taskBstReadWrite(void);
|
||||
void bstProcessInCommand(void);
|
||||
void bstSlaveProcessInCommand(void);
|
||||
void taskBstMasterProcess(void);
|
||||
void taskBstCheckCommand(void);
|
||||
|
||||
//void writeGpsPositionPrameToBST(void);
|
||||
//void writeGPSTimeFrameToBST(void);
|
||||
//void writeDataToBST(void);
|
||||
bool writeGpsPositionPrameToBST(void);
|
||||
bool writeRollPitchYawToBST(void);
|
||||
bool writeRCChannelToBST(void);
|
||||
|
|
|
@ -245,6 +245,19 @@ const ledConfig_t defaultLedStripConfig[] = {
|
|||
{ CALCULATE_LED_XY( 1, 1), 3, LED_FUNCTION_THRUST_RING},
|
||||
{ CALCULATE_LED_XY( 1, 1), 3, LED_FUNCTION_THRUST_RING},
|
||||
};
|
||||
#elif defined(USE_COLIBTI_RACE_LED_DEFAULT_CONFIG)
|
||||
const ledConfig_t defaultLedStripConfig[] = {
|
||||
{ CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
};
|
||||
#else
|
||||
const ledConfig_t defaultLedStripConfig[] = {
|
||||
{ CALCULATE_LED_XY(15, 15), 0, LED_DIRECTION_SOUTH | LED_DIRECTION_EAST | LED_FUNCTION_INDICATOR | LED_FUNCTION_ARM_STATE },
|
||||
|
|
|
@ -113,10 +113,13 @@ bool areSticksInApModePosition(uint16_t ap_mode)
|
|||
|
||||
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||
{
|
||||
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (rxConfig->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig->midrc + deadband3d_throttle)))
|
||||
return THROTTLE_LOW;
|
||||
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig->mincheck))
|
||||
return THROTTLE_LOW;
|
||||
if (feature(FEATURE_3D) && !IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH)) {
|
||||
if ((rcData[THROTTLE] > (rxConfig->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig->midrc + deadband3d_throttle)))
|
||||
return THROTTLE_LOW;
|
||||
} else {
|
||||
if (rcData[THROTTLE] < rxConfig->mincheck)
|
||||
return THROTTLE_LOW;
|
||||
}
|
||||
|
||||
return THROTTLE_HIGH;
|
||||
}
|
||||
|
@ -476,7 +479,6 @@ void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adj
|
|||
|
||||
void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustmentFunction, int delta) {
|
||||
int newValue;
|
||||
float newFloatValue;
|
||||
|
||||
if (delta > 0) {
|
||||
beeperConfirmationBeeps(2);
|
||||
|
@ -523,114 +525,63 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm
|
|||
break;
|
||||
case ADJUSTMENT_PITCH_ROLL_P:
|
||||
case ADJUSTMENT_PITCH_P:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->P_f[PIDPITCH] + (float)(delta / 100.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P_f[PIDPITCH] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_PITCH_P, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->P8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P8[PIDPITCH] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_P, newValue);
|
||||
}
|
||||
newValue = constrain((int)pidProfile->P8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P8[PIDPITCH] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_P, newValue);
|
||||
|
||||
if (adjustmentFunction == ADJUSTMENT_PITCH_P) {
|
||||
break;
|
||||
}
|
||||
// follow though for combined ADJUSTMENT_PITCH_ROLL_P
|
||||
case ADJUSTMENT_ROLL_P:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->P_f[PIDROLL] + (float)(delta / 100.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P_f[PIDROLL] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_ROLL_P, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->P8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P8[PIDROLL] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_P, newValue);
|
||||
}
|
||||
newValue = constrain((int)pidProfile->P8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P8[PIDROLL] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_P, newValue);
|
||||
break;
|
||||
case ADJUSTMENT_PITCH_ROLL_I:
|
||||
case ADJUSTMENT_PITCH_I:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->I_f[PIDPITCH] + (float)(delta / 100.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I_f[PIDPITCH] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_PITCH_I, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->I8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I8[PIDPITCH] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_I, newValue);
|
||||
}
|
||||
newValue = constrain((int)pidProfile->I8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I8[PIDPITCH] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_I, newValue);
|
||||
|
||||
if (adjustmentFunction == ADJUSTMENT_PITCH_I) {
|
||||
break;
|
||||
}
|
||||
// follow though for combined ADJUSTMENT_PITCH_ROLL_I
|
||||
case ADJUSTMENT_ROLL_I:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->I_f[PIDROLL] + (float)(delta / 100.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I_f[PIDROLL] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_ROLL_I, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->I8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I8[PIDROLL] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_I, newValue);
|
||||
}
|
||||
newValue = constrain((int)pidProfile->I8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I8[PIDROLL] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_I, newValue);
|
||||
break;
|
||||
case ADJUSTMENT_PITCH_ROLL_D:
|
||||
case ADJUSTMENT_PITCH_D:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->D_f[PIDPITCH] + (float)(delta / 1000.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D_f[PIDPITCH] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_PITCH_D, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->D8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D8[PIDPITCH] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_D, newValue);
|
||||
}
|
||||
newValue = constrain((int)pidProfile->D8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D8[PIDPITCH] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_D, newValue);
|
||||
|
||||
if (adjustmentFunction == ADJUSTMENT_PITCH_D) {
|
||||
break;
|
||||
}
|
||||
// follow though for combined ADJUSTMENT_PITCH_ROLL_D
|
||||
case ADJUSTMENT_ROLL_D:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->D_f[PIDROLL] + (float)(delta / 1000.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D_f[PIDROLL] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_ROLL_D, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->D8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D8[PIDROLL] = newValue;
|
||||
newValue = constrain((int)pidProfile->D8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D8[PIDROLL] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_D, newValue);
|
||||
}
|
||||
break;
|
||||
case ADJUSTMENT_YAW_P:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->P_f[PIDYAW] + (float)(delta / 100.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P_f[PIDYAW] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_YAW_P, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->P8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P8[PIDYAW] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_P, newValue);
|
||||
}
|
||||
newValue = constrain((int)pidProfile->P8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->P8[PIDYAW] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_P, newValue);
|
||||
break;
|
||||
case ADJUSTMENT_YAW_I:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->I_f[PIDYAW] + (float)(delta / 100.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I_f[PIDYAW] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_YAW_I, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->I8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I8[PIDYAW] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_I, newValue);
|
||||
}
|
||||
newValue = constrain((int)pidProfile->I8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->I8[PIDYAW] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_I, newValue);
|
||||
break;
|
||||
case ADJUSTMENT_YAW_D:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||
newFloatValue = constrainf(pidProfile->D_f[PIDYAW] + (float)(delta / 1000.0f), 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D_f[PIDYAW] = newFloatValue;
|
||||
blackboxLogInflightAdjustmentEventFloat(ADJUSTMENT_YAW_D, newFloatValue);
|
||||
} else {
|
||||
newValue = constrain((int)pidProfile->D8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D8[PIDYAW] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_D, newValue);
|
||||
}
|
||||
newValue = constrain((int)pidProfile->D8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in serial_cli.c
|
||||
pidProfile->D8[PIDYAW] = newValue;
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_D, newValue);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
|
|
|
@ -49,7 +49,7 @@ typedef enum {
|
|||
BOXBLACKBOX,
|
||||
BOXFAILSAFE,
|
||||
BOXAIRMODE,
|
||||
BOXACROPLUS,
|
||||
BOXSUPEREXPO,
|
||||
BOX3DDISABLESWITCH,
|
||||
CHECKBOX_ITEM_COUNT
|
||||
} boxId_e;
|
||||
|
|
|
@ -1,216 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
|
||||
* by Nathan Tsoi <nathan@vertile.com>
|
||||
* Several updates by 4712 in order to optimize interaction with BLHeliSuite
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SERIAL_1WIRE
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/system.h"
|
||||
#include "io/serial_1wire.h"
|
||||
#include "io/beeper.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "flight/mixer.h"
|
||||
|
||||
uint8_t escCount; // we detect the hardware dynamically
|
||||
|
||||
static escHardware_t escHardware[MAX_PWM_MOTORS];
|
||||
|
||||
static void gpio_set_mode(GPIO_TypeDef* gpio, uint16_t pin, GPIO_Mode mode) {
|
||||
gpio_config_t cfg;
|
||||
cfg.pin = pin;
|
||||
cfg.mode = mode;
|
||||
cfg.speed = Speed_10MHz;
|
||||
gpioInit(gpio, &cfg);
|
||||
}
|
||||
|
||||
static uint32_t GetPinPos(uint32_t pin) {
|
||||
uint32_t pinPos;
|
||||
for (pinPos = 0; pinPos < 16; pinPos++) {
|
||||
uint32_t pinMask = (0x1 << pinPos);
|
||||
if (pin & pinMask) {
|
||||
// pos found
|
||||
return pinPos;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
void usb1WireInitialize()
|
||||
{
|
||||
escCount = 0;
|
||||
memset(&escHardware,0,sizeof(escHardware));
|
||||
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmGetOutputConfiguration();
|
||||
for (volatile uint8_t i = 0; i < pwmOutputConfiguration->outputCount; i++) {
|
||||
if ((pwmOutputConfiguration->portConfigurations[i].flags & PWM_PF_MOTOR) == PWM_PF_MOTOR) {
|
||||
if(motor[pwmOutputConfiguration->portConfigurations[i].index] >0 ) {
|
||||
escHardware[escCount].gpio = pwmOutputConfiguration->portConfigurations[i].timerHardware->gpio;
|
||||
escHardware[escCount].pin = pwmOutputConfiguration->portConfigurations[i].timerHardware->pin;
|
||||
escHardware[escCount].pinpos = GetPinPos(escHardware[escCount].pin);
|
||||
gpio_set_mode(escHardware[escCount].gpio,escHardware[escCount].pin, Mode_IPU); //GPIO_Mode_IPU
|
||||
escCount++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef STM32F10X
|
||||
static volatile uint32_t in_cr_mask, out_cr_mask;
|
||||
|
||||
static __IO uint32_t *cr;
|
||||
static void gpio_prep_vars(uint32_t escIndex)
|
||||
{
|
||||
GPIO_TypeDef *gpio = escHardware[escIndex].gpio;
|
||||
uint32_t pinpos = escHardware[escIndex].pinpos;
|
||||
// mask out extra bits from pinmode, leaving just CNF+MODE
|
||||
uint32_t inmode = Mode_IPU & 0x0F;
|
||||
uint32_t outmode = (Mode_Out_PP & 0x0F) | Speed_10MHz;
|
||||
// reference CRL or CRH, depending whether pin number is 0..7 or 8..15
|
||||
cr = &gpio->CRL + (pinpos / 8);
|
||||
// offset to CNF and MODE portions of CRx register
|
||||
uint32_t shift = (pinpos % 8) * 4;
|
||||
// Read out current CRx value
|
||||
in_cr_mask = out_cr_mask = *cr;
|
||||
// Mask out 4 bits
|
||||
in_cr_mask &= ~(0xF << shift);
|
||||
out_cr_mask &= ~(0xF << shift);
|
||||
// save current pinmode
|
||||
in_cr_mask |= inmode << shift;
|
||||
out_cr_mask |= outmode << shift;
|
||||
}
|
||||
|
||||
static void gpioSetOne(uint32_t escIndex, GPIO_Mode mode) {
|
||||
// reference CRL or CRH, depending whether pin number is 0..7 or 8..15
|
||||
if (mode == Mode_IPU) {
|
||||
*cr = in_cr_mask;
|
||||
escHardware[escIndex].gpio->ODR |= escHardware[escIndex].pin;
|
||||
}
|
||||
else {
|
||||
*cr = out_cr_mask;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#define ESC_HI(escIndex) ((escHardware[escIndex].gpio->IDR & escHardware[escIndex].pin) != (uint32_t)Bit_RESET)
|
||||
#define RX_HI ((S1W_RX_GPIO->IDR & S1W_RX_PIN) != (uint32_t)Bit_RESET)
|
||||
#define ESC_SET_HI(escIndex) escHardware[escIndex].gpio->BSRR = escHardware[escIndex].pin
|
||||
#define ESC_SET_LO(escIndex) escHardware[escIndex].gpio->BRR = escHardware[escIndex].pin
|
||||
#define TX_SET_HIGH S1W_TX_GPIO->BSRR = S1W_TX_PIN
|
||||
#define TX_SET_LO S1W_TX_GPIO->BRR = S1W_TX_PIN
|
||||
|
||||
#ifdef STM32F303xC
|
||||
#define ESC_INPUT(escIndex) escHardware[escIndex].gpio->MODER &= ~(GPIO_MODER_MODER0 << (escHardware[escIndex].pinpos * 2))
|
||||
#define ESC_OUTPUT(escIndex) escHardware[escIndex].gpio->MODER |= GPIO_Mode_OUT << (escHardware[escIndex].pinpos * 2)
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X
|
||||
#define ESC_INPUT(escIndex) gpioSetOne(escIndex, Mode_IPU)
|
||||
#define ESC_OUTPUT(escIndex) gpioSetOne(escIndex, Mode_Out_PP)
|
||||
#endif
|
||||
|
||||
#define RX_LED_OFF LED0_OFF
|
||||
#define RX_LED_ON LED0_ON
|
||||
#define TX_LED_OFF LED1_OFF
|
||||
#define TX_LED_ON LED1_ON
|
||||
|
||||
// This method translates 2 wires (a tx and rx line) to 1 wire, by letting the
|
||||
// RX line control when data should be read or written from the single line
|
||||
void usb1WirePassthrough(uint8_t escIndex)
|
||||
{
|
||||
#ifdef BEEPER
|
||||
// fix for buzzer often starts beeping continuously when the ESCs are read
|
||||
// switch beeper silent here
|
||||
beeperSilence();
|
||||
#endif
|
||||
|
||||
// disable all interrupts
|
||||
__disable_irq();
|
||||
|
||||
// prepare MSP UART port for direct pin access
|
||||
// reset all the pins
|
||||
GPIO_ResetBits(S1W_RX_GPIO, S1W_RX_PIN);
|
||||
GPIO_ResetBits(S1W_TX_GPIO, S1W_TX_PIN);
|
||||
// configure gpio
|
||||
gpio_set_mode(S1W_RX_GPIO, S1W_RX_PIN, Mode_IPU);
|
||||
gpio_set_mode(S1W_TX_GPIO, S1W_TX_PIN, Mode_Out_PP);
|
||||
|
||||
#ifdef STM32F10X
|
||||
// reset our gpio register pointers and bitmask values
|
||||
gpio_prep_vars(escIndex);
|
||||
#endif
|
||||
|
||||
ESC_OUTPUT(escIndex);
|
||||
ESC_SET_HI(escIndex);
|
||||
TX_SET_HIGH;
|
||||
// Wait for programmer to go from 1 -> 0 indicating incoming data
|
||||
while(RX_HI);
|
||||
|
||||
while(1) {
|
||||
// A new iteration on this loop starts when we have data from the programmer (read_programmer goes low)
|
||||
// Setup escIndex pin to send data, pullup is the default
|
||||
ESC_OUTPUT(escIndex);
|
||||
// Write the first bit
|
||||
ESC_SET_LO(escIndex);
|
||||
// Echo on the programmer tx line
|
||||
TX_SET_LO;
|
||||
//set LEDs
|
||||
RX_LED_OFF;
|
||||
TX_LED_ON;
|
||||
// Wait for programmer to go 0 -> 1
|
||||
uint32_t ct=3333;
|
||||
while(!RX_HI) {
|
||||
if (ct > 0) ct--; // count down until 0;
|
||||
// check for low time ->ct=3333 ~600uS //byte LO time for 0 @ 19200 baud -> 9*52 uS => 468.75uS
|
||||
// App must send a 0 at 9600 baud (or lower) which has a LO time of at 104uS (or more) > 0 = 937.5uS LO
|
||||
// BLHeliSuite will use 4800 baud
|
||||
}
|
||||
// Programmer is high, end of bit
|
||||
// At first Echo to the esc, which helps to charge input capacities at ESC
|
||||
ESC_SET_HI(escIndex);
|
||||
// Listen to the escIndex, input mode, pullup resistor is on
|
||||
gpio_set_mode(escHardware[escIndex].gpio, escHardware[escIndex].pin, Mode_IPU);
|
||||
TX_LED_OFF;
|
||||
if (ct==0) break; //we reached zero
|
||||
// Listen to the escIndex while there is no data from the programmer
|
||||
while (RX_HI) {
|
||||
if (ESC_HI(escIndex)) {
|
||||
TX_SET_HIGH;
|
||||
RX_LED_OFF;
|
||||
}
|
||||
else {
|
||||
TX_SET_LO;
|
||||
RX_LED_ON;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// we get here in case ct reached zero
|
||||
TX_SET_HIGH;
|
||||
RX_LED_OFF;
|
||||
// Enable all irq (for Hardware UART)
|
||||
__enable_irq();
|
||||
return;
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,842 @@
|
|||
/*
|
||||
* 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/>.
|
||||
* Author: 4712
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdarg.h>
|
||||
|
||||
#include "platform.h"
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/serial_4way.h"
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#include "io/serial_4way_avrootloader.h"
|
||||
#endif
|
||||
#if defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
|
||||
#include "io/serial_4way_stk500v2.h"
|
||||
#endif
|
||||
|
||||
#define USE_TXRX_LED
|
||||
|
||||
#ifdef USE_TXRX_LED
|
||||
#define RX_LED_OFF LED0_OFF
|
||||
#define RX_LED_ON LED0_ON
|
||||
#ifdef LED1
|
||||
#define TX_LED_OFF LED1_OFF
|
||||
#define TX_LED_ON LED1_ON
|
||||
#else
|
||||
#define TX_LED_OFF LED0_OFF
|
||||
#define TX_LED_ON LED0_ON
|
||||
#endif
|
||||
#else
|
||||
#define RX_LED_OFF
|
||||
#define RX_LED_ON
|
||||
#define TX_LED_OFF
|
||||
#define TX_LED_ON
|
||||
#endif
|
||||
|
||||
#define SERIAL_4WAY_INTERFACE_NAME_STR "m4wFCIntf"
|
||||
// *** change to adapt Revision
|
||||
#define SERIAL_4WAY_VER_MAIN 14
|
||||
#define SERIAL_4WAY_VER_SUB_1 (uint8_t) 4
|
||||
#define SERIAL_4WAY_VER_SUB_2 (uint8_t) 04
|
||||
|
||||
#define SERIAL_4WAY_PROTOCOL_VER 106
|
||||
// *** end
|
||||
|
||||
#if (SERIAL_4WAY_VER_MAIN > 24)
|
||||
#error "beware of SERIAL_4WAY_VER_SUB_1 is uint8_t"
|
||||
#endif
|
||||
|
||||
#define SERIAL_4WAY_VERSION (uint16_t) ((SERIAL_4WAY_VER_MAIN * 1000) + (SERIAL_4WAY_VER_SUB_1 * 100) + SERIAL_4WAY_VER_SUB_2)
|
||||
|
||||
#define SERIAL_4WAY_VERSION_HI (uint8_t) (SERIAL_4WAY_VERSION / 100)
|
||||
#define SERIAL_4WAY_VERSION_LO (uint8_t) (SERIAL_4WAY_VERSION % 100)
|
||||
|
||||
static uint8_t escCount;
|
||||
|
||||
escHardware_t escHardware[MAX_PWM_MOTORS];
|
||||
|
||||
uint8_t selected_esc;
|
||||
|
||||
uint8_32_u DeviceInfo;
|
||||
|
||||
#define DeviceInfoSize 4
|
||||
|
||||
inline bool isMcuConnected(void)
|
||||
{
|
||||
return (DeviceInfo.bytes[0] > 0);
|
||||
}
|
||||
|
||||
inline bool isEscHi(uint8_t selEsc)
|
||||
{
|
||||
return (digitalIn(escHardware[selEsc].gpio, escHardware[selEsc].pin) != Bit_RESET);
|
||||
}
|
||||
inline bool isEscLo(uint8_t selEsc)
|
||||
{
|
||||
return (digitalIn(escHardware[selEsc].gpio, escHardware[selEsc].pin) == Bit_RESET);
|
||||
}
|
||||
|
||||
inline void setEscHi(uint8_t selEsc)
|
||||
{
|
||||
digitalHi(escHardware[selEsc].gpio, escHardware[selEsc].pin);
|
||||
}
|
||||
|
||||
inline void setEscLo(uint8_t selEsc)
|
||||
{
|
||||
digitalLo(escHardware[selEsc].gpio, escHardware[selEsc].pin);
|
||||
}
|
||||
|
||||
inline void setEscInput(uint8_t selEsc)
|
||||
{
|
||||
gpioInit(escHardware[selEsc].gpio, &escHardware[selEsc].gpio_config_INPUT);
|
||||
}
|
||||
|
||||
inline void setEscOutput(uint8_t selEsc)
|
||||
{
|
||||
gpioInit(escHardware[selEsc].gpio, &escHardware[selEsc].gpio_config_OUTPUT);
|
||||
}
|
||||
|
||||
static uint32_t GetPinPos(uint32_t pin)
|
||||
{
|
||||
uint32_t pinPos;
|
||||
for (pinPos = 0; pinPos < 16; pinPos++) {
|
||||
uint32_t pinMask = (0x1 << pinPos);
|
||||
if (pin & pinMask) {
|
||||
return pinPos;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t Initialize4WayInterface(void)
|
||||
{
|
||||
// StopPwmAllMotors();
|
||||
pwmDisableMotors();
|
||||
escCount = 0;
|
||||
memset(&escHardware, 0, sizeof(escHardware));
|
||||
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmGetOutputConfiguration();
|
||||
for (volatile uint8_t i = 0; i < pwmOutputConfiguration->outputCount; i++) {
|
||||
if ((pwmOutputConfiguration->portConfigurations[i].flags & PWM_PF_MOTOR) == PWM_PF_MOTOR) {
|
||||
if(motor[pwmOutputConfiguration->portConfigurations[i].index] > 0) {
|
||||
escHardware[escCount].gpio = pwmOutputConfiguration->portConfigurations[i].timerHardware->gpio;
|
||||
escHardware[escCount].pin = pwmOutputConfiguration->portConfigurations[i].timerHardware->pin;
|
||||
escHardware[escCount].pinpos = GetPinPos(escHardware[escCount].pin);
|
||||
escHardware[escCount].gpio_config_INPUT.pin = escHardware[escCount].pin;
|
||||
escHardware[escCount].gpio_config_INPUT.speed = Speed_2MHz; // see pwmOutConfig()
|
||||
escHardware[escCount].gpio_config_INPUT.mode = Mode_IPU;
|
||||
escHardware[escCount].gpio_config_OUTPUT = escHardware[escCount].gpio_config_INPUT;
|
||||
escHardware[escCount].gpio_config_OUTPUT.mode = Mode_Out_PP;
|
||||
setEscInput(escCount);
|
||||
setEscHi(escCount);
|
||||
escCount++;
|
||||
}
|
||||
}
|
||||
}
|
||||
return escCount;
|
||||
}
|
||||
|
||||
void DeInitialize4WayInterface(void)
|
||||
{
|
||||
while (escCount > 0) {
|
||||
escCount--;
|
||||
escHardware[escCount].gpio_config_OUTPUT.mode = Mode_AF_PP; // see pwmOutConfig()
|
||||
setEscOutput(escCount);
|
||||
setEscLo(escCount);
|
||||
}
|
||||
pwmEnableMotors();
|
||||
}
|
||||
|
||||
|
||||
#define SET_DISCONNECTED DeviceInfo.words[0] = 0
|
||||
|
||||
#define INTF_MODE_IDX 3 // index for DeviceInfostate
|
||||
|
||||
// Interface related only
|
||||
// establish and test connection to the Interface
|
||||
|
||||
// Send Structure
|
||||
// ESC + CMD PARAM_LEN [PARAM (if len > 0)] CRC16_Hi CRC16_Lo
|
||||
// Return
|
||||
// ESC CMD PARAM_LEN [PARAM (if len > 0)] + ACK (uint8_t OK or ERR) + CRC16_Hi CRC16_Lo
|
||||
|
||||
#define cmd_Remote_Escape 0x2E // '.'
|
||||
#define cmd_Local_Escape 0x2F // '/'
|
||||
|
||||
// Test Interface still present
|
||||
#define cmd_InterfaceTestAlive 0x30 // '0' alive
|
||||
// RETURN: ACK
|
||||
|
||||
// get Protocol Version Number 01..255
|
||||
#define cmd_ProtocolGetVersion 0x31 // '1' version
|
||||
// RETURN: uint8_t VersionNumber + ACK
|
||||
|
||||
// get Version String
|
||||
#define cmd_InterfaceGetName 0x32 // '2' name
|
||||
// RETURN: String + ACK
|
||||
|
||||
//get Version Number 01..255
|
||||
#define cmd_InterfaceGetVersion 0x33 // '3' version
|
||||
// RETURN: uint8_t AVersionNumber + ACK
|
||||
|
||||
|
||||
// Exit / Restart Interface - can be used to switch to Box Mode
|
||||
#define cmd_InterfaceExit 0x34 // '4' exit
|
||||
// RETURN: ACK
|
||||
|
||||
// Reset the Device connected to the Interface
|
||||
#define cmd_DeviceReset 0x35 // '5' reset
|
||||
// RETURN: ACK
|
||||
|
||||
// Get the Device ID connected
|
||||
// #define cmd_DeviceGetID 0x36 //'6' device id removed since 06/106
|
||||
// RETURN: uint8_t DeviceID + ACK
|
||||
|
||||
// Initialize Flash Access for Device connected
|
||||
#define cmd_DeviceInitFlash 0x37 // '7' init flash access
|
||||
// RETURN: ACK
|
||||
|
||||
// Erase the whole Device Memory of connected Device
|
||||
#define cmd_DeviceEraseAll 0x38 // '8' erase all
|
||||
// RETURN: ACK
|
||||
|
||||
// Erase one Page of Device Memory of connected Device
|
||||
#define cmd_DevicePageErase 0x39 // '9' page erase
|
||||
// PARAM: uint8_t APageNumber
|
||||
// RETURN: ACK
|
||||
|
||||
// Read to Buffer from Device Memory of connected Device // Buffer Len is Max 256 Bytes
|
||||
// BuffLen = 0 means 256 Bytes
|
||||
#define cmd_DeviceRead 0x3A // ':' read Device
|
||||
// PARAM: uint8_t ADRESS_Hi + ADRESS_Lo + BuffLen[0..255]
|
||||
// RETURN: PARAM: uint8_t ADRESS_Hi + ADRESS_Lo + BUffLen + Buffer[0..255] ACK
|
||||
|
||||
// Write to Buffer for Device Memory of connected Device // Buffer Len is Max 256 Bytes
|
||||
// BuffLen = 0 means 256 Bytes
|
||||
#define cmd_DeviceWrite 0x3B // ';' write
|
||||
// PARAM: uint8_t ADRESS_Hi + ADRESS_Lo + BUffLen + Buffer[0..255]
|
||||
// RETURN: ACK
|
||||
|
||||
// Set C2CK low infinite ) permanent Reset state
|
||||
#define cmd_DeviceC2CK_LOW 0x3C // '<'
|
||||
// RETURN: ACK
|
||||
|
||||
// Read to Buffer from Device Memory of connected Device //Buffer Len is Max 256 Bytes
|
||||
// BuffLen = 0 means 256 Bytes
|
||||
#define cmd_DeviceReadEEprom 0x3D // '=' read Device
|
||||
// PARAM: uint8_t ADRESS_Hi + ADRESS_Lo + BuffLen[0..255]
|
||||
// RETURN: PARAM: uint8_t ADRESS_Hi + ADRESS_Lo + BUffLen + Buffer[0..255] ACK
|
||||
|
||||
// Write to Buffer for Device Memory of connected Device // Buffer Len is Max 256 Bytes
|
||||
// BuffLen = 0 means 256 Bytes
|
||||
#define cmd_DeviceWriteEEprom 0x3E // '>' write
|
||||
// PARAM: uint8_t ADRESS_Hi + ADRESS_Lo + BUffLen + Buffer[0..255]
|
||||
// RETURN: ACK
|
||||
|
||||
// Set Interface Mode
|
||||
#define cmd_InterfaceSetMode 0x3F // '?'
|
||||
// #define imC2 0
|
||||
// #define imSIL_BLB 1
|
||||
// #define imATM_BLB 2
|
||||
// #define imSK 3
|
||||
// PARAM: uint8_t Mode
|
||||
// RETURN: ACK or ACK_I_INVALID_CHANNEL
|
||||
|
||||
// responses
|
||||
#define ACK_OK 0x00
|
||||
// #define ACK_I_UNKNOWN_ERROR 0x01
|
||||
#define ACK_I_INVALID_CMD 0x02
|
||||
#define ACK_I_INVALID_CRC 0x03
|
||||
#define ACK_I_VERIFY_ERROR 0x04
|
||||
// #define ACK_D_INVALID_COMMAND 0x05
|
||||
// #define ACK_D_COMMAND_FAILED 0x06
|
||||
// #define ACK_D_UNKNOWN_ERROR 0x07
|
||||
|
||||
#define ACK_I_INVALID_CHANNEL 0x08
|
||||
#define ACK_I_INVALID_PARAM 0x09
|
||||
#define ACK_D_GENERAL_ERROR 0x0F
|
||||
|
||||
/* Copyright (c) 2002, 2003, 2004 Marek Michalkiewicz
|
||||
Copyright (c) 2005, 2007 Joerg Wunsch
|
||||
Copyright (c) 2013 Dave Hylands
|
||||
Copyright (c) 2013 Frederic Nadeau
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in
|
||||
the documentation and/or other materials provided with the
|
||||
distribution.
|
||||
|
||||
* Neither the name of the copyright holders nor the names of
|
||||
contributors may be used to endorse or promote products derived
|
||||
from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
||||
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGE. */
|
||||
uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data) {
|
||||
int i;
|
||||
|
||||
crc = crc ^ ((uint16_t)data << 8);
|
||||
for (i=0; i < 8; i++){
|
||||
if (crc & 0x8000)
|
||||
crc = (crc << 1) ^ 0x1021;
|
||||
else
|
||||
crc <<= 1;
|
||||
}
|
||||
return crc;
|
||||
}
|
||||
// * End copyright
|
||||
|
||||
|
||||
#define ATMEL_DEVICE_MATCH ((pDeviceInfo->words[0] == 0x9307) || (pDeviceInfo->words[0] == 0x930A) || \
|
||||
(pDeviceInfo->words[0] == 0x930F) || (pDeviceInfo->words[0] == 0x940B))
|
||||
|
||||
#define SILABS_DEVICE_MATCH ((pDeviceInfo->words[0] == 0xF310)||(pDeviceInfo->words[0] ==0xF330) || \
|
||||
(pDeviceInfo->words[0] == 0xF410) || (pDeviceInfo->words[0] == 0xF390) || \
|
||||
(pDeviceInfo->words[0] == 0xF850) || (pDeviceInfo->words[0] == 0xE8B1) || \
|
||||
(pDeviceInfo->words[0] == 0xE8B2))
|
||||
|
||||
static uint8_t CurrentInterfaceMode;
|
||||
|
||||
static uint8_t Connect(uint8_32_u *pDeviceInfo)
|
||||
{
|
||||
for (uint8_t I = 0; I < 3; ++I) {
|
||||
#if (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
|
||||
if (Stk_ConnectEx(pDeviceInfo) && ATMEL_DEVICE_MATCH) {
|
||||
CurrentInterfaceMode = imSK;
|
||||
return 1;
|
||||
} else {
|
||||
if (BL_ConnectEx(pDeviceInfo)) {
|
||||
if SILABS_DEVICE_MATCH {
|
||||
CurrentInterfaceMode = imSIL_BLB;
|
||||
return 1;
|
||||
} else if ATMEL_DEVICE_MATCH {
|
||||
CurrentInterfaceMode = imATM_BLB;
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
#elif defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER)
|
||||
if (BL_ConnectEx(pDeviceInfo)) {
|
||||
if SILABS_DEVICE_MATCH {
|
||||
CurrentInterfaceMode = imSIL_BLB;
|
||||
return 1;
|
||||
} else if ATMEL_DEVICE_MATCH {
|
||||
CurrentInterfaceMode = imATM_BLB;
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
#elif defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
|
||||
if (Stk_ConnectEx(pDeviceInfo)) {
|
||||
CurrentInterfaceMode = imSK;
|
||||
if ATMEL_DEVICE_MATCH return 1;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static mspPort_t *_mspPort;
|
||||
static bufWriter_t *_writer;
|
||||
|
||||
static uint8_t ReadByte(void) {
|
||||
// need timeout?
|
||||
while (!serialRxBytesWaiting(_mspPort->port));
|
||||
return serialRead(_mspPort->port);
|
||||
}
|
||||
|
||||
static uint8_16_u CRC_in;
|
||||
static uint8_t ReadByteCrc(void) {
|
||||
uint8_t b = ReadByte();
|
||||
CRC_in.word = _crc_xmodem_update(CRC_in.word, b);
|
||||
return b;
|
||||
}
|
||||
static void WriteByte(uint8_t b){
|
||||
bufWriterAppend(_writer, b);
|
||||
}
|
||||
|
||||
static uint8_16_u CRCout;
|
||||
static void WriteByteCrc(uint8_t b){
|
||||
WriteByte(b);
|
||||
CRCout.word = _crc_xmodem_update(CRCout.word, b);
|
||||
}
|
||||
|
||||
void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
|
||||
|
||||
uint8_t ParamBuf[256];
|
||||
uint8_t ESC;
|
||||
uint8_t I_PARAM_LEN;
|
||||
uint8_t CMD;
|
||||
uint8_t ACK_OUT;
|
||||
uint8_16_u CRC_check;
|
||||
uint8_16_u Dummy;
|
||||
uint8_t O_PARAM_LEN;
|
||||
uint8_t *O_PARAM;
|
||||
uint8_t *InBuff;
|
||||
ioMem_t ioMem;
|
||||
|
||||
_mspPort = mspPort;
|
||||
_writer = bufwriter;
|
||||
|
||||
// Start here with UART Main loop
|
||||
#ifdef BEEPER
|
||||
// fix for buzzer often starts beeping continuously when the ESCs are read
|
||||
// switch beeper silent here
|
||||
beeperSilence();
|
||||
#endif
|
||||
bool isExitScheduled = false;
|
||||
|
||||
while(1) {
|
||||
// restart looking for new sequence from host
|
||||
do {
|
||||
CRC_in.word = 0;
|
||||
ESC = ReadByteCrc();
|
||||
} while (ESC != cmd_Local_Escape);
|
||||
|
||||
RX_LED_ON;
|
||||
|
||||
Dummy.word = 0;
|
||||
O_PARAM = &Dummy.bytes[0];
|
||||
O_PARAM_LEN = 1;
|
||||
CMD = ReadByteCrc();
|
||||
ioMem.D_FLASH_ADDR_H = ReadByteCrc();
|
||||
ioMem.D_FLASH_ADDR_L = ReadByteCrc();
|
||||
I_PARAM_LEN = ReadByteCrc();
|
||||
|
||||
InBuff = ParamBuf;
|
||||
uint8_t i = I_PARAM_LEN;
|
||||
do {
|
||||
*InBuff = ReadByteCrc();
|
||||
InBuff++;
|
||||
i--;
|
||||
} while (i != 0);
|
||||
|
||||
CRC_check.bytes[1] = ReadByte();
|
||||
CRC_check.bytes[0] = ReadByte();
|
||||
|
||||
RX_LED_OFF;
|
||||
|
||||
if(CRC_check.word == CRC_in.word) {
|
||||
ACK_OUT = ACK_OK;
|
||||
} else {
|
||||
ACK_OUT = ACK_I_INVALID_CRC;
|
||||
}
|
||||
|
||||
if (ACK_OUT == ACK_OK)
|
||||
{
|
||||
// wtf.D_FLASH_ADDR_H=Adress_H;
|
||||
// wtf.D_FLASH_ADDR_L=Adress_L;
|
||||
ioMem.D_PTR_I = ParamBuf;
|
||||
|
||||
switch(CMD) {
|
||||
// ******* Interface related stuff *******
|
||||
case cmd_InterfaceTestAlive:
|
||||
{
|
||||
if (isMcuConnected()){
|
||||
switch(CurrentInterfaceMode)
|
||||
{
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case imATM_BLB:
|
||||
case imSIL_BLB:
|
||||
{
|
||||
if (!BL_SendCMDKeepAlive()) { // SetStateDisconnected() included
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case imSK:
|
||||
{
|
||||
if (!Stk_SignOn()) { // SetStateDisconnected();
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
default:
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
if ( ACK_OUT != ACK_OK) SET_DISCONNECTED;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case cmd_ProtocolGetVersion:
|
||||
{
|
||||
// Only interface itself, no matter what Device
|
||||
Dummy.bytes[0] = SERIAL_4WAY_PROTOCOL_VER;
|
||||
break;
|
||||
}
|
||||
|
||||
case cmd_InterfaceGetName:
|
||||
{
|
||||
// Only interface itself, no matter what Device
|
||||
// O_PARAM_LEN=16;
|
||||
O_PARAM_LEN = strlen(SERIAL_4WAY_INTERFACE_NAME_STR);
|
||||
O_PARAM = (uint8_t *)SERIAL_4WAY_INTERFACE_NAME_STR;
|
||||
break;
|
||||
}
|
||||
|
||||
case cmd_InterfaceGetVersion:
|
||||
{
|
||||
// Only interface itself, no matter what Device
|
||||
// Dummy = iUart_res_InterfVersion;
|
||||
O_PARAM_LEN = 2;
|
||||
Dummy.bytes[0] = SERIAL_4WAY_VERSION_HI;
|
||||
Dummy.bytes[1] = SERIAL_4WAY_VERSION_LO;
|
||||
break;
|
||||
}
|
||||
case cmd_InterfaceExit:
|
||||
{
|
||||
isExitScheduled = true;
|
||||
break;
|
||||
}
|
||||
case cmd_InterfaceSetMode:
|
||||
{
|
||||
#if defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
|
||||
if ((ParamBuf[0] <= imSK) && (ParamBuf[0] >= imSIL_BLB)) {
|
||||
#elif defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER)
|
||||
if ((ParamBuf[0] <= imATM_BLB) && (ParamBuf[0] >= imSIL_BLB)) {
|
||||
#elif defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
|
||||
if (ParamBuf[0] == imSK) {
|
||||
#endif
|
||||
CurrentInterfaceMode = ParamBuf[0];
|
||||
} else {
|
||||
ACK_OUT = ACK_I_INVALID_PARAM;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case cmd_DeviceReset:
|
||||
{
|
||||
if (ParamBuf[0] < escCount) {
|
||||
// Channel may change here
|
||||
selected_esc = ParamBuf[0];
|
||||
}
|
||||
else {
|
||||
ACK_OUT = ACK_I_INVALID_CHANNEL;
|
||||
break;
|
||||
}
|
||||
switch (CurrentInterfaceMode)
|
||||
{
|
||||
case imSIL_BLB:
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case imATM_BLB:
|
||||
{
|
||||
BL_SendCMDRunRestartBootloader(&DeviceInfo);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case imSK:
|
||||
{
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
SET_DISCONNECTED;
|
||||
break;
|
||||
}
|
||||
case cmd_DeviceInitFlash:
|
||||
{
|
||||
SET_DISCONNECTED;
|
||||
if (ParamBuf[0] < escCount) {
|
||||
//Channel may change here
|
||||
//ESC_LO or ESC_HI; Halt state for prev channel
|
||||
selected_esc = ParamBuf[0];
|
||||
} else {
|
||||
ACK_OUT = ACK_I_INVALID_CHANNEL;
|
||||
break;
|
||||
}
|
||||
O_PARAM_LEN = DeviceInfoSize; //4
|
||||
O_PARAM = (uint8_t *)&DeviceInfo;
|
||||
if(Connect(&DeviceInfo)) {
|
||||
DeviceInfo.bytes[INTF_MODE_IDX] = CurrentInterfaceMode;
|
||||
} else {
|
||||
SET_DISCONNECTED;
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case cmd_DeviceEraseAll:
|
||||
{
|
||||
switch(CurrentInterfaceMode)
|
||||
{
|
||||
case imSK:
|
||||
{
|
||||
if (!Stk_Chip_Erase()) ACK_OUT=ACK_D_GENERAL_ERROR;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
ACK_OUT = ACK_I_INVALID_CMD;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case cmd_DevicePageErase:
|
||||
{
|
||||
switch (CurrentInterfaceMode)
|
||||
{
|
||||
case imSIL_BLB:
|
||||
{
|
||||
Dummy.bytes[0] = ParamBuf[0];
|
||||
//Address = Page * 512
|
||||
ioMem.D_FLASH_ADDR_H = (Dummy.bytes[0] << 1);
|
||||
ioMem.D_FLASH_ADDR_L = 0;
|
||||
if (!BL_PageErase(&ioMem)) ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
ACK_OUT = ACK_I_INVALID_CMD;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
//*** Device Memory Read Ops ***
|
||||
case cmd_DeviceRead:
|
||||
{
|
||||
ioMem.D_NUM_BYTES = ParamBuf[0];
|
||||
/*
|
||||
wtf.D_FLASH_ADDR_H=Adress_H;
|
||||
wtf.D_FLASH_ADDR_L=Adress_L;
|
||||
wtf.D_PTR_I = BUF_I;
|
||||
*/
|
||||
switch(CurrentInterfaceMode)
|
||||
{
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case imSIL_BLB:
|
||||
case imATM_BLB:
|
||||
{
|
||||
if(!BL_ReadFlash(CurrentInterfaceMode, &ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case imSK:
|
||||
{
|
||||
if(!Stk_ReadFlash(&ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
default:
|
||||
ACK_OUT = ACK_I_INVALID_CMD;
|
||||
}
|
||||
if (ACK_OUT == ACK_OK)
|
||||
{
|
||||
O_PARAM_LEN = ioMem.D_NUM_BYTES;
|
||||
O_PARAM = (uint8_t *)&ParamBuf;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case cmd_DeviceReadEEprom:
|
||||
{
|
||||
ioMem.D_NUM_BYTES = ParamBuf[0];
|
||||
/*
|
||||
wtf.D_FLASH_ADDR_H = Adress_H;
|
||||
wtf.D_FLASH_ADDR_L = Adress_L;
|
||||
wtf.D_PTR_I = BUF_I;
|
||||
*/
|
||||
switch (CurrentInterfaceMode)
|
||||
{
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case imATM_BLB:
|
||||
{
|
||||
if (!BL_ReadEEprom(&ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case imSK:
|
||||
{
|
||||
if (!Stk_ReadEEprom(&ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
default:
|
||||
ACK_OUT = ACK_I_INVALID_CMD;
|
||||
}
|
||||
if(ACK_OUT == ACK_OK)
|
||||
{
|
||||
O_PARAM_LEN = ioMem.D_NUM_BYTES;
|
||||
O_PARAM = (uint8_t *)&ParamBuf;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
//*** Device Memory Write Ops ***
|
||||
case cmd_DeviceWrite:
|
||||
{
|
||||
ioMem.D_NUM_BYTES = I_PARAM_LEN;
|
||||
/*
|
||||
wtf.D_FLASH_ADDR_H=Adress_H;
|
||||
wtf.D_FLASH_ADDR_L=Adress_L;
|
||||
wtf.D_PTR_I = BUF_I;
|
||||
*/
|
||||
switch (CurrentInterfaceMode)
|
||||
{
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case imSIL_BLB:
|
||||
case imATM_BLB:
|
||||
{
|
||||
if (!BL_WriteFlash(&ioMem)) {
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case imSK:
|
||||
{
|
||||
if (!Stk_WriteFlash(&ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case cmd_DeviceWriteEEprom:
|
||||
{
|
||||
ioMem.D_NUM_BYTES = I_PARAM_LEN;
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
/*
|
||||
wtf.D_FLASH_ADDR_H=Adress_H;
|
||||
wtf.D_FLASH_ADDR_L=Adress_L;
|
||||
wtf.D_PTR_I = BUF_I;
|
||||
*/
|
||||
switch (CurrentInterfaceMode)
|
||||
{
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case imSIL_BLB:
|
||||
{
|
||||
ACK_OUT = ACK_I_INVALID_CMD;
|
||||
break;
|
||||
}
|
||||
case imATM_BLB:
|
||||
{
|
||||
if (BL_WriteEEprom(&ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_OK;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case imSK:
|
||||
{
|
||||
if (Stk_WriteEEprom(&ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_OK;
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
ACK_OUT = ACK_I_INVALID_CMD;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
CRCout.word = 0;
|
||||
|
||||
TX_LED_ON;
|
||||
serialBeginWrite(_mspPort->port);
|
||||
WriteByteCrc(cmd_Remote_Escape);
|
||||
WriteByteCrc(CMD);
|
||||
WriteByteCrc(ioMem.D_FLASH_ADDR_H);
|
||||
WriteByteCrc(ioMem.D_FLASH_ADDR_L);
|
||||
WriteByteCrc(O_PARAM_LEN);
|
||||
|
||||
i=O_PARAM_LEN;
|
||||
do {
|
||||
WriteByteCrc(*O_PARAM);
|
||||
O_PARAM++;
|
||||
i--;
|
||||
} while (i > 0);
|
||||
|
||||
WriteByteCrc(ACK_OUT);
|
||||
WriteByte(CRCout.bytes[1]);
|
||||
WriteByte(CRCout.bytes[0]);
|
||||
serialEndWrite(_mspPort->port);
|
||||
bufWriterFlush(_writer);
|
||||
TX_LED_OFF;
|
||||
if (isExitScheduled) {
|
||||
DeInitialize4WayInterface();
|
||||
return;
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
|
||||
#endif
|
|
@ -0,0 +1,76 @@
|
|||
/*
|
||||
* 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/>.
|
||||
* Author: 4712
|
||||
*/
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#define USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
|
||||
#define imC2 0
|
||||
#define imSIL_BLB 1
|
||||
#define imATM_BLB 2
|
||||
#define imSK 3
|
||||
|
||||
typedef struct {
|
||||
GPIO_TypeDef* gpio;
|
||||
uint16_t pinpos;
|
||||
uint16_t pin;
|
||||
gpio_config_t gpio_config_INPUT;
|
||||
gpio_config_t gpio_config_OUTPUT;
|
||||
} escHardware_t;
|
||||
|
||||
extern uint8_t selected_esc;
|
||||
|
||||
bool isEscHi(uint8_t selEsc);
|
||||
bool isEscLo(uint8_t selEsc);
|
||||
void setEscHi(uint8_t selEsc);
|
||||
void setEscLo(uint8_t selEsc);
|
||||
void setEscInput(uint8_t selEsc);
|
||||
void setEscOutput(uint8_t selEsc);
|
||||
|
||||
#define ESC_IS_HI isEscHi(selected_esc)
|
||||
#define ESC_IS_LO isEscLo(selected_esc)
|
||||
#define ESC_SET_HI setEscHi(selected_esc)
|
||||
#define ESC_SET_LO setEscLo(selected_esc)
|
||||
#define ESC_INPUT setEscInput(selected_esc)
|
||||
#define ESC_OUTPUT setEscOutput(selected_esc)
|
||||
|
||||
typedef struct ioMem_s {
|
||||
uint8_t D_NUM_BYTES;
|
||||
uint8_t D_FLASH_ADDR_H;
|
||||
uint8_t D_FLASH_ADDR_L;
|
||||
uint8_t *D_PTR_I;
|
||||
} ioMem_t;
|
||||
|
||||
extern ioMem_t ioMem;
|
||||
|
||||
typedef union __attribute__ ((packed)) {
|
||||
uint8_t bytes[2];
|
||||
uint16_t word;
|
||||
} uint8_16_u;
|
||||
|
||||
typedef union __attribute__ ((packed)) {
|
||||
uint8_t bytes[4];
|
||||
uint16_t words[2];
|
||||
uint32_t dword;
|
||||
} uint8_32_u;
|
||||
|
||||
//extern uint8_32_u DeviceInfo;
|
||||
|
||||
bool isMcuConnected(void);
|
||||
uint8_t Initialize4WayInterface(void);
|
||||
void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter);
|
||||
void DeInitialize4WayInterface(void);
|
|
@ -0,0 +1,337 @@
|
|||
/*
|
||||
* 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/>.
|
||||
* Author: 4712
|
||||
* for info about Hagens AVRootloader:
|
||||
* http://www.mikrocontroller.net/topic/avr-bootloader-mit-verschluesselung
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/serial_4way.h"
|
||||
#include "io/serial_4way_avrootloader.h"
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
|
||||
|
||||
// Bootloader commands
|
||||
// RunCmd
|
||||
#define RestartBootloader 0
|
||||
#define ExitBootloader 1
|
||||
|
||||
#define CMD_RUN 0x00
|
||||
#define CMD_PROG_FLASH 0x01
|
||||
#define CMD_ERASE_FLASH 0x02
|
||||
#define CMD_READ_FLASH_SIL 0x03
|
||||
#define CMD_VERIFY_FLASH 0x03
|
||||
#define CMD_READ_EEPROM 0x04
|
||||
#define CMD_PROG_EEPROM 0x05
|
||||
#define CMD_READ_SRAM 0x06
|
||||
#define CMD_READ_FLASH_ATM 0x07
|
||||
#define CMD_KEEP_ALIVE 0xFD
|
||||
#define CMD_SET_ADDRESS 0xFF
|
||||
#define CMD_SET_BUFFER 0xFE
|
||||
|
||||
#define CMD_BOOTINIT 0x07
|
||||
#define CMD_BOOTSIGN 0x08
|
||||
|
||||
// Bootloader result codes
|
||||
|
||||
#define brSUCCESS 0x30
|
||||
#define brERRORCOMMAND 0xC1
|
||||
#define brERRORCRC 0xC2
|
||||
#define brNONE 0xFF
|
||||
|
||||
|
||||
#define START_BIT_TIMEOUT_MS 2
|
||||
|
||||
#define BIT_TIME (52) //52uS
|
||||
#define BIT_TIME_HALVE (BIT_TIME >> 1) //26uS
|
||||
#define START_BIT_TIME (BIT_TIME_HALVE + 1)
|
||||
//#define STOP_BIT_TIME ((BIT_TIME * 9) + BIT_TIME_HALVE)
|
||||
|
||||
static uint8_t suart_getc_(uint8_t *bt)
|
||||
{
|
||||
uint32_t btime;
|
||||
uint32_t start_time;
|
||||
|
||||
uint32_t wait_time = millis() + START_BIT_TIMEOUT_MS;
|
||||
while (ESC_IS_HI) {
|
||||
// check for startbit begin
|
||||
if (millis() >= wait_time) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
// start bit
|
||||
start_time = micros();
|
||||
btime = start_time + START_BIT_TIME;
|
||||
uint16_t bitmask = 0;
|
||||
uint8_t bit = 0;
|
||||
while (micros() < btime);
|
||||
while(1) {
|
||||
if (ESC_IS_HI)
|
||||
{
|
||||
bitmask |= (1 << bit);
|
||||
}
|
||||
btime = btime + BIT_TIME;
|
||||
bit++;
|
||||
if (bit == 10) break;
|
||||
while (micros() < btime);
|
||||
}
|
||||
// check start bit and stop bit
|
||||
if ((bitmask & 1) || (!(bitmask & (1 << 9)))) {
|
||||
return 0;
|
||||
}
|
||||
*bt = bitmask >> 1;
|
||||
return 1;
|
||||
}
|
||||
|
||||
static void suart_putc_(uint8_t *tx_b)
|
||||
{
|
||||
// shift out stopbit first
|
||||
uint16_t bitmask = (*tx_b << 2) | 1 | (1 << 10);
|
||||
uint32_t btime = micros();
|
||||
while(1) {
|
||||
if(bitmask & 1) {
|
||||
ESC_SET_HI; // 1
|
||||
}
|
||||
else {
|
||||
ESC_SET_LO; // 0
|
||||
}
|
||||
btime = btime + BIT_TIME;
|
||||
bitmask = (bitmask >> 1);
|
||||
if (bitmask == 0) break; // stopbit shifted out - but don't wait
|
||||
while (micros() < btime);
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_16_u CRC_16;
|
||||
static uint8_16_u LastCRC_16;
|
||||
|
||||
static void ByteCrc(uint8_t *bt)
|
||||
{
|
||||
uint8_t xb = *bt;
|
||||
for (uint8_t i = 0; i < 8; i++)
|
||||
{
|
||||
if (((xb & 0x01) ^ (CRC_16.word & 0x0001)) !=0 ) {
|
||||
CRC_16.word = CRC_16.word >> 1;
|
||||
CRC_16.word = CRC_16.word ^ 0xA001;
|
||||
} else {
|
||||
CRC_16.word = CRC_16.word >> 1;
|
||||
}
|
||||
xb = xb >> 1;
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_t BL_ReadBuf(uint8_t *pstring, uint8_t len)
|
||||
{
|
||||
// len 0 means 256
|
||||
CRC_16.word = 0;
|
||||
LastCRC_16.word = 0;
|
||||
uint8_t LastACK = brNONE;
|
||||
do {
|
||||
if(!suart_getc_(pstring)) goto timeout;
|
||||
ByteCrc(pstring);
|
||||
pstring++;
|
||||
len--;
|
||||
} while(len > 0);
|
||||
|
||||
if(isMcuConnected()) {
|
||||
//With CRC read 3 more
|
||||
if(!suart_getc_(&LastCRC_16.bytes[0])) goto timeout;
|
||||
if(!suart_getc_(&LastCRC_16.bytes[1])) goto timeout;
|
||||
if(!suart_getc_(&LastACK)) goto timeout;
|
||||
if (CRC_16.word != LastCRC_16.word) {
|
||||
LastACK = brERRORCRC;
|
||||
}
|
||||
} else {
|
||||
if(!suart_getc_(&LastACK)) goto timeout;
|
||||
}
|
||||
timeout:
|
||||
return (LastACK == brSUCCESS);
|
||||
}
|
||||
|
||||
static void BL_SendBuf(uint8_t *pstring, uint8_t len)
|
||||
{
|
||||
ESC_OUTPUT;
|
||||
CRC_16.word=0;
|
||||
do {
|
||||
suart_putc_(pstring);
|
||||
ByteCrc(pstring);
|
||||
pstring++;
|
||||
len--;
|
||||
} while (len > 0);
|
||||
|
||||
if (isMcuConnected()) {
|
||||
suart_putc_(&CRC_16.bytes[0]);
|
||||
suart_putc_(&CRC_16.bytes[1]);
|
||||
}
|
||||
ESC_INPUT;
|
||||
}
|
||||
|
||||
uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo)
|
||||
{
|
||||
#define BootMsgLen 4
|
||||
#define DevSignHi (BootMsgLen)
|
||||
#define DevSignLo (BootMsgLen+1)
|
||||
|
||||
//DeviceInfo.dword=0; is set before
|
||||
uint8_t BootInfo[9];
|
||||
uint8_t BootMsg[BootMsgLen-1] = "471";
|
||||
// x * 0 + 9
|
||||
#if defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
|
||||
uint8_t BootInit[] = {0,0,0,0,0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
|
||||
BL_SendBuf(BootInit, 21);
|
||||
#else
|
||||
uint8_t BootInit[] = {0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
|
||||
BL_SendBuf(BootInit, 17);
|
||||
#endif
|
||||
if (!BL_ReadBuf(BootInfo, BootMsgLen + 4)) {
|
||||
return 0;
|
||||
}
|
||||
// BootInfo has no CRC (ACK byte already analyzed... )
|
||||
// Format = BootMsg("471c") SIGNATURE_001, SIGNATURE_002, BootVersion (always 6), BootPages (,ACK)
|
||||
for (uint8_t i = 0; i < (BootMsgLen - 1); i++) { // Check only the first 3 letters -> 471x OK
|
||||
if (BootInfo[i] != BootMsg[i]) {
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
||||
//only 2 bytes used $1E9307 -> 0x9307
|
||||
pDeviceInfo->bytes[2] = BootInfo[BootMsgLen - 1];
|
||||
pDeviceInfo->bytes[1] = BootInfo[DevSignHi];
|
||||
pDeviceInfo->bytes[0] = BootInfo[DevSignLo];
|
||||
return (1);
|
||||
}
|
||||
|
||||
static uint8_t BL_GetACK(uint32_t Timeout)
|
||||
{
|
||||
uint8_t LastACK = brNONE;
|
||||
while (!(suart_getc_(&LastACK)) && (Timeout)) {
|
||||
Timeout--;
|
||||
} ;
|
||||
return (LastACK);
|
||||
}
|
||||
|
||||
uint8_t BL_SendCMDKeepAlive(void)
|
||||
{
|
||||
uint8_t sCMD[] = {CMD_KEEP_ALIVE, 0};
|
||||
BL_SendBuf(sCMD, 2);
|
||||
if (BL_GetACK(1) != brERRORCOMMAND) {
|
||||
return 0;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo)
|
||||
{
|
||||
uint8_t sCMD[] = {RestartBootloader, 0};
|
||||
pDeviceInfo->bytes[0] = 1;
|
||||
BL_SendBuf(sCMD, 2); //sends simply 4 x 0x00 (CRC =00)
|
||||
return;
|
||||
}
|
||||
|
||||
static uint8_t BL_SendCMDSetAddress(ioMem_t *pMem) //supports only 16 bit Adr
|
||||
{
|
||||
// skip if adr == 0xFFFF
|
||||
if((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
|
||||
uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, pMem->D_FLASH_ADDR_H, pMem->D_FLASH_ADDR_L };
|
||||
BL_SendBuf(sCMD, 4);
|
||||
return (BL_GetACK(2) == brSUCCESS);
|
||||
}
|
||||
|
||||
static uint8_t BL_SendCMDSetBuffer(ioMem_t *pMem)
|
||||
{
|
||||
uint8_t sCMD[] = {CMD_SET_BUFFER, 0, 0, pMem->D_NUM_BYTES};
|
||||
if (pMem->D_NUM_BYTES == 0) {
|
||||
// set high byte
|
||||
sCMD[2] = 1;
|
||||
}
|
||||
BL_SendBuf(sCMD, 4);
|
||||
if (BL_GetACK(2) != brNONE) return 0;
|
||||
BL_SendBuf(pMem->D_PTR_I, pMem->D_NUM_BYTES);
|
||||
return (BL_GetACK(40) == brSUCCESS);
|
||||
}
|
||||
|
||||
static uint8_t BL_ReadA(uint8_t cmd, ioMem_t *pMem)
|
||||
{
|
||||
if (BL_SendCMDSetAddress(pMem)) {
|
||||
uint8_t sCMD[] = {cmd, pMem->D_NUM_BYTES};
|
||||
BL_SendBuf(sCMD, 2);
|
||||
return (BL_ReadBuf(pMem->D_PTR_I, pMem->D_NUM_BYTES ));
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint8_t BL_WriteA(uint8_t cmd, ioMem_t *pMem, uint32_t timeout)
|
||||
{
|
||||
if (BL_SendCMDSetAddress(pMem)) {
|
||||
if (!BL_SendCMDSetBuffer(pMem)) return 0;
|
||||
uint8_t sCMD[] = {cmd, 0x01};
|
||||
BL_SendBuf(sCMD, 2);
|
||||
return (BL_GetACK(timeout) == brSUCCESS);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem)
|
||||
{
|
||||
if(interface_mode == imATM_BLB) {
|
||||
return BL_ReadA(CMD_READ_FLASH_ATM, pMem);
|
||||
} else {
|
||||
return BL_ReadA(CMD_READ_FLASH_SIL, pMem);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
uint8_t BL_ReadEEprom(ioMem_t *pMem)
|
||||
{
|
||||
return BL_ReadA(CMD_READ_EEPROM, pMem);
|
||||
}
|
||||
|
||||
uint8_t BL_PageErase(ioMem_t *pMem)
|
||||
{
|
||||
if (BL_SendCMDSetAddress(pMem)) {
|
||||
uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};
|
||||
BL_SendBuf(sCMD, 2);
|
||||
return (BL_GetACK((40 / START_BIT_TIMEOUT_MS)) == brSUCCESS);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t BL_WriteEEprom(ioMem_t *pMem)
|
||||
{
|
||||
return BL_WriteA(CMD_PROG_EEPROM, pMem, (3000 / START_BIT_TIMEOUT_MS));
|
||||
}
|
||||
|
||||
uint8_t BL_WriteFlash(ioMem_t *pMem)
|
||||
{
|
||||
return BL_WriteA(CMD_PROG_FLASH, pMem, (40 / START_BIT_TIMEOUT_MS));
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif
|
|
@ -0,0 +1,31 @@
|
|||
/*
|
||||
* 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/>.
|
||||
* Author: 4712
|
||||
* for info about Hagens AVRootloader:
|
||||
* http://www.mikrocontroller.net/topic/avr-bootloader-mit-verschluesselung
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
void BL_SendBootInit(void);
|
||||
uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo);
|
||||
uint8_t BL_SendCMDKeepAlive(void);
|
||||
uint8_t BL_PageErase(ioMem_t *pMem);
|
||||
uint8_t BL_ReadEEprom(ioMem_t *pMem);
|
||||
uint8_t BL_WriteEEprom(ioMem_t *pMem);
|
||||
uint8_t BL_WriteFlash(ioMem_t *pMem);
|
||||
uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem);
|
||||
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo);
|
|
@ -0,0 +1,423 @@
|
|||
/*
|
||||
* 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/>.
|
||||
* Author: 4712
|
||||
* have a look at https://github.com/sim-/tgy/blob/master/boot.inc
|
||||
* for info about the stk500v2 implementation
|
||||
*/
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "config/config.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/serial_4way.h"
|
||||
#include "io/serial_4way_stk500v2.h"
|
||||
#include "drivers/system.h"
|
||||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
|
||||
#define BIT_LO_US (32) //32uS
|
||||
#define BIT_HI_US (2*BIT_LO_US)
|
||||
|
||||
static uint8_t StkInBuf[16];
|
||||
|
||||
#define STK_BIT_TIMEOUT 250 // micro seconds
|
||||
#define STK_WAIT_TICKS (1000 / STK_BIT_TIMEOUT) // per ms
|
||||
#define STK_WAITCYLCES (STK_WAIT_TICKS * 35) // 35ms
|
||||
#define STK_WAITCYLCES_START (STK_WAIT_TICKS / 2) // 0.5 ms
|
||||
#define STK_WAITCYLCES_EXT (STK_WAIT_TICKS * 5000) //5 s
|
||||
|
||||
#define WaitPinLo while (ESC_IS_HI) {if (micros() > timeout_timer) goto timeout;}
|
||||
#define WaitPinHi while (ESC_IS_LO) {if (micros() > timeout_timer) goto timeout;}
|
||||
|
||||
static uint32_t LastBitTime;
|
||||
static uint32_t HiLoTsh;
|
||||
|
||||
static uint8_t SeqNumber;
|
||||
static uint8_t StkCmd;
|
||||
static uint8_t ckSumIn;
|
||||
static uint8_t ckSumOut;
|
||||
|
||||
// used STK message constants from ATMEL AVR - Application note
|
||||
#define MESSAGE_START 0x1B
|
||||
#define TOKEN 0x0E
|
||||
|
||||
#define CMD_SIGN_ON 0x01
|
||||
#define CMD_LOAD_ADDRESS 0x06
|
||||
#define CMD_CHIP_ERASE_ISP 0x12
|
||||
#define CMD_PROGRAM_FLASH_ISP 0x13
|
||||
#define CMD_READ_FLASH_ISP 0x14
|
||||
#define CMD_PROGRAM_EEPROM_ISP 0x15
|
||||
#define CMD_READ_EEPROM_ISP 0x16
|
||||
#define CMD_READ_SIGNATURE_ISP 0x1B
|
||||
#define CMD_SPI_MULTI 0x1D
|
||||
|
||||
#define STATUS_CMD_OK 0x00
|
||||
|
||||
#define CmdFlashEepromRead 0xA0
|
||||
#define EnterIspCmd1 0xAC
|
||||
#define EnterIspCmd2 0x53
|
||||
#define signature_r 0x30
|
||||
|
||||
#define delay_us(x) delayMicroseconds(x)
|
||||
#define IRQ_OFF // dummy
|
||||
#define IRQ_ON // dummy
|
||||
|
||||
static void StkSendByte(uint8_t dat)
|
||||
{
|
||||
ckSumOut ^= dat;
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
if (dat & 0x01) {
|
||||
// 1-bits are encoded as 64.0us high, 72.8us low (135.8us total).
|
||||
ESC_SET_HI;
|
||||
delay_us(BIT_HI_US);
|
||||
ESC_SET_LO;
|
||||
delay_us(BIT_HI_US);
|
||||
} else {
|
||||
// 0-bits are encoded as 27.8us high, 34.5us low, 34.4us high, 37.9 low (134.6us total)
|
||||
ESC_SET_HI;
|
||||
delay_us(BIT_LO_US);
|
||||
ESC_SET_LO;
|
||||
delay_us(BIT_LO_US);
|
||||
ESC_SET_HI;
|
||||
delay_us(BIT_LO_US);
|
||||
ESC_SET_LO;
|
||||
delay_us(BIT_LO_US);
|
||||
}
|
||||
dat >>= 1;
|
||||
}
|
||||
}
|
||||
|
||||
static void StkSendPacketHeader(void)
|
||||
{
|
||||
IRQ_OFF;
|
||||
ESC_OUTPUT;
|
||||
StkSendByte(0xFF);
|
||||
StkSendByte(0xFF);
|
||||
StkSendByte(0x7F);
|
||||
ckSumOut = 0;
|
||||
StkSendByte(MESSAGE_START);
|
||||
StkSendByte(++SeqNumber);
|
||||
}
|
||||
|
||||
static void StkSendPacketFooter(void)
|
||||
{
|
||||
StkSendByte(ckSumOut);
|
||||
ESC_SET_HI;
|
||||
delay_us(BIT_LO_US);
|
||||
ESC_INPUT;
|
||||
IRQ_ON;
|
||||
}
|
||||
|
||||
|
||||
|
||||
static int8_t ReadBit(void)
|
||||
{
|
||||
uint32_t btimer = micros();
|
||||
uint32_t timeout_timer = btimer + STK_BIT_TIMEOUT;
|
||||
WaitPinLo;
|
||||
WaitPinHi;
|
||||
LastBitTime = micros() - btimer;
|
||||
if (LastBitTime <= HiLoTsh) {
|
||||
timeout_timer = timeout_timer + STK_BIT_TIMEOUT;
|
||||
WaitPinLo;
|
||||
WaitPinHi;
|
||||
//lo-bit
|
||||
return 0;
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
timeout:
|
||||
return -1;
|
||||
}
|
||||
|
||||
static uint8_t ReadByte(uint8_t *bt)
|
||||
{
|
||||
*bt = 0;
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
int8_t bit = ReadBit();
|
||||
if (bit == -1) goto timeout;
|
||||
if (bit == 1) {
|
||||
*bt |= (1 << i);
|
||||
}
|
||||
}
|
||||
ckSumIn ^=*bt;
|
||||
return 1;
|
||||
timeout:
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint8_t StkReadLeader(void)
|
||||
{
|
||||
|
||||
// Reset learned timing
|
||||
HiLoTsh = BIT_HI_US + BIT_LO_US;
|
||||
|
||||
// Wait for the first bit
|
||||
uint32_t waitcycl; //250uS each
|
||||
|
||||
if((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP)) {
|
||||
waitcycl = STK_WAITCYLCES_EXT;
|
||||
} else if(StkCmd == CMD_SIGN_ON) {
|
||||
waitcycl = STK_WAITCYLCES_START;
|
||||
} else {
|
||||
waitcycl= STK_WAITCYLCES;
|
||||
}
|
||||
for ( ; waitcycl >0 ; waitcycl--) {
|
||||
//check is not timeout
|
||||
if (ReadBit() >- 1) break;
|
||||
}
|
||||
|
||||
//Skip the first bits
|
||||
if (waitcycl == 0){
|
||||
goto timeout;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < 10; i++) {
|
||||
if (ReadBit() == -1) goto timeout;
|
||||
}
|
||||
|
||||
// learn timing
|
||||
HiLoTsh = (LastBitTime >> 1) + (LastBitTime >> 2);
|
||||
|
||||
// Read until we get a 0 bit
|
||||
int8_t bit;
|
||||
do {
|
||||
bit = ReadBit();
|
||||
if (bit == -1) goto timeout;
|
||||
} while (bit > 0);
|
||||
return 1;
|
||||
timeout:
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint8_t StkRcvPacket(uint8_t *pstring)
|
||||
{
|
||||
uint8_t bt = 0;
|
||||
uint8_16_u Len;
|
||||
|
||||
IRQ_OFF;
|
||||
if (!StkReadLeader()) goto Err;
|
||||
ckSumIn=0;
|
||||
if (!ReadByte(&bt) || (bt != MESSAGE_START)) goto Err;
|
||||
if (!ReadByte(&bt) || (bt != SeqNumber)) goto Err;
|
||||
ReadByte(&Len.bytes[1]);
|
||||
if (Len.bytes[1] > 1) goto Err;
|
||||
ReadByte(&Len.bytes[0]);
|
||||
if (Len.bytes[0] < 1) goto Err;
|
||||
if (!ReadByte(&bt) || (bt != TOKEN)) goto Err;
|
||||
if (!ReadByte(&bt) || (bt != StkCmd)) goto Err;
|
||||
if (!ReadByte(&bt) || (bt != STATUS_CMD_OK)) goto Err;
|
||||
for (uint16_t i = 0; i < (Len.word - 2); i++)
|
||||
{
|
||||
if (!ReadByte(pstring)) goto Err;
|
||||
pstring++;
|
||||
}
|
||||
ReadByte(&bt);
|
||||
if (ckSumIn != 0) goto Err;
|
||||
IRQ_ON;
|
||||
return 1;
|
||||
Err:
|
||||
IRQ_ON;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint8_t _CMD_SPI_MULTI_EX(volatile uint8_t * ResByte,uint8_t Cmd,uint8_t AdrHi,uint8_t AdrLo)
|
||||
{
|
||||
StkCmd= CMD_SPI_MULTI;
|
||||
StkSendPacketHeader();
|
||||
StkSendByte(0); // hi byte Msg len
|
||||
StkSendByte(8); // lo byte Msg len
|
||||
StkSendByte(TOKEN);
|
||||
StkSendByte(CMD_SPI_MULTI);
|
||||
StkSendByte(4); // NumTX
|
||||
StkSendByte(4); // NumRX
|
||||
StkSendByte(0); // RxStartAdr
|
||||
StkSendByte(Cmd); // {TxData} Cmd
|
||||
StkSendByte(AdrHi); // {TxData} AdrHi
|
||||
StkSendByte(AdrLo); // {TxData} AdrLoch
|
||||
StkSendByte(0); // {TxData} 0
|
||||
StkSendPacketFooter();
|
||||
if (StkRcvPacket((void *)StkInBuf)) { // NumRX + 3
|
||||
if ((StkInBuf[0] == 0x00) && ((StkInBuf[1] == Cmd)||(StkInBuf[1] == 0x00)/* ignore zero returns */) &&(StkInBuf[2] == 0x00)) {
|
||||
*ResByte = StkInBuf[3];
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint8_t _CMD_LOAD_ADDRESS(ioMem_t *pMem)
|
||||
{
|
||||
// ignore 0xFFFF
|
||||
// assume address is set before and we read or write the immediately following package
|
||||
if((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
|
||||
StkCmd = CMD_LOAD_ADDRESS;
|
||||
StkSendPacketHeader();
|
||||
StkSendByte(0); // hi byte Msg len
|
||||
StkSendByte(5); // lo byte Msg len
|
||||
StkSendByte(TOKEN);
|
||||
StkSendByte(CMD_LOAD_ADDRESS);
|
||||
StkSendByte(0);
|
||||
StkSendByte(0);
|
||||
StkSendByte(pMem->D_FLASH_ADDR_H);
|
||||
StkSendByte(pMem->D_FLASH_ADDR_L);
|
||||
StkSendPacketFooter();
|
||||
return (StkRcvPacket((void *)StkInBuf));
|
||||
}
|
||||
|
||||
static uint8_t _CMD_READ_MEM_ISP(ioMem_t *pMem)
|
||||
{
|
||||
uint8_t LenHi;
|
||||
if (pMem->D_NUM_BYTES>0) {
|
||||
LenHi=0;
|
||||
} else {
|
||||
LenHi=1;
|
||||
}
|
||||
StkSendPacketHeader();
|
||||
StkSendByte(0); // hi byte Msg len
|
||||
StkSendByte(4); // lo byte Msg len
|
||||
StkSendByte(TOKEN);
|
||||
StkSendByte(StkCmd);
|
||||
StkSendByte(LenHi);
|
||||
StkSendByte(pMem->D_NUM_BYTES);
|
||||
StkSendByte(CmdFlashEepromRead);
|
||||
StkSendPacketFooter();
|
||||
return (StkRcvPacket(pMem->D_PTR_I));
|
||||
}
|
||||
|
||||
static uint8_t _CMD_PROGRAM_MEM_ISP(ioMem_t *pMem)
|
||||
{
|
||||
uint8_16_u Len;
|
||||
uint8_t LenLo = pMem->D_NUM_BYTES;
|
||||
uint8_t LenHi;
|
||||
if (LenLo) {
|
||||
LenHi = 0;
|
||||
Len.word = LenLo + 10;
|
||||
} else {
|
||||
LenHi = 1;
|
||||
Len.word = 256 + 10;
|
||||
}
|
||||
StkSendPacketHeader();
|
||||
StkSendByte(Len.bytes[1]); // high byte Msg len
|
||||
StkSendByte(Len.bytes[0]); // low byte Msg len
|
||||
StkSendByte(TOKEN);
|
||||
StkSendByte(StkCmd);
|
||||
StkSendByte(LenHi);
|
||||
StkSendByte(LenLo);
|
||||
StkSendByte(0); // mode
|
||||
StkSendByte(0); // delay
|
||||
StkSendByte(0); // cmd1
|
||||
StkSendByte(0); // cmd2
|
||||
StkSendByte(0); // cmd3
|
||||
StkSendByte(0); // poll1
|
||||
StkSendByte(0); // poll2
|
||||
do {
|
||||
StkSendByte(*pMem->D_PTR_I);
|
||||
pMem->D_PTR_I++;
|
||||
LenLo--;
|
||||
} while (LenLo);
|
||||
StkSendPacketFooter();
|
||||
return StkRcvPacket((void *)StkInBuf);
|
||||
}
|
||||
|
||||
uint8_t Stk_SignOn(void)
|
||||
{
|
||||
StkCmd=CMD_SIGN_ON;
|
||||
StkSendPacketHeader();
|
||||
StkSendByte(0); // hi byte Msg len
|
||||
StkSendByte(1); // lo byte Msg len
|
||||
StkSendByte(TOKEN);
|
||||
StkSendByte(CMD_SIGN_ON);
|
||||
StkSendPacketFooter();
|
||||
return (StkRcvPacket((void *) StkInBuf));
|
||||
}
|
||||
|
||||
uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo)
|
||||
{
|
||||
if (Stk_SignOn()) {
|
||||
if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[1], signature_r,0,1)) {
|
||||
if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[0], signature_r,0,2)) {
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t Stk_Chip_Erase(void)
|
||||
{
|
||||
StkCmd = CMD_CHIP_ERASE_ISP;
|
||||
StkSendPacketHeader();
|
||||
StkSendByte(0); // high byte Msg len
|
||||
StkSendByte(7); // low byte Msg len
|
||||
StkSendByte(TOKEN);
|
||||
StkSendByte(CMD_CHIP_ERASE_ISP);
|
||||
StkSendByte(20); // ChipErase_eraseDelay atmega8
|
||||
StkSendByte(0); // ChipErase_pollMethod atmega8
|
||||
StkSendByte(0xAC);
|
||||
StkSendByte(0x88);
|
||||
StkSendByte(0x13);
|
||||
StkSendByte(0x76);
|
||||
StkSendPacketFooter();
|
||||
return (StkRcvPacket(StkInBuf));
|
||||
}
|
||||
|
||||
uint8_t Stk_ReadFlash(ioMem_t *pMem)
|
||||
{
|
||||
if (_CMD_LOAD_ADDRESS(pMem)) {
|
||||
StkCmd = CMD_READ_FLASH_ISP;
|
||||
return (_CMD_READ_MEM_ISP(pMem));
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
uint8_t Stk_ReadEEprom(ioMem_t *pMem)
|
||||
{
|
||||
if (_CMD_LOAD_ADDRESS(pMem)) {
|
||||
StkCmd = CMD_READ_EEPROM_ISP;
|
||||
return (_CMD_READ_MEM_ISP(pMem));
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t Stk_WriteFlash(ioMem_t *pMem)
|
||||
{
|
||||
if (_CMD_LOAD_ADDRESS(pMem)) {
|
||||
StkCmd = CMD_PROGRAM_FLASH_ISP;
|
||||
return (_CMD_PROGRAM_MEM_ISP(pMem));
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t Stk_WriteEEprom(ioMem_t *pMem)
|
||||
{
|
||||
if (_CMD_LOAD_ADDRESS(pMem)) {
|
||||
StkCmd = CMD_PROGRAM_EEPROM_ISP;
|
||||
return (_CMD_PROGRAM_MEM_ISP(pMem));
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
#endif
|
|
@ -13,24 +13,15 @@
|
|||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
|
||||
* by Nathan Tsoi <nathan@vertile.com>
|
||||
*/
|
||||
|
||||
* Author: 4712
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#ifdef USE_SERIAL_1WIRE
|
||||
uint8_t Stk_SignOn(void);
|
||||
uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo);
|
||||
uint8_t Stk_ReadEEprom(ioMem_t *pMem);
|
||||
uint8_t Stk_WriteEEprom(ioMem_t *pMem);
|
||||
uint8_t Stk_ReadFlash(ioMem_t *pMem);
|
||||
uint8_t Stk_WriteFlash(ioMem_t *pMem);
|
||||
uint8_t Stk_Chip_Erase(void);
|
||||
|
||||
extern uint8_t escCount;
|
||||
|
||||
typedef struct {
|
||||
GPIO_TypeDef* gpio;
|
||||
uint16_t pinpos;
|
||||
uint16_t pin;
|
||||
} escHardware_t;
|
||||
|
||||
|
||||
void usb1WireInitialize();
|
||||
void usb1WirePassthrough(uint8_t escIndex);
|
||||
#endif
|
|
@ -194,7 +194,7 @@ static const char * const featureNames[] = {
|
|||
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
|
||||
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
||||
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
|
||||
"BLACKBOX", "CHANNEL_FORWARDING", NULL
|
||||
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", NULL
|
||||
};
|
||||
|
||||
// sync this with rxFailsafeChannelMode_e
|
||||
|
@ -372,7 +372,7 @@ static const char * const lookupTableBlackboxDevice[] = {
|
|||
|
||||
|
||||
static const char * const lookupTablePidController[] = {
|
||||
"MW23", "MWREWRITE", "LUX"
|
||||
"UNUSED", "MWREWRITE", "LUX"
|
||||
};
|
||||
|
||||
static const char * const lookupTableSerialRX[] = {
|
||||
|
@ -427,10 +427,6 @@ static const char * const lookupTableMagHardware[] = {
|
|||
"AK8963"
|
||||
};
|
||||
|
||||
static const char * const lookupDeltaMethod[] = {
|
||||
"ERROR", "MEASUREMENT"
|
||||
};
|
||||
|
||||
static const char * const lookupTableDebug[] = {
|
||||
"NONE",
|
||||
"CYCLETIME",
|
||||
|
@ -448,6 +444,10 @@ static const char * const lookupTableOsdType[] = {
|
|||
};
|
||||
#endif
|
||||
|
||||
static const char * const lookupTableSuperExpoYaw[] = {
|
||||
"OFF", "ON", "ALWAYS"
|
||||
};
|
||||
|
||||
typedef struct lookupTableEntry_s {
|
||||
const char * const *values;
|
||||
const uint8_t valueCount;
|
||||
|
@ -462,7 +462,7 @@ typedef enum {
|
|||
TABLE_GPS_SBAS_MODE,
|
||||
#endif
|
||||
#ifdef BLACKBOX
|
||||
TABLE_BLACKBOX_DEVICE,
|
||||
TABLE_BLACKBOX_DEVICE,
|
||||
#endif
|
||||
TABLE_CURRENT_SENSOR,
|
||||
TABLE_GIMBAL_MODE,
|
||||
|
@ -472,8 +472,8 @@ typedef enum {
|
|||
TABLE_ACC_HARDWARE,
|
||||
TABLE_BARO_HARDWARE,
|
||||
TABLE_MAG_HARDWARE,
|
||||
TABLE_DELTA_METHOD,
|
||||
TABLE_DEBUG,
|
||||
TABLE_SUPEREXPO_YAW,
|
||||
#ifdef OSD
|
||||
TABLE_OSD,
|
||||
#endif
|
||||
|
@ -498,8 +498,8 @@ static const lookupTableEntry_t lookupTables[] = {
|
|||
{ lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
|
||||
{ lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
|
||||
{ lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
|
||||
{ lookupDeltaMethod, sizeof(lookupDeltaMethod) / sizeof(char *) },
|
||||
{ lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
|
||||
{ lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) }
|
||||
#ifdef OSD
|
||||
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
|
||||
#endif
|
||||
|
@ -648,6 +648,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
|
||||
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
|
||||
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
|
||||
{ "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbathysteresis, .config.minmax = { 0, 250 } },
|
||||
{ "vbat_pid_compensation", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
|
||||
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
|
||||
|
@ -666,7 +667,7 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
{ "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
|
||||
{ "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
|
||||
{ "gyro_soft_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } },
|
||||
{ "gyro_lowpass_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } },
|
||||
{ "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
|
||||
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
|
||||
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
|
||||
|
@ -700,8 +701,9 @@ const clivalue_t valueTable[] = {
|
|||
{ "yaw_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
|
||||
{ "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
|
||||
{ "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
|
||||
{ "acro_plus_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusFactor, .config.minmax = {1, 100 } },
|
||||
{ "acro_plus_offset", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusOffset, .config.minmax = {1, 90 } },
|
||||
{ "super_expo_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.superExpoFactor, .config.minmax = {1, 100 } },
|
||||
{ "super_expo_factor_yaw", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.superExpoFactorYaw, .config.minmax = {1, 100 } },
|
||||
{ "super_expo_yaw", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.superExpoYawMode, .config.lookup = { TABLE_SUPEREXPO_YAW } },
|
||||
|
||||
{ "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
|
||||
{ "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
|
||||
|
@ -733,9 +735,12 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
||||
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
|
||||
{ "pid_delta_method", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaMethod, .config.lookup = { TABLE_DELTA_METHOD } },
|
||||
{ "dterm_lpf_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
|
||||
{ "dterm_average_count", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_average_count, .config.minmax = {2, 12 } },
|
||||
{ "dterm_lowpass_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
|
||||
{ "dterm_differentiator", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dterm_differentiator, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "iterm_always_reset", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetAlways, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetRate, .config.minmax = {50, 1000 } },
|
||||
{ "yaw_iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermResetRate, .config.minmax = {25, 1000 } },
|
||||
{ "yaw_lowpass_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
|
||||
{ "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
|
||||
|
||||
{ "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
|
||||
|
@ -750,20 +755,6 @@ const clivalue_t valueTable[] = {
|
|||
{ "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } },
|
||||
{ "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } },
|
||||
|
||||
{ "p_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[PITCH], .config.minmax = { 0, 100 } },
|
||||
{ "i_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[PITCH], .config.minmax = { 0, 100 } },
|
||||
{ "d_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[PITCH], .config.minmax = { 0, 100 } },
|
||||
{ "p_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[ROLL], .config.minmax = { 0, 100 } },
|
||||
{ "i_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[ROLL], .config.minmax = { 0, 100 } },
|
||||
{ "d_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[ROLL], .config.minmax = { 0, 100 } },
|
||||
{ "p_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[YAW], .config.minmax = { 0, 100 } },
|
||||
{ "i_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[YAW], .config.minmax = { 0, 100 } },
|
||||
{ "d_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[YAW], .config.minmax = { 0, 100 } },
|
||||
|
||||
{ "level_horizon", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_level, .config.minmax = { 0, 10 } },
|
||||
{ "level_angle", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.A_level, .config.minmax = { 0, 10 } },
|
||||
{ "sensitivity_horizon", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_sensitivity, .config.minmax = { 0, 250 } },
|
||||
|
||||
{ "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } },
|
||||
{ "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } },
|
||||
{ "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } },
|
||||
|
@ -812,6 +803,7 @@ typedef union {
|
|||
|
||||
static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
|
||||
static void cliPrintVar(const clivalue_t *var, uint32_t full);
|
||||
static void cliPrintVarRange(const clivalue_t *var);
|
||||
static void cliPrint(const char *str);
|
||||
static void cliPrintf(const char *fmt, ...);
|
||||
static void cliWrite(uint8_t ch);
|
||||
|
@ -1819,6 +1811,7 @@ typedef enum {
|
|||
DUMP_MASTER = (1 << 0),
|
||||
DUMP_PROFILE = (1 << 1),
|
||||
DUMP_RATES = (1 << 2),
|
||||
DUMP_ALL = (1 << 3),
|
||||
} dumpFlags_e;
|
||||
|
||||
|
||||
|
@ -1847,7 +1840,11 @@ static void cliDump(char *cmdline)
|
|||
dumpMask = DUMP_RATES;
|
||||
}
|
||||
|
||||
if (dumpMask & DUMP_MASTER) {
|
||||
if (strcasecmp(cmdline, "all") == 0) {
|
||||
dumpMask = DUMP_ALL; // All profiles and rates
|
||||
}
|
||||
|
||||
if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
|
||||
|
||||
cliPrint("\r\n# version\r\n");
|
||||
cliVersion(NULL);
|
||||
|
@ -1989,22 +1986,32 @@ static void cliDump(char *cmdline)
|
|||
cliPrint("\r\n# rxfail\r\n");
|
||||
cliRxFail("");
|
||||
|
||||
uint8_t activeProfile = masterConfig.current_profile_index;
|
||||
uint8_t i;
|
||||
for (i=0; i<MAX_PROFILE_COUNT;i++)
|
||||
cliDumpProfile(i);
|
||||
|
||||
changeProfile(activeProfile);
|
||||
|
||||
if (dumpMask & DUMP_ALL) {
|
||||
uint8_t activeProfile = masterConfig.current_profile_index;
|
||||
uint8_t currentRateIndex = currentProfile->activeRateProfile;
|
||||
uint8_t profileCount;
|
||||
uint8_t rateCount;
|
||||
for (profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) {
|
||||
cliDumpProfile(profileCount);
|
||||
for (rateCount=0; rateCount<MAX_RATEPROFILES; rateCount++)
|
||||
cliDumpRateProfile(rateCount);
|
||||
}
|
||||
|
||||
changeProfile(activeProfile);
|
||||
changeControlRateProfile(currentRateIndex);
|
||||
} else {
|
||||
cliDumpProfile(masterConfig.current_profile_index);
|
||||
cliDumpRateProfile(currentProfile->activeRateProfile);
|
||||
}
|
||||
}
|
||||
|
||||
if (dumpMask & DUMP_PROFILE) {
|
||||
cliDumpProfile(masterConfig.current_profile_index);
|
||||
|
||||
}
|
||||
|
||||
if (dumpMask & DUMP_RATES) {
|
||||
cliDumpRateProfile(currentProfile->activeRateProfile);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
@ -2015,15 +2022,11 @@ void cliDumpProfile(uint8_t profileIndex) {
|
|||
changeProfile(profileIndex);
|
||||
cliPrint("\r\n# profile\r\n");
|
||||
cliProfile("");
|
||||
cliPrintf("############################# PROFILE VALUES ####################################\r\n");
|
||||
cliProfile("");
|
||||
printSectionBreak();
|
||||
dumpValues(PROFILE_VALUE);
|
||||
uint8_t currentRateIndex = currentProfile->activeRateProfile;
|
||||
uint8_t i;
|
||||
for (i=0; i<MAX_RATEPROFILES; i++)
|
||||
cliDumpRateProfile(i);
|
||||
|
||||
changeControlRateProfile(currentRateIndex);
|
||||
cliPrintf("\r\n# Active rateprofile for profile %d, \r\n", profileIndex); // output rateprofile again to mark "active rateprofile"
|
||||
|
||||
cliRateProfile("");
|
||||
}
|
||||
void cliDumpRateProfile(uint8_t rateProfileIndex) {
|
||||
|
@ -2474,7 +2477,7 @@ static void cliWrite(uint8_t ch)
|
|||
static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
||||
{
|
||||
int32_t value = 0;
|
||||
char buf[8];
|
||||
char buf[13];
|
||||
|
||||
void *ptr = var->ptr;
|
||||
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
||||
|
@ -2527,7 +2530,27 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
|||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static void cliPrintVarRange(const clivalue_t *var)
|
||||
{
|
||||
switch (var->type & VALUE_MODE_MASK) {
|
||||
case (MODE_DIRECT): {
|
||||
cliPrintf("Allowed range: %d - %d\n", var->config.minmax.min, var->config.minmax.max);
|
||||
}
|
||||
break;
|
||||
case (MODE_LOOKUP): {
|
||||
const lookupTableEntry_t *tableEntry = &lookupTables[var->config.lookup.tableIndex];
|
||||
cliPrint("Allowed values:");
|
||||
uint8_t i;
|
||||
for (i = 0; i < tableEntry->valueCount ; i++) {
|
||||
if (i > 0)
|
||||
cliPrint(",");
|
||||
cliPrintf(" %s", tableEntry->values[i]);
|
||||
}
|
||||
cliPrint("\n");
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
|
||||
{
|
||||
void *ptr = var->ptr;
|
||||
|
@ -2639,6 +2662,7 @@ static void cliSet(char *cmdline)
|
|||
cliPrintVar(val, 0);
|
||||
} else {
|
||||
cliPrint("Invalid value\r\n");
|
||||
cliPrintVarRange(val);
|
||||
}
|
||||
|
||||
return;
|
||||
|
@ -2662,6 +2686,8 @@ static void cliGet(char *cmdline)
|
|||
val = &valueTable[i];
|
||||
cliPrintf("%s = ", valueTable[i].name);
|
||||
cliPrintVar(val, 0);
|
||||
cliPrint("\n");
|
||||
cliPrintVarRange(val);
|
||||
cliPrint("\r\n");
|
||||
|
||||
matchedCommands++;
|
||||
|
|
|
@ -95,9 +95,10 @@
|
|||
|
||||
#include "serial_msp.h"
|
||||
|
||||
#ifdef USE_SERIAL_1WIRE
|
||||
#include "io/serial_1wire.h"
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#include "io/serial_4way.h"
|
||||
#endif
|
||||
|
||||
static serialPort_t *mspSerialPort;
|
||||
|
||||
extern uint16_t cycleTime; // FIXME dependency on mw.c
|
||||
|
@ -126,7 +127,7 @@ void setGyroSamplingSpeed(uint16_t looptime) {
|
|||
masterConfig.mag_hardware = 1;
|
||||
masterConfig.pid_process_denom = 2;
|
||||
} else if (looptime < 375) {
|
||||
#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3)
|
||||
#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3) || defined(SPRACINGF3EVO) || defined(DOGE)
|
||||
masterConfig.acc_hardware = 0;
|
||||
#else
|
||||
masterConfig.acc_hardware = 1;
|
||||
|
@ -219,7 +220,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
|
|||
{ BOXBLACKBOX, "BLACKBOX;", 26 },
|
||||
{ BOXFAILSAFE, "FAILSAFE;", 27 },
|
||||
{ BOXAIRMODE, "AIR MODE;", 28 },
|
||||
{ BOXACROPLUS, "ACRO PLUS;", 29 },
|
||||
{ BOXSUPEREXPO, "SUPER EXPO;", 29 },
|
||||
{ BOX3DDISABLESWITCH, "DISABLE 3D SWITCH;", 30},
|
||||
{ CHECKBOX_ITEM_COUNT, NULL, 0xFF }
|
||||
};
|
||||
|
@ -547,7 +548,7 @@ void mspInit(serialConfig_t *serialConfig)
|
|||
}
|
||||
|
||||
activeBoxIds[activeBoxIdCount++] = BOXAIRMODE;
|
||||
activeBoxIds[activeBoxIdCount++] = BOXACROPLUS;
|
||||
activeBoxIds[activeBoxIdCount++] = BOXSUPEREXPO;
|
||||
activeBoxIds[activeBoxIdCount++] = BOX3DDISABLESWITCH;
|
||||
|
||||
if (sensors(SENSOR_BARO)) {
|
||||
|
@ -654,7 +655,7 @@ static uint32_t packFlightModeFlags(void)
|
|||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX |
|
||||
IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)) << BOXAIRMODE |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXACROPLUS)) << BOXACROPLUS;
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) << BOXSUPEREXPO;
|
||||
|
||||
for (i = 0; i < activeBoxIdCount; i++) {
|
||||
int flag = (tmp & (1 << activeBoxIds[i]));
|
||||
|
@ -879,29 +880,10 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
break;
|
||||
case MSP_PID:
|
||||
headSerialReply(3 * PID_ITEM_COUNT);
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid
|
||||
for (i = 0; i < 3; i++) {
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.P_f[i] * 40.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.I_f[i] * 100.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.D_f[i] * 4000.0f), 0, 255));
|
||||
}
|
||||
for (i = 3; i < PID_ITEM_COUNT; i++) {
|
||||
if (i == PIDLEVEL) {
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.A_level * 10.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.H_level * 10.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.H_sensitivity), 0, 255));
|
||||
} else {
|
||||
serialize8(currentProfile->pidProfile.P8[i]);
|
||||
serialize8(currentProfile->pidProfile.I8[i]);
|
||||
serialize8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
serialize8(currentProfile->pidProfile.P8[i]);
|
||||
serialize8(currentProfile->pidProfile.I8[i]);
|
||||
serialize8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
serialize8(currentProfile->pidProfile.P8[i]);
|
||||
serialize8(currentProfile->pidProfile.I8[i]);
|
||||
serialize8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
break;
|
||||
case MSP_PIDNAMES:
|
||||
|
@ -1332,34 +1314,15 @@ static bool processInCommand(void)
|
|||
break;
|
||||
case MSP_SET_PID_CONTROLLER:
|
||||
oldPid = currentProfile->pidProfile.pidController;
|
||||
currentProfile->pidProfile.pidController = read8();
|
||||
currentProfile->pidProfile.pidController = constrain(read8(), 1, 2);
|
||||
pidSetController(currentProfile->pidProfile.pidController);
|
||||
if (oldPid != currentProfile->pidProfile.pidController) setGyroSamplingSpeed(0); // recalculate looptimes for new PID
|
||||
break;
|
||||
case MSP_SET_PID:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {
|
||||
for (i = 0; i < 3; i++) {
|
||||
currentProfile->pidProfile.P_f[i] = (float)read8() / 40.0f;
|
||||
currentProfile->pidProfile.I_f[i] = (float)read8() / 100.0f;
|
||||
currentProfile->pidProfile.D_f[i] = (float)read8() / 4000.0f;
|
||||
}
|
||||
for (i = 3; i < PID_ITEM_COUNT; i++) {
|
||||
if (i == PIDLEVEL) {
|
||||
currentProfile->pidProfile.A_level = (float)read8() / 10.0f;
|
||||
currentProfile->pidProfile.H_level = (float)read8() / 10.0f;
|
||||
currentProfile->pidProfile.H_sensitivity = read8();
|
||||
} else {
|
||||
currentProfile->pidProfile.P8[i] = read8();
|
||||
currentProfile->pidProfile.I8[i] = read8();
|
||||
currentProfile->pidProfile.D8[i] = read8();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
currentProfile->pidProfile.P8[i] = read8();
|
||||
currentProfile->pidProfile.I8[i] = read8();
|
||||
currentProfile->pidProfile.D8[i] = read8();
|
||||
}
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
currentProfile->pidProfile.P8[i] = read8();
|
||||
currentProfile->pidProfile.I8[i] = read8();
|
||||
currentProfile->pidProfile.D8[i] = read8();
|
||||
}
|
||||
break;
|
||||
case MSP_SET_MODE_RANGE:
|
||||
|
@ -1806,70 +1769,26 @@ static bool processInCommand(void)
|
|||
isRebootScheduled = true;
|
||||
break;
|
||||
|
||||
#ifdef USE_SERIAL_1WIRE
|
||||
case MSP_SET_1WIRE:
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
case MSP_SET_4WAY_IF:
|
||||
// get channel number
|
||||
i = read8();
|
||||
// we do not give any data back, assume channel number is transmitted OK
|
||||
if (i == 0xFF) {
|
||||
// 0xFF -> preinitialize the Passthrough
|
||||
// switch all motor lines HI
|
||||
usb1WireInitialize();
|
||||
// reply the count of ESC found
|
||||
headSerialReply(1);
|
||||
serialize8(escCount);
|
||||
|
||||
// and come back right afterwards
|
||||
// rem: App: Wait at least appx. 500 ms for BLHeli to jump into
|
||||
// bootloader mode before try to connect any ESC
|
||||
|
||||
return true;
|
||||
}
|
||||
else {
|
||||
// Check for channel number 0..ESC_COUNT-1
|
||||
if (i < escCount) {
|
||||
// because we do not come back after calling usb1WirePassthrough
|
||||
// proceed with a success reply first
|
||||
headSerialReply(0);
|
||||
tailSerialReply();
|
||||
// flush the transmit buffer
|
||||
bufWriterFlush(writer);
|
||||
// wait for all data to send
|
||||
waitForSerialPortToFinishTransmitting(currentPort->port);
|
||||
// Start to activate here
|
||||
// motor 1 => index 0
|
||||
|
||||
// search currentPort portIndex
|
||||
/* next lines seems to be unnecessary, because the currentPort always point to the same mspPorts[portIndex]
|
||||
uint8_t portIndex;
|
||||
for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
|
||||
if (currentPort == &mspPorts[portIndex]) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
*/
|
||||
mspReleasePortIfAllocated(mspSerialPort); // CloseSerialPort also marks currentPort as UNUSED_PORT
|
||||
usb1WirePassthrough(i);
|
||||
// Wait a bit more to let App read the 0 byte and switch baudrate
|
||||
// 2ms will most likely do the job, but give some grace time
|
||||
delay(10);
|
||||
// rebuild/refill currentPort structure, does openSerialPort if marked UNUSED_PORT - used ports are skiped
|
||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||
/* restore currentPort and mspSerialPort
|
||||
setCurrentPort(&mspPorts[portIndex]); // not needed same index will be restored
|
||||
*/
|
||||
// former used MSP uart is active again
|
||||
// restore MSP_SET_1WIRE as current command for correct headSerialReply(0)
|
||||
currentPort->cmdMSP = MSP_SET_1WIRE;
|
||||
} else {
|
||||
// ESC channel higher than max. allowed
|
||||
// rem: BLHeliSuite will not support more than 8
|
||||
headSerialError(0);
|
||||
}
|
||||
// proceed as usual with MSP commands
|
||||
// and wait to switch to next channel
|
||||
// rem: App needs to call MSP_BOOT to deinitialize Passthrough
|
||||
}
|
||||
// switch all motor lines HI
|
||||
// reply the count of ESC found
|
||||
headSerialReply(1);
|
||||
serialize8(Initialize4WayInterface());
|
||||
// because we do not come back after calling Process4WayInterface
|
||||
// proceed with a success reply first
|
||||
tailSerialReply();
|
||||
// flush the transmit buffer
|
||||
bufWriterFlush(writer);
|
||||
// wait for all data to send
|
||||
waitForSerialPortToFinishTransmitting(currentPort->port);
|
||||
// rem: App: Wait at least appx. 500 ms for BLHeli to jump into
|
||||
// bootloader mode before try to connect any ESC
|
||||
// Start to activate here
|
||||
Process4WayInterface(currentPort, writer);
|
||||
// former used MSP uart is still active
|
||||
// proceed as usual with MSP commands
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
|
|
|
@ -263,7 +263,7 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
|||
#define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values
|
||||
#define MSP_SERVO_MIX_RULES 241 //out message Returns servo mixer configuration
|
||||
#define MSP_SET_SERVO_MIX_RULE 242 //in message Sets servo mixer configuration
|
||||
#define MSP_SET_1WIRE 243 //in message Sets 1Wire paththrough
|
||||
#define MSP_SET_4WAY_IF 245 //in message Sets 4way interface
|
||||
|
||||
// Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 2 MSP ports.
|
||||
#define MAX_MSP_PORT_COUNT 2
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void transponderInit(uint8_t* transponderCode);
|
||||
|
||||
void transponderEnable(void);
|
||||
void transponderDisable(void);
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
@ -52,9 +53,9 @@
|
|||
#include "drivers/flash_m25p16.h"
|
||||
#include "drivers/sonar_hcsr04.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
#include "drivers/sdcard.h"
|
||||
#include "drivers/usb_io.h"
|
||||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/sdcard.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
@ -131,9 +132,7 @@ void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse);
|
|||
void spektrumBind(rxConfig_t *rxConfig);
|
||||
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig);
|
||||
void sonarInit(const sonarHardware_t *sonarHardware);
|
||||
void transponderInit(uint8_t* transponderCode);
|
||||
void osdInit(void);
|
||||
//void usbCableDetectInit(void);
|
||||
|
||||
#ifdef STM32F303xC
|
||||
// from system_stm32f30x.c
|
||||
|
@ -258,6 +257,8 @@ void init(void)
|
|||
|
||||
timerInit(); // timer must be initialized before any channel is allocated
|
||||
|
||||
dmaInit();
|
||||
|
||||
serialInit(&masterConfig.serialConfig, feature(FEATURE_SOFTSERIAL));
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
|
@ -542,12 +543,10 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
/* TODO - Fix in the future
|
||||
#ifdef USB_CABLE_DETECTION
|
||||
usbCableDetectInit();
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef TRANSPONDER
|
||||
if (feature(FEATURE_TRANSPONDER)) {
|
||||
transponderInit(masterConfig.transponderData);
|
||||
|
@ -556,7 +555,6 @@ void init(void)
|
|||
systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED;
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
#ifdef NAZE
|
||||
|
@ -708,6 +706,10 @@ int main(void) {
|
|||
#endif
|
||||
#ifdef MAG
|
||||
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
|
||||
#ifdef SPRACINGF3EVO
|
||||
// fixme temporary solution for AK6983 via slave I2C on MPU9250
|
||||
rescheduleTask(TASK_COMPASS, 1000000 / 40);
|
||||
#endif
|
||||
#endif
|
||||
#ifdef BARO
|
||||
setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));
|
||||
|
@ -736,7 +738,6 @@ int main(void) {
|
|||
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
|
||||
#endif
|
||||
#ifdef USE_BST
|
||||
setTaskEnabled(TASK_BST_READ_WRITE, true);
|
||||
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
|
||||
#endif
|
||||
|
||||
|
@ -746,6 +747,66 @@ int main(void) {
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef DEBUG_HARDFAULTS
|
||||
//from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/
|
||||
/**
|
||||
* hard_fault_handler_c:
|
||||
* This is called from the HardFault_HandlerAsm with a pointer the Fault stack
|
||||
* as the parameter. We can then read the values from the stack and place them
|
||||
* into local variables for ease of reading.
|
||||
* We then read the various Fault Status and Address Registers to help decode
|
||||
* cause of the fault.
|
||||
* The function ends with a BKPT instruction to force control back into the debugger
|
||||
*/
|
||||
void hard_fault_handler_c(unsigned long *hardfault_args){
|
||||
volatile unsigned long stacked_r0 ;
|
||||
volatile unsigned long stacked_r1 ;
|
||||
volatile unsigned long stacked_r2 ;
|
||||
volatile unsigned long stacked_r3 ;
|
||||
volatile unsigned long stacked_r12 ;
|
||||
volatile unsigned long stacked_lr ;
|
||||
volatile unsigned long stacked_pc ;
|
||||
volatile unsigned long stacked_psr ;
|
||||
volatile unsigned long _CFSR ;
|
||||
volatile unsigned long _HFSR ;
|
||||
volatile unsigned long _DFSR ;
|
||||
volatile unsigned long _AFSR ;
|
||||
volatile unsigned long _BFAR ;
|
||||
volatile unsigned long _MMAR ;
|
||||
|
||||
stacked_r0 = ((unsigned long)hardfault_args[0]) ;
|
||||
stacked_r1 = ((unsigned long)hardfault_args[1]) ;
|
||||
stacked_r2 = ((unsigned long)hardfault_args[2]) ;
|
||||
stacked_r3 = ((unsigned long)hardfault_args[3]) ;
|
||||
stacked_r12 = ((unsigned long)hardfault_args[4]) ;
|
||||
stacked_lr = ((unsigned long)hardfault_args[5]) ;
|
||||
stacked_pc = ((unsigned long)hardfault_args[6]) ;
|
||||
stacked_psr = ((unsigned long)hardfault_args[7]) ;
|
||||
|
||||
// Configurable Fault Status Register
|
||||
// Consists of MMSR, BFSR and UFSR
|
||||
_CFSR = (*((volatile unsigned long *)(0xE000ED28))) ;
|
||||
|
||||
// Hard Fault Status Register
|
||||
_HFSR = (*((volatile unsigned long *)(0xE000ED2C))) ;
|
||||
|
||||
// Debug Fault Status Register
|
||||
_DFSR = (*((volatile unsigned long *)(0xE000ED30))) ;
|
||||
|
||||
// Auxiliary Fault Status Register
|
||||
_AFSR = (*((volatile unsigned long *)(0xE000ED3C))) ;
|
||||
|
||||
// Read the Fault Address Registers. These may not contain valid values.
|
||||
// Check BFARVALID/MMARVALID to see if they are valid values
|
||||
// MemManage Fault Address Register
|
||||
_MMAR = (*((volatile unsigned long *)(0xE000ED34))) ;
|
||||
// Bus Fault Address Register
|
||||
_BFAR = (*((volatile unsigned long *)(0xE000ED38))) ;
|
||||
|
||||
__asm("BKPT #0\n") ; // Break into the debugger
|
||||
}
|
||||
|
||||
#else
|
||||
void HardFault_Handler(void)
|
||||
{
|
||||
// fall out of the sky
|
||||
|
@ -763,3 +824,4 @@ void HardFault_Handler(void)
|
|||
|
||||
while (1);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -104,8 +104,6 @@ enum {
|
|||
|
||||
uint16_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
|
||||
|
||||
float dT;
|
||||
|
||||
int16_t magHold;
|
||||
int16_t headFreeModeHold;
|
||||
|
||||
|
@ -115,11 +113,12 @@ int16_t telemTemperature1; // gyro sensor temperature
|
|||
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||
|
||||
extern uint32_t currentTime;
|
||||
extern uint8_t dynP8[3], dynI8[3], dynD8[3], PIDweight[3];
|
||||
extern uint8_t PIDweight[3];
|
||||
extern bool antiWindupProtection;
|
||||
|
||||
uint16_t filteredCycleTime;
|
||||
static bool isRXDataNew;
|
||||
static bool armingCalibrationWasInitialised;
|
||||
|
||||
typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype
|
||||
|
@ -225,16 +224,16 @@ void scaleRcCommandToFpvCamAngle(void) {
|
|||
void annexCode(void)
|
||||
{
|
||||
int32_t tmp, tmp2;
|
||||
int32_t axis, prop1 = 0, prop2;
|
||||
int32_t axis, prop;
|
||||
|
||||
// PITCH & ROLL only dynamic PID adjustment, depending on throttle value
|
||||
if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) {
|
||||
prop2 = 100;
|
||||
prop = 100;
|
||||
} else {
|
||||
if (rcData[THROTTLE] < 2000) {
|
||||
prop2 = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint);
|
||||
prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint);
|
||||
} else {
|
||||
prop2 = 100 - currentControlRateProfile->dynThrPID;
|
||||
prop = 100 - currentControlRateProfile->dynThrPID;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -251,8 +250,6 @@ void annexCode(void)
|
|||
|
||||
tmp2 = tmp / 100;
|
||||
rcCommand[axis] = lookupPitchRollRC[tmp2] + (tmp - tmp2 * 100) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 100;
|
||||
prop1 = 100 - (uint16_t)currentControlRateProfile->rates[axis] * tmp / 500;
|
||||
prop1 = (uint16_t)prop1 * prop2 / 100;
|
||||
} else if (axis == YAW) {
|
||||
if (masterConfig.rcControlsConfig.yaw_deadband) {
|
||||
if (tmp > masterConfig.rcControlsConfig.yaw_deadband) {
|
||||
|
@ -263,20 +260,10 @@ void annexCode(void)
|
|||
}
|
||||
tmp2 = tmp / 100;
|
||||
rcCommand[axis] = (lookupYawRC[tmp2] + (tmp - tmp2 * 100) * (lookupYawRC[tmp2 + 1] - lookupYawRC[tmp2]) / 100) * -masterConfig.yaw_control_direction;
|
||||
prop1 = 100 - (uint16_t)currentControlRateProfile->rates[axis] * ABS(tmp) / 500;
|
||||
}
|
||||
// FIXME axis indexes into pids. use something like lookupPidIndex(rc_alias_e alias) to reduce coupling.
|
||||
dynP8[axis] = (uint16_t)currentProfile->pidProfile.P8[axis] * prop1 / 100;
|
||||
dynI8[axis] = (uint16_t)currentProfile->pidProfile.I8[axis] * prop1 / 100;
|
||||
dynD8[axis] = (uint16_t)currentProfile->pidProfile.D8[axis] * prop1 / 100;
|
||||
|
||||
// non coupled PID reduction scaler used in PID controller 1 and PID controller 2. YAW TPA disabled. 100 means 100% of the pids
|
||||
if (axis == YAW) {
|
||||
PIDweight[axis] = 100;
|
||||
}
|
||||
else {
|
||||
PIDweight[axis] = prop2;
|
||||
}
|
||||
// non coupled PID reduction scaler used in PID controller 1 and PID controller 2.
|
||||
PIDweight[axis] = prop;
|
||||
|
||||
if (rcData[axis] < masterConfig.rxConfig.midrc)
|
||||
rcCommand[axis] = -rcCommand[axis];
|
||||
|
@ -315,7 +302,7 @@ void annexCode(void)
|
|||
if (ARMING_FLAG(ARMED)) {
|
||||
LED0_ON;
|
||||
} else {
|
||||
if (IS_RC_MODE_ACTIVE(BOXARM) == 0) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXARM) == 0 || armingCalibrationWasInitialised) {
|
||||
ENABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
||||
|
@ -344,6 +331,8 @@ void annexCode(void)
|
|||
|
||||
void mwDisarm(void)
|
||||
{
|
||||
armingCalibrationWasInitialised = false;
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
DISABLE_ARMING_FLAG(ARMED);
|
||||
|
||||
|
@ -369,9 +358,15 @@ void releaseSharedTelemetryPorts(void) {
|
|||
|
||||
void mwArm(void)
|
||||
{
|
||||
if (!ARMING_FLAG(WAS_EVER_ARMED) && masterConfig.gyro_cal_on_first_arm) {
|
||||
gyroSetCalibrationCycles(calculateCalibratingCycles());
|
||||
}
|
||||
static bool firstArmingCalibrationWasCompleted;
|
||||
|
||||
if (masterConfig.gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) {
|
||||
gyroSetCalibrationCycles(calculateCalibratingCycles());
|
||||
armingCalibrationWasInitialised = true;
|
||||
firstArmingCalibrationWasCompleted = true;
|
||||
}
|
||||
|
||||
if (!isGyroCalibrationComplete()) return; // prevent arming before gyro is calibrated
|
||||
|
||||
if (ARMING_FLAG(OK_TO_ARM)) {
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
|
|
|
@ -13,13 +13,19 @@
|
|||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*
|
||||
* Driver for IBUS (Flysky) receiver
|
||||
* - initial implementation for MultiWii by Cesco/Plüschi
|
||||
* - implementation for BaseFlight by Andreas (fiendie) Tacke
|
||||
* - ported to CleanFlight by Konstantin (digitalentity) Sharlaimov
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
|
@ -32,9 +38,7 @@
|
|||
#include "rx/rx.h"
|
||||
#include "rx/ibus.h"
|
||||
|
||||
// Driver for IBUS (Flysky) receiver
|
||||
|
||||
#define IBUS_MAX_CHANNEL 8
|
||||
#define IBUS_MAX_CHANNEL 10
|
||||
#define IBUS_BUFFSIZE 32
|
||||
#define IBUS_SYNCBYTE 0x20
|
||||
|
||||
|
@ -95,7 +99,7 @@ static void ibusDataReceive(uint16_t c)
|
|||
|
||||
uint8_t ibusFrameStatus(void)
|
||||
{
|
||||
uint8_t i;
|
||||
uint8_t i, offset;
|
||||
uint8_t frameStatus = SERIAL_RX_FRAME_PENDING;
|
||||
uint16_t chksum, rxsum;
|
||||
|
||||
|
@ -112,15 +116,9 @@ uint8_t ibusFrameStatus(void)
|
|||
rxsum = ibus[30] + (ibus[31] << 8);
|
||||
|
||||
if (chksum == rxsum) {
|
||||
ibusChannelData[0] = (ibus[ 3] << 8) + ibus[ 2];
|
||||
ibusChannelData[1] = (ibus[ 5] << 8) + ibus[ 4];
|
||||
ibusChannelData[2] = (ibus[ 7] << 8) + ibus[ 6];
|
||||
ibusChannelData[3] = (ibus[ 9] << 8) + ibus[ 8];
|
||||
ibusChannelData[4] = (ibus[11] << 8) + ibus[10];
|
||||
ibusChannelData[5] = (ibus[13] << 8) + ibus[12];
|
||||
ibusChannelData[6] = (ibus[15] << 8) + ibus[14];
|
||||
ibusChannelData[7] = (ibus[17] << 8) + ibus[16];
|
||||
|
||||
for (i = 0, offset = 2; i < IBUS_MAX_CHANNEL; i++, offset += 2) {
|
||||
ibusChannelData[i] = ibus[offset] + (ibus[offset + 1] << 8);
|
||||
}
|
||||
frameStatus = SERIAL_RX_FRAME_COMPLETE;
|
||||
}
|
||||
|
||||
|
|
|
@ -18,3 +18,4 @@
|
|||
#pragma once
|
||||
|
||||
uint8_t ibusFrameStatus(void);
|
||||
bool ibusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
|
|
|
@ -124,8 +124,9 @@ typedef struct rxConfig_s {
|
|||
uint8_t rcSmoothing;
|
||||
uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
|
||||
uint8_t max_aux_channel;
|
||||
uint8_t acroPlusFactor; // Air mode acrobility factor
|
||||
uint8_t acroPlusOffset; // Air mode stick offset
|
||||
uint8_t superExpoFactor; // Super Expo Factor
|
||||
uint8_t superExpoFactorYaw; // Super Expo Factor Yaw
|
||||
uint8_t superExpoYawMode; // Seperate Super expo for yaw
|
||||
|
||||
uint16_t rx_min_usec;
|
||||
uint16_t rx_max_usec;
|
||||
|
|
|
@ -83,7 +83,6 @@ typedef enum {
|
|||
TASK_OSD,
|
||||
#endif
|
||||
#ifdef USE_BST
|
||||
TASK_BST_READ_WRITE,
|
||||
TASK_BST_MASTER_PROCESS,
|
||||
#endif
|
||||
|
||||
|
|
|
@ -198,13 +198,6 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
#endif
|
||||
|
||||
#ifdef USE_BST
|
||||
[TASK_BST_READ_WRITE] = {
|
||||
.taskName = "BST_MASTER_WRITE",
|
||||
.taskFunc = taskBstReadWrite,
|
||||
.desiredPeriod = 1000000 / 100, // 100 Hz
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
|
||||
[TASK_BST_MASTER_PROCESS] = {
|
||||
.taskName = "BST_MASTER_PROCESS",
|
||||
.taskFunc = taskBstMasterProcess,
|
||||
|
|
|
@ -83,8 +83,6 @@ static void updateBatteryVoltage(void)
|
|||
}
|
||||
|
||||
#define VBATTERY_STABLE_DELAY 40
|
||||
/* Batt Hysteresis of +/-100mV */
|
||||
#define VBATT_HYSTERESIS 1
|
||||
|
||||
void updateBattery(void)
|
||||
{
|
||||
|
@ -123,23 +121,23 @@ void updateBattery(void)
|
|||
switch(batteryState)
|
||||
{
|
||||
case BATTERY_OK:
|
||||
if (vbat <= (batteryWarningVoltage - VBATT_HYSTERESIS)) {
|
||||
if (vbat <= (batteryWarningVoltage - batteryConfig->vbathysteresis)) {
|
||||
batteryState = BATTERY_WARNING;
|
||||
beeper(BEEPER_BAT_LOW);
|
||||
}
|
||||
break;
|
||||
case BATTERY_WARNING:
|
||||
if (vbat <= (batteryCriticalVoltage - VBATT_HYSTERESIS)) {
|
||||
if (vbat <= (batteryCriticalVoltage - batteryConfig->vbathysteresis)) {
|
||||
batteryState = BATTERY_CRITICAL;
|
||||
beeper(BEEPER_BAT_CRIT_LOW);
|
||||
} else if (vbat > (batteryWarningVoltage + VBATT_HYSTERESIS)){
|
||||
} else if (vbat > (batteryWarningVoltage + batteryConfig->vbathysteresis)){
|
||||
batteryState = BATTERY_OK;
|
||||
} else {
|
||||
beeper(BEEPER_BAT_LOW);
|
||||
}
|
||||
break;
|
||||
case BATTERY_CRITICAL:
|
||||
if (vbat > (batteryCriticalVoltage + VBATT_HYSTERESIS)){
|
||||
if (vbat > (batteryCriticalVoltage + batteryConfig->vbathysteresis)){
|
||||
batteryState = BATTERY_WARNING;
|
||||
beeper(BEEPER_BAT_LOW);
|
||||
} else {
|
||||
|
|
|
@ -40,6 +40,7 @@ typedef struct batteryConfig_s {
|
|||
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
|
||||
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery critical alarm, in 0.1V units, default is 33 (3.3V)
|
||||
uint8_t vbatwarningcellvoltage; // warning voltage per cell, this triggers battery warning alarm, in 0.1V units, default is 35 (3.5V)
|
||||
uint8_t vbathysteresis; // hysteresis for alarm, default 1 = 0.1V
|
||||
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
|
||||
|
||||
int16_t currentMeterScale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
|
||||
|
|
|
@ -117,7 +117,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3) || defined(SPRACINGF3MINI)
|
||||
#if defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(SPRACINGF3EVO)
|
||||
static const extiConfig_t spRacingF3MPUIntExtiConfig = {
|
||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
|
||||
.gpioPort = GPIOC,
|
||||
|
@ -169,6 +169,19 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
|
|||
return &RaceMPUIntExtiConfig;
|
||||
#endif
|
||||
|
||||
#if defined(DOGE)
|
||||
static const extiConfig_t dogeMPUIntExtiConfig = {
|
||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
|
||||
.gpioPort = GPIOC,
|
||||
.gpioPin = Pin_13,
|
||||
.exti_port_source = EXTI_PortSourceGPIOC,
|
||||
.exti_pin_source = EXTI_PinSource13,
|
||||
.exti_line = EXTI_Line13,
|
||||
.exti_irqn = EXTI15_10_IRQn
|
||||
};
|
||||
return &dogeMPUIntExtiConfig;
|
||||
#endif
|
||||
|
||||
#if defined(MOTOLAB) || defined(SPARKY)
|
||||
static const extiConfig_t MotolabF3MPU6050Config = {
|
||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
|
||||
|
|
|
@ -0,0 +1,501 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file startup_stm32f30x.s
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 04-Spetember-2012
|
||||
* @brief STM32F30x Devices vector table for RIDE7 toolchain.
|
||||
* This module performs:
|
||||
* - Set the initial SP
|
||||
* - Set the initial PC == Reset_Handler,
|
||||
* - Set the vector table entries with the exceptions ISR address
|
||||
* - Configure the clock system and the external SRAM mounted on
|
||||
* STM3230C-EVAL board to be used as data memory (optional,
|
||||
* to be enabled by user)
|
||||
* - Branches to main in the C library (which eventually
|
||||
* calls main()).
|
||||
* After Reset the Cortex-M4 processor is in Thread mode,
|
||||
* priority is Privileged, and the Stack is set to Main.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2012 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
.syntax unified
|
||||
.cpu cortex-m4
|
||||
.fpu softvfp
|
||||
.thumb
|
||||
|
||||
.global g_pfnVectors
|
||||
.global Default_Handler
|
||||
|
||||
.global HardFault_Handler
|
||||
.extern hard_fault_handler_c
|
||||
|
||||
/* start address for the initialization values of the .data section.
|
||||
defined in linker script */
|
||||
.word _sidata
|
||||
/* start address for the .data section. defined in linker script */
|
||||
.word _sdata
|
||||
/* end address for the .data section. defined in linker script */
|
||||
.word _edata
|
||||
/* start address for the .bss section. defined in linker script */
|
||||
.word _sbss
|
||||
/* end address for the .bss section. defined in linker script */
|
||||
.word _ebss
|
||||
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor first
|
||||
* starts execution following a reset event. Only the absolutely
|
||||
* necessary set is performed, after which the application
|
||||
* supplied main() routine is called.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
|
||||
.section .text.Reset_Handler
|
||||
.weak Reset_Handler
|
||||
.type Reset_Handler, %function
|
||||
Reset_Handler:
|
||||
ldr r0, =0x20009FFC // HJI 11/9/2012
|
||||
ldr r1, =0xDEADBEEF // HJI 11/9/2012
|
||||
ldr r2, [r0, #0] // HJI 11/9/2012
|
||||
str r0, [r0, #0] // HJI 11/9/2012
|
||||
cmp r2, r1 // HJI 11/9/2012
|
||||
beq Reboot_Loader // HJI 11/9/2012
|
||||
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
movs r1, #0
|
||||
b LoopCopyDataInit
|
||||
|
||||
CopyDataInit:
|
||||
ldr r3, =_sidata
|
||||
ldr r3, [r3, r1]
|
||||
str r3, [r0, r1]
|
||||
adds r1, r1, #4
|
||||
|
||||
LoopCopyDataInit:
|
||||
ldr r0, =_sdata
|
||||
ldr r3, =_edata
|
||||
adds r2, r0, r1
|
||||
cmp r2, r3
|
||||
bcc CopyDataInit
|
||||
ldr r2, =_sbss
|
||||
b LoopFillZerobss
|
||||
/* Zero fill the bss segment. */
|
||||
FillZerobss:
|
||||
movs r3, #0
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillZerobss:
|
||||
ldr r3, = _ebss
|
||||
cmp r2, r3
|
||||
bcc FillZerobss
|
||||
|
||||
/* Call the clock system intitialization function.*/
|
||||
bl SystemInit
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
bx lr
|
||||
|
||||
LoopForever:
|
||||
b LoopForever
|
||||
|
||||
Reboot_Loader: // HJI 11/9/2012
|
||||
|
||||
// Reboot to ROM // HJI 11/9/2012
|
||||
ldr r0, =0x1FFFD800 // HJI 4/26/2013
|
||||
ldr sp,[r0, #0] // HJI 11/9/2012
|
||||
ldr r0,[r0, #4] // HJI 11/9/2012
|
||||
bx r0 // HJI 11/9/2012
|
||||
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
.section .text.Reset_Handler
|
||||
.weak HardFault_Handler
|
||||
.type HardFault_Handler, %function
|
||||
HardFault_Handler:
|
||||
movs r0,#4
|
||||
movs r1, lr
|
||||
tst r0, r1
|
||||
beq _MSP
|
||||
mrs r0, psp
|
||||
b _HALT
|
||||
_MSP:
|
||||
mrs r0, msp
|
||||
_HALT:
|
||||
ldr r1,[r0,#20]
|
||||
b hard_fault_handler_c
|
||||
bkpt #0
|
||||
|
||||
.size HardFault_Handler, .-HardFault_Handler
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* unexpected interrupt. This simply enters an infinite loop, preserving
|
||||
* the system state for examination by a debugger.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
Infinite_Loop:
|
||||
b Infinite_Loop
|
||||
.size Default_Handler, .-Default_Handler
|
||||
/******************************************************************************
|
||||
*
|
||||
* The minimal vector table for a Cortex M4. Note that the proper constructs
|
||||
* must be placed on this to ensure that it ends up at physical address
|
||||
* 0x0000.0000.
|
||||
*
|
||||
*******************************************************************************/
|
||||
.section .isr_vector,"a",%progbits
|
||||
.type g_pfnVectors, %object
|
||||
.size g_pfnVectors, .-g_pfnVectors
|
||||
|
||||
g_pfnVectors:
|
||||
.word _estack
|
||||
.word Reset_Handler
|
||||
.word NMI_Handler
|
||||
.word HardFault_Handler
|
||||
.word MemManage_Handler
|
||||
.word BusFault_Handler
|
||||
.word UsageFault_Handler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word SVC_Handler
|
||||
.word DebugMon_Handler
|
||||
.word 0
|
||||
.word PendSV_Handler
|
||||
.word SysTick_Handler
|
||||
.word WWDG_IRQHandler
|
||||
.word PVD_IRQHandler
|
||||
.word TAMPER_STAMP_IRQHandler
|
||||
.word RTC_WKUP_IRQHandler
|
||||
.word FLASH_IRQHandler
|
||||
.word RCC_IRQHandler
|
||||
.word EXTI0_IRQHandler
|
||||
.word EXTI1_IRQHandler
|
||||
.word EXTI2_TS_IRQHandler
|
||||
.word EXTI3_IRQHandler
|
||||
.word EXTI4_IRQHandler
|
||||
.word DMA1_Channel1_IRQHandler
|
||||
.word DMA1_Channel2_IRQHandler
|
||||
.word DMA1_Channel3_IRQHandler
|
||||
.word DMA1_Channel4_IRQHandler
|
||||
.word DMA1_Channel5_IRQHandler
|
||||
.word DMA1_Channel6_IRQHandler
|
||||
.word DMA1_Channel7_IRQHandler
|
||||
.word ADC1_2_IRQHandler
|
||||
.word USB_HP_CAN1_TX_IRQHandler
|
||||
.word USB_LP_CAN1_RX0_IRQHandler
|
||||
.word CAN1_RX1_IRQHandler
|
||||
.word CAN1_SCE_IRQHandler
|
||||
.word EXTI9_5_IRQHandler
|
||||
.word TIM1_BRK_TIM15_IRQHandler
|
||||
.word TIM1_UP_TIM16_IRQHandler
|
||||
.word TIM1_TRG_COM_TIM17_IRQHandler
|
||||
.word TIM1_CC_IRQHandler
|
||||
.word TIM2_IRQHandler
|
||||
.word TIM3_IRQHandler
|
||||
.word TIM4_IRQHandler
|
||||
.word I2C1_EV_IRQHandler
|
||||
.word I2C1_ER_IRQHandler
|
||||
.word I2C2_EV_IRQHandler
|
||||
.word I2C2_ER_IRQHandler
|
||||
.word SPI1_IRQHandler
|
||||
.word SPI2_IRQHandler
|
||||
.word USART1_IRQHandler
|
||||
.word USART2_IRQHandler
|
||||
.word USART3_IRQHandler
|
||||
.word EXTI15_10_IRQHandler
|
||||
.word RTC_Alarm_IRQHandler
|
||||
.word USBWakeUp_IRQHandler
|
||||
.word TIM8_BRK_IRQHandler
|
||||
.word TIM8_UP_IRQHandler
|
||||
.word TIM8_TRG_COM_IRQHandler
|
||||
.word TIM8_CC_IRQHandler
|
||||
.word ADC3_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word SPI3_IRQHandler
|
||||
.word UART4_IRQHandler
|
||||
.word UART5_IRQHandler
|
||||
.word TIM6_DAC_IRQHandler
|
||||
.word TIM7_IRQHandler
|
||||
.word DMA2_Channel1_IRQHandler
|
||||
.word DMA2_Channel2_IRQHandler
|
||||
.word DMA2_Channel3_IRQHandler
|
||||
.word DMA2_Channel4_IRQHandler
|
||||
.word DMA2_Channel5_IRQHandler
|
||||
.word ADC4_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word COMP1_2_3_IRQHandler
|
||||
.word COMP4_5_6_IRQHandler
|
||||
.word COMP7_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word USB_HP_IRQHandler
|
||||
.word USB_LP_IRQHandler
|
||||
.word USBWakeUp_RMP_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word FPU_IRQHandler
|
||||
|
||||
/*******************************************************************************
|
||||
*
|
||||
* Provide weak aliases for each Exception handler to the Default_Handler.
|
||||
* As they are weak aliases, any function with the same name will override
|
||||
* this definition.
|
||||
*
|
||||
*******************************************************************************/
|
||||
|
||||
.weak NMI_Handler
|
||||
.thumb_set NMI_Handler,Default_Handler
|
||||
|
||||
.weak MemManage_Handler
|
||||
.thumb_set MemManage_Handler,Default_Handler
|
||||
|
||||
.weak BusFault_Handler
|
||||
.thumb_set BusFault_Handler,Default_Handler
|
||||
|
||||
.weak UsageFault_Handler
|
||||
.thumb_set UsageFault_Handler,Default_Handler
|
||||
|
||||
.weak SVC_Handler
|
||||
.thumb_set SVC_Handler,Default_Handler
|
||||
|
||||
.weak DebugMon_Handler
|
||||
.thumb_set DebugMon_Handler,Default_Handler
|
||||
|
||||
.weak PendSV_Handler
|
||||
.thumb_set PendSV_Handler,Default_Handler
|
||||
|
||||
.weak SysTick_Handler
|
||||
.thumb_set SysTick_Handler,Default_Handler
|
||||
|
||||
.weak WWDG_IRQHandler
|
||||
.thumb_set WWDG_IRQHandler,Default_Handler
|
||||
|
||||
.weak PVD_IRQHandler
|
||||
.thumb_set PVD_IRQHandler,Default_Handler
|
||||
|
||||
.weak TAMPER_STAMP_IRQHandler
|
||||
.thumb_set TAMPER_STAMP_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTC_WKUP_IRQHandler
|
||||
.thumb_set RTC_WKUP_IRQHandler,Default_Handler
|
||||
|
||||
.weak FLASH_IRQHandler
|
||||
.thumb_set FLASH_IRQHandler,Default_Handler
|
||||
|
||||
.weak RCC_IRQHandler
|
||||
.thumb_set RCC_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI0_IRQHandler
|
||||
.thumb_set EXTI0_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI1_IRQHandler
|
||||
.thumb_set EXTI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI2_TS_IRQHandler
|
||||
.thumb_set EXTI2_TS_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI3_IRQHandler
|
||||
.thumb_set EXTI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI4_IRQHandler
|
||||
.thumb_set EXTI4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel1_IRQHandler
|
||||
.thumb_set DMA1_Channel1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel2_IRQHandler
|
||||
.thumb_set DMA1_Channel2_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel3_IRQHandler
|
||||
.thumb_set DMA1_Channel3_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel4_IRQHandler
|
||||
.thumb_set DMA1_Channel4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel5_IRQHandler
|
||||
.thumb_set DMA1_Channel5_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel6_IRQHandler
|
||||
.thumb_set DMA1_Channel6_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel7_IRQHandler
|
||||
.thumb_set DMA1_Channel7_IRQHandler,Default_Handler
|
||||
|
||||
.weak ADC1_2_IRQHandler
|
||||
.thumb_set ADC1_2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_HP_CAN1_TX_IRQHandler
|
||||
.thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_LP_CAN1_RX0_IRQHandler
|
||||
.thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN1_RX1_IRQHandler
|
||||
.thumb_set CAN1_RX1_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN1_SCE_IRQHandler
|
||||
.thumb_set CAN1_SCE_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI9_5_IRQHandler
|
||||
.thumb_set EXTI9_5_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_BRK_TIM15_IRQHandler
|
||||
.thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_UP_TIM16_IRQHandler
|
||||
.thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_TRG_COM_TIM17_IRQHandler
|
||||
.thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_CC_IRQHandler
|
||||
.thumb_set TIM1_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM2_IRQHandler
|
||||
.thumb_set TIM2_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM3_IRQHandler
|
||||
.thumb_set TIM3_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM4_IRQHandler
|
||||
.thumb_set TIM4_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_EV_IRQHandler
|
||||
.thumb_set I2C1_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_ER_IRQHandler
|
||||
.thumb_set I2C1_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_EV_IRQHandler
|
||||
.thumb_set I2C2_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_ER_IRQHandler
|
||||
.thumb_set I2C2_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI1_IRQHandler
|
||||
.thumb_set SPI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI2_IRQHandler
|
||||
.thumb_set SPI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART1_IRQHandler
|
||||
.thumb_set USART1_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART2_IRQHandler
|
||||
.thumb_set USART2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART3_IRQHandler
|
||||
.thumb_set USART3_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI15_10_IRQHandler
|
||||
.thumb_set EXTI15_10_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTC_Alarm_IRQHandler
|
||||
.thumb_set RTC_Alarm_IRQHandler,Default_Handler
|
||||
|
||||
.weak USBWakeUp_IRQHandler
|
||||
.thumb_set USBWakeUp_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_BRK_IRQHandler
|
||||
.thumb_set TIM8_BRK_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_UP_IRQHandler
|
||||
.thumb_set TIM8_UP_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_TRG_COM_IRQHandler
|
||||
.thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_CC_IRQHandler
|
||||
.thumb_set TIM8_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak ADC3_IRQHandler
|
||||
.thumb_set ADC3_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI3_IRQHandler
|
||||
.thumb_set SPI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART4_IRQHandler
|
||||
.thumb_set UART4_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART5_IRQHandler
|
||||
.thumb_set UART5_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM6_DAC_IRQHandler
|
||||
.thumb_set TIM6_DAC_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM7_IRQHandler
|
||||
.thumb_set TIM7_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel1_IRQHandler
|
||||
.thumb_set DMA2_Channel1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel2_IRQHandler
|
||||
.thumb_set DMA2_Channel2_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel3_IRQHandler
|
||||
.thumb_set DMA2_Channel3_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel4_IRQHandler
|
||||
.thumb_set DMA2_Channel4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel5_IRQHandler
|
||||
.thumb_set DMA2_Channel5_IRQHandler,Default_Handler
|
||||
|
||||
.weak ADC4_IRQHandler
|
||||
.thumb_set ADC4_IRQHandler,Default_Handler
|
||||
|
||||
.weak COMP1_2_3_IRQHandler
|
||||
.thumb_set COMP1_2_3_IRQHandler,Default_Handler
|
||||
|
||||
.weak COMP4_5_6_IRQHandler
|
||||
.thumb_set COMP4_5_6_IRQHandler,Default_Handler
|
||||
|
||||
.weak COMP7_IRQHandler
|
||||
.thumb_set COMP7_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_HP_IRQHandler
|
||||
.thumb_set USB_HP_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_LP_IRQHandler
|
||||
.thumb_set USB_LP_IRQHandler,Default_Handler
|
||||
|
||||
.weak USBWakeUp_RMP_IRQHandler
|
||||
.thumb_set USBWakeUp_RMP_IRQHandler,Default_Handler
|
||||
|
||||
.weak FPU_IRQHandler
|
||||
.thumb_set FPU_IRQHandler,Default_Handler
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -124,16 +124,8 @@
|
|||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// FlexPort (pin 21/22, TX/RX respectively):
|
||||
// Note, FlexPort has 10k pullups on both TX and RX
|
||||
// JST Pin3 TX - connect to external UART/USB RX
|
||||
#define S1W_TX_GPIO GPIOB
|
||||
#define S1W_TX_PIN GPIO_Pin_10
|
||||
// JST Pin4 RX - connect to external UART/USB TX
|
||||
#define S1W_RX_GPIO GPIOB
|
||||
#define S1W_RX_PIN GPIO_Pin_11
|
||||
|
||||
#undef DISPLAY
|
||||
#undef SONAR
|
||||
|
|
|
@ -43,6 +43,11 @@
|
|||
#define MPU6500_CS_PIN GPIO_Pin_4
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define MPU6000_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define MPU6000_CS_GPIO GPIOA
|
||||
#define MPU6000_CS_PIN GPIO_Pin_4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
|
@ -60,11 +65,15 @@
|
|||
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_SPI_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||
|
@ -73,7 +82,9 @@
|
|||
#define USE_BARO_MS5611
|
||||
|
||||
#define MAG
|
||||
#define USE_MPU9250_MAG
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
|
||||
#define BEEPER
|
||||
|
@ -155,6 +166,7 @@
|
|||
#define GPS
|
||||
//#define GTUNE
|
||||
#define LED_STRIP
|
||||
#define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG
|
||||
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
|
||||
|
@ -181,8 +193,4 @@
|
|||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
#define S1W_TX_GPIO GPIOB
|
||||
#define S1W_TX_PIN GPIO_Pin_10
|
||||
#define S1W_RX_GPIO GPIOB
|
||||
#define S1W_RX_PIN GPIO_Pin_11
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -0,0 +1,372 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 28-March-2014
|
||||
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||
* This file contains the system clock configuration for STM32F30x devices,
|
||||
* and is generated by the clock configuration tool
|
||||
* stm32f30x_Clock_Configuration_V1.0.0.xls
|
||||
*
|
||||
* 1. This file provides two functions and one global variable to be called from
|
||||
* user application:
|
||||
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
|
||||
* and Divider factors, AHB/APBx prescalers and Flash settings),
|
||||
* depending on the configuration made in the clock xls tool.
|
||||
* This function is called at startup just after reset and
|
||||
* before branch to main program. This call is made inside
|
||||
* the "startup_stm32f30x.s" file.
|
||||
*
|
||||
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||
* by the user application to setup the SysTick
|
||||
* timer or configure other parameters.
|
||||
*
|
||||
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||
* be called whenever the core clock is changed
|
||||
* during program execution.
|
||||
*
|
||||
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
|
||||
* Then SystemInit() function is called, in "startup_stm32f30x.s" file, to
|
||||
* configure the system clock before to branch to main program.
|
||||
*
|
||||
* 3. If the system clock source selected by user fails to startup, the SystemInit()
|
||||
* function will do nothing and HSI still used as system clock source. User can
|
||||
* add some code to deal with this issue inside the SetSysClock() function.
|
||||
*
|
||||
* 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
|
||||
* in "stm32f30x.h" file. When HSE is used as system clock source, directly or
|
||||
* through PLL, and you are using different crystal you have to adapt the HSE
|
||||
* value to your own configuration.
|
||||
*
|
||||
* 5. This file configures the system clock as follows:
|
||||
*=============================================================================
|
||||
* Supported STM32F30x device
|
||||
*-----------------------------------------------------------------------------
|
||||
* System Clock source | PLL (HSE)
|
||||
*-----------------------------------------------------------------------------
|
||||
* SYSCLK(Hz) | 72000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* HCLK(Hz) | 72000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* AHB Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB2 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB1 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* HSE Frequency(Hz) | 8000000
|
||||
*----------------------------------------------------------------------------
|
||||
* PLLMUL | 9
|
||||
*-----------------------------------------------------------------------------
|
||||
* PREDIV | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* USB Clock | ENABLE
|
||||
*-----------------------------------------------------------------------------
|
||||
* Flash Latency(WS) | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* Prefetch Buffer | ON
|
||||
*-----------------------------------------------------------------------------
|
||||
*=============================================================================
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include "stm32f30x.h"
|
||||
|
||||
uint32_t hse_value = HSE_VALUE;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||
Internal SRAM. */
|
||||
/* #define VECT_TAB_SRAM */
|
||||
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
|
||||
This value must be a multiple of 0x200. */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
uint32_t SystemCoreClock = 72000000;
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
void SetSysClock(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system
|
||||
* Initialize the Embedded Flash Interface, the PLL and update the
|
||||
* SystemFrequency variable.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemInit(void)
|
||||
{
|
||||
/* FPU settings ------------------------------------------------------------*/
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||
#endif
|
||||
|
||||
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||
/* Set HSION bit */
|
||||
RCC->CR |= (uint32_t)0x00000001;
|
||||
|
||||
/* Reset CFGR register */
|
||||
RCC->CFGR &= 0xF87FC00C;
|
||||
|
||||
/* Reset HSEON, CSSON and PLLON bits */
|
||||
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||
|
||||
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
|
||||
RCC->CFGR &= (uint32_t)0xFF80FFFF;
|
||||
|
||||
/* Reset PREDIV1[3:0] bits */
|
||||
RCC->CFGR2 &= (uint32_t)0xFFFFFFF0;
|
||||
|
||||
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
|
||||
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
|
||||
|
||||
/* Disable all interrupts */
|
||||
RCC->CIR = 0x00000000;
|
||||
|
||||
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||
//SetSysClock(); // called from main()
|
||||
|
||||
#ifdef VECT_TAB_SRAM
|
||||
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
|
||||
#else
|
||||
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||
* be used by the user application to setup the SysTick timer or configure
|
||||
* other parameters.
|
||||
*
|
||||
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||
* based on this variable will be incorrect.
|
||||
*
|
||||
* @note - The system frequency computed by this function is not the real
|
||||
* frequency in the chip. It is calculated based on the predefined
|
||||
* constant and the selected clock source:
|
||||
*
|
||||
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||
*
|
||||
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
*
|
||||
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||
*
|
||||
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
|
||||
* 8 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
|
||||
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||
* frequency of the crystal used. Otherwise, this function may
|
||||
* have wrong result.
|
||||
*
|
||||
* - The result of this function could be not correct when using fractional
|
||||
* value for HSE crystal.
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemCoreClockUpdate (void)
|
||||
{
|
||||
uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00: /* HSI used as system clock */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04: /* HSE used as system clock */
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08: /* PLL used as system clock */
|
||||
/* Get PLL clock source and multiplication factor ----------------------*/
|
||||
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
|
||||
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
|
||||
pllmull = ( pllmull >> 18) + 2;
|
||||
|
||||
if (pllsource == 0x00)
|
||||
{
|
||||
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
|
||||
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||
}
|
||||
else
|
||||
{
|
||||
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
|
||||
/* HSE oscillator clock selected as PREDIV1 clock entry */
|
||||
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
|
||||
}
|
||||
break;
|
||||
default: /* HSI used as system clock */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
/* Compute HCLK clock frequency ----------------*/
|
||||
/* Get HCLK prescaler */
|
||||
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||
/* HCLK clock frequency */
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||
* AHB/APBx prescalers and Flash settings
|
||||
* @note This function should be called only once the RCC clock configuration
|
||||
* is reset to the default reset state (done in SystemInit() function).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SetSysClock(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
/******************************************************************************/
|
||||
/* PLL (clocked by HSE) used as System clock source */
|
||||
/******************************************************************************/
|
||||
|
||||
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
|
||||
/* Enable HSE */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable Prefetch Buffer and set Flash Latency */
|
||||
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
|
||||
|
||||
/* HCLK = SYSCLK / 1 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
|
||||
|
||||
/* PCLK2 = HCLK / 1 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
|
||||
|
||||
/* PCLK1 = HCLK / 2 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
|
||||
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||
configuration. User can add here some code to deal with this error */
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
@ -0,0 +1,76 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 28-March-2014
|
||||
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Define to prevent recursive inclusion
|
||||
*/
|
||||
#ifndef __SYSTEM_STM32F30X_H
|
||||
#define __SYSTEM_STM32F30X_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
/** @addtogroup STM32F30x_System_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__SYSTEM_STM32F30X_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,204 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "DOGE"
|
||||
|
||||
// tqfp48 pin 34
|
||||
#define LED0_GPIO GPIOA
|
||||
#define LED0_PIN Pin_13
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
||||
// tqfp48 pin 37
|
||||
#define LED1_GPIO GPIOA
|
||||
#define LED1_PIN Pin_14
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
||||
// tqfp48 pin 38
|
||||
#define LED2_GPIO GPIOA
|
||||
#define LED2_PIN Pin_15
|
||||
#define LED2_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
||||
#define BEEP_GPIO GPIOB
|
||||
#define BEEP_PIN Pin_2
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
//#define BEEPER_INVERTED
|
||||
|
||||
// #define BEEP_GPIO GPIOB
|
||||
// #define BEEP_PIN Pin_13
|
||||
// #define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
// #define BEEPER_INVERTED
|
||||
|
||||
// tqfp48 pin 3
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define MPU6500_CS_GPIO GPIOC
|
||||
#define MPU6500_CS_PIN GPIO_Pin_14
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
// tqfp48 pin 25
|
||||
#define BMP280_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define BMP280_CS_GPIO GPIOB
|
||||
#define BMP280_CS_PIN GPIO_Pin_12
|
||||
#define BMP280_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define SPI1_GPIO GPIOB
|
||||
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
// tqfp48 pin 39
|
||||
#define SPI1_SCK_PIN GPIO_Pin_3
|
||||
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
|
||||
// tqfp48 pin 40
|
||||
#define SPI1_MISO_PIN GPIO_Pin_4
|
||||
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
|
||||
// tqfp48 pin 41
|
||||
#define SPI1_MOSI_PIN GPIO_Pin_5
|
||||
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
|
||||
|
||||
#define SPI2_GPIO GPIOB
|
||||
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
// tqfp48 pin 26
|
||||
#define SPI2_SCK_PIN GPIO_Pin_13
|
||||
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
|
||||
// tqfp48 pin 27
|
||||
#define SPI2_MISO_PIN GPIO_Pin_14
|
||||
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
|
||||
// tqfp48 pin 28
|
||||
#define SPI2_MOSI_PIN GPIO_Pin_15
|
||||
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
|
||||
|
||||
// timer definitions in drivers/timer.c
|
||||
// channel mapping in drivers/pwm_mapping.c
|
||||
// only 6 outputs available on hardware
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 9
|
||||
|
||||
#define USE_ESCSERIAL
|
||||
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||
|
||||
#define GYRO
|
||||
// #define USE_FAKE_GYRO
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define GYRO_MPU6500_ALIGN CW270_DEG // ??
|
||||
|
||||
#define ACC
|
||||
// #define USE_FAKE_ACC
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW270_DEG // ??
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_SPI_BMP280
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define LED2
|
||||
|
||||
#define USB_IO
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
// tqfp48 pin 42
|
||||
#define UART1_TX_PIN GPIO_Pin_6
|
||||
// tqfp48 pin 43
|
||||
#define UART1_RX_PIN GPIO_Pin_7
|
||||
#define UART1_GPIO GPIOB
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource6
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource7
|
||||
|
||||
// tqfp48 pin 12
|
||||
#define UART2_TX_PIN GPIO_Pin_2
|
||||
// tqfp48 pin 13
|
||||
#define UART2_RX_PIN GPIO_Pin_3
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource2
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource3
|
||||
|
||||
// tqfp48 pin 21
|
||||
#define UART3_TX_PIN GPIO_Pin_10
|
||||
// tqfp48 pin 22
|
||||
#define UART3_RX_PIN GPIO_Pin_11
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
|
||||
// tqfp48 pin 14
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
// tqfp48 pin 15
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
// mpu_int definition in sensors/initialisation.c
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
|
||||
|
||||
#define BLACKBOX
|
||||
#define GPS
|
||||
//#define GTUNE
|
||||
#define LED_STRIP
|
||||
|
||||
// tqfp48 pin 16
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define WS2811_GPIO_AF GPIO_AF_1
|
||||
#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource6
|
||||
#define WS2811_TIMER TIM16
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel3
|
||||
#define WS2811_IRQ DMA1_Channel3_IRQn
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
|
||||
|
||||
#define TELEMETRY
|
||||
#define SERIAL_RX
|
||||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// Use UART3 for speksat
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
@ -162,8 +162,22 @@
|
|||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#define USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
|
||||
#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
|
||||
#ifdef USE_VCP
|
||||
#define USE_SERIAL_1WIRE_VCP
|
||||
#else
|
||||
#define USE_SERIAL_1WIRE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERIAL_1WIRE
|
||||
#define S1W_TX_GPIO GPIOA
|
||||
#define S1W_TX_PIN GPIO_Pin_9
|
||||
#define S1W_RX_GPIO GPIOA
|
||||
#define S1W_RX_PIN GPIO_Pin_10
|
||||
#endif
|
||||
|
||||
|
||||
|
|
|
@ -162,9 +162,4 @@
|
|||
#define BIND_PORT GPIOC
|
||||
#define BIND_PIN Pin_5
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
// Untested
|
||||
#define S1W_TX_GPIO GPIOB
|
||||
#define S1W_TX_PIN GPIO_Pin_10
|
||||
#define S1W_RX_GPIO GPIOB
|
||||
#define S1W_RX_PIN GPIO_Pin_11
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -188,10 +188,4 @@
|
|||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_4
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
|
||||
#define S1W_TX_GPIO GPIOB
|
||||
#define S1W_TX_PIN GPIO_Pin_6
|
||||
#define S1W_RX_GPIO GPIOB
|
||||
#define S1W_RX_PIN GPIO_Pin_7
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -188,14 +188,7 @@
|
|||
#define BIND_PORT GPIOA
|
||||
#define BIND_PIN Pin_3
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
|
||||
// STM32F103CBT6-LQFP48 Pin30 (PA9) TX - PC3 connects to onboard CP2102 RX
|
||||
#define S1W_TX_GPIO GPIOA
|
||||
#define S1W_TX_PIN GPIO_Pin_9
|
||||
// STM32F103CBT6-LQFP48 Pin31 (PA10) RX - PC1 to onboard CP2102 TX
|
||||
#define S1W_RX_GPIO GPIOA
|
||||
#define S1W_RX_PIN GPIO_Pin_10
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// alternative defaults for AlienWii32 F1 target
|
||||
#ifdef ALIENWII32
|
||||
|
|
|
@ -156,3 +156,5 @@
|
|||
#define TELEMETRY
|
||||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -154,9 +154,4 @@
|
|||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
|
||||
#define S1W_TX_GPIO GPIOA
|
||||
#define S1W_TX_PIN GPIO_Pin_9
|
||||
#define S1W_RX_GPIO GPIOA
|
||||
#define S1W_RX_PIN GPIO_Pin_10
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -163,12 +163,7 @@
|
|||
#define WS2811_IRQ DMA1_Channel7_IRQn
|
||||
#endif
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
|
||||
#define S1W_TX_GPIO GPIOB
|
||||
#define S1W_TX_PIN GPIO_Pin_6
|
||||
#define S1W_RX_GPIO GPIOB
|
||||
#define S1W_RX_PIN GPIO_Pin_7
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
|
|
|
@ -163,9 +163,4 @@
|
|||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
|
||||
#define S1W_TX_GPIO GPIOA
|
||||
#define S1W_TX_PIN GPIO_Pin_9
|
||||
#define S1W_RX_GPIO GPIOA
|
||||
#define S1W_RX_PIN GPIO_Pin_10
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -0,0 +1,371 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 28-March-2014
|
||||
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||
* This file contains the system clock configuration for STM32F30x devices,
|
||||
* and is generated by the clock configuration tool
|
||||
* stm32f30x_Clock_Configuration_V1.0.0.xls
|
||||
*
|
||||
* 1. This file provides two functions and one global variable to be called from
|
||||
* user application:
|
||||
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
|
||||
* and Divider factors, AHB/APBx prescalers and Flash settings),
|
||||
* depending on the configuration made in the clock xls tool.
|
||||
* This function is called at startup just after reset and
|
||||
* before branch to main program. This call is made inside
|
||||
* the "startup_stm32f30x.s" file.
|
||||
*
|
||||
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||
* by the user application to setup the SysTick
|
||||
* timer or configure other parameters.
|
||||
*
|
||||
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||
* be called whenever the core clock is changed
|
||||
* during program execution.
|
||||
*
|
||||
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
|
||||
* Then SystemInit() function is called, in "startup_stm32f30x.s" file, to
|
||||
* configure the system clock before to branch to main program.
|
||||
*
|
||||
* 3. If the system clock source selected by user fails to startup, the SystemInit()
|
||||
* function will do nothing and HSI still used as system clock source. User can
|
||||
* add some code to deal with this issue inside the SetSysClock() function.
|
||||
*
|
||||
* 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
|
||||
* in "stm32f30x.h" file. When HSE is used as system clock source, directly or
|
||||
* through PLL, and you are using different crystal you have to adapt the HSE
|
||||
* value to your own configuration.
|
||||
*
|
||||
* 5. This file configures the system clock as follows:
|
||||
*=============================================================================
|
||||
* Supported STM32F30x device
|
||||
*-----------------------------------------------------------------------------
|
||||
* System Clock source | PLL (HSE)
|
||||
*-----------------------------------------------------------------------------
|
||||
* SYSCLK(Hz) | 72000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* HCLK(Hz) | 72000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* AHB Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB2 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB1 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* HSE Frequency(Hz) | 8000000
|
||||
*----------------------------------------------------------------------------
|
||||
* PLLMUL | 9
|
||||
*-----------------------------------------------------------------------------
|
||||
* PREDIV | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* USB Clock | ENABLE
|
||||
*-----------------------------------------------------------------------------
|
||||
* Flash Latency(WS) | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* Prefetch Buffer | ON
|
||||
*-----------------------------------------------------------------------------
|
||||
*=============================================================================
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include "stm32f30x.h"
|
||||
|
||||
uint32_t hse_value = HSE_VALUE;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||
Internal SRAM. */
|
||||
/* #define VECT_TAB_SRAM */
|
||||
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
|
||||
This value must be a multiple of 0x200. */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
uint32_t SystemCoreClock = 72000000;
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
void SetSysClock(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system
|
||||
* Initialize the Embedded Flash Interface, the PLL and update the
|
||||
* SystemFrequency variable.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemInit(void)
|
||||
{
|
||||
/* FPU settings ------------------------------------------------------------*/
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||
#endif
|
||||
|
||||
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||
/* Set HSION bit */
|
||||
RCC->CR |= (uint32_t)0x00000001;
|
||||
|
||||
/* Reset CFGR register */
|
||||
RCC->CFGR &= 0xF87FC00C;
|
||||
|
||||
/* Reset HSEON, CSSON and PLLON bits */
|
||||
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||
|
||||
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
|
||||
RCC->CFGR &= (uint32_t)0xFF80FFFF;
|
||||
|
||||
/* Reset PREDIV1[3:0] bits */
|
||||
RCC->CFGR2 &= (uint32_t)0xFFFFFFF0;
|
||||
|
||||
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
|
||||
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
|
||||
|
||||
/* Disable all interrupts */
|
||||
RCC->CIR = 0x00000000;
|
||||
|
||||
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||
//SetSysClock(); // called from main()
|
||||
|
||||
#ifdef VECT_TAB_SRAM
|
||||
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
|
||||
#else
|
||||
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||
* be used by the user application to setup the SysTick timer or configure
|
||||
* other parameters.
|
||||
*
|
||||
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||
* based on this variable will be incorrect.
|
||||
*
|
||||
* @note - The system frequency computed by this function is not the real
|
||||
* frequency in the chip. It is calculated based on the predefined
|
||||
* constant and the selected clock source:
|
||||
*
|
||||
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||
*
|
||||
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
*
|
||||
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||
*
|
||||
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
|
||||
* 8 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
|
||||
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||
* frequency of the crystal used. Otherwise, this function may
|
||||
* have wrong result.
|
||||
*
|
||||
* - The result of this function could be not correct when using fractional
|
||||
* value for HSE crystal.
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemCoreClockUpdate (void)
|
||||
{
|
||||
uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00: /* HSI used as system clock */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04: /* HSE used as system clock */
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08: /* PLL used as system clock */
|
||||
/* Get PLL clock source and multiplication factor ----------------------*/
|
||||
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
|
||||
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
|
||||
pllmull = ( pllmull >> 18) + 2;
|
||||
|
||||
if (pllsource == 0x00)
|
||||
{
|
||||
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
|
||||
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||
}
|
||||
else
|
||||
{
|
||||
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
|
||||
/* HSE oscillator clock selected as PREDIV1 clock entry */
|
||||
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
|
||||
}
|
||||
break;
|
||||
default: /* HSI used as system clock */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
/* Compute HCLK clock frequency ----------------*/
|
||||
/* Get HCLK prescaler */
|
||||
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||
/* HCLK clock frequency */
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||
* AHB/APBx prescalers and Flash settings
|
||||
* @note This function should be called only once the RCC clock configuration
|
||||
* is reset to the default reset state (done in SystemInit() function).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SetSysClock(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
/******************************************************************************/
|
||||
/* PLL (clocked by HSE) used as System clock source */
|
||||
/******************************************************************************/
|
||||
|
||||
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
|
||||
/* Enable HSE */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable Prefetch Buffer and set Flash Latency */
|
||||
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
|
||||
|
||||
/* HCLK = SYSCLK / 1 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
|
||||
|
||||
/* PCLK2 = HCLK / 1 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
|
||||
|
||||
/* PCLK1 = HCLK / 2 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
|
||||
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||
configuration. User can add here some code to deal with this error */
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,76 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 28-March-2014
|
||||
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Define to prevent recursive inclusion
|
||||
*/
|
||||
#ifndef __SYSTEM_STM32F30X_H
|
||||
#define __SYSTEM_STM32F30X_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
/** @addtogroup STM32F30x_System_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__SYSTEM_STM32F30X_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,225 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "SPEV"
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_8
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
|
||||
#define BEEP_GPIO GPIOC
|
||||
#define BEEP_PIN Pin_15
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip
|
||||
|
||||
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
|
||||
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_BMP280
|
||||
|
||||
//#define MAG
|
||||
//#define USE_MPU9250_MAG // Enables bypass configuration
|
||||
//#define USE_MAG_AK8963
|
||||
//#define USE_MAG_HMC5883 // External
|
||||
|
||||
//#define MAG_AK8963_ALIGN CW90_DEG_FLIP
|
||||
|
||||
//#define SONAR
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USB_IO
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#ifndef UART1_GPIO
|
||||
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||
#define UART1_GPIO GPIOA
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||
#endif
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN GPIO_Pin_15 // PA15
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource14
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource15
|
||||
|
||||
#ifndef UART3_GPIO
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#endif
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
|
||||
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 SPI2 (SDCard)
|
||||
|
||||
#define SPI1_GPIO GPIOB
|
||||
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define SPI1_NSS_PIN Pin_9
|
||||
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource9
|
||||
#define SPI1_SCK_PIN Pin_3
|
||||
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
|
||||
#define SPI1_MISO_PIN Pin_4
|
||||
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
|
||||
#define SPI1_MOSI_PIN Pin_5
|
||||
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
|
||||
|
||||
#define SPI2_GPIO GPIOB
|
||||
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define SPI2_NSS_PIN Pin_12
|
||||
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
|
||||
#define SPI2_SCK_PIN Pin_13
|
||||
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
|
||||
#define SPI2_MISO_PIN Pin_14
|
||||
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
|
||||
#define SPI2_MOSI_PIN Pin_15
|
||||
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
|
||||
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI2
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN GPIO_Pin_14
|
||||
#define SDCARD_DETECT_EXTI_LINE EXTI_Line14
|
||||
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
|
||||
#define SDCARD_DETECT_GPIO_PORT GPIOC
|
||||
#define SDCARD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
|
||||
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOC
|
||||
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
|
||||
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL SPI1_GPIO_PERIPHERAL
|
||||
#define MPU6500_CS_GPIO SPI1_GPIO
|
||||
#define MPU6500_CS_PIN GPIO_Pin_9
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define WS2811_GPIO_AF GPIO_AF_6
|
||||
#define WS2811_PIN GPIO_Pin_8
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource8
|
||||
#define WS2811_TIMER TIM1
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
#define WS2811_IRQ DMA1_Channel2_IRQn
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
#define TRANSPONDER
|
||||
#define TRANSPONDER_GPIO GPIOA
|
||||
#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define TRANSPONDER_GPIO_AF GPIO_AF_6
|
||||
#define TRANSPONDER_PIN GPIO_Pin_8
|
||||
#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8
|
||||
#define TRANSPONDER_TIMER TIM1
|
||||
#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2
|
||||
#define TRANSPONDER_IRQ DMA1_Channel2_IRQn
|
||||
#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2
|
||||
#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
|
||||
#define GPS
|
||||
#define BLACKBOX
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#define TELEMETRY
|
||||
#define SERIAL_RX
|
||||
#define DISPLAY
|
||||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
@ -232,9 +232,4 @@
|
|||
#define BINDPLUG_PORT BUTTON_B_PORT
|
||||
#define BINDPLUG_PIN BUTTON_B_PIN
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
|
||||
#define S1W_TX_GPIO UART1_GPIO
|
||||
#define S1W_TX_PIN UART1_TX_PIN
|
||||
#define S1W_RX_GPIO UART1_GPIO
|
||||
#define S1W_RX_PIN UART1_RX_PIN
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -152,6 +152,20 @@
|
|||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
#define WS2811_GPIO GPIOB
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define WS2811_GPIO_AF GPIO_AF_1
|
||||
#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource8
|
||||
#define WS2811_TIMER TIM16
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel3
|
||||
#define WS2811_IRQ DMA1_Channel3_IRQn
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
|
||||
|
||||
#define BLACKBOX
|
||||
#define GPS
|
||||
//#define GTUNE
|
||||
|
@ -162,12 +176,4 @@
|
|||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
// How many escs does this board support?
|
||||
#define ESC_COUNT 6
|
||||
// STM32F3DISCOVERY TX - PD5 connects to UART RX
|
||||
#define S1W_TX_GPIO GPIOD
|
||||
#define S1W_TX_PIN GPIO_Pin_5
|
||||
// STM32F3DISCOVERY RX - PD6 connects to UART TX
|
||||
#define S1W_RX_GPIO GPIOD
|
||||
#define S1W_RX_PIN GPIO_Pin_6
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -84,7 +84,7 @@ enum
|
|||
// remaining 3 bits are crc (according to comments in openTx code)
|
||||
};
|
||||
|
||||
// these data identifiers are obtained from http://diydrones.com/forum/topics/amp-to-frsky-x8r-sport-converter
|
||||
// these data identifiers are obtained from https://github.com/opentx/opentx/blob/master/radio/src/telemetry/frsky.h
|
||||
enum
|
||||
{
|
||||
FSSP_DATAID_SPEED = 0x0830 ,
|
||||
|
@ -107,6 +107,8 @@ enum
|
|||
FSSP_DATAID_T1 = 0x0400 ,
|
||||
FSSP_DATAID_T2 = 0x0410 ,
|
||||
FSSP_DATAID_GPS_ALT = 0x0820 ,
|
||||
FSSP_DATAID_A3 = 0x0900 ,
|
||||
FSSP_DATAID_A4 = 0x0910 ,
|
||||
};
|
||||
|
||||
const uint16_t frSkyDataIdTable[] = {
|
||||
|
@ -131,6 +133,7 @@ const uint16_t frSkyDataIdTable[] = {
|
|||
FSSP_DATAID_T1 ,
|
||||
FSSP_DATAID_T2 ,
|
||||
FSSP_DATAID_GPS_ALT ,
|
||||
FSSP_DATAID_A4 ,
|
||||
0
|
||||
};
|
||||
|
||||
|
@ -472,6 +475,12 @@ void handleSmartPortTelemetry(void)
|
|||
}
|
||||
break;
|
||||
#endif
|
||||
case FSSP_DATAID_A4 :
|
||||
if (feature(FEATURE_VBAT)) {
|
||||
smartPortSendPackage(id, vbat * 10 / batteryCellCount ); // given in 0.1V, convert to volts
|
||||
smartPortHasRequest = 0;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
// if nothing is sent, smartPortHasRequest isn't cleared, we already incremented the counter, just loop back to the start
|
||||
|
|
|
@ -362,4 +362,17 @@ uint8_t usbIsConnected(void)
|
|||
return (bDeviceState != UNCONNECTED);
|
||||
}
|
||||
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : CDC_BaudRate.
|
||||
* Description : Get the current baud rate
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : Baud rate in bps
|
||||
*******************************************************************************/
|
||||
uint32_t CDC_BaudRate(void)
|
||||
{
|
||||
return Virtual_Com_Port_GetBaudRate();
|
||||
}
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
|
@ -59,6 +59,7 @@ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength); // HJI
|
|||
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); // HJI
|
||||
uint8_t usbIsConfigured(void); // HJI
|
||||
uint8_t usbIsConnected(void); // HJI
|
||||
uint32_t CDC_BaudRate(void);
|
||||
/* External variables --------------------------------------------------------*/
|
||||
|
||||
extern __IO uint32_t receiveLength; // HJI
|
||||
|
|
|
@ -358,5 +358,17 @@ uint8_t *Virtual_Com_Port_SetLineCoding(uint16_t Length)
|
|||
return (uint8_t *)&linecoding;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : Virtual_Com_Port_GetBaudRate.
|
||||
* Description : Get the current baudrate
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : baudrate in bps
|
||||
*******************************************************************************/
|
||||
uint32_t Virtual_Com_Port_GetBaudRate(void)
|
||||
{
|
||||
return linecoding.bitrate;
|
||||
}
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
||||
|
|
|
@ -79,6 +79,7 @@ uint8_t *Virtual_Com_Port_GetStringDescriptor( uint16_t);
|
|||
uint8_t *Virtual_Com_Port_GetLineCoding(uint16_t Length);
|
||||
uint8_t *Virtual_Com_Port_SetLineCoding(uint16_t Length);
|
||||
|
||||
uint32_t Virtual_Com_Port_GetBaudRate(void);
|
||||
#endif /* __usb_prop_H */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
|
@ -16,8 +16,8 @@
|
|||
*/
|
||||
|
||||
#define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc)
|
||||
#define FC_VERSION_MINOR 5 // increment when a minor release is made (small new feature, change etc)
|
||||
#define FC_VERSION_PATCH_LEVEL 4 // increment when a bug is fixed
|
||||
#define FC_VERSION_MINOR 6 // increment when a minor release is made (small new feature, change etc)
|
||||
#define FC_VERSION_PATCH_LEVEL 2 // increment when a bug is fixed
|
||||
|
||||
#define STR_HELPER(x) #x
|
||||
#define STR(x) STR_HELPER(x)
|
||||
|
|
|
@ -2,6 +2,7 @@ ALL_TARGETS := naze
|
|||
ALL_TARGETS += cc3d
|
||||
ALL_TARGETS += cc3d_opbl
|
||||
ALL_TARGETS += spracingf3
|
||||
ALL_TARGETS += spracingf3evo
|
||||
ALL_TARGETS += spracingf3mini
|
||||
ALL_TARGETS += sparky
|
||||
ALL_TARGETS += alienflightf1
|
||||
|
@ -12,6 +13,7 @@ ALL_TARGETS += motolab
|
|||
ALL_TARGETS += rmdo
|
||||
ALL_TARGETS += ircfusionf3
|
||||
ALL_TARGETS += afromini
|
||||
ALL_TARGETS += doge
|
||||
|
||||
CLEAN_TARGETS := $(addprefix clean_, $(ALL_TARGETS))
|
||||
|
||||
|
@ -20,6 +22,7 @@ clean_cc3d cc3d: opts := TARGET=CC3D
|
|||
clean_cc3d_opbl cc3d_opbl : opts := TARGET=CC3D_OPBL
|
||||
clean_spracingf3mini spracingf3mini : opts := TARGET=SPRACINGF3MINI
|
||||
clean_spracingf3 spracingf3 : opts := TARGET=SPRACINGF3
|
||||
clean_spracingf3evo spracingf3evo : opts := TARGET=SPRACINGF3EVO
|
||||
clean_sparky sparky : opts := TARGET=SPARKY
|
||||
clean_alienflightf1 alienflightf1 : opts := TARGET=ALIENFLIGHTF1
|
||||
clean_alienflightf3 alienflightf3 : opts := TARGET=ALIENFLIGHTF3
|
||||
|
@ -29,6 +32,7 @@ clean_motolab motolab : opts := TARGET=MOTOLAB
|
|||
clean_rmdo rmdo : opts := TARGET=RMDO
|
||||
clean_ircfusionf3 ircfusionf3 : opts := TARGET=IRCFUSIONF3
|
||||
clean_afromini afromini : opts := TARGET=AFROMINI
|
||||
clean_doge doge : opts := TARGET=DOGE
|
||||
|
||||
|
||||
.PHONY: all clean
|
||||
|
@ -45,7 +49,7 @@ everything: $(ALL_TARGETS)
|
|||
|
||||
.PHONY:$(ALL_TARGETS)
|
||||
$(ALL_TARGETS):
|
||||
make -f Makefile $(opts)
|
||||
make -f Makefile hex binary $(opts)
|
||||
|
||||
.PHONY: $(CLEAN_TARGETS)
|
||||
$(CLEAN_TARGETS):
|
||||
|
|
Loading…
Reference in New Issue