Skip to content

Commit

Permalink
fixed compiler warnings
Browse files Browse the repository at this point in the history
there were several types of warnings:

 - range of variable. We had several places that were checking an
   unsigned value for < 0, or a uint16_t for > 65535

 - use of "static" and "inline". The C language requires these before
   the return type of the function

 - comparison of unsigned and signed numbers, which can lead to bugs
  • Loading branch information
tridge committed Aug 26, 2024
1 parent bf16823 commit 65e7ba9
Show file tree
Hide file tree
Showing 10 changed files with 18 additions and 44 deletions.
2 changes: 1 addition & 1 deletion Inc/functions.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include "main.h"
#include "targets.h"

int getAbsDif(int number1, int number2);
uint32_t getAbsDif(int number1, int number2);
void delayMicros(uint32_t micros);
void delayMillis(uint32_t millis);
long map(long x, long in_min, long in_max, long out_min, long out_max);
Expand Down
2 changes: 1 addition & 1 deletion Mcu/e230/Src/systick.c
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#include "gd32e23x.h"

volatile static uint32_t delay;
static volatile uint32_t delay;

/*!
\brief configure systick
Expand Down
10 changes: 5 additions & 5 deletions Mcu/f051/Src/peripherals.c
Original file line number Diff line number Diff line change
Expand Up @@ -527,13 +527,13 @@ void setDutyCycleAll(uint16_t newdc)
TIM1->CCR3 = newdc;
}

void inline setPWMCompare1(uint16_t compareone) { TIM1->CCR1 = compareone; }
void inline setPWMCompare2(uint16_t comparetwo) { TIM1->CCR2 = comparetwo; }
void inline setPWMCompare3(uint16_t comparethree) { TIM1->CCR3 = comparethree; }
inline void setPWMCompare1(uint16_t compareone) { TIM1->CCR1 = compareone; }
inline void setPWMCompare2(uint16_t comparetwo) { TIM1->CCR2 = comparetwo; }
inline void setPWMCompare3(uint16_t comparethree) { TIM1->CCR3 = comparethree; }

void inline generatePwmTimerEvent() { LL_TIM_GenerateEvent_UPDATE(TIM1); }
inline void generatePwmTimerEvent() { LL_TIM_GenerateEvent_UPDATE(TIM1); }

void inline resetInputCaptureTimer()
inline void resetInputCaptureTimer()
{
IC_TIMER_REGISTER->PSC = 0;
IC_TIMER_REGISTER->CNT = 0;
Expand Down
20 changes: 0 additions & 20 deletions Mcu/f415/Inc/functions.h

This file was deleted.

10 changes: 5 additions & 5 deletions Mcu/l431/Src/peripherals.c
Original file line number Diff line number Diff line change
Expand Up @@ -650,13 +650,13 @@ void setDutyCycleAll(uint16_t newdc)
TIM1->CCR3 = newdc;
}

void inline setPWMCompare1(uint16_t compareone) { TIM1->CCR1 = compareone; }
void inline setPWMCompare2(uint16_t comparetwo) { TIM1->CCR2 = comparetwo; }
void inline setPWMCompare3(uint16_t comparethree) { TIM1->CCR3 = comparethree; }
inline void setPWMCompare1(uint16_t compareone) { TIM1->CCR1 = compareone; }
inline void setPWMCompare2(uint16_t comparetwo) { TIM1->CCR2 = comparetwo; }
inline void setPWMCompare3(uint16_t comparethree) { TIM1->CCR3 = comparethree; }

void inline generatePwmTimerEvent() { LL_TIM_GenerateEvent_UPDATE(TIM1); }
inline void generatePwmTimerEvent() { LL_TIM_GenerateEvent_UPDATE(TIM1); }

void inline resetInputCaptureTimer()
inline void resetInputCaptureTimer()
{
IC_TIMER_REGISTER->PSC = 0;
IC_TIMER_REGISTER->CNT = 0;
Expand Down
2 changes: 1 addition & 1 deletion Src/dshot.c
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ void make_dshot_package(uint16_t com_time)
dshot_full_number = send_extended_dshot;
send_extended_dshot = 0;
} else {
if (!running || (com_time > 65535)) {
if (!running) {
com_time = 65535;
}
// calculate shift amount for data in format eee mmm mmm mmm, first 1 found
Expand Down
4 changes: 2 additions & 2 deletions Src/functions.c
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@ long map(long x, long in_min, long in_max, long out_min, long out_max)
return map(x, in_mid + 1, in_max, out_mid, out_max);
}

int getAbsDif(int number1, int number2)
uint32_t getAbsDif(int number1, int number2)
{
int result = number1 - number2;
if (result < 0) {
result = -result;
}
return result;
return (uint32_t)result;
}

#ifdef STMICRO
Expand Down
4 changes: 2 additions & 2 deletions Src/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -805,7 +805,7 @@ void loadEEpromSettings()
sine_mode_power = eepromBuffer[45];
}

if (eepromBuffer[46] >= 0 && eepromBuffer[46] < 10) {
if (eepromBuffer[46] < 10) {
switch (eepromBuffer[46]) {
case AUTO_IN:
dshot = 0;
Expand Down Expand Up @@ -1340,7 +1340,7 @@ void setInput()
}
}
if (!prop_brake_active) {
if (input >= 47 && (zero_crosses < (30 >> stall_protection))) {
if (input >= 47 && (zero_crosses < (30U >> stall_protection))) {
if (duty_cycle_setpoint < min_startup_duty) {
duty_cycle_setpoint = min_startup_duty;
}
Expand Down
3 changes: 0 additions & 3 deletions Src/signal.c
Original file line number Diff line number Diff line change
Expand Up @@ -171,9 +171,6 @@ void transfercomplete()
dshot_frametime_low = (average_packet_length >> 3) - (average_packet_length >> 7);
}
}
if (adjusted_input < 0) {
adjusted_input = 0;
}
if (adjusted_input == 0 && calibration_required == 0) { // note this in input..not newinput so it
// will be adjusted be main loop
zero_input_count++;
Expand Down
5 changes: 1 addition & 4 deletions Src/sounds.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,6 @@ void setVolume(uint8_t volume)
if (volume > 11) {
volume = 11;
}
if (volume < 0) {
volume = 0;
}
beep_volume = volume * 2; // volume variable from 0 - 11 equates to CCR value of 0-22
}

Expand Down Expand Up @@ -756,4 +753,4 @@ void playBeaconTune3()
// TMR1->pr = TIMER1_MAX_ARR;
// __enable_irq();
// }
// #endif
// #endif

0 comments on commit 65e7ba9

Please sign in to comment.