1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 13:25:30 +03:00

various: tidy up various things found when building with a C++ compiler.

Remove duplicate consts.
Pull in the include files where functions and variables are declared.
Mark file local but duplicated variables as static.
Mark some variable declarations as extern.
Remove duplicated variable definition.

Signed-off-by: Michael Hope <mlhx@google.com>
This commit is contained in:
Michael Hope 2015-06-04 22:21:19 +02:00
parent 49e22265dc
commit 5c6760fd82
15 changed files with 27 additions and 23 deletions

View file

@ -21,7 +21,9 @@
*
******************************************************************************/
#include <stdint.h>
// TODO(michaelh): needed for IRQn_Type which is chip specific.
#include "stm32f10x_conf.h"
#include "core_cm3.h"
/* define compiler specific symbols */
#if defined ( __CC_ARM )

View file

@ -32,7 +32,7 @@ typedef enum BlackboxDevice {
BLACKBOX_DEVICE_END
} BlackboxDevice;
uint8_t blackboxWriteChunkSize;
extern uint8_t blackboxWriteChunkSize;
void blackboxWrite(uint8_t value);

View file

@ -31,7 +31,7 @@
unsigned char CHAR_FORMAT = NORMAL_CHAR_FORMAT;
static const uint8_t const multiWiiFont[][5] = { // Refer to "Times New Roman" Font Database... 5 x 7 font
static const uint8_t multiWiiFont[][5] = { // Refer to "Times New Roman" Font Database... 5 x 7 font
{ 0x00, 0x00, 0x00, 0x00, 0x00 }, { 0x00, 0x00, 0x4F, 0x00, 0x00 }, // ( 1) ! - 0x0021 Exclamation Mark
{ 0x00, 0x07, 0x00, 0x07, 0x00 }, // ( 2) " - 0x0022 Quotation Mark
{ 0x14, 0x7F, 0x14, 0x7F, 0x14 }, // ( 3) # - 0x0023 Number Sign

View file

@ -675,7 +675,7 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
tim->SR = mask;
tim_status &= mask;
switch(bit) {
case __builtin_clz(TIM_IT_Update):
case __builtin_clz(TIM_IT_Update): {
if(timerConfig->forcedOverflowTimerValue != 0){
capture = timerConfig->forcedOverflowTimerValue - 1;
@ -690,6 +690,7 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
cb = cb->next;
}
break;
}
case __builtin_clz(TIM_IT_CC1):
timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
break;

View file

@ -55,10 +55,10 @@ int32_t AltHold;
int32_t vario = 0; // variometer in cm/s
barometerConfig_t *barometerConfig;
pidProfile_t *pidProfile;
rcControlsConfig_t *rcControlsConfig;
escAndServoConfig_t *escAndServoConfig;
static barometerConfig_t *barometerConfig;
static pidProfile_t *pidProfile;
static rcControlsConfig_t *rcControlsConfig;
static escAndServoConfig_t *escAndServoConfig;
void configureAltitudeHold(
pidProfile_t *initialPidProfile,

View file

@ -65,9 +65,9 @@ float gyroScaleRad;
rollAndPitchInclination_t inclination = { { 0, 0 } }; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
float anglerad[2] = { 0.0f, 0.0f }; // absolute angle inclination in radians
imuRuntimeConfig_t *imuRuntimeConfig;
pidProfile_t *pidProfile;
accDeadband_t *accDeadband;
static imuRuntimeConfig_t *imuRuntimeConfig;
static pidProfile_t *pidProfile;
static accDeadband_t *accDeadband;
void imuConfigure(
imuRuntimeConfig_t *initialImuRuntimeConfig,

View file

@ -151,7 +151,7 @@ typedef struct beeperTableEntry_s {
#define BEEPER_ENTRY(a,b,c,d) a,b,c
#endif
static const beeperTableEntry_t const beeperTable[] = {
static const beeperTableEntry_t beeperTable[] = {
{ BEEPER_ENTRY(BEEPER_GYRO_CALIBRATED, 0, beep_gyroCalibrated, "GYRO_CALIBRATED") },
{ BEEPER_ENTRY(BEEPER_RX_LOST_LANDING, 1, beep_sos, "RX_LOST_LANDING") },
{ BEEPER_ENTRY(BEEPER_RX_LOST, 2, beep_txLostBeep, "RX_LOST") },

View file

@ -100,7 +100,7 @@ static const char* const pageTitles[] = {
#define PAGE_COUNT (PAGE_RX + 1)
const uint8_t cyclePageIds[] = {
const pageId_e cyclePageIds[] = {
PAGE_PROFILE,
#ifdef GPS
PAGE_GPS,

View file

@ -74,8 +74,6 @@ static uint32_t nextRotationUpdateAt = 0;
#error "Led strip length must match driver"
#endif
hsvColor_t *colors;
// H S V
#define LED_BLACK { 0, 0, 0}
#define LED_WHITE { 0, 255, 255}
@ -892,11 +890,11 @@ void updateLedStrip(void)
uint32_t now = micros();
bool indicatorFlashNow = indicatorFlashNow = (int32_t)(now - nextIndicatorFlashAt) >= 0L;
bool warningFlashNow = warningFlashNow = (int32_t)(now - nextWarningFlashAt) >= 0L;
bool indicatorFlashNow = (int32_t)(now - nextIndicatorFlashAt) >= 0L;
bool warningFlashNow = (int32_t)(now - nextWarningFlashAt) >= 0L;
bool rotationUpdateNow = (int32_t)(now - nextRotationUpdateAt) >= 0L;
#ifdef USE_LED_ANIMATION
bool animationUpdateNow = animationUpdateNow = (int32_t)(now - nextAnimationUpdateAt) >= 0L;
bool animationUpdateNow = (int32_t)(now - nextAnimationUpdateAt) >= 0L;
#endif
if (!(
indicatorFlashNow ||

View file

@ -315,7 +315,7 @@ typedef struct box_e {
} box_t;
// FIXME remove ;'s
static const box_t const boxes[CHECKBOX_ITEM_COUNT + 1] = {
static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
{ BOXARM, "ARM;", 0 },
{ BOXANGLE, "ANGLE;", 1 },
{ BOXHORIZON, "HORIZON;", 2 },

View file

@ -68,6 +68,7 @@
#include "sensors/gyro.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "sensors/initialisation.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox.h"
@ -110,7 +111,6 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura
void rxInit(rxConfig_t *rxConfig);
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig);
void navigationInit(gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int8_t magHardwareToUse, int16_t magDeclinationFromConfig);
void imuInit(void);
void displayInit(rxConfig_t *intialRxConfig);
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse);

View file

@ -41,7 +41,7 @@ static int32_t baroGroundAltitude = 0;
static int32_t baroGroundPressure = 0;
static uint32_t baroPressureSum = 0;
barometerConfig_t *barometerConfig;
static barometerConfig_t *barometerConfig;
void useBarometerConfig(barometerConfig_t *barometerConfigToUse)
{

View file

@ -60,6 +60,7 @@
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/sonar.h"
#include "sensors/initialisation.h"
#ifdef NAZE
#include "hardware_revision.h"

View file

@ -41,14 +41,14 @@ static int32_t calculatedAltitude;
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig)
{
#if defined(NAZE) || defined(EUSTM32F103RC) || defined(PORT103R)
static const sonarHardware_t const sonarPWM56 = {
static const sonarHardware_t sonarPWM56 = {
.trigger_pin = Pin_8, // PWM5 (PB8) - 5v tolerant
.echo_pin = Pin_9, // PWM6 (PB9) - 5v tolerant
.exti_line = EXTI_Line9,
.exti_pin_source = GPIO_PinSource9,
.exti_irqn = EXTI9_5_IRQn
};
static const sonarHardware_t const sonarRC78 = {
static const sonarHardware_t sonarRC78 = {
.trigger_pin = Pin_0, // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
.echo_pin = Pin_1, // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
.exti_line = EXTI_Line1,

View file

@ -15,6 +15,8 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include "version.h"
const char * const targetName = __TARGET__;
const char * const shortGitRevision = __REVISION__;
const char * const buildDate = __DATE__;