Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

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

Merged
merged 19 commits into from
May 25, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
49 changes: 43 additions & 6 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@ jobs:
- 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
- name: Upload artifacts
uses: actions/upload-artifact@v2-preview
uses: actions/upload-artifact@v3
with:
name: ${{ env.BUILD_NAME }}.zip
name: ${{ env.BUILD_NAME }}
path: ./build/*.hex

build-SITL-Linux:
Expand Down Expand Up @@ -68,9 +68,46 @@ jobs:
- 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@v2-preview
uses: actions/upload-artifact@v3
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

build-SITL-Windows:
Expand Down Expand Up @@ -103,9 +140,9 @@ jobs:
- 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@v2-preview
uses: actions/upload-artifact@v3
with:
name: ${{ env.BUILD_NAME }}_SITL-WIN.zip
name: ${{ env.BUILD_NAME }}_SITL-WIN
path: ./build_SITL/*.exe


Expand Down
4 changes: 4 additions & 0 deletions cmake/sitl.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,10 @@ if(NOT MACOSX)
-Wno-error=maybe-uninitialized
-fsingle-precision-constant
)
else()
set(SITL_COMPILE_OPTIONS ${SITL_COMPILE_OPTIONS}
-Wno-missing-braces
)
endif()

set(SITL_DEFINITIONS
Expand Down
3 changes: 0 additions & 3 deletions lib/main/MAVLink/mavlink_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -574,8 +574,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
mavlink_message_t* r_message,
mavlink_status_t* r_mavlink_status)
{
int bufferIndex = 0;

status->msg_received = MAVLINK_FRAMING_INCOMPLETE;

switch (status->parse_state)
Expand Down Expand Up @@ -801,7 +799,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
break;
}

bufferIndex++;
// If a message has been sucessfully decoded, check index
if (status->msg_received == MAVLINK_FRAMING_OK)
{
Expand Down
15 changes: 11 additions & 4 deletions src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -1326,12 +1326,19 @@ static void loadSlowState(blackboxSlowState_t *slow)
#endif

bool valid_temp;
valid_temp = getIMUTemperature(&slow->imuTemperature);
if (!valid_temp) slow->imuTemperature = TEMPERATURE_INVALID_VALUE;
int16_t newTemp = 0;
valid_temp = getIMUTemperature(&newTemp);
if (valid_temp)
slow->imuTemperature = newTemp;
else
slow->imuTemperature = TEMPERATURE_INVALID_VALUE;

#ifdef USE_BARO
valid_temp = getBaroTemperature(&slow->baroTemperature);
if (!valid_temp) slow->baroTemperature = TEMPERATURE_INVALID_VALUE;
valid_temp = getBaroTemperature(&newTemp);
if (valid_temp)
slow->baroTemperature = newTemp;
else
slow->baroTemperature = TEMPERATURE_INVALID_VALUE;
#endif

#ifdef USE_TEMPERATURE_SENSOR
Expand Down
2 changes: 1 addition & 1 deletion src/main/cms/cms_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ typedef struct OSD_SETTING_s {
const uint8_t step;
} __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_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)
Expand Down
8 changes: 4 additions & 4 deletions src/main/common/constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@
#pragma once

#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 METERS_PER_KILOMETER 1000
#define METERS_PER_MILE 1609.344
#define METERS_PER_FOOT 3.28084
#define METERS_PER_NAUTICALMILE 1852.001
#define METERS_PER_MILE 1609.344f
#define METERS_PER_FOOT 3.28084f
#define METERS_PER_NAUTICALMILE 1852.001f
2 changes: 1 addition & 1 deletion src/main/common/maths.c
Original file line number Diff line number Diff line change
Expand Up @@ -521,7 +521,7 @@ float bellCurve(const float x, const float 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;
#ifdef USE_ARM_MATH
arm_sqrt_f32(value, &ret);
Expand Down
20 changes: 10 additions & 10 deletions src/main/common/maths.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,13 @@
#define RAD (M_PIf / 180.0f)

#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 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_TO_DEKADEGREES(angle) ((angle) / DEGREES_PER_DEKADEGREE)
Expand All @@ -56,15 +56,15 @@
#define RADIANS_TO_CENTIDEGREES(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_FEET(cm) (cm / 30.48)
#define CENTIMETERS_TO_METERS(cm) (cm / 100)
#define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048f)
#define CENTIMETERS_TO_FEET(cm) (cm / 30.48f)
#define CENTIMETERS_TO_METERS(cm) (cm / 100.0f)

#define METERS_TO_CENTIMETERS(m) (m * 100)

#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363)
#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6)
#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845)
#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363f)
#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f)
#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f)

#define C_TO_KELVIN(temp) (temp + 273.15f)

Expand Down Expand Up @@ -188,6 +188,6 @@ float acos_approx(float x);
void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count);

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_3D(const float firstElement, const float secondElement, const float thirdElement);
2 changes: 1 addition & 1 deletion src/main/common/memory.c
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ void * memAllocate(size_t wantedSize, resourceOwner_e owner)
retPointer = &dynHeap[dynHeapFreeWord];
dynHeapFreeWord += wantedWords;
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 {
// OOM
Expand Down
2 changes: 1 addition & 1 deletion src/main/common/quaternion.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ static inline void quaternionToAxisAngle(fpAxisAngle_t * result, const fpQuatern
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
if (sinVal > 1e-4f) {
Expand Down
5 changes: 2 additions & 3 deletions src/main/common/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
// than inlined version (inlining is cheaper for very small moves < 8 bytes / 2 store instructions)
#ifdef UNIT_TEST
// Call memcpy when building unittest - this is easier that asm symbol name mangling (symbols start with _underscore on win32)
#if defined(UNIT_TEST) || defined(SITL_BUILD)
#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
void *memcpy_fn(void *destination, const void *source, size_t num) asm("memcpy");
#endif
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/rangefinder/rangefinder_vl53l0x.c
Original file line number Diff line number Diff line change
Expand Up @@ -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.
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;
}

Expand Down
4 changes: 2 additions & 2 deletions src/main/fc/fc_core.c
Original file line number Diff line number Diff line change
Expand Up @@ -983,12 +983,12 @@ void taskUpdateRxMain(timeUs_t currentTimeUs)
}

// returns seconds
float getFlightTime()
float getFlightTime(void)
{
return US2S(flightTime);
}

float getArmTime()
float getArmTime(void)
{
return US2S(armTime);
}
Expand Down
4 changes: 2 additions & 2 deletions src/main/fc/runtime_config.c
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void)

#ifdef USE_SIMULATOR
simulatorData_t simulatorData = {
flags: 0,
debugIndex: 0
.flags = 0,
.debugIndex = 0
};
#endif
2 changes: 1 addition & 1 deletion src/main/fc/stats.c
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ static uint32_t arm_distance_cm;
static uint32_t arm_mWhDrawn;
static uint32_t flyingEnergy; // energy drawn during flying up to last disarm (ARMED) mWh

uint32_t getFlyingEnergy() {
uint32_t getFlyingEnergy(void) {
return flyingEnergy;
}
#endif
Expand Down
4 changes: 2 additions & 2 deletions src/main/flight/imu.c
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@ static void imuResetOrientationQuaternion(const fpVector3_t * accBF)

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)) {
return true;
Expand Down Expand Up @@ -480,7 +480,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe
const float thetaMagnitudeSq = vectorNormSquared(&vTheta);

// If calculated rotation is zero - don't update quaternion
if (thetaMagnitudeSq >= 1e-20) {
if (thetaMagnitudeSq >= 1e-20f) {
// Calculate quaternion delta:
// 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.
Expand Down
2 changes: 1 addition & 1 deletion src/main/flight/mixer.c
Original file line number Diff line number Diff line change
Expand Up @@ -461,7 +461,7 @@ static int getReversibleMotorsThrottleDeadband(void)
return feature(FEATURE_MOTOR_STOP) ? reversibleMotorsConfig()->neutral : directionValue;
}

void FAST_CODE mixTable()
void FAST_CODE mixTable(void)
{
#ifdef USE_DSHOT
if (FLIGHT_MODE(TURTLE_MODE)) {
Expand Down
4 changes: 2 additions & 2 deletions src/main/flight/pid.c
Original file line number Diff line number Diff line change
Expand Up @@ -477,7 +477,7 @@ void schedulePidGainsUpdate(void)
pidGainsUpdateRequired = true;
}

void updatePIDCoefficients()
void updatePIDCoefficients(void)
{
STATIC_FASTRAM uint16_t prevThrottle = 0;

Expand Down Expand Up @@ -864,7 +864,7 @@ void resetHeadingHoldTarget(int16_t heading)
pt1FilterReset(&headingHoldRateFilter, 0.0f);
}

int16_t getHeadingHoldTarget() {
int16_t getHeadingHoldTarget(void) {
return headingHoldTarget;
}

Expand Down
18 changes: 9 additions & 9 deletions src/main/flight/power_limits.c
Original file line number Diff line number Diff line change
Expand Up @@ -162,14 +162,14 @@ void powerLimiterApply(int16_t *throttleCommand) {
int32_t overCurrent = current - activeCurrentLimit;

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);

if (activeCurrentLimit && currentThrAttned < *throttleCommand) {
Expand All @@ -191,12 +191,12 @@ void powerLimiterApply(int16_t *throttleCommand) {
int32_t overPower = power - activePowerLimit;

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;
uint16_t powerThrAttned = MAX(PWM_RANGE_MIN, (int16_t)throttleBase - powerThrAttn);
Expand Down Expand Up @@ -244,11 +244,11 @@ bool powerLimiterIsLimitingPower(void) {
// returns seconds
float powerLimiterGetRemainingBurstTime(void) {
uint16_t currentBurstOverContinuous = currentBatteryProfile->powerLimits.burstCurrent - currentBatteryProfile->powerLimits.continuousCurrent;
float remainingCurrentBurstTime = burstCurrentReserve / currentBurstOverContinuous / 1e7;
float remainingCurrentBurstTime = burstCurrentReserve / currentBurstOverContinuous / 1e7f;

#ifdef USE_ADC
uint16_t powerBurstOverContinuous = currentBatteryProfile->powerLimits.burstPower - currentBatteryProfile->powerLimits.continuousPower;
float remainingPowerBurstTime = burstPowerReserve / powerBurstOverContinuous / 1e7;
float remainingPowerBurstTime = burstPowerReserve / powerBurstOverContinuous / 1e7f;

if (!currentBatteryProfile->powerLimits.continuousCurrent) {
return remainingPowerBurstTime;
Expand Down
2 changes: 1 addition & 1 deletion src/main/flight/rth_estimator.c
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ static float calculateRemainingEnergyBeforeRTH(bool takeWindIntoAccount) {

float RTH_heading; // degrees
#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 windHeadingDegrees = CENTIDEGREES_TO_DEGREES((float)windHeading);
const float verticalWindSpeed = -getEstimatedWindSpeed(Z) / 100; //from NED to NEU
Expand Down
2 changes: 1 addition & 1 deletion src/main/flight/smith_predictor.c
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
if (delay > 0.1) {
if (delay > 0.1f) {
predictor->enabled = true;
predictor->samples = (delay * 1000) / looptime;
predictor->idx = 0;
Expand Down
2 changes: 1 addition & 1 deletion src/main/io/dashboard.c
Original file line number Diff line number Diff line change
Expand Up @@ -400,7 +400,7 @@ static void showStatusPage(void)

#ifdef USE_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();
i2c_OLED_set_line(rowIndex);
i2c_OLED_send_string(lineBuffer);
Expand Down
Loading