Skip to content

Commit

Permalink
Merge remote-tracking branch 'betaflight/master' into betaflight-master
Browse files Browse the repository at this point in the history
  • Loading branch information
hydra committed Oct 17, 2017
2 parents 670b8e3 + 3038eb7 commit fa9b9db
Show file tree
Hide file tree
Showing 152 changed files with 3,934 additions and 2,313 deletions.
9 changes: 9 additions & 0 deletions .github/pull_request_template.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
## Important considerations when opening a pull request:

1.) Pull requests will only be accepted if they are opened against the `master` branch. Pull requests opened against other branches without prior consent from the maintainers will be closed;

2.) Please follow the coding style guidlines: https://github.com/cleanflight/cleanflight/blob/master/docs/development/CodingStyle.md

3.) If your pull request is a fix for one or more issues that are open in GitHub, add their numbers in the form `Fixes #<issue number>`. This will cause the issues to be closed when the pull request is merged;

4.) Remove this Text :).
24 changes: 12 additions & 12 deletions lib/main/MAVLink/mavlink_conversions.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,12 +117,12 @@ MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float
*/
MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
{
float cosPhi_2 = cosf(roll / 2);
float sinPhi_2 = sinf(roll / 2);
float cosTheta_2 = cosf(pitch / 2);
float sinTheta_2 = sinf(pitch / 2);
float cosPsi_2 = cosf(yaw / 2);
float sinPsi_2 = sinf(yaw / 2);
float cosPhi_2 = cos_approx(roll / 2);
float sinPhi_2 = sin_approx(roll / 2);
float cosTheta_2 = cos_approx(pitch / 2);
float sinTheta_2 = sin_approx(pitch / 2);
float cosPsi_2 = cos_approx(yaw / 2);
float sinPsi_2 = sin_approx(yaw / 2);
quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
sinPhi_2 * sinTheta_2 * sinPsi_2);
quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
Expand Down Expand Up @@ -188,12 +188,12 @@ MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quate
*/
MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
{
float cosPhi = cosf(roll);
float sinPhi = sinf(roll);
float cosThe = cosf(pitch);
float sinThe = sinf(pitch);
float cosPsi = cosf(yaw);
float sinPsi = sinf(yaw);
float cosPhi = cos_approx(roll);
float sinPhi = sin_approx(roll);
float cosThe = cos_approx(pitch);
float sinThe = sin_approx(pitch);
float cosPsi = cos_approx(yaw);
float sinPsi = sin_approx(yaw);

dcm[0][0] = cosThe * cosPsi;
dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
Expand Down
1 change: 0 additions & 1 deletion make/mcu/STM32F7.mk
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@ EXCLUDES = stm32f7xx_hal_can.c \
stm32f7xx_ll_rng.c \
stm32f7xx_ll_rtc.c \
stm32f7xx_ll_sdmmc.c \
stm32f7xx_ll_tim.c \
stm32f7xx_ll_usart.c

STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
Expand Down
1 change: 1 addition & 0 deletions make/source.mk
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,7 @@ FC_SRC = \
telemetry/srxl.c \
telemetry/frsky.c \
telemetry/hott.c \
telemetry/jetiexbus.c \
telemetry/smartport.c \
telemetry/ltm.c \
telemetry/mavlink.c \
Expand Down
2 changes: 1 addition & 1 deletion src/main/build/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,4 +37,4 @@ extern const char* const buildDate; // "MMM DD YYYY" MMM = Jan/Feb/...
#define BUILD_TIME_LENGTH 8
extern const char* const buildTime; // "HH:MM:SS"

#define MSP_API_VERSION_STRING STR(API_VERSION_MAJOR) "." STR(API_VERSION_MINOR)
#define MSP_API_VERSION_STRING STR(API_VERSION_MAJOR) "." STR(API_VERSION_MINOR)
34 changes: 23 additions & 11 deletions src/main/cms/cms_menu_imu.c
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,9 @@ static OSD_Entry cmsx_menuRateProfileEntries[] =
{ "RC EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo8, 0, 100, 1, 10 }, 0 },
{ "RC YAW EXP", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcYawExpo8, 0, 100, 1, 10 }, 0 },

{ "THRPID ATT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.dynThrPID, 0, 100, 1, 10}, 0 },
{ "THR MID", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.thrMid8, 0, 100, 1}, 0 },
{ "THR EXPO", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.thrExpo8, 0, 100, 1}, 0 },
{ "THRPID ATT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.dynThrPID, 0, 100, 1, 10}, 0 },
{ "TPA BRKPT", OME_UINT16, NULL, &(OSD_UINT16_t){ &rateProfile.tpa_breakpoint, 1000, 2000, 10}, 0 },

{ "BACK", OME_Back, NULL, NULL, 0 },
Expand All @@ -228,11 +230,13 @@ static CMS_Menu cmsx_menuRateProfile = {
.entries = cmsx_menuRateProfileEntries
};

static uint8_t cmsx_dtermSetpointWeight;
static uint8_t cmsx_setpointRelaxRatio;
static uint8_t cmsx_angleStrength;
static uint8_t cmsx_horizonStrength;
static uint8_t cmsx_horizonTransition;
static uint8_t cmsx_dtermSetpointWeight;
static uint8_t cmsx_setpointRelaxRatio;
static uint8_t cmsx_angleStrength;
static uint8_t cmsx_horizonStrength;
static uint8_t cmsx_horizonTransition;
static uint16_t cmsx_itermAcceleratorGain;
static uint16_t cmsx_itermThrottleThreshold;

static long cmsx_profileOtherOnEnter(void)
{
Expand All @@ -246,6 +250,9 @@ static long cmsx_profileOtherOnEnter(void)
cmsx_horizonStrength = pidProfile->pid[PID_LEVEL].I;
cmsx_horizonTransition = pidProfile->pid[PID_LEVEL].D;

cmsx_itermAcceleratorGain = pidProfile->itermAcceleratorGain;
cmsx_itermThrottleThreshold = pidProfile->itermThrottleThreshold;

return 0;
}

Expand All @@ -262,17 +269,22 @@ static long cmsx_profileOtherOnExit(const OSD_Entry *self)
pidProfile->pid[PID_LEVEL].I = cmsx_horizonStrength;
pidProfile->pid[PID_LEVEL].D = cmsx_horizonTransition;

pidProfile->itermAcceleratorGain = cmsx_itermAcceleratorGain;
pidProfile->itermThrottleThreshold = cmsx_itermThrottleThreshold;

return 0;
}

static OSD_Entry cmsx_menuProfileOtherEntries[] = {
{ "-- OTHER PP --", OME_Label, NULL, pidProfileIndexString, 0 },

{ "D SETPT WT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_dtermSetpointWeight, 0, 255, 1, 10 }, 0 },
{ "SETPT TRS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_setpointRelaxRatio, 0, 100, 1, 10 }, 0 },
{ "ANGLE STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_angleStrength, 0, 200, 1 } , 0 },
{ "HORZN STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonStrength, 0, 200, 1 } , 0 },
{ "HORZN TRS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonTransition, 0, 200, 1 } , 0 },
{ "D SETPT WT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_dtermSetpointWeight, 0, 255, 1, 10 }, 0 },
{ "SETPT TRS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_setpointRelaxRatio, 0, 100, 1, 10 }, 0 },
{ "ANGLE STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_angleStrength, 0, 200, 1 } , 0 },
{ "HORZN STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonStrength, 0, 200, 1 } , 0 },
{ "HORZN TRS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonTransition, 0, 200, 1 } , 0 },
{ "AG GAIN", OME_UINT16, NULL, &(OSD_UINT16_t) { &cmsx_itermAcceleratorGain, 1000, 30000, 1 } , 0 },
{ "AG THR", OME_UINT16, NULL, &(OSD_UINT16_t) { &cmsx_itermThrottleThreshold, 20, 1000, 1 } , 0 },

{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
Expand Down
4 changes: 2 additions & 2 deletions src/main/common/filter.c
Original file line number Diff line number Diff line change
Expand Up @@ -108,8 +108,8 @@ void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refresh
{
// setup variables
const float omega = 2.0f * M_PI_FLOAT * filterFreq * refreshRate * 0.000001f;
const float sn = sinf(omega);
const float cs = cosf(omega);
const float sn = sin_approx(omega);
const float cs = cos_approx(omega);
const float alpha = sn / (2.0f * Q);

float b0 = 0, b1 = 0, b2 = 0, a0 = 0, a1 = 0, a2 = 0;
Expand Down
2 changes: 1 addition & 1 deletion src/main/config/config_eeprom.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <stdint.h>
#include <stdbool.h>

#define EEPROM_CONF_VERSION 163
#define EEPROM_CONF_VERSION 165

bool isEEPROMContentValid(void);
bool loadEEPROM(void);
Expand Down
3 changes: 2 additions & 1 deletion src/main/config/parameter_group_ids.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,8 @@
#define PG_CAMERA_CONTROL_CONFIG 522
#define PG_FRSKY_D_CONFIG 523
#define PG_MAX7456_CONFIG 524
#define PG_BETAFLIGHT_END 524
#define PG_FLYSKY_CONFIG 525
#define PG_BETAFLIGHT_END 525


// OSD configuration (subject to change)
Expand Down
24 changes: 7 additions & 17 deletions src/main/drivers/barometer/barometer_bmp085.c
Original file line number Diff line number Diff line change
Expand Up @@ -155,16 +155,6 @@ void bmp085Disable(const bmp085Config_t *config)
BMP085_OFF;
}

bool bmp085ReadRegister(busDevice_t *busdev, uint8_t cmd, uint8_t len, uint8_t *data)
{
return i2cBusReadRegisterBuffer(busdev, cmd, data, len);
}

bool bmp085WriteRegister(busDevice_t *busdev, uint8_t cmd, uint8_t byte)
{
return i2cBusWriteRegister(busdev, cmd, byte);
}

bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
{
uint8_t data;
Expand Down Expand Up @@ -205,13 +195,13 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
defaultAddressApplied = true;
}

ack = bmp085ReadRegister(busdev, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
ack = busReadRegisterBuffer(busdev, BMP085_CHIP_ID__REG, &data, 1); /* read Chip Id */
if (ack) {
bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
bmp085.oversampling_setting = 3;

if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */
bmp085ReadRegister(busdev, BMP085_VERSION_REG, 1, &data); /* read Version reg */
busReadRegisterBuffer(busdev, BMP085_VERSION_REG, &data, 1); /* read Version reg */
bmp085.ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */
bmp085.al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */
bmp085_get_cal_param(busdev); /* readout bmp085 calibparam structure */
Expand Down Expand Up @@ -302,7 +292,7 @@ static void bmp085_start_ut(baroDev_t *baro)
#if defined(BARO_EOC_GPIO)
isConversionComplete = false;
#endif
bmp085WriteRegister(&baro->busdev, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
busWriteRegister(&baro->busdev, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
}

static void bmp085_get_ut(baroDev_t *baro)
Expand All @@ -316,7 +306,7 @@ static void bmp085_get_ut(baroDev_t *baro)
}
#endif

bmp085ReadRegister(&baro->busdev, BMP085_ADC_OUT_MSB_REG, 2, data);
busReadRegisterBuffer(&baro->busdev, BMP085_ADC_OUT_MSB_REG, data, 2);
bmp085_ut = (data[0] << 8) | data[1];
}

Expand All @@ -330,7 +320,7 @@ static void bmp085_start_up(baroDev_t *baro)
isConversionComplete = false;
#endif

bmp085WriteRegister(&baro->busdev, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
busWriteRegister(&baro->busdev, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
}

/** read out up for pressure conversion
Expand All @@ -348,7 +338,7 @@ static void bmp085_get_up(baroDev_t *baro)
}
#endif

bmp085ReadRegister(&baro->busdev, BMP085_ADC_OUT_MSB_REG, 3, data);
busReadRegisterBuffer(&baro->busdev, BMP085_ADC_OUT_MSB_REG, data, 3);
bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2])
>> (8 - bmp085.oversampling_setting);
}
Expand All @@ -368,7 +358,7 @@ STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature
static void bmp085_get_cal_param(busDevice_t *busdev)
{
uint8_t data[22];
bmp085ReadRegister(busdev, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
busReadRegisterBuffer(busdev, BMP085_PROM_START__ADDR, data, BMP085_PROM_DATA__LEN);

/*parameters AC1-AC6*/
bmp085.cal_param.ac1 = (data[0] << 8) | data[1];
Expand Down
42 changes: 6 additions & 36 deletions src/main/drivers/barometer/barometer_bmp280.c
Original file line number Diff line number Diff line change
Expand Up @@ -65,43 +65,13 @@ static void bmp280_get_up(baroDev_t *baro);

STATIC_UNIT_TESTED void bmp280_calculate(int32_t *pressure, int32_t *temperature);

bool bmp280ReadRegister(busDevice_t *busdev, uint8_t reg, uint8_t length, uint8_t *data)
{
switch (busdev->bustype) {
#ifdef USE_BARO_SPI_BMP280
case BUSTYPE_SPI:
return spiBusReadRegisterBuffer(busdev, reg | 0x80, data, length);
#endif
#ifdef USE_BARO_BMP280
case BUSTYPE_I2C:
return i2cBusReadRegisterBuffer(busdev, reg, data, length);
#endif
}
return false;
}

bool bmp280WriteRegister(busDevice_t *busdev, uint8_t reg, uint8_t data)
{
switch (busdev->bustype) {
#ifdef USE_BARO_SPI_BMP280
case BUSTYPE_SPI:
return spiBusWriteRegister(busdev, reg & 0x7f, data);
#endif
#ifdef USE_BARO_BMP280
case BUSTYPE_I2C:
return i2cBusWriteRegister(busdev, reg, data);
#endif
}
return false;
}

void bmp280BusInit(busDevice_t *busdev)
{
#ifdef USE_BARO_SPI_BMP280
if (busdev->bustype == BUSTYPE_SPI) {
IOHi(busdev->busdev_u.spi.csnPin); // Disable
IOInit(busdev->busdev_u.spi.csnPin, OWNER_BARO_CS, 0);
IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_OUT_PP);
IOHi(busdev->busdev_u.spi.csnPin); // Disable
spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_STANDARD); // XXX
}
#else
Expand Down Expand Up @@ -137,7 +107,7 @@ bool bmp280Detect(baroDev_t *baro)
defaultAddressApplied = true;
}

bmp280ReadRegister(busdev, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
busReadRegisterBuffer(busdev, BMP280_CHIP_ID_REG, &bmp280_chip_id, 1); /* read Chip Id */

if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID) {
bmp280BusDeinit(busdev);
Expand All @@ -148,10 +118,10 @@ bool bmp280Detect(baroDev_t *baro)
}

// read calibration
bmp280ReadRegister(busdev, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
busReadRegisterBuffer(busdev, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, (uint8_t *)&bmp280_cal, 24);

// set oversampling + power mode (forced), and start sampling
bmp280WriteRegister(busdev, BMP280_CTRL_MEAS_REG, BMP280_MODE);
busWriteRegister(busdev, BMP280_CTRL_MEAS_REG, BMP280_MODE);

// these are dummy as temperature is measured as part of pressure
baro->ut_delay = 0;
Expand Down Expand Up @@ -182,15 +152,15 @@ static void bmp280_start_up(baroDev_t *baro)
{
// start measurement
// set oversampling + power mode (forced), and start sampling
bmp280WriteRegister(&baro->busdev, BMP280_CTRL_MEAS_REG, BMP280_MODE);
busWriteRegister(&baro->busdev, BMP280_CTRL_MEAS_REG, BMP280_MODE);
}

static void bmp280_get_up(baroDev_t *baro)
{
uint8_t data[BMP280_DATA_FRAME_SIZE];

// read data from sensor
bmp280ReadRegister(&baro->busdev, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
busReadRegisterBuffer(&baro->busdev, BMP280_PRESSURE_MSB_REG, data, BMP280_DATA_FRAME_SIZE);
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));
}
Expand Down
Loading

0 comments on commit fa9b9db

Please sign in to comment.