mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 04:15:44 +03:00
Cleanup line endings.
This commit is contained in:
parent
2238f535be
commit
9f1a0fcb4c
47 changed files with 6212 additions and 6191 deletions
|
@ -25,7 +25,8 @@
|
|||
#define M_PI 3.14159265358979323846f
|
||||
#endif /* M_PI */
|
||||
|
||||
#define RADX10 (M_PI / 1800.0f) // 0.001745329252f
#define RAD (M_PI / 180.0f)
|
||||
#define RADX10 (M_PI / 1800.0f) // 0.001745329252f
|
||||
#define RAD (M_PI / 180.0f)
|
||||
|
||||
#define DEG2RAD(degrees) (degrees * RAD)
|
||||
|
||||
|
|
|
@ -76,6 +76,7 @@ void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DCon
|
|||
|
||||
// use the last flash pages for storage
|
||||
static uint32_t flashWriteAddress = (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG));
|
||||
|
||||
master_t masterConfig; // master config struct with data independent from profiles
|
||||
profile_t currentProfile; // profile config struct
|
||||
|
||||
|
@ -404,7 +405,7 @@ void activateConfig(void)
|
|||
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
|
||||
imuRuntimeConfig.acc_lpf_factor = currentProfile.acc_lpf_factor;
|
||||
imuRuntimeConfig.acc_unarmedcal = currentProfile.acc_unarmedcal;;
|
||||
|
||||
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
||||
|
||||
configureImu(&imuRuntimeConfig, ¤tProfile.pidProfile, ¤tProfile.barometerConfig, ¤tProfile.accDeadband);
|
||||
|
||||
|
|
|
@ -36,12 +36,25 @@
|
|||
#define DMP_MEM_START_ADDR 0x6E
|
||||
#define DMP_MEM_R_W 0x6F
|
||||
|
||||
#define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN
#define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN
#define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN
#define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
#define MPU_RA_XA_OFFS_L_TC 0x07
|
||||
#define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
#define MPU_RA_YA_OFFS_L_TC 0x09
|
||||
#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
#define MPU_RA_ZA_OFFS_L_TC 0x0B
|
||||
#define MPU_RA_PRODUCT_ID 0x0C // Product ID Register
#define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
#define MPU_RA_XG_OFFS_USRL 0x14
|
||||
#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
#define MPU_RA_YG_OFFS_USRL 0x16
|
||||
#define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
#define MPU_RA_ZG_OFFS_USRL 0x18
|
||||
#define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
|
||||
#define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
|
||||
#define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
|
||||
#define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN
|
||||
#define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN
|
||||
#define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN
|
||||
#define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
|
||||
#define MPU_RA_XA_OFFS_L_TC 0x07
|
||||
#define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
|
||||
#define MPU_RA_YA_OFFS_L_TC 0x09
|
||||
#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
|
||||
#define MPU_RA_ZA_OFFS_L_TC 0x0B
|
||||
#define MPU_RA_PRODUCT_ID 0x0C // Product ID Register
|
||||
#define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
|
||||
#define MPU_RA_XG_OFFS_USRL 0x14
|
||||
#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
|
||||
#define MPU_RA_YG_OFFS_USRL 0x16
|
||||
#define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
|
||||
#define MPU_RA_ZG_OFFS_USRL 0x18
|
||||
#define MPU_RA_SMPLRT_DIV 0x19
|
||||
#define MPU_RA_CONFIG 0x1A
|
||||
#define MPU_RA_GYRO_CONFIG 0x1B
|
||||
|
@ -113,6 +126,7 @@
|
|||
#define MPU_RA_WHO_AM_I 0x75
|
||||
|
||||
#define MPU6050_SMPLRT_DIV 0 // 8000Hz
|
||||
|
||||
#define MPU6050_LPF_256HZ 0
|
||||
#define MPU6050_LPF_188HZ 1
|
||||
#define MPU6050_LPF_98HZ 2
|
||||
|
|
|
@ -75,7 +75,9 @@ typedef struct {
|
|||
#define E_SENSOR_NOT_DETECTED (char) 0
|
||||
#define BMP085_PROM_START__ADDR 0xaa
|
||||
#define BMP085_PROM_DATA__LEN 22
|
||||
#define BMP085_T_MEASURE 0x2E // temperature measurent
#define BMP085_P_MEASURE 0x34 // pressure measurement
#define BMP085_CTRL_MEAS_REG 0xF4
|
||||
#define BMP085_T_MEASURE 0x2E // temperature measurent
|
||||
#define BMP085_P_MEASURE 0x34 // pressure measurement
|
||||
#define BMP085_CTRL_MEAS_REG 0xF4
|
||||
#define BMP085_ADC_OUT_MSB_REG 0xF6
|
||||
#define BMP085_ADC_OUT_LSB_REG 0xF7
|
||||
#define BMP085_CHIP_ID__POS 0
|
||||
|
@ -96,7 +98,10 @@ typedef struct {
|
|||
#define BMP085_GET_BITSLICE(regvar, bitname) (regvar & bitname##__MSK) >> bitname##__POS
|
||||
#define BMP085_SET_BITSLICE(regvar, bitname, val) (regvar & ~bitname##__MSK) | ((val<<bitname##__POS)&bitname##__MSK)
|
||||
|
||||
#define SMD500_PARAM_MG 3038 //calibration parameter
#define SMD500_PARAM_MH -7357 //calibration parameter
#define SMD500_PARAM_MI 3791 //calibration parameter
|
||||
#define SMD500_PARAM_MG 3038 //calibration parameter
|
||||
#define SMD500_PARAM_MH -7357 //calibration parameter
|
||||
#define SMD500_PARAM_MI 3791 //calibration parameter
|
||||
|
||||
static bmp085_t bmp085 = { { 0, } };
|
||||
static bool bmp085InitDone = false;
|
||||
static uint16_t bmp085_ut; // static result of temperature measurement
|
||||
|
|
|
@ -83,6 +83,14 @@ pidProfile_t *pidProfile;
|
|||
barometerConfig_t *barometerConfig;
|
||||
accDeadband_t *accDeadband;
|
||||
|
||||
void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile, barometerConfig_t *intialBarometerConfig, accDeadband_t *initialAccDeadband)
|
||||
{
|
||||
imuRuntimeConfig = initialImuRuntimeConfig;
|
||||
pidProfile = initialPidProfile;
|
||||
barometerConfig = intialBarometerConfig;
|
||||
accDeadband = initialAccDeadband;
|
||||
}
|
||||
|
||||
void imuInit()
|
||||
{
|
||||
smallAngle = lrintf(acc_1G * cosf(RAD * imuRuntimeConfig->small_angle));
|
||||
|
@ -95,14 +103,6 @@ void calculateThrottleAngleScale(uint16_t throttle_correction_angle)
|
|||
throttleAngleScale = (1800.0f / M_PI) * (900.0f / throttle_correction_angle);
|
||||
}
|
||||
|
||||
void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile, barometerConfig_t *intialBarometerConfig, accDeadband_t *initialAccDeadband)
|
||||
{
|
||||
imuRuntimeConfig = initialImuRuntimeConfig;
|
||||
pidProfile = initialPidProfile;
|
||||
barometerConfig = intialBarometerConfig;
|
||||
accDeadband = initialAccDeadband;
|
||||
}
|
||||
|
||||
void computeIMU(rollAndPitchTrims_t *accelerometerTrims, uint8_t mixerConfiguration)
|
||||
{
|
||||
static int16_t gyroYawSmooth = 0;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue