mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Merge branch 'master' into RP2350
This commit is contained in:
commit
6848720f73
31 changed files with 67 additions and 73 deletions
|
@ -9,9 +9,7 @@
|
|||
#endif
|
||||
#include <math.h>
|
||||
|
||||
#ifndef M_PI_2
|
||||
#define M_PI_2 ((float)asin(1))
|
||||
#endif
|
||||
#define MAVLINK_EPS (0.001f)
|
||||
|
||||
/**
|
||||
* @file mavlink_conversions.h
|
||||
|
@ -70,12 +68,12 @@ MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, flo
|
|||
float phi, theta, psi;
|
||||
theta = asinf(-dcm[2][0]);
|
||||
|
||||
if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
|
||||
if (fabsf(theta - M_PIf / 2.0f) < MAVLINK_EPS) {
|
||||
phi = 0.0f;
|
||||
psi = (atan2f(dcm[1][2] - dcm[0][1],
|
||||
dcm[0][2] + dcm[1][1]) + phi);
|
||||
|
||||
} else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
|
||||
} else if (fabsf(theta + M_PIf / 2.0f) < MAVLINK_EPS) {
|
||||
phi = 0.0f;
|
||||
psi = atan2f(dcm[1][2] - dcm[0][1],
|
||||
dcm[0][2] + dcm[1][1] - phi);
|
||||
|
|
|
@ -106,8 +106,8 @@ int OLC_Encode(const OLC_LatLon* location, size_t length, char* code,
|
|||
// floating point operations.
|
||||
long long int lat_val = kLatMaxDegrees * 2.5e7;
|
||||
long long int lng_val = kLonMaxDegrees * 8.192e6;
|
||||
lat_val += latitude * 2.5e7;
|
||||
lng_val += longitude * 8.192e6;
|
||||
lat_val += latitude * 2.5e7f;
|
||||
lng_val += longitude * 8.192e6f;
|
||||
|
||||
size_t pos = kMaximumDigitCount;
|
||||
// Compute the grid part of the code if necessary.
|
||||
|
@ -202,7 +202,7 @@ int OLC_Shorten(const char* code, size_t size, const OLC_LatLon* reference,
|
|||
|
||||
// Yes, magic numbers... sob.
|
||||
int start = 0;
|
||||
const double safety_factor = 0.3;
|
||||
const double safety_factor = 0.3f;
|
||||
const int removal_lengths[3] = {8, 6, 4};
|
||||
for (int j = 0; j < sizeof(removal_lengths) / sizeof(removal_lengths[0]);
|
||||
++j) {
|
||||
|
@ -255,10 +255,10 @@ int OLC_RecoverNearest(const char* short_code, size_t size,
|
|||
}
|
||||
|
||||
// The resolution (height and width) of the padded area in degrees.
|
||||
double resolution = pow_neg(kEncodingBase, 2.0 - (padding_length / 2.0));
|
||||
double resolution = pow_neg(kEncodingBase, 2.0f - (padding_length / 2.0f));
|
||||
|
||||
// Distance from the center to an edge (in degrees).
|
||||
double half_res = resolution / 2.0;
|
||||
double half_res = resolution / 2.0f;
|
||||
|
||||
// Use the reference location to pad the supplied short code and decode it.
|
||||
OLC_LatLon latlon = {lat, lon};
|
||||
|
|
|
@ -38,9 +38,9 @@ static const size_t kSeparatorPosition = 8;
|
|||
static const size_t kPairPrecisionInverse = 8000;
|
||||
// Inverse (1/) of the precision of the final grid digits in degrees.
|
||||
// Latitude is kEncodingBase^3 * kGridRows^kGridCodeLength
|
||||
static const size_t kGridLatPrecisionInverse = 2.5e7;
|
||||
static const size_t kGridLatPrecisionInverse = 2.5e7f;
|
||||
// Longitude is kEncodingBase^3 * kGridColumns^kGridCodeLength
|
||||
static const size_t kGridLonPrecisionInverse = 8.192e6;
|
||||
static const size_t kGridLonPrecisionInverse = 8.192e6f;
|
||||
// Latitude bounds are -kLatMaxDegrees degrees and +kLatMaxDegrees degrees
|
||||
// which we transpose to 0 and 180 degrees.
|
||||
static const double kLatMaxDegrees = OLC_kLatMaxDegrees;
|
||||
|
|
|
@ -87,7 +87,6 @@ COMMON_SRC = \
|
|||
config/simplified_tuning.c \
|
||||
cli/cli.c \
|
||||
cli/settings.c \
|
||||
config/config.c \
|
||||
drivers/dshot.c \
|
||||
drivers/dshot_command.c \
|
||||
drivers/buf_writer.c \
|
||||
|
@ -308,7 +307,6 @@ COMMON_SRC += \
|
|||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/accgyro/accgyro_spi_mpu9250.c \
|
||||
drivers/accgyro/accgyro_virtual.c \
|
||||
drivers/accgyro/gyro_sync.c \
|
||||
BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \
|
||||
drivers/barometer/barometer_2smpb_02b.c \
|
||||
drivers/barometer/barometer_bmp085.c \
|
||||
|
@ -466,7 +464,6 @@ SPEED_OPTIMISED_SRC += \
|
|||
rx/sumd.c \
|
||||
rx/xbus.c \
|
||||
rx/fport.c \
|
||||
rx/frsky_crc.c \
|
||||
scheduler/scheduler.c \
|
||||
sensors/acceleration.c \
|
||||
sensors/boardalignment.c \
|
||||
|
|
|
@ -1 +1 @@
|
|||
Subproject commit ec429513a68b3362647ead039719f12f156edcf4
|
||||
Subproject commit e3aaa6a827c8a6215e70f373f83c3f57ae8abe64
|
|
@ -5307,7 +5307,7 @@ static bool strToPin(char *ptr, ioTag_t *tag)
|
|||
|
||||
char *end;
|
||||
const long pin = strtol(ptr, &end, 10);
|
||||
if (end != ptr && pin >= 0 && pin < 16) {
|
||||
if (end != ptr && pin >= 0 && pin < DEFIO_PORT_PINS) {
|
||||
*tag = DEFIO_TAG_MAKE(port, pin);
|
||||
|
||||
return true;
|
||||
|
|
|
@ -243,22 +243,22 @@ bool qmp6988Detect(baroDev_t *baro)
|
|||
else
|
||||
Coe_a0_ = temp2;
|
||||
|
||||
qmp6988_cal.Coe_a0=(float)Coe_a0_/16.0;
|
||||
qmp6988_cal.Coe_a1=(-6.30E-03)+(4.30E-04)*(float)Coe_a1_/32767.0;
|
||||
qmp6988_cal.Coe_a2=(-1.9E-11)+(1.2E-10)*(float)Coe_a2_/32767.0;
|
||||
qmp6988_cal.Coe_a0 = (float)Coe_a0_/16.0f;
|
||||
qmp6988_cal.Coe_a1 = (-6.30E-03f)+(4.30E-04f)*(float)Coe_a1_/32767.0f;
|
||||
qmp6988_cal.Coe_a2 = (-1.9E-11f)+(1.2E-10f)*(float)Coe_a2_/32767.0f;
|
||||
|
||||
qmp6988_cal.Coe_b00 = Coe_b00_/16.0;
|
||||
qmp6988_cal.Coe_bt1 = (1.00E-01)+(9.10E-02)*(float)Coe_bt1_/32767.0;
|
||||
qmp6988_cal.Coe_bt2= (1.20E-08)+(1.20E-06)*(float)Coe_bt2_/32767.0;
|
||||
qmp6988_cal.Coe_b00 = Coe_b00_/16.0f;
|
||||
qmp6988_cal.Coe_bt1 = (1.00E-01f)+(9.10E-02f)*(float)Coe_bt1_/32767.0f;
|
||||
qmp6988_cal.Coe_bt2 = (1.20E-08f)+(1.20E-06f)*(float)Coe_bt2_/32767.0f;
|
||||
|
||||
qmp6988_cal.Coe_bp1 = (3.30E-02)+(1.90E-02)*(float)Coe_bp1_/32767.0;
|
||||
qmp6988_cal.Coe_b11= (2.10E-07)+(1.40E-07)*(float)Coe_b11_/32767.0;
|
||||
qmp6988_cal.Coe_bp1 = (3.30E-02f)+(1.90E-02f)*(float)Coe_bp1_/32767.0f;
|
||||
qmp6988_cal.Coe_b11 = (2.10E-07f)+(1.40E-07f)*(float)Coe_b11_/32767.0f;
|
||||
|
||||
qmp6988_cal.Coe_bp2 = (-6.30E-10)+(3.50E-10)*(float)Coe_bp2_/32767.0;
|
||||
qmp6988_cal.Coe_b12= (2.90E-13)+(7.60E-13)*(float)Coe_b12_/32767.0;
|
||||
qmp6988_cal.Coe_bp2 = (-6.30E-10f)+(3.50E-10f)*(float)Coe_bp2_/32767.0f;
|
||||
qmp6988_cal.Coe_b12 = (2.90E-13f)+(7.60E-13f)*(float)Coe_b12_/32767.0f;
|
||||
|
||||
qmp6988_cal.Coe_b21 = (2.10E-15)+(1.20E-14)*(float)Coe_b21_/32767.0;
|
||||
qmp6988_cal.Coe_bp3= (1.30E-16)+(7.90E-17)*(float)Coe_bp3_/32767.0;
|
||||
qmp6988_cal.Coe_b21 = (2.10E-15f)+(1.20E-14f)*(float)Coe_b21_/32767.0f;
|
||||
qmp6988_cal.Coe_bp3 = (1.30E-16f)+(7.90E-17f)*(float)Coe_bp3_/32767.0f;
|
||||
|
||||
// Set power mode and sample times
|
||||
busWriteRegister(dev, QMP6988_CTRL_MEAS_REG, QMP6988_PWR_SAMPLE_MODE);
|
||||
|
|
|
@ -305,25 +305,25 @@ uint32_t sx127xGetCurrBandwidth(const sx127xBandwidth_e bw)
|
|||
{
|
||||
switch (bw) {
|
||||
case SX127x_BW_7_80_KHZ:
|
||||
return 7.8E3;
|
||||
return 7.8E3f;
|
||||
case SX127x_BW_10_40_KHZ:
|
||||
return 10.4E3;
|
||||
return 10.4E3f;
|
||||
case SX127x_BW_15_60_KHZ:
|
||||
return 15.6E3;
|
||||
return 15.6E3f;
|
||||
case SX127x_BW_20_80_KHZ:
|
||||
return 20.8E3;
|
||||
return 20.8E3f;
|
||||
case SX127x_BW_31_25_KHZ:
|
||||
return 31.25E3;
|
||||
return 31.25E3f;
|
||||
case SX127x_BW_41_70_KHZ:
|
||||
return 41.7E3;
|
||||
return 41.7E3f;
|
||||
case SX127x_BW_62_50_KHZ:
|
||||
return 62.5E3;
|
||||
return 62.5E3f;
|
||||
case SX127x_BW_125_00_KHZ:
|
||||
return 125E3;
|
||||
return 125E3f;
|
||||
case SX127x_BW_250_00_KHZ:
|
||||
return 250E3;
|
||||
return 250E3f;
|
||||
case SX127x_BW_500_00_KHZ:
|
||||
return 500E3;
|
||||
return 500E3f;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
|
|
@ -292,7 +292,7 @@ typedef enum {
|
|||
|
||||
#define SX127x_MAX_POWER 0x0F //17dBm
|
||||
|
||||
#define SX127x_FREQ_STEP 61.03515625
|
||||
#define SX127x_FREQ_STEP (61.03515625) // 61.03515625 Hz, used for frequency calculations
|
||||
|
||||
#define SX127x_FREQ_CORRECTION_MAX ((int32_t)(100000 / SX127x_FREQ_STEP))
|
||||
#define SX127x_FREQ_CORRECTION_MIN ((int32_t)(-100000 / SX127x_FREQ_STEP))
|
||||
|
|
|
@ -600,7 +600,7 @@ void tryArm(void)
|
|||
resetMaxFFT();
|
||||
#endif
|
||||
|
||||
disarmAt = currentTimeUs + armingConfig()->auto_disarm_delay * 1e6; // start disarm timeout, will be extended when throttle is nonzero
|
||||
disarmAt = currentTimeUs + armingConfig()->auto_disarm_delay * 1000 * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||
|
||||
lastArmingDisabledReason = 0;
|
||||
|
||||
|
@ -926,7 +926,7 @@ void processRxModes(timeUs_t currentTimeUs)
|
|||
// When armed and motors aren't spinning, do beeps and then disarm
|
||||
// board after delay so users without buzzer won't lose fingers.
|
||||
// mixTable constrains motor commands, so checking throttleStatus is enough
|
||||
const timeUs_t autoDisarmDelayUs = armingConfig()->auto_disarm_delay * 1e6;
|
||||
const timeUs_t autoDisarmDelayUs = armingConfig()->auto_disarm_delay * 1e6f;
|
||||
if (ARMING_FLAG(ARMED)
|
||||
&& featureIsEnabled(FEATURE_MOTOR_STOP)
|
||||
&& !isFixedWing()
|
||||
|
@ -1019,7 +1019,7 @@ void processRxModes(timeUs_t currentTimeUs)
|
|||
|
||||
#ifdef USE_ALTITUDE_HOLD
|
||||
// only if armed; can coexist with position hold
|
||||
if (ARMING_FLAG(ARMED)
|
||||
if (ARMING_FLAG(ARMED)
|
||||
// and not in GPS_RESCUE_MODE, to give it priority over Altitude Hold
|
||||
&& !FLIGHT_MODE(GPS_RESCUE_MODE)
|
||||
// and either the alt_hold switch is activated, or are in failsafe landing mode
|
||||
|
@ -1040,7 +1040,7 @@ void processRxModes(timeUs_t currentTimeUs)
|
|||
|
||||
#ifdef USE_POSITION_HOLD
|
||||
// only if armed; can coexist with altitude hold
|
||||
if (ARMING_FLAG(ARMED)
|
||||
if (ARMING_FLAG(ARMED)
|
||||
// and not in GPS_RESCUE_MODE, to give it priority over Position Hold
|
||||
&& !FLIGHT_MODE(GPS_RESCUE_MODE)
|
||||
// and either the alt_hold switch is activated, or are in failsafe landing mode
|
||||
|
@ -1254,7 +1254,7 @@ static FAST_CODE_NOINLINE void subTaskPidSubprocesses(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
#ifdef USE_TELEMETRY
|
||||
#define GYRO_TEMP_READ_DELAY_US 3e6 // Only read the gyro temp every 3 seconds
|
||||
#define GYRO_TEMP_READ_DELAY_US (3 * 1000 * 1000) // Only read the gyro temp every 3 seconds
|
||||
void subTaskTelemetryPollSensors(timeUs_t currentTimeUs)
|
||||
{
|
||||
static timeUs_t lastGyroTempTimeUs = 0;
|
||||
|
|
|
@ -263,8 +263,8 @@ static void scaleRawSetpointToFpvCamAngle(void)
|
|||
{
|
||||
//recalculate sin/cos only when rxConfig()->fpvCamAngleDegrees changed
|
||||
static uint8_t lastFpvCamAngleDegrees = 0;
|
||||
static float cosFactor = 1.0;
|
||||
static float sinFactor = 0.0;
|
||||
static float cosFactor = 1.0f;
|
||||
static float sinFactor = 0.0f;
|
||||
|
||||
if (lastFpvCamAngleDegrees != rxConfig()->fpvCamAngleDegrees) {
|
||||
lastFpvCamAngleDegrees = rxConfig()->fpvCamAngleDegrees;
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
|
||||
#include "rc_modes.h"
|
||||
|
||||
#define STICKY_MODE_BOOT_DELAY_US 5e6
|
||||
#define STICKY_MODE_BOOT_DELAY_US (5 * 1000 * 1000)
|
||||
|
||||
boxBitmask_t rcModeActivationMask; // one bit per mode defined in boxId_e
|
||||
static boxBitmask_t stickyModesEverDisabled;
|
||||
|
|
|
@ -371,7 +371,7 @@ void mixerInitProfile(void)
|
|||
mixerRuntime.rpmLimiterPGain = mixerConfig()->rpm_limit_p * 15e-6f;
|
||||
mixerRuntime.rpmLimiterIGain = mixerConfig()->rpm_limit_i * 1e-3f * pidGetDT();
|
||||
mixerRuntime.rpmLimiterDGain = mixerConfig()->rpm_limit_d * 3e-7f * pidGetPidFrequency();
|
||||
mixerRuntime.rpmLimiterI = 0.0;
|
||||
mixerRuntime.rpmLimiterI = 0.0f;
|
||||
pt1FilterInit(&mixerRuntime.rpmLimiterAverageRpmFilter, pt1FilterGain(6.0f, pidGetDT()));
|
||||
pt1FilterInit(&mixerRuntime.rpmLimiterThrottleScaleOffsetFilter, pt1FilterGain(2.0f, pidGetDT()));
|
||||
mixerResetRpmLimiter();
|
||||
|
@ -385,7 +385,7 @@ void mixerInitProfile(void)
|
|||
#ifdef USE_RPM_LIMIT
|
||||
void mixerResetRpmLimiter(void)
|
||||
{
|
||||
mixerRuntime.rpmLimiterI = 0.0;
|
||||
mixerRuntime.rpmLimiterI = 0.0f;
|
||||
mixerRuntime.rpmLimiterThrottleScale = constrainf(mixerRuntime.rpmLimiterRpmLimit / motorEstimateMaxRpm(), 0.0f, 1.0f);
|
||||
mixerRuntime.rpmLimiterInitialThrottleScale = mixerRuntime.rpmLimiterThrottleScale;
|
||||
}
|
||||
|
|
|
@ -105,7 +105,7 @@ static uint8_t previousProfileColorIndex = COLOR_UNDEFINED;
|
|||
// Decay the estimated max task duration by 1/(1 << LED_EXEC_TIME_SHIFT) on every invocation
|
||||
#define LED_EXEC_TIME_SHIFT 7
|
||||
|
||||
#define PROFILE_COLOR_UPDATE_INTERVAL_US 1e6 // normally updates when color changes but this is a 1 second forced update
|
||||
#define PROFILE_COLOR_UPDATE_INTERVAL_US 1e6f // normally updates when color changes but this is a 1 second forced update
|
||||
|
||||
#define VISUAL_BEEPER_COLOR COLOR_WHITE
|
||||
|
||||
|
|
|
@ -1196,7 +1196,7 @@ static timeDelta_t osdShowArmed(void)
|
|||
uint8_t midRow = osdDisplayPort->rows / 2;
|
||||
uint8_t midCol = osdDisplayPort->cols / 2;
|
||||
osdDrawLogo(midCol - (OSD_LOGO_COLS) / 2, midRow - 5, osdConfig()->arming_logo);
|
||||
ret = osdConfig()->logo_on_arming_duration * 1e5;
|
||||
ret = osdConfig()->logo_on_arming_duration * 100 * 1000; // convert to microseconds
|
||||
} else {
|
||||
ret = (REFRESH_1S / 2);
|
||||
}
|
||||
|
|
|
@ -799,7 +799,7 @@ static void osdElementUpDownReference(osdElementParms_t *element)
|
|||
char *symbol[2] = {"U", "D"}; // character buffer
|
||||
int direction;
|
||||
|
||||
if(attitude.values.pitch>0.0){ //nose down
|
||||
if (attitude.values.pitch > 0.0f){ //nose down
|
||||
thetaB = -earthUpinBodyFrame[2]; // get pitch w/re to nadir (use small angle approx for sine)
|
||||
psiB = -earthUpinBodyFrame[1]; // calculate the yaw w/re to nadir (use small angle approx for sine)
|
||||
direction = DOWN;
|
||||
|
@ -1589,7 +1589,7 @@ static void osdElementRemainingTimeEstimate(osdElementParms_t *element)
|
|||
element->attr = DISPLAYPORT_SEVERITY_CRITICAL;
|
||||
}
|
||||
|
||||
if (mAhDrawn <= 0.1 * osdConfig()->cap_alarm) { // also handles the mAhDrawn == 0 condition
|
||||
if (mAhDrawn <= 0.1f * osdConfig()->cap_alarm) { // also handles the mAhDrawn == 0 condition
|
||||
tfp_sprintf(element->buff, "--:--");
|
||||
} else if (mAhDrawn > osdConfig()->cap_alarm) {
|
||||
tfp_sprintf(element->buff, "00:00");
|
||||
|
|
|
@ -52,7 +52,7 @@
|
|||
#define ELRS_MODELMATCH_MASK 0x3F
|
||||
|
||||
#define FREQ_HZ_TO_REG_VAL_900(freq) ((uint32_t)(freq / SX127x_FREQ_STEP))
|
||||
#define FREQ_HZ_TO_REG_VAL_24(freq) ((uint32_t)(freq / SX1280_FREQ_STEP))
|
||||
#define FREQ_HZ_TO_REG_VAL_24(freq) ((uint32_t)(freq / SX1280_FREQ_STEP))
|
||||
|
||||
#define ELRS_RATE_MAX_24 6
|
||||
#define ELRS_RATE_MAX_900 4
|
||||
|
|
|
@ -667,7 +667,7 @@ FAST_CODE void scheduler(void)
|
|||
minGyroPeriod = gyroCyclesNow;
|
||||
}
|
||||
// Crude detection of missed cycles caused by configurator traffic
|
||||
if ((gyroCyclesNow > maxGyroPeriod) && (gyroCyclesNow < (1.5 * minGyroPeriod))) {
|
||||
if ((gyroCyclesNow > maxGyroPeriod) && (gyroCyclesNow < minGyroPeriod + minGyroPeriod / 2)) { // 1.5 * minGyroPeriod
|
||||
maxGyroPeriod = gyroCyclesNow;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -52,8 +52,8 @@
|
|||
|
||||
#define TASK_AGE_EXPEDITE_RX schedulerConfig()->rxRelaxDeterminism // Make RX tasks more schedulable if it's failed to be scheduled this many times
|
||||
#define TASK_AGE_EXPEDITE_OSD schedulerConfig()->osdRelaxDeterminism // Make OSD tasks more schedulable if it's failed to be scheduled this many times
|
||||
#define TASK_AGE_EXPEDITE_COUNT 1 // Make aged tasks more schedulable
|
||||
#define TASK_AGE_EXPEDITE_SCALE 0.9 // By scaling their expected execution time
|
||||
#define TASK_AGE_EXPEDITE_COUNT 1 // Make aged tasks more schedulable
|
||||
#define TASK_AGE_EXPEDITE_SCALE 0.9f // By scaling their expected execution time
|
||||
|
||||
// Gyro interrupt counts over which to measure loop time and skew
|
||||
#define GYRO_RATE_COUNT 25000
|
||||
|
|
|
@ -242,7 +242,7 @@ void batteryUpdatePresence(void)
|
|||
batteryCriticalVoltage = 0;
|
||||
batteryWarningHysteresisVoltage = 0;
|
||||
batteryCriticalHysteresisVoltage = 0;
|
||||
wattHoursDrawn = 0.0;
|
||||
wattHoursDrawn = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -376,7 +376,7 @@ bool compassInit(void)
|
|||
if (magDev.magOdrHz) {
|
||||
// For Mags that send data at a fixed ODR, we wait some quiet period after a read before checking for new data
|
||||
// allow two re-check intervals, plus a margin for clock variations in mag vs FC
|
||||
uint16_t odrInterval = 1e6 / magDev.magOdrHz;
|
||||
uint16_t odrInterval = (1000 * 1000) / magDev.magOdrHz;
|
||||
compassReadIntervalUs = odrInterval - (2 * COMPASS_RECHECK_INTERVAL_US) - (odrInterval / 20);
|
||||
} else {
|
||||
// Mags which have no specified ODR will be pinged at the compass task rate
|
||||
|
@ -522,7 +522,7 @@ uint32_t compassUpdate(timeUs_t currentTimeUs)
|
|||
static timeUs_t previousTimeUs = 0;
|
||||
const timeDelta_t dataIntervalUs = cmpTimeUs(currentTimeUs, previousTimeUs); // time since last data received
|
||||
previousTimeUs = currentTimeUs;
|
||||
const uint16_t actualCompassDataRateHz = 1e6 / dataIntervalUs;
|
||||
const uint16_t actualCompassDataRateHz = 1e6f / dataIntervalUs;
|
||||
timeDelta_t executeTimeUs = micros() - currentTimeUs;
|
||||
DEBUG_SET(DEBUG_MAG_TASK_RATE, 0, TASK_COMPASS_RATE_HZ);
|
||||
DEBUG_SET(DEBUG_MAG_TASK_RATE, 1, actualCompassDataRateHz);
|
||||
|
|
|
@ -190,6 +190,7 @@ void voltageMeterADCRefresh(void)
|
|||
#endif
|
||||
#else
|
||||
UNUSED(voltageAdcToVoltage);
|
||||
UNUSED(voltageMeterAdcChannelMap);
|
||||
|
||||
state->voltageDisplayFiltered = 0;
|
||||
state->voltageUnfiltered = 0;
|
||||
|
|
|
@ -413,7 +413,7 @@ static void mavlinkSendHUDAndHeartbeat(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
mavAltitude = getEstimatedAltitudeCm() / 100.0;
|
||||
mavAltitude = getEstimatedAltitudeCm() / 100.0f;
|
||||
|
||||
mavlink_msg_vfr_hud_pack(0, 200, &mavMsg,
|
||||
// airspeed Current airspeed in m/s
|
||||
|
|
|
@ -127,7 +127,7 @@ INCLUDE_DIRS += \
|
|||
$(SRC_DIR)/msc
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
|
||||
DEVICE_FLAGS = -DUSE_DAL_DRIVER -DHSE_VALUE=$(HSE_VALUE) -DAPM32
|
||||
|
||||
|
|
|
@ -78,7 +78,7 @@ else
|
|||
LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xg.ld
|
||||
endif
|
||||
|
||||
ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32 -DUSE_OTG_HOST_MODE
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
|
|
|
@ -425,8 +425,7 @@ uint64_t micros64(void)
|
|||
out += (now - last) * simRate;
|
||||
last = now;
|
||||
|
||||
return out*1e-3;
|
||||
// return micros64_real();
|
||||
return out / 1000;
|
||||
}
|
||||
|
||||
uint64_t millis64(void)
|
||||
|
@ -438,8 +437,7 @@ uint64_t millis64(void)
|
|||
out += (now - last) * simRate;
|
||||
last = now;
|
||||
|
||||
return out*1e-6;
|
||||
// return millis64_real();
|
||||
return out / (1000 * 1000);
|
||||
}
|
||||
|
||||
uint32_t micros(void)
|
||||
|
|
|
@ -150,7 +150,7 @@ DEVICE_FLAGS += -DUSE_STDPERIPH_DRIVER
|
|||
endif
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
|
||||
ifeq ($(TARGET_MCU),STM32F411xE)
|
||||
DEVICE_FLAGS += -DSTM32F411xE -finline-limit=20
|
||||
|
|
|
@ -97,7 +97,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
|||
$(TARGET_PLATFORM_DIR)/vcp_hal
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16
|
||||
|
||||
# Flags that are used in the STM32 libraries
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
|
||||
|
|
|
@ -90,7 +90,7 @@ INCLUDE_DIRS := \
|
|||
$(TARGET_PLATFORM_DIR)/vcp_hal
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -DUSE_DMA_RAM -DMAX_MPU_REGIONS=16
|
||||
|
||||
|
|
|
@ -99,7 +99,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
|||
$(TARGET_PLATFORM_DIR)/vcp_hal
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16
|
||||
|
||||
# Flags that are used in the STM32 libraries
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
|
||||
|
|
|
@ -103,7 +103,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
|||
$(TARGET_PLATFORM_DIR)/vcp_hal
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16
|
||||
|
||||
# Flags that are used in the STM32 libraries
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue