Files
flix/gazebo/flix.h
Oleg Kalachev c8e5e08b03 Move all global variable declarations to the appropriate subsystems
As it makes the subsystems code easier to understand.
Declare the most used variables in main sketch file as forward declarations.
Make all control input zero by default (except controlMode).
Minor changes.
2026-01-03 13:28:18 +03:00

76 lines
2.0 KiB
C++

// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Declarations of some functions and variables in Arduino code
#include <cmath>
#include <stdio.h>
#include "vector.h"
#include "quaternion.h"
#include "Arduino.h"
#include "wifi.h"
#define WIFI_ENABLED 1
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector rates;
extern Quaternion attitude;
extern bool landed;
extern float motors[4];
Vector gyro, acc, imuRotation;
Vector accBias, gyroBias, accScale(1, 1, 1);
// declarations
void step();
void computeLoopRate();
void applyGyro();
void applyAcc();
void control();
void interpretControls();
void controlAttitude();
void controlRates();
void controlTorque();
const char* getModeName();
void sendMotors();
bool motorsActive();
void testMotor(int n);
void print(const char* format, ...);
void pause(float duration);
void doCommand(String str, bool echo);
void handleInput();
void normalizeRC();
void calibrateRC();
void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void printRCCalibration();
void printLogHeader();
void printLogData();
void processMavlink();
void sendMavlink();
void sendMessage(const void *msg);
void receiveMavlink();
void handleMavlink(const void *_msg);
void mavlinkPrint(const char* str);
void sendMavlinkPrint();
inline Quaternion fluToFrd(const Quaternion &q);
void failsafe();
void rcLossFailsafe();
void descend();
void autoFailsafe();
int parametersCount();
const char *getParameterName(int index);
float getParameter(int index);
float getParameter(const char *name);
bool setParameter(const char *name, const float value);
void printParameters();
void resetParameters();
// mocks
void setLED(bool on) {};
void calibrateGyro() { print("Skip gyro calibrating\n"); };
void calibrateAccel() { print("Skip accel calibrating\n"); };
void printIMUCalibration() { print("cal: N/A\n"); };
void printIMUInfo() {};
void printWiFiInfo() {};