1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 16:25:26 +03:00

[SITL OSX] Fix some of the warnings and add macosx SITL build to workflows (#9063)

clang can be verbose with warnings, but some of it is probably valid when building a 64bit binary.

Highlighted changes:

* Call float versions of math functions to avoid conversion to double by the compiler (absf, sqrtf, roundf, etc)
* Make sure floating point constants are marked as floats, to avoid conversion to double by the compiler. (1.0 is a double, 1.0f is a float and when doing math between float and double, all values get upgraded to double!)
* Changed memcpy_fn in unit test AND SITL builds to be a macro to memcpy (instead of inline function calling memcpy), this fixes linker errors for memcpy as macos compiler mangles the symbol in a different way and would not work with asm("memcpy") call.
* Some simulator code made heavy use of doubles, but since all the data in INAV is float, that is probably overkill and some functions/macros had float in the name, while upconvertting to double.

Open questions:

* Should scale in osdFormatCentiNumber be changed to float? It is currently uint32_t but some of the scale defines are, correctly, not integer numbers.
* I changed CENTIDEGREES_TO_DEGREES to use float on the division path, but the code seems to be ok, or assuming it would be converted to integer anyway. Is this the correct solution?
* This still does not fix the invalid settings issues, I suspect it is related to the lack of linker scripts in clang, to preserve the section data of settings.
* Binary is still not multi platform (arm/x86_64).
This commit is contained in:
Marcelo Bezerra 2023-05-25 13:12:03 +02:00 committed by GitHub
parent ccd75e7a2e
commit 69bd3e9d93
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
42 changed files with 227 additions and 182 deletions

View file

@ -38,9 +38,9 @@ jobs:
- name: Build targets (${{ matrix.id }}) - name: Build targets (${{ matrix.id }})
run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -G Ninja .. && ninja ci run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -G Ninja .. && ninja ci
- name: Upload artifacts - name: Upload artifacts
uses: actions/upload-artifact@v2-preview uses: actions/upload-artifact@v3
with: with:
name: ${{ env.BUILD_NAME }}.zip name: ${{ env.BUILD_NAME }}
path: ./build/*.hex path: ./build/*.hex
build-SITL-Linux: build-SITL-Linux:
@ -68,9 +68,46 @@ jobs:
- name: Build SITL - name: Build SITL
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja
- name: Upload artifacts - name: Upload artifacts
uses: actions/upload-artifact@v2-preview uses: actions/upload-artifact@v3
with: with:
name: ${{ env.BUILD_NAME }}_SITL.zip name: ${{ env.BUILD_NAME }}_SITL
path: ./build_SITL/*_SITL
build-SITL-Mac:
runs-on: macos-latest
steps:
- uses: actions/checkout@v3
- name: Install dependencies
run: |
brew update
brew install cmake ninja ruby
- name: Setup environment
env:
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
run: |
# This is the hash of the commit for the PR
# when the action is triggered by PR, empty otherwise
COMMIT_ID=${{ github.event.pull_request.head.sha }}
# This is the hash of the commit when triggered by push
# but the hash of refs/pull/<n>/merge, which is different
# from the hash of the latest commit in the PR, that's
# why we try github.event.pull_request.head.sha first
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
- name: Build SITL
run: |
mkdir -p build_SITL && cd build_SITL
cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja ..
ninja
- name: Upload artifacts
uses: actions/upload-artifact@v3
with:
name: ${{ env.BUILD_NAME }}_SITL-MacOS
path: ./build_SITL/*_SITL path: ./build_SITL/*_SITL
build-SITL-Windows: build-SITL-Windows:
@ -103,9 +140,9 @@ jobs:
- name: Build SITL - name: Build SITL
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja
- name: Upload artifacts - name: Upload artifacts
uses: actions/upload-artifact@v2-preview uses: actions/upload-artifact@v3
with: with:
name: ${{ env.BUILD_NAME }}_SITL-WIN.zip name: ${{ env.BUILD_NAME }}_SITL-WIN
path: ./build_SITL/*.exe path: ./build_SITL/*.exe

View file

@ -59,6 +59,10 @@ if(NOT MACOSX)
-Wno-error=maybe-uninitialized -Wno-error=maybe-uninitialized
-fsingle-precision-constant -fsingle-precision-constant
) )
else()
set(SITL_COMPILE_OPTIONS ${SITL_COMPILE_OPTIONS}
-Wno-missing-braces
)
endif() endif()
set(SITL_DEFINITIONS set(SITL_DEFINITIONS

View file

@ -574,8 +574,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
mavlink_message_t* r_message, mavlink_message_t* r_message,
mavlink_status_t* r_mavlink_status) mavlink_status_t* r_mavlink_status)
{ {
int bufferIndex = 0;
status->msg_received = MAVLINK_FRAMING_INCOMPLETE; status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
switch (status->parse_state) switch (status->parse_state)
@ -801,7 +799,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
break; break;
} }
bufferIndex++;
// If a message has been sucessfully decoded, check index // If a message has been sucessfully decoded, check index
if (status->msg_received == MAVLINK_FRAMING_OK) if (status->msg_received == MAVLINK_FRAMING_OK)
{ {

View file

@ -1326,12 +1326,19 @@ static void loadSlowState(blackboxSlowState_t *slow)
#endif #endif
bool valid_temp; bool valid_temp;
valid_temp = getIMUTemperature(&slow->imuTemperature); int16_t newTemp = 0;
if (!valid_temp) slow->imuTemperature = TEMPERATURE_INVALID_VALUE; valid_temp = getIMUTemperature(&newTemp);
if (valid_temp)
slow->imuTemperature = newTemp;
else
slow->imuTemperature = TEMPERATURE_INVALID_VALUE;
#ifdef USE_BARO #ifdef USE_BARO
valid_temp = getBaroTemperature(&slow->baroTemperature); valid_temp = getBaroTemperature(&newTemp);
if (!valid_temp) slow->baroTemperature = TEMPERATURE_INVALID_VALUE; if (valid_temp)
slow->baroTemperature = newTemp;
else
slow->baroTemperature = TEMPERATURE_INVALID_VALUE;
#endif #endif
#ifdef USE_TEMPERATURE_SENSOR #ifdef USE_TEMPERATURE_SENSOR

View file

@ -192,7 +192,7 @@ typedef struct OSD_SETTING_s {
const uint8_t step; const uint8_t step;
} __attribute__((packed)) OSD_SETTING_t; } __attribute__((packed)) OSD_SETTING_t;
#define OSD_SETTING_ENTRY_STEP_TYPE(name, setting, step, type) { name, NULL, &(const OSD_SETTING_t){ setting, step }, OME_Setting, type } #define OSD_SETTING_ENTRY_STEP_TYPE(name, setting, step, type) { name, { NULL }, &(const OSD_SETTING_t){ setting, step }, OME_Setting, type }
#define OSD_SETTING_ENTRY_TYPE(name, setting, type) OSD_SETTING_ENTRY_STEP_TYPE(name, setting, 0, type) #define OSD_SETTING_ENTRY_TYPE(name, setting, type) OSD_SETTING_ENTRY_STEP_TYPE(name, setting, 0, type)
#define OSD_SETTING_ENTRY_STEP(name, setting, step) OSD_SETTING_ENTRY_STEP_TYPE(name, setting, step, 0) #define OSD_SETTING_ENTRY_STEP(name, setting, step) OSD_SETTING_ENTRY_STEP_TYPE(name, setting, step, 0)
#define OSD_SETTING_ENTRY(name, setting) OSD_SETTING_ENTRY_STEP(name, setting, 0) #define OSD_SETTING_ENTRY(name, setting) OSD_SETTING_ENTRY_STEP(name, setting, 0)

View file

@ -18,9 +18,9 @@
#pragma once #pragma once
#define FEET_PER_MILE 5280 #define FEET_PER_MILE 5280
#define FEET_PER_NAUTICALMILE 6076.118 #define FEET_PER_NAUTICALMILE 6076.118f
#define FEET_PER_KILOFEET 1000 // Used for altitude #define FEET_PER_KILOFEET 1000 // Used for altitude
#define METERS_PER_KILOMETER 1000 #define METERS_PER_KILOMETER 1000
#define METERS_PER_MILE 1609.344 #define METERS_PER_MILE 1609.344f
#define METERS_PER_FOOT 3.28084 #define METERS_PER_FOOT 3.28084f
#define METERS_PER_NAUTICALMILE 1852.001 #define METERS_PER_NAUTICALMILE 1852.001f

View file

@ -521,7 +521,7 @@ float bellCurve(const float x, const float curveWidth)
return powf(M_Ef, -sq(x) / (2.0f * sq(curveWidth))); return powf(M_Ef, -sq(x) / (2.0f * sq(curveWidth)));
} }
float fast_fsqrtf(const double value) { float fast_fsqrtf(const float value) {
float ret = 0.0f; float ret = 0.0f;
#ifdef USE_ARM_MATH #ifdef USE_ARM_MATH
arm_sqrt_f32(value, &ret); arm_sqrt_f32(value, &ret);

View file

@ -36,13 +36,13 @@
#define RAD (M_PIf / 180.0f) #define RAD (M_PIf / 180.0f)
#define DEGREES_TO_CENTIDEGREES(angle) ((angle) * 100) #define DEGREES_TO_CENTIDEGREES(angle) ((angle) * 100)
#define CENTIDEGREES_TO_DEGREES(angle) ((angle) / 100) #define CENTIDEGREES_TO_DEGREES(angle) ((angle) / 100.0f)
#define CENTIDEGREES_TO_DECIDEGREES(angle) ((angle) / 10) #define CENTIDEGREES_TO_DECIDEGREES(angle) ((angle) / 10.0f)
#define DECIDEGREES_TO_CENTIDEGREES(angle) ((angle) * 10) #define DECIDEGREES_TO_CENTIDEGREES(angle) ((angle) * 10)
#define DEGREES_TO_DECIDEGREES(angle) ((angle) * 10) #define DEGREES_TO_DECIDEGREES(angle) ((angle) * 10)
#define DECIDEGREES_TO_DEGREES(angle) ((angle) / 10) #define DECIDEGREES_TO_DEGREES(angle) ((angle) / 10.0f)
#define DEGREES_PER_DEKADEGREE 10 #define DEGREES_PER_DEKADEGREE 10
#define DEGREES_TO_DEKADEGREES(angle) ((angle) / DEGREES_PER_DEKADEGREE) #define DEGREES_TO_DEKADEGREES(angle) ((angle) / DEGREES_PER_DEKADEGREE)
@ -56,15 +56,15 @@
#define RADIANS_TO_CENTIDEGREES(angle) (((angle) * 100.0f) / RAD) #define RADIANS_TO_CENTIDEGREES(angle) (((angle) * 100.0f) / RAD)
#define CENTIDEGREES_TO_RADIANS(angle) (((angle) / 100.0f) * RAD) #define CENTIDEGREES_TO_RADIANS(angle) (((angle) / 100.0f) * RAD)
#define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048) #define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048f)
#define CENTIMETERS_TO_FEET(cm) (cm / 30.48) #define CENTIMETERS_TO_FEET(cm) (cm / 30.48f)
#define CENTIMETERS_TO_METERS(cm) (cm / 100) #define CENTIMETERS_TO_METERS(cm) (cm / 100.0f)
#define METERS_TO_CENTIMETERS(m) (m * 100) #define METERS_TO_CENTIMETERS(m) (m * 100)
#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363) #define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363f)
#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6) #define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f)
#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845) #define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f)
#define C_TO_KELVIN(temp) (temp + 273.15f) #define C_TO_KELVIN(temp) (temp + 273.15f)
@ -188,6 +188,6 @@ float acos_approx(float x);
void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count); void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count);
float bellCurve(const float x, const float curveWidth); float bellCurve(const float x, const float curveWidth);
float fast_fsqrtf(const double value); float fast_fsqrtf(const float value);
float calc_length_pythagorean_2D(const float firstElement, const float secondElement); float calc_length_pythagorean_2D(const float firstElement, const float secondElement);
float calc_length_pythagorean_3D(const float firstElement, const float secondElement, const float thirdElement); float calc_length_pythagorean_3D(const float firstElement, const float secondElement, const float thirdElement);

View file

@ -52,7 +52,7 @@ void * memAllocate(size_t wantedSize, resourceOwner_e owner)
retPointer = &dynHeap[dynHeapFreeWord]; retPointer = &dynHeap[dynHeapFreeWord];
dynHeapFreeWord += wantedWords; dynHeapFreeWord += wantedWords;
dynHeapUsage[owner] += wantedWords * sizeof(uint32_t); dynHeapUsage[owner] += wantedWords * sizeof(uint32_t);
LOG_DEBUG(SYSTEM, "Memory allocated. Free memory = %d", memGetAvailableBytes()); LOG_DEBUG(SYSTEM, "Memory allocated. Free memory = %ld", (unsigned long)memGetAvailableBytes());
} }
else { else {
// OOM // OOM

View file

@ -58,7 +58,7 @@ static inline void quaternionToAxisAngle(fpAxisAngle_t * result, const fpQuatern
a.angle -= 2.0f * M_PIf; a.angle -= 2.0f * M_PIf;
} }
const float sinVal = sqrt(1.0f - q->q0 * q->q0); const float sinVal = sqrtf(1.0f - q->q0 * q->q0);
// Axis is only valid when rotation is large enough sin(0.0057 deg) = 0.0001 // Axis is only valid when rotation is large enough sin(0.0057 deg) = 0.0001
if (sinVal > 1e-4f) { if (sinVal > 1e-4f) {

View file

@ -90,10 +90,9 @@ static inline int32_t cmp32(uint32_t a, uint32_t b) { return a-b; }
// using memcpy_fn will force memcpy function call, instead of inlining it. In most cases function call takes fewer instructions // using memcpy_fn will force memcpy function call, instead of inlining it. In most cases function call takes fewer instructions
// than inlined version (inlining is cheaper for very small moves < 8 bytes / 2 store instructions) // than inlined version (inlining is cheaper for very small moves < 8 bytes / 2 store instructions)
#ifdef UNIT_TEST #if defined(UNIT_TEST) || defined(SITL_BUILD)
// Call memcpy when building unittest - this is easier that asm symbol name mangling (symbols start with _underscore on win32)
#include <string.h> #include <string.h>
static inline void memcpy_fn(void *destination, const void *source, size_t num) { memcpy(destination, source, num); }; #define memcpy_fn(destination, source, num) memcpy(destination, source, num)
#else #else
void *memcpy_fn(void *destination, const void *source, size_t num) asm("memcpy"); void *memcpy_fn(void *destination, const void *source, size_t num) asm("memcpy");
#endif #endif

View file

@ -367,7 +367,7 @@ uint16_t encodeTimeout(uint16_t timeout_mclks)
// Defaults to 0.25 MCPS as initialized by the ST API and this library. // Defaults to 0.25 MCPS as initialized by the ST API and this library.
bool setSignalRateLimit(busDevice_t * busDev, float limit_Mcps) bool setSignalRateLimit(busDevice_t * busDev, float limit_Mcps)
{ {
if (limit_Mcps < 0 || limit_Mcps > 511.99) { if (limit_Mcps < 0 || limit_Mcps > 511.99f) {
return false; return false;
} }

View file

@ -983,12 +983,12 @@ void taskUpdateRxMain(timeUs_t currentTimeUs)
} }
// returns seconds // returns seconds
float getFlightTime() float getFlightTime(void)
{ {
return US2S(flightTime); return US2S(flightTime);
} }
float getArmTime() float getArmTime(void)
{ {
return US2S(armTime); return US2S(armTime);
} }

View file

@ -179,7 +179,7 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void)
#ifdef USE_SIMULATOR #ifdef USE_SIMULATOR
simulatorData_t simulatorData = { simulatorData_t simulatorData = {
flags: 0, .flags = 0,
debugIndex: 0 .debugIndex = 0
}; };
#endif #endif

View file

@ -36,7 +36,7 @@ static uint32_t arm_distance_cm;
static uint32_t arm_mWhDrawn; static uint32_t arm_mWhDrawn;
static uint32_t flyingEnergy; // energy drawn during flying up to last disarm (ARMED) mWh static uint32_t flyingEnergy; // energy drawn during flying up to last disarm (ARMED) mWh
uint32_t getFlyingEnergy() { uint32_t getFlyingEnergy(void) {
return flyingEnergy; return flyingEnergy;
} }
#endif #endif

View file

@ -277,7 +277,7 @@ static void imuResetOrientationQuaternion(const fpVector3_t * accBF)
static bool imuValidateQuaternion(const fpQuaternion_t * quat) static bool imuValidateQuaternion(const fpQuaternion_t * quat)
{ {
const float check = fabs(quat->q0) + fabs(quat->q1) + fabs(quat->q2) + fabs(quat->q3); const float check = fabsf(quat->q0) + fabsf(quat->q1) + fabsf(quat->q2) + fabsf(quat->q3);
if (!isnan(check) && !isinf(check)) { if (!isnan(check) && !isinf(check)) {
return true; return true;
@ -480,7 +480,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe
const float thetaMagnitudeSq = vectorNormSquared(&vTheta); const float thetaMagnitudeSq = vectorNormSquared(&vTheta);
// If calculated rotation is zero - don't update quaternion // If calculated rotation is zero - don't update quaternion
if (thetaMagnitudeSq >= 1e-20) { if (thetaMagnitudeSq >= 1e-20f) {
// Calculate quaternion delta: // Calculate quaternion delta:
// Theta is a axis/angle rotation. Direction of a vector is axis, magnitude is angle/2. // Theta is a axis/angle rotation. Direction of a vector is axis, magnitude is angle/2.
// Proper quaternion from axis/angle involves computing sin/cos, but the formula becomes numerically unstable as Theta approaches zero. // Proper quaternion from axis/angle involves computing sin/cos, but the formula becomes numerically unstable as Theta approaches zero.

View file

@ -461,7 +461,7 @@ static int getReversibleMotorsThrottleDeadband(void)
return feature(FEATURE_MOTOR_STOP) ? reversibleMotorsConfig()->neutral : directionValue; return feature(FEATURE_MOTOR_STOP) ? reversibleMotorsConfig()->neutral : directionValue;
} }
void FAST_CODE mixTable() void FAST_CODE mixTable(void)
{ {
#ifdef USE_DSHOT #ifdef USE_DSHOT
if (FLIGHT_MODE(TURTLE_MODE)) { if (FLIGHT_MODE(TURTLE_MODE)) {

View file

@ -477,7 +477,7 @@ void schedulePidGainsUpdate(void)
pidGainsUpdateRequired = true; pidGainsUpdateRequired = true;
} }
void updatePIDCoefficients() void updatePIDCoefficients(void)
{ {
STATIC_FASTRAM uint16_t prevThrottle = 0; STATIC_FASTRAM uint16_t prevThrottle = 0;
@ -864,7 +864,7 @@ void resetHeadingHoldTarget(int16_t heading)
pt1FilterReset(&headingHoldRateFilter, 0.0f); pt1FilterReset(&headingHoldRateFilter, 0.0f);
} }
int16_t getHeadingHoldTarget() { int16_t getHeadingHoldTarget(void) {
return headingHoldTarget; return headingHoldTarget;
} }

View file

@ -162,14 +162,14 @@ void powerLimiterApply(int16_t *throttleCommand) {
int32_t overCurrent = current - activeCurrentLimit; int32_t overCurrent = current - activeCurrentLimit;
if (lastCallTimestamp) { if (lastCallTimestamp) {
currentThrAttnIntegrator = constrainf(currentThrAttnIntegrator + overCurrent * powerLimitsConfig()->piI * callTimeDelta * 2e-7, 0, PWM_RANGE_MAX - PWM_RANGE_MIN); currentThrAttnIntegrator = constrainf(currentThrAttnIntegrator + overCurrent * powerLimitsConfig()->piI * callTimeDelta * 2e-7f, 0, PWM_RANGE_MAX - PWM_RANGE_MIN);
} }
float currentThrAttnProportional = MAX(0, overCurrent) * powerLimitsConfig()->piP * 1e-3; float currentThrAttnProportional = MAX(0, overCurrent) * powerLimitsConfig()->piP * 1e-3f;
uint16_t currentThrAttn = lrintf(pt1FilterApply3(&currentThrAttnFilter, currentThrAttnProportional + currentThrAttnIntegrator, callTimeDelta * 1e-6)); uint16_t currentThrAttn = lrintf(pt1FilterApply3(&currentThrAttnFilter, currentThrAttnProportional + currentThrAttnIntegrator, callTimeDelta * 1e-6f));
throttleBase = wasLimitingCurrent ? lrintf(pt1FilterApply3(&currentThrLimitingBaseFilter, *throttleCommand, callTimeDelta * 1e-6)) : *throttleCommand; throttleBase = wasLimitingCurrent ? lrintf(pt1FilterApply3(&currentThrLimitingBaseFilter, *throttleCommand, callTimeDelta * 1e-6f)) : *throttleCommand;
uint16_t currentThrAttned = MAX(PWM_RANGE_MIN, (int16_t)throttleBase - currentThrAttn); uint16_t currentThrAttned = MAX(PWM_RANGE_MIN, (int16_t)throttleBase - currentThrAttn);
if (activeCurrentLimit && currentThrAttned < *throttleCommand) { if (activeCurrentLimit && currentThrAttned < *throttleCommand) {
@ -191,12 +191,12 @@ void powerLimiterApply(int16_t *throttleCommand) {
int32_t overPower = power - activePowerLimit; int32_t overPower = power - activePowerLimit;
if (lastCallTimestamp) { if (lastCallTimestamp) {
powerThrAttnIntegrator = constrainf(powerThrAttnIntegrator + overPower * powerLimitsConfig()->piI * callTimeDelta / voltage * 2e-5, 0, PWM_RANGE_MAX - PWM_RANGE_MIN); powerThrAttnIntegrator = constrainf(powerThrAttnIntegrator + overPower * powerLimitsConfig()->piI * callTimeDelta / voltage * 2e-5f, 0, PWM_RANGE_MAX - PWM_RANGE_MIN);
} }
float powerThrAttnProportional = MAX(0, overPower) * powerLimitsConfig()->piP / voltage * 1e-1; float powerThrAttnProportional = MAX(0, overPower) * powerLimitsConfig()->piP / voltage * 1e-1f;
uint16_t powerThrAttn = lrintf(pt1FilterApply3(&powerThrAttnFilter, powerThrAttnProportional + powerThrAttnIntegrator, callTimeDelta * 1e-6)); uint16_t powerThrAttn = lrintf(pt1FilterApply3(&powerThrAttnFilter, powerThrAttnProportional + powerThrAttnIntegrator, callTimeDelta * 1e-6f));
throttleBase = wasLimitingPower ? lrintf(pt1FilterApply3(&powerThrLimitingBaseFilter, *throttleCommand, callTimeDelta * 1e-6)) : *throttleCommand; throttleBase = wasLimitingPower ? lrintf(pt1FilterApply3(&powerThrLimitingBaseFilter, *throttleCommand, callTimeDelta * 1e-6)) : *throttleCommand;
uint16_t powerThrAttned = MAX(PWM_RANGE_MIN, (int16_t)throttleBase - powerThrAttn); uint16_t powerThrAttned = MAX(PWM_RANGE_MIN, (int16_t)throttleBase - powerThrAttn);
@ -244,11 +244,11 @@ bool powerLimiterIsLimitingPower(void) {
// returns seconds // returns seconds
float powerLimiterGetRemainingBurstTime(void) { float powerLimiterGetRemainingBurstTime(void) {
uint16_t currentBurstOverContinuous = currentBatteryProfile->powerLimits.burstCurrent - currentBatteryProfile->powerLimits.continuousCurrent; uint16_t currentBurstOverContinuous = currentBatteryProfile->powerLimits.burstCurrent - currentBatteryProfile->powerLimits.continuousCurrent;
float remainingCurrentBurstTime = burstCurrentReserve / currentBurstOverContinuous / 1e7; float remainingCurrentBurstTime = burstCurrentReserve / currentBurstOverContinuous / 1e7f;
#ifdef USE_ADC #ifdef USE_ADC
uint16_t powerBurstOverContinuous = currentBatteryProfile->powerLimits.burstPower - currentBatteryProfile->powerLimits.continuousPower; uint16_t powerBurstOverContinuous = currentBatteryProfile->powerLimits.burstPower - currentBatteryProfile->powerLimits.continuousPower;
float remainingPowerBurstTime = burstPowerReserve / powerBurstOverContinuous / 1e7; float remainingPowerBurstTime = burstPowerReserve / powerBurstOverContinuous / 1e7f;
if (!currentBatteryProfile->powerLimits.continuousCurrent) { if (!currentBatteryProfile->powerLimits.continuousCurrent) {
return remainingPowerBurstTime; return remainingPowerBurstTime;

View file

@ -150,7 +150,7 @@ static float calculateRemainingEnergyBeforeRTH(bool takeWindIntoAccount) {
float RTH_heading; // degrees float RTH_heading; // degrees
#ifdef USE_WIND_ESTIMATOR #ifdef USE_WIND_ESTIMATOR
uint16_t windHeading; // centidegrees uint16_t windHeading = 0; // centidegrees
const float horizontalWindSpeed = takeWindIntoAccount ? getEstimatedHorizontalWindSpeed(&windHeading) / 100 : 0; // m/s const float horizontalWindSpeed = takeWindIntoAccount ? getEstimatedHorizontalWindSpeed(&windHeading) / 100 : 0; // m/s
const float windHeadingDegrees = CENTIDEGREES_TO_DEGREES((float)windHeading); const float windHeadingDegrees = CENTIDEGREES_TO_DEGREES((float)windHeading);
const float verticalWindSpeed = -getEstimatedWindSpeed(Z) / 100; //from NED to NEU const float verticalWindSpeed = -getEstimatedWindSpeed(Z) / 100; //from NED to NEU

View file

@ -54,7 +54,7 @@ float applySmithPredictor(uint8_t axis, smithPredictor_t *predictor, float sampl
} }
void smithPredictorInit(smithPredictor_t *predictor, float delay, float strength, uint16_t filterLpfHz, uint32_t looptime) { void smithPredictorInit(smithPredictor_t *predictor, float delay, float strength, uint16_t filterLpfHz, uint32_t looptime) {
if (delay > 0.1) { if (delay > 0.1f) {
predictor->enabled = true; predictor->enabled = true;
predictor->samples = (delay * 1000) / looptime; predictor->samples = (delay * 1000) / looptime;
predictor->idx = 0; predictor->idx = 0;

View file

@ -400,7 +400,7 @@ static void showStatusPage(void)
#ifdef USE_MAG #ifdef USE_MAG
if (sensors(SENSOR_MAG)) { if (sensors(SENSOR_MAG)) {
tfp_sprintf(lineBuffer, "HDG: %d", DECIDEGREES_TO_DEGREES(attitude.values.yaw)); tfp_sprintf(lineBuffer, "HDG: %d", (int)DECIDEGREES_TO_DEGREES(attitude.values.yaw));
padHalfLineBuffer(); padHalfLineBuffer();
i2c_OLED_set_line(rowIndex); i2c_OLED_set_line(rowIndex);
i2c_OLED_send_string(lineBuffer); i2c_OLED_send_string(lineBuffer);

View file

@ -365,7 +365,7 @@ static void frskyOSDUpdateReceiveBuffer(void)
// Full uvarint decoded. Check against buffer size. // Full uvarint decoded. Check against buffer size.
if (state.recvBuffer.expected > sizeof(state.recvBuffer.data)) { if (state.recvBuffer.expected > sizeof(state.recvBuffer.data)) {
FRSKY_OSD_ERROR("Can't handle payload of size %u with a buffer of size %u", FRSKY_OSD_ERROR("Can't handle payload of size %u with a buffer of size %u",
state.recvBuffer.expected, sizeof(state.recvBuffer.data)); state.recvBuffer.expected, (unsigned int)sizeof(state.recvBuffer.data));
frskyOSDResetReceiveBuffer(); frskyOSDResetReceiveBuffer();
break; break;
} }

View file

@ -207,11 +207,11 @@ static bool osdDisplayHasCanvas;
PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 8); PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 8);
PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1);
void osdStartedSaveProcess() { void osdStartedSaveProcess(void) {
savingSettings = true; savingSettings = true;
} }
void osdShowEEPROMSavedNotification() { void osdShowEEPROMSavedNotification(void) {
savingSettings = false; savingSettings = false;
notify_settings_saved = millis() + 5000; notify_settings_saved = millis() + 5000;
} }
@ -329,7 +329,7 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals)
buff[sym_index + 1] = '\0'; buff[sym_index + 1] = '\0';
break; break;
case OSD_UNIT_GA: case OSD_UNIT_GA:
if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_NAUTICALMILE, decimals, 3, digits)) { if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), (uint32_t)FEET_PER_NAUTICALMILE, decimals, 3, digits)) {
buff[sym_index] = symbol_nm; buff[sym_index] = symbol_nm;
} else { } else {
buff[sym_index] = symbol_ft; buff[sym_index] = symbol_ft;
@ -1092,7 +1092,7 @@ void osdCrosshairPosition(uint8_t *x, uint8_t *y)
* Check if this OSD layout is using scaled or unscaled throttle. * Check if this OSD layout is using scaled or unscaled throttle.
* If both are used, it will default to scaled. * If both are used, it will default to scaled.
*/ */
bool osdUsingScaledThrottle() bool osdUsingScaledThrottle(void)
{ {
bool usingScaledThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_SCALED_THROTTLE_POS]); bool usingScaledThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_SCALED_THROTTLE_POS]);
bool usingRCThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_THROTTLE_POS]); bool usingRCThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_THROTTLE_POS]);
@ -1209,7 +1209,7 @@ uint16_t osdGetRemainingGlideTime(void) {
value = 0; value = 0;
} }
return (uint16_t)round(value); return (uint16_t)roundf(value);
} }
static bool osdIsHeadingValid(void) static bool osdIsHeadingValid(void)
@ -1434,7 +1434,7 @@ static void osdDisplayTelemetry(void)
trk_bearing %= 360; trk_bearing %= 360;
int32_t alt = CENTIMETERS_TO_METERS(osdGetAltitude()); int32_t alt = CENTIMETERS_TO_METERS(osdGetAltitude());
float at = atan2(alt, GPS_distanceToHome); float at = atan2(alt, GPS_distanceToHome);
trk_elevation = (float)at * 57.2957795; // 57.2957795 = 1 rad trk_elevation = at * 57.2957795f; // 57.2957795 = 1 rad
trk_elevation += 37; // because elevation in telemetry should be from -37 to 90 trk_elevation += 37; // because elevation in telemetry should be from -37 to 90
if (trk_elevation < 0) { if (trk_elevation < 0) {
trk_elevation = 0; trk_elevation = 0;
@ -1751,7 +1751,7 @@ static bool osdDrawSingleElement(uint8_t item)
else if (!batteryWasFullWhenPluggedIn()) else if (!batteryWasFullWhenPluggedIn())
tfp_sprintf(buff, " NF"); tfp_sprintf(buff, " NF");
else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH) else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH)
tfp_sprintf(buff, "%4lu", getBatteryRemainingCapacity()); tfp_sprintf(buff, "%4lu", (unsigned long)getBatteryRemainingCapacity());
else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH
osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3); osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3);
@ -3095,9 +3095,9 @@ static bool osdDrawSingleElement(uint8_t item)
buff, buff,
"[%u]=%8ld [%u]=%8ld", "[%u]=%8ld [%u]=%8ld",
bufferIndex, bufferIndex,
constrain(debug[bufferIndex], -9999999, 99999999), (long)constrain(debug[bufferIndex], -9999999, 99999999),
bufferIndex+1, bufferIndex+1,
constrain(debug[bufferIndex+1], -9999999, 99999999) (long)constrain(debug[bufferIndex+1], -9999999, 99999999)
); );
displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); displayWrite(osdDisplayPort, elemPosX, elemPosY, buff);
} }

View file

@ -279,7 +279,7 @@ static void osdDrawArtificialHorizonShapes(displayCanvas_t *canvas, float pitchA
itoa(absLevel, buf, 10); itoa(absLevel, buf, 10);
int pos = level * pixelsPerDegreeLevel; int pos = level * pixelsPerDegreeLevel;
int charY = 9 - pos * 2; int charY = 9 - pos * 2;
int cx = (absLevel >= 100 ? -1.5f : -1.0) * canvas->gridElementWidth; int cx = (absLevel >= 100 ? -1.5f : -1.0f) * canvas->gridElementWidth;
int px = cx + (pitchOffset + pos) * sx * 2; int px = cx + (pitchOffset + pos) * sx * 2;
int py = -charY - (pitchOffset + pos) * (1 - sy) * 2; int py = -charY - (pitchOffset + pos) * (1 - sy) * 2;
displayCanvasDrawString(canvas, px, py, buf, 0); displayCanvasDrawString(canvas, px, py, buf, 0);

View file

@ -721,7 +721,7 @@ static void osdDJIFormatThrottlePosition(char *buff, bool autoThr )
thr = rcCommand[THROTTLE]; thr = rcCommand[THROTTLE];
} }
tfp_sprintf(buff, "%3ld%s", (constrain(thr, PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN), "%THR"); tfp_sprintf(buff, "%3ld%s", (unsigned long)((constrain(thr, PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN)), "%THR");
} }
/** /**

View file

@ -265,9 +265,9 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu
case OSD_UNIT_GA: case OSD_UNIT_GA:
{ {
if (poiType == 1) { if (poiType == 1) {
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_NAUTICALMILE, 0, 4, 4); osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 4, 4);
} else { } else {
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_NAUTICALMILE, 0, 3, 3); osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 3, 3);
} }
} }
break; break;

View file

@ -1247,7 +1247,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_CLIMB_TO_SAFE_ALT(n
} }
const uint8_t rthClimbMarginPercent = STATE(FIXED_WING_LEGACY) ? FW_RTH_CLIMB_MARGIN_PERCENT : MR_RTH_CLIMB_MARGIN_PERCENT; const uint8_t rthClimbMarginPercent = STATE(FIXED_WING_LEGACY) ? FW_RTH_CLIMB_MARGIN_PERCENT : MR_RTH_CLIMB_MARGIN_PERCENT;
const float rthAltitudeMargin = MAX(FW_RTH_CLIMB_MARGIN_MIN_CM, (rthClimbMarginPercent/100.0) * fabsf(posControl.rthState.rthInitialAltitude - posControl.rthState.homePosition.pos.z)); const float rthAltitudeMargin = MAX(FW_RTH_CLIMB_MARGIN_MIN_CM, (rthClimbMarginPercent/100.0f) * fabsf(posControl.rthState.rthInitialAltitude - posControl.rthState.homePosition.pos.z));
// If we reached desired initial RTH altitude or we don't want to climb first // If we reached desired initial RTH altitude or we don't want to climb first
if (((navGetCurrentActualPositionAndVelocity()->pos.z - posControl.rthState.rthInitialAltitude) > -rthAltitudeMargin) || (navConfig()->general.flags.rth_climb_first == RTH_CLIMB_OFF) || rthAltControlStickOverrideCheck(ROLL) || rthClimbStageActiveAndComplete()) { if (((navGetCurrentActualPositionAndVelocity()->pos.z - posControl.rthState.rthInitialAltitude) > -rthAltitudeMargin) || (navConfig()->general.flags.rth_climb_first == RTH_CLIMB_OFF) || rthAltControlStickOverrideCheck(ROLL) || rthClimbStageActiveAndComplete()) {
@ -1878,7 +1878,7 @@ static navigationFSMState_t navSetNewFSMState(navigationFSMState_t newState)
static void navProcessFSMEvents(navigationFSMEvent_t injectedEvent) static void navProcessFSMEvents(navigationFSMEvent_t injectedEvent)
{ {
const timeMs_t currentMillis = millis(); const timeMs_t currentMillis = millis();
navigationFSMState_t previousState; navigationFSMState_t previousState = NAV_STATE_UNDEFINED;
static timeMs_t lastStateProcessTime = 0; static timeMs_t lastStateProcessTime = 0;
/* Process new injected event if event defined, /* Process new injected event if event defined,
@ -2627,7 +2627,7 @@ static bool rthAltControlStickOverrideCheck(unsigned axis)
* transiton in to turn. * transiton in to turn.
* Limited to fixed wing only. * Limited to fixed wing only.
* --------------------------------------------------- */ * --------------------------------------------------- */
bool rthClimbStageActiveAndComplete() { bool rthClimbStageActiveAndComplete(void) {
if ((STATE(FIXED_WING_LEGACY) || STATE(AIRPLANE)) && (navConfig()->general.rth_climb_first_stage_altitude > 0)) { if ((STATE(FIXED_WING_LEGACY) || STATE(AIRPLANE)) && (navConfig()->general.rth_climb_first_stage_altitude > 0)) {
if (posControl.actualState.abs.pos.z >= posControl.rthState.rthClimbStageAltitude) { if (posControl.actualState.abs.pos.z >= posControl.rthState.rthClimbStageAltitude) {
return true; return true;
@ -3221,7 +3221,7 @@ void loadSelectedMultiMission(uint8_t missionIndex)
posControl.geoWaypointCount = 0; posControl.geoWaypointCount = 0;
for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) { for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) {
if ((missionCount == missionIndex)) { if (missionCount == missionIndex) {
/* store details of selected mission: start wp index, mission wp count, geo wp count */ /* store details of selected mission: start wp index, mission wp count, geo wp count */
if (!(posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || if (!(posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI ||
posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD ||
@ -4389,7 +4389,7 @@ int32_t navigationGetHomeHeading(void)
} }
// returns m/s // returns m/s
float calculateAverageSpeed() { float calculateAverageSpeed(void) {
float flightTime = getFlightTime(); float flightTime = getFlightTime();
if (flightTime == 0.0f) return 0; if (flightTime == 0.0f) return 0;
return (float)getTotalTravelDistance() / (flightTime * 100); return (float)getTotalTravelDistance() / (flightTime * 100);

View file

@ -670,7 +670,7 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat
#endif #endif
} }
bool isFixedWingAutoThrottleManuallyIncreased() bool isFixedWingAutoThrottleManuallyIncreased(void)
{ {
return isAutoThrottleManuallyIncreased; return isAutoThrottleManuallyIncreased;
} }

View file

@ -69,8 +69,6 @@ typedef struct sbusFrameData_s {
// Receive ISR callback // Receive ISR callback
static void sbusDataReceive(uint16_t c, void *data) static void sbusDataReceive(uint16_t c, void *data)
{ {
static uint16_t sbusDesyncCounter = 0;
sbusFrameData_t *sbusFrameData = data; sbusFrameData_t *sbusFrameData = data;
const timeUs_t currentTimeUs = micros(); const timeUs_t currentTimeUs = micros();
const timeDelta_t timeSinceLastByteUs = cmpTimeUs(currentTimeUs, sbusFrameData->lastActivityTimeUs); const timeDelta_t timeSinceLastByteUs = cmpTimeUs(currentTimeUs, sbusFrameData->lastActivityTimeUs);
@ -110,7 +108,6 @@ static void sbusDataReceive(uint16_t c, void *data)
default: // Failed end marker default: // Failed end marker
sbusFrameData->state = STATE_SBUS_WAIT_SYNC; sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
sbusDesyncCounter++;
break; break;
} }

View file

@ -157,7 +157,7 @@ bool srxl2ProcessHandshake(const Srxl2Header* header)
/* priority */ 10, /* priority */ 10,
/* baudSupported*/ baudRate, /* baudSupported*/ baudRate,
/* info */ 0, /* info */ 0,
// U_ID_2 0 // U_ID_2
} }
}; };

View file

@ -716,11 +716,11 @@ uint16_t getPowerSupplyImpedance(void) {
} }
// returns cW (0.01W) // returns cW (0.01W)
int32_t calculateAveragePower() { int32_t calculateAveragePower(void) {
return (int64_t)mWhDrawn * 360 / getFlightTime(); return (int64_t)mWhDrawn * 360 / getFlightTime();
} }
// returns mWh / meter // returns mWh / meter
int32_t calculateAverageEfficiency() { int32_t calculateAverageEfficiency(void) {
return getFlyingEnergy() * 100 / getTotalTravelDistance(); return getFlyingEnergy() * 100 / getTotalTravelDistance();
} }

View file

@ -442,7 +442,7 @@ static bool FAST_CODE NOINLINE gyroUpdateAndCalibrate(gyroDev_t * gyroDev, zeroC
} }
} }
void FAST_CODE NOINLINE gyroFilter() void FAST_CODE NOINLINE gyroFilter(void)
{ {
if (!gyro.initialized) { if (!gyro.initialized) {
return; return;
@ -504,7 +504,7 @@ void FAST_CODE NOINLINE gyroFilter()
} }
void FAST_CODE NOINLINE gyroUpdate() void FAST_CODE NOINLINE gyroUpdate(void)
{ {
#ifdef USE_SIMULATOR #ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { if (ARMING_FLAG(SIMULATOR_MODE_HITL)) {

View file

@ -204,7 +204,7 @@ void opflowUpdate(timeUs_t currentTimeUs)
// If quality of the flow from the sensor is good - process further // If quality of the flow from the sensor is good - process further
if (opflow.flowQuality == OPFLOW_QUALITY_VALID) { if (opflow.flowQuality == OPFLOW_QUALITY_VALID) {
const float integralToRateScaler = (opticalFlowConfig()->opflow_scale > 0.01f) ? (1.0e6 / opflow.dev.rawData.deltaTime) / (float)opticalFlowConfig()->opflow_scale : 0.0f; const float integralToRateScaler = (opticalFlowConfig()->opflow_scale > 0.01f) ? (1.0e6f / opflow.dev.rawData.deltaTime) / (float)opticalFlowConfig()->opflow_scale : 0.0f;
// Apply sensor alignment // Apply sensor alignment
applySensorAlignment(opflow.dev.rawData.flowRateRaw, opflow.dev.rawData.flowRateRaw, opticalFlowConfig()->opflow_align); applySensorAlignment(opflow.dev.rawData.flowRateRaw, opflow.dev.rawData.flowRateRaw, opticalFlowConfig()->opflow_align);

View file

@ -163,7 +163,7 @@ void tempSensorAddressToString(uint64_t address, char *hex_address)
tfp_sprintf(hex_address, "%d", (int)address); tfp_sprintf(hex_address, "%d", (int)address);
else { else {
uint32_t *address32 = (uint32_t *)&address; uint32_t *address32 = (uint32_t *)&address;
tfp_sprintf(hex_address, "%08lx%08lx", address32[1], address32[0]); tfp_sprintf(hex_address, "%08lx%08lx", (unsigned long)address32[1], (unsigned long)address32[0]);
} }
} }

View file

@ -80,46 +80,46 @@ static bool useImu = false;
typedef struct typedef struct
{ {
double m_channelValues[RF_MAX_PWM_OUTS]; float m_channelValues[RF_MAX_PWM_OUTS];
double m_currentPhysicsSpeedMultiplier; float m_currentPhysicsSpeedMultiplier;
double m_currentPhysicsTime_SEC; float m_currentPhysicsTime_SEC;
double m_airspeed_MPS; float m_airspeed_MPS;
double m_altitudeASL_MTR; float m_altitudeASL_MTR;
double m_altitudeAGL_MTR; float m_altitudeAGL_MTR;
double m_groundspeed_MPS; float m_groundspeed_MPS;
double m_pitchRate_DEGpSEC; float m_pitchRate_DEGpSEC;
double m_rollRate_DEGpSEC; float m_rollRate_DEGpSEC;
double m_yawRate_DEGpSEC; float m_yawRate_DEGpSEC;
double m_azimuth_DEG; float m_azimuth_DEG;
double m_inclination_DEG; float m_inclination_DEG;
double m_roll_DEG; float m_roll_DEG;
double m_orientationQuaternion_X; float m_orientationQuaternion_X;
double m_orientationQuaternion_Y; float m_orientationQuaternion_Y;
double m_orientationQuaternion_Z; float m_orientationQuaternion_Z;
double m_orientationQuaternion_W; float m_orientationQuaternion_W;
double m_aircraftPositionX_MTR; float m_aircraftPositionX_MTR;
double m_aircraftPositionY_MTR; float m_aircraftPositionY_MTR;
double m_velocityWorldU_MPS; float m_velocityWorldU_MPS;
double m_velocityWorldV_MPS; float m_velocityWorldV_MPS;
double m_velocityWorldW_MPS; float m_velocityWorldW_MPS;
double m_velocityBodyU_MPS; float m_velocityBodyU_MPS;
double m_velocityBodyV_MPS; float m_velocityBodyV_MPS;
double m_velocityBodyW_MPS; float m_velocityBodyW_MPS;
double m_accelerationWorldAX_MPS2; float m_accelerationWorldAX_MPS2;
double m_accelerationWorldAY_MPS2; float m_accelerationWorldAY_MPS2;
double m_accelerationWorldAZ_MPS2; float m_accelerationWorldAZ_MPS2;
double m_accelerationBodyAX_MPS2; float m_accelerationBodyAX_MPS2;
double m_accelerationBodyAY_MPS2; float m_accelerationBodyAY_MPS2;
double m_accelerationBodyAZ_MPS2; float m_accelerationBodyAZ_MPS2;
double m_windX_MPS; float m_windX_MPS;
double m_windY_MPS; float m_windY_MPS;
double m_windZ_MPSPS; float m_windZ_MPSPS;
double m_propRPM; float m_propRPM;
double m_heliMainRotorRPM; float m_heliMainRotorRPM;
double m_batteryVoltage_VOLTS; float m_batteryVoltage_VOLTS;
double m_batteryCurrentDraw_AMPS; float m_batteryCurrentDraw_AMPS;
double m_batteryRemainingCapacity_MAH; float m_batteryRemainingCapacity_MAH;
double m_fuelRemaining_OZ; float m_fuelRemaining_OZ;
bool m_isLocked; bool m_isLocked;
bool m_hasLostComponents; bool m_hasLostComponents;
bool m_anEngineIsRunning; bool m_anEngineIsRunning;
@ -244,34 +244,38 @@ static bool getChannelValues(const char* response, uint16_t* channelValues)
} }
static void fakeCoords(double posX, double posY, double distanceX, double distanceY, double *lat, double *lon) static void fakeCoords(float posX, float posY, float distanceX, float distanceY, float *lat, float *lon)
{ {
double m = 1 / (2 * (double)M_PIf / 360 * EARTH_RADIUS) / 1000; float m = 1 / (2 * M_PIf / 360 * EARTH_RADIUS) / 1000;
*lat = (double)(posX + (distanceX * m)); *lat = (posX + (distanceX * m));
*lon = (double)(posY + (distanceY * m) / cos(posX * ((double)M_PIf / 180))); *lon = (posY + (distanceY * m) / cosf(posX * (M_PIf / 180)));
} }
static double convertAzimuth(double azimuth) static float convertAzimuth(float azimuth)
{ {
if (azimuth < 0) { if (azimuth < 0) {
azimuth += 360; azimuth += 360;
} }
return 360 - fmod(azimuth + 90, 360.0f); return 360 - fmodf(azimuth + 90, 360.0f);
} }
static void exchangeData(void) static void exchangeData(void)
{ {
double servoValues[RF_MAX_PWM_OUTS] = { 0 }; double servoValues[RF_MAX_PWM_OUTS] = { };
for (int i = 0; i < mappingCount; i++) { for (int i = 0; i < mappingCount; i++) {
if (pwmMapping[i] & 0x80){ // Motor if (pwmMapping[i] & 0x80) { // Motor
servoValues[i] = PWM_TO_FLOAT_0_1(motor[pwmMapping[i] & 0x7f]); servoValues[i] = (double)PWM_TO_FLOAT_0_1(motor[pwmMapping[i] & 0x7f]);
} else { } else {
servoValues[i] = PWM_TO_FLOAT_0_1(servo[pwmMapping[i]]); servoValues[i] = (double)PWM_TO_FLOAT_0_1(servo[pwmMapping[i]]);
} }
} }
startRequest("ExchangeData", "<ExchangeData><pControlInputs><m-selectedChannels>%u</m-selectedChannels><m-channelValues-0to1><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item></m-channelValues-0to1></pControlInputs></ExchangeData>", startRequest("ExchangeData", "<ExchangeData><pControlInputs><m-selectedChannels>%u</m-selectedChannels>"
0xFFF, servoValues[0], servoValues[1], servoValues[2], servoValues[3], servoValues[4], servoValues[5], servoValues[6], servoValues[7], servoValues[8], servoValues[9], servoValues[10], servoValues[11]); "<m-channelValues-0to1><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item>"
"<item>%.4f</item><item>%.4f</item><item>%.4f</item><item>%.4f</item></m-channelValues-0to1></pControlInputs></ExchangeData>",
0xFFF,
servoValues[0], servoValues[1], servoValues[2], servoValues[3], servoValues[4], servoValues[5], servoValues[6], servoValues[7],
servoValues[8], servoValues[9], servoValues[10], servoValues[11]);
char* response = endRequest(); char* response = endRequest();
//rfValues.m_currentPhysicsTime_SEC = getDoubleFromResponse(response, "m-currentPhysicsTime-SEC"); //rfValues.m_currentPhysicsTime_SEC = getDoubleFromResponse(response, "m-currentPhysicsTime-SEC");
@ -325,18 +329,18 @@ static void exchangeData(void)
getChannelValues(response, channelValues); getChannelValues(response, channelValues);
rxSimSetChannelValue(channelValues, RF_MAX_CHANNEL_COUNT); rxSimSetChannelValue(channelValues, RF_MAX_CHANNEL_COUNT);
double lat, lon; float lat, lon;
fakeCoords(FAKE_LAT, FAKE_LON, rfValues.m_aircraftPositionX_MTR, -rfValues.m_aircraftPositionY_MTR, &lat, &lon); fakeCoords(FAKE_LAT, FAKE_LON, rfValues.m_aircraftPositionX_MTR, -rfValues.m_aircraftPositionY_MTR, &lat, &lon);
int16_t course = (int16_t)round(convertAzimuth(rfValues.m_azimuth_DEG) * 10); int16_t course = (int16_t)roundf(convertAzimuth(rfValues.m_azimuth_DEG) * 10);
int32_t altitude = (int32_t)round(rfValues.m_altitudeASL_MTR * 100); int32_t altitude = (int32_t)roundf(rfValues.m_altitudeASL_MTR * 100);
gpsFakeSet( gpsFakeSet(
GPS_FIX_3D, GPS_FIX_3D,
16, 16,
(int32_t)round(lat * 10000000), (int32_t)roundf(lat * 10000000),
(int32_t)round(lon * 10000000), (int32_t)roundf(lon * 10000000),
altitude, altitude,
(int16_t)round(rfValues.m_groundspeed_MPS * 100), (int16_t)roundf(rfValues.m_groundspeed_MPS * 100),
course, course,
0, 0,
0, 0,
@ -344,15 +348,15 @@ static void exchangeData(void)
0 0
); );
int32_t altitudeOverGround = (int32_t)round(rfValues.m_altitudeAGL_MTR * 100); int32_t altitudeOverGround = (int32_t)roundf(rfValues.m_altitudeAGL_MTR * 100);
if (altitudeOverGround > 0 && altitudeOverGround <= RANGEFINDER_VIRTUAL_MAX_RANGE_CM) { if (altitudeOverGround > 0 && altitudeOverGround <= RANGEFINDER_VIRTUAL_MAX_RANGE_CM) {
fakeRangefindersSetData(altitudeOverGround); fakeRangefindersSetData(altitudeOverGround);
} else { } else {
fakeRangefindersSetData(-1); fakeRangefindersSetData(-1);
} }
const int16_t roll_inav = (int16_t)round(rfValues.m_roll_DEG * 10); const int16_t roll_inav = (int16_t)roundf(rfValues.m_roll_DEG * 10);
const int16_t pitch_inav = (int16_t)round(-rfValues.m_inclination_DEG * 10); const int16_t pitch_inav = (int16_t)roundf(-rfValues.m_inclination_DEG * 10);
const int16_t yaw_inav = course; const int16_t yaw_inav = course;
if (!useImu) { if (!useImu) {
imuSetAttitudeRPY(roll_inav, pitch_inav, yaw_inav); imuSetAttitudeRPY(roll_inav, pitch_inav, yaw_inav);
@ -376,16 +380,16 @@ static void exchangeData(void)
fakeAccSet(accX, accY, accZ); fakeAccSet(accX, accY, accZ);
fakeGyroSet( fakeGyroSet(
constrainToInt16(rfValues.m_rollRate_DEGpSEC * (double)16.0), constrainToInt16(rfValues.m_rollRate_DEGpSEC * 16.0f),
constrainToInt16(-rfValues.m_pitchRate_DEGpSEC * (double)16.0), constrainToInt16(-rfValues.m_pitchRate_DEGpSEC * 16.0f),
constrainToInt16(rfValues.m_yawRate_DEGpSEC * (double)16.0) constrainToInt16(rfValues.m_yawRate_DEGpSEC * 16.0f)
); );
fakeBaroSet(altitudeToPressure(altitude), DEGREES_TO_CENTIDEGREES(21)); fakeBaroSet(altitudeToPressure(altitude), DEGREES_TO_CENTIDEGREES(21));
fakePitotSetAirspeed(rfValues.m_airspeed_MPS * 100); fakePitotSetAirspeed(rfValues.m_airspeed_MPS * 100);
fakeBattSensorSetVbat((uint16_t)round(rfValues.m_batteryVoltage_VOLTS * 100)); fakeBattSensorSetVbat((uint16_t)roundf(rfValues.m_batteryVoltage_VOLTS * 100));
fakeBattSensorSetAmperage((uint16_t)round(rfValues.m_batteryCurrentDraw_AMPS * 100)); fakeBattSensorSetAmperage((uint16_t)roundf(rfValues.m_batteryCurrentDraw_AMPS * 100));
fpQuaternion_t quat; fpQuaternion_t quat;
fpVector3_t north; fpVector3_t north;

View file

@ -30,7 +30,7 @@
#include "target/SITL/sim/simHelper.h" #include "target/SITL/sim/simHelper.h"
inline int16_t constrainToInt16(double value) inline int16_t constrainToInt16(float value)
{ {
return (int16_t)round(constrain(value, INT16_MIN, INT16_MAX)); return (int16_t)round(constrain(value, INT16_MIN, INT16_MAX));
} }

View file

@ -26,12 +26,12 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/quaternion.h" #include "common/quaternion.h"
#define EARTH_RADIUS ((double)6378.137) #define EARTH_RADIUS (6378.137f)
#define PWM_TO_FLOAT_0_1(x) (((int)x - 1000) / 1000.0f) #define PWM_TO_FLOAT_0_1(x) ((float)(((int)x - 1000) / 1000.0f))
#define PWM_TO_FLOAT_MINUS_1_1(x) (((int)x - 1500) / 500.0f) #define PWM_TO_FLOAT_MINUS_1_1(x) ((float)(((int)x - 1500) / 500.0f))
#define FLOAT_0_1_TO_PWM(x) ((uint16_t)(x * 1000.0f) + 1000.0f) #define FLOAT_0_1_TO_PWM(x) ((uint16_t)(x * 1000.0f) + 1000.0f)
#define FLOAT_MINUS_1_1_TO_PWM(x) ((uint16_t)((x + 1.0f) / 2.0f * 1000.0f) + 1000.0f) #define FLOAT_MINUS_1_1_TO_PWM(x) ((float)((uint16_t)((x + 1.0f) / 2.0f * 1000.0f) + 1000.0f))
int16_t constrainToInt16(double value); int16_t constrainToInt16(float value);
void transformVectorEarthToBody(fpVector3_t *v, const fpQuaternion_t *quat); void transformVectorEarthToBody(fpVector3_t *v, const fpQuaternion_t *quat);
void computeQuaternionFromRPY(fpQuaternion_t *quat, int16_t initialRoll, int16_t initialPitch, int16_t initialYaw); void computeQuaternionFromRPY(fpQuaternion_t *quat, int16_t initialRoll, int16_t initialPitch, int16_t initialYaw);

View file

@ -369,18 +369,18 @@ static void* listenWorker(void* arg)
gpsFakeSet( gpsFakeSet(
GPS_FIX_3D, GPS_FIX_3D,
16, 16,
(int32_t)round(lattitude * 10000000), (int32_t)roundf(lattitude * 10000000),
(int32_t)round(longitude * 10000000), (int32_t)roundf(longitude * 10000000),
(int32_t)round(elevation * 100), (int32_t)roundf(elevation * 100),
(int16_t)round(groundspeed * 100), (int16_t)roundf(groundspeed * 100),
(int16_t)round(hpath * 10), (int16_t)roundf(hpath * 10),
0, //(int16_t)round(-local_vz * 100), 0, //(int16_t)roundf(-local_vz * 100),
0, //(int16_t)round(local_vx * 100), 0, //(int16_t)roundf(local_vx * 100),
0, //(int16_t)round(-local_vy * 100), 0, //(int16_t)roundf(-local_vy * 100),
0 0
); );
const int32_t altitideOverGround = (int32_t)round(agl * 100); const int32_t altitideOverGround = (int32_t)roundf(agl * 100);
if (altitideOverGround > 0 && altitideOverGround <= RANGEFINDER_VIRTUAL_MAX_RANGE_CM) { if (altitideOverGround > 0 && altitideOverGround <= RANGEFINDER_VIRTUAL_MAX_RANGE_CM) {
fakeRangefindersSetData(altitideOverGround); fakeRangefindersSetData(altitideOverGround);
} else { } else {
@ -397,9 +397,9 @@ static void* listenWorker(void* arg)
} }
fakeAccSet( fakeAccSet(
constrainToInt16(-accel_x * GRAVITY_MSS * 1000), constrainToInt16(-accel_x * GRAVITY_MSS * 1000.0f),
constrainToInt16(accel_y * GRAVITY_MSS * 1000), constrainToInt16(accel_y * GRAVITY_MSS * 1000.0f),
constrainToInt16(accel_z * GRAVITY_MSS * 1000) constrainToInt16(accel_z * GRAVITY_MSS * 1000.0f)
); );
fakeGyroSet( fakeGyroSet(
@ -408,16 +408,16 @@ static void* listenWorker(void* arg)
constrainToInt16(-gyro_z * 16.0f) constrainToInt16(-gyro_z * 16.0f)
); );
fakeBaroSet((int32_t)round(barometer * 3386.39f), DEGREES_TO_CENTIDEGREES(21)); fakeBaroSet((int32_t)roundf(barometer * 3386.39f), DEGREES_TO_CENTIDEGREES(21));
fakePitotSetAirspeed(airspeed * 100.0f); fakePitotSetAirspeed(airspeed * 100.0f);
fakeBattSensorSetVbat(16.8 * 100); fakeBattSensorSetVbat(16.8f * 100);
fpQuaternion_t quat; fpQuaternion_t quat;
fpVector3_t north; fpVector3_t north;
north.x = 1.0f; north.x = 1.0f;
north.y = 0; north.y = 0.0f;
north.z = 0; north.z = 0.0f;
computeQuaternionFromRPY(&quat, roll_inav, pitch_inav, yaw_inav); computeQuaternionFromRPY(&quat, roll_inav, pitch_inav, yaw_inav);
transformVectorEarthToBody(&north, &quat); transformVectorEarthToBody(&north, &quat);
fakeMagSet( fakeMagSet(

View file

@ -375,8 +375,8 @@ static void sendSMS(void)
amps / 10, amps % 10, amps / 10, amps % 10,
getAltitudeMeters(), getAltitudeMeters(),
groundSpeed, avgSpeed / 10, avgSpeed % 10, groundSpeed, avgSpeed / 10, avgSpeed % 10,
GPS_distanceToHome, getTotalTravelDistance() / 100, (unsigned long)GPS_distanceToHome, getTotalTravelDistance() / 100ul,
DECIDEGREES_TO_DEGREES(attitude.values.yaw), (int)DECIDEGREES_TO_DEGREES(attitude.values.yaw),
gpsSol.numSat, gpsFixIndicators[gpsSol.fixType], gpsSol.numSat, gpsFixIndicators[gpsSol.fixType],
simRssi, simRssi,
getStateOfForcedRTH() == RTH_IDLE ? modeDescriptions[getFlightModeForTelemetry()] : "RTH", getStateOfForcedRTH() == RTH_IDLE ? modeDescriptions[getFlightModeForTelemetry()] : "RTH",
@ -388,7 +388,7 @@ static void sendSMS(void)
atCommandStatus = SIM_AT_WAITING_FOR_RESPONSE; atCommandStatus = SIM_AT_WAITING_FOR_RESPONSE;
} }
void handleSimTelemetry() void handleSimTelemetry(void)
{ {
static uint16_t simResponseIndex = 0; static uint16_t simResponseIndex = 0;
uint32_t now = millis(); uint32_t now = millis();

View file

@ -17,8 +17,8 @@
#pragma once #pragma once
#define SIM_MIN_TRANSMIT_INTERVAL 10 #define SIM_MIN_TRANSMIT_INTERVAL 10u
#define SIM_DEFAULT_TRANSMIT_INTERVAL 60 #define SIM_DEFAULT_TRANSMIT_INTERVAL 60u
#define SIM_N_TX_FLAGS 5 #define SIM_N_TX_FLAGS 5
#define SIM_DEFAULT_TX_FLAGS "f" #define SIM_DEFAULT_TX_FLAGS "f"
#define SIM_PIN "0000" #define SIM_PIN "0000"

View file

@ -627,7 +627,7 @@ class Generator
enc = @value_encoder.encode_values(min, max) enc = @value_encoder.encode_values(min, max)
buf << ", .config.minmax.indexes = #{enc}" buf << ", .config.minmax.indexes = #{enc}"
end end
buf << ", offsetof(#{group["type"]}, #{member["field"]}) },\n" buf << ", (setting_offset_t)offsetof(#{group["type"]}, #{member["field"]}) },\n"
end end
buf << "};\n" buf << "};\n"
@ -1002,7 +1002,7 @@ class Generator
typ = "uint32_t" typ = "uint32_t"
when "float" when "float"
typ = "float" typ = "float"
when /^char \[(\d+)\]/ when /^char\s*\[(\d+)\]/
# Substract 1 to show the maximum string size without the null terminator # Substract 1 to show the maximum string size without the null terminator
member["max"] = $1.to_i - 1; member["max"] = $1.to_i - 1;
typ = "string" typ = "string"