From 39875cafb9e96b84a9fae1ec74b8b0a73be78bc3 Mon Sep 17 00:00:00 2001 From: Oleg Kalachev Date: Wed, 31 May 2023 20:12:45 +0300 Subject: [PATCH] Remove non-effective `static`s --- flix/cli.ino | 8 ++++---- flix/control.ino | 10 +++++----- flix/imu.ino | 8 ++++---- flix/log.ino | 4 ++-- flix/mavlink.ino | 6 +++--- flix/rc.ino | 6 +++--- flix/test_motors.ino | 2 +- gazebo/flix.h | 12 ++++++------ 8 files changed, 28 insertions(+), 28 deletions(-) diff --git a/flix/cli.ino b/flix/cli.ino index fca2bf8..d90b127 100644 --- a/flix/cli.ino +++ b/flix/cli.ino @@ -30,7 +30,7 @@ const char* motd = "fullmot - test motor on all signals\n" "wifi - start wi-fi access point\n"; -static const struct Param { +const struct Param { const char* name; float* value; float* value2; @@ -51,7 +51,7 @@ static const struct Param { // {"m", &mode, nullptr}, }; -static void doCommand(String& command, String& value) +void doCommand(String& command, String& value) { if (command == "help" || command == "motd") { Serial.println(motd); @@ -110,7 +110,7 @@ static void doCommand(String& command, String& value) } } -static void showTable() +void showTable() { for (uint8_t i = 0; i < sizeof(params) / sizeof(params[0]); i++) { Serial.print(params[i].name); @@ -119,7 +119,7 @@ static void showTable() } } -static void cliTestMotor(uint8_t n) +void cliTestMotor(uint8_t n) { Serial.printf("Testing motor %d\n", n); motors[n] = 1; diff --git a/flix/control.ino b/flix/control.ino index 6c16fb6..2113cb1 100644 --- a/flix/control.ino +++ b/flix/control.ino @@ -98,7 +98,7 @@ void interpretRC() } } -static void controlAttitude() +void controlAttitude() { if (!armed) { rollPID.reset(); @@ -149,7 +149,7 @@ static void controlAttitude() // std::cout << "rsp: " << ratesTarget.x << " " << ratesTarget.y << std::endl; } -static void controlAttitudeAlter() +void controlAttitudeAlter() { if (!armed) { rollPID.reset(); @@ -169,7 +169,7 @@ static void controlAttitudeAlter() } // passthrough mode -static void controlManual() +void controlManual() { if (controls[RC_CHANNEL_THROTTLE] < 0.1) { memset(motors, 0, sizeof(motors)); @@ -195,7 +195,7 @@ static void controlManual() motors[3] = constrain(motors[3], 0, 1); } -static void controlRate() +void controlRate() { if (!armed) { // TODO: too rough memset(motors, 0, sizeof(motors)); @@ -257,7 +257,7 @@ void desaturate(float& a, float& b, float& c, float& d) static bool motorsSaturation = false; -static inline void indicateSaturation() { +inline void indicateSaturation() { bool sat = motors[0] > 1 || motors[1] > 1 || motors[2] > 1 || motors[3] > 1 || motors[0] < 0 || motors[1] < 0 || motors[2] < 0 || motors[3] < 0; if (motorsSaturation != sat) { diff --git a/flix/imu.ino b/flix/imu.ino index 8bddc6b..9372f90 100644 --- a/flix/imu.ino +++ b/flix/imu.ino @@ -53,7 +53,7 @@ bool readIMU() return rates != lastRates; } -static void calibrateGyro() +void calibrateGyro() { Serial.println("Calibrating gyro, stand still"); delay(500); @@ -63,7 +63,7 @@ static void calibrateGyro() printIMUCal(); } -static void calibrateAccel() +void calibrateAccel() { Serial.println("Cal accel: place level"); delay(3000); IMU.calibrateAccel(); @@ -80,14 +80,14 @@ static void calibrateAccel() printIMUCal(); } -static void loadAccelCal() +void loadAccelCal() { IMU.setAccelCalX(-0.0048542023, 1.0008112192); IMU.setAccelCalY(0.0521845818, 0.9985780716); IMU.setAccelCalZ(0.5754694939, 1.0045746565); } -static void loadGyroCal() +void loadGyroCal() { IMU.setGyroBiasX_rads(-0.0185128022); IMU.setGyroBiasY_rads(-0.0262369743); diff --git a/flix/log.ino b/flix/log.ino index 834ca00..e0344b2 100644 --- a/flix/log.ino +++ b/flix/log.ino @@ -9,8 +9,8 @@ const float LOG_PERIOD = 1 / LOG_RATE; const int LOG_SIZE = LOG_DURATION * LOG_RATE; const int LOG_COLUMNS = 14; -static float logBuffer[LOG_SIZE][LOG_COLUMNS]; // * 4 (float) -static int logPointer = 0; +float logBuffer[LOG_SIZE][LOG_COLUMNS]; // * 4 (float) +int logPointer = 0; void logData() { diff --git a/flix/mavlink.ino b/flix/mavlink.ino index d4c74d0..3714e04 100644 --- a/flix/mavlink.ino +++ b/flix/mavlink.ino @@ -9,8 +9,8 @@ #define PERIOD_SLOW 1000000 // us #define PERIOD_FAST 100000 // us -static uint32_t lastSlow; -static uint32_t lastFast; +uint32_t lastSlow; +uint32_t lastFast; void sendMavlink() { @@ -60,7 +60,7 @@ void sendMavlink() } } -static inline void sendMessage(const void *msg) +inline void sendMessage(const void *msg) { uint8_t buf[MAVLINK_MAX_PACKET_LEN]; uint16_t len = mavlink_msg_to_send_buffer(buf, (mavlink_message_t *)msg); diff --git a/flix/rc.ino b/flix/rc.ino index bf02ecd..42d3a7d 100644 --- a/flix/rc.ino +++ b/flix/rc.ino @@ -3,10 +3,10 @@ #include -static const uint16_t channelNeutral[] = {995, 883, 200, 972, 512, 512}; -static const uint16_t channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472}; +const uint16_t channelNeutral[] = {995, 883, 200, 972, 512, 512}; +const uint16_t channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472}; -static SBUS RC(Serial2); +SBUS RC(Serial2); void setupRC() { diff --git a/flix/test_motors.ino b/flix/test_motors.ino index 0b92b06..35765df 100644 --- a/flix/test_motors.ino +++ b/flix/test_motors.ino @@ -1,7 +1,7 @@ // Copyright (c) 2023 Oleg Kalachev // Repository: https://github.com/okalachev/flix -static void _pwm(int n, uint16_t pwm) +void _pwm(int n, uint16_t pwm) { printf("Motor %d: %d\n", n, pwm); ledcWrite(n, pwmToDutyCycle(pwm)); diff --git a/gazebo/flix.h b/gazebo/flix.h index 1e80fae..174998c 100644 --- a/gazebo/flix.h +++ b/gazebo/flix.h @@ -33,13 +33,13 @@ void applyAcc(); void signalizeHorizontality(); void control(); void interpretRC(); -static void controlAttitude(); -static void controlManual(); -static void controlRate(); +void controlAttitude(); +void controlManual(); +void controlRate(); void desaturate(float& a, float& b, float& c, float& d); -static void indicateSaturation(); -static void showTable(); -static void cliTestMotor(uint8_t n); +void indicateSaturation(); +void showTable(); +void cliTestMotor(uint8_t n); // mocks void setLED(bool on) {};