Make motor indexes definition const int and move them to motors.ino

Remove motor indexes definitions from flix.ino
Add motors.ino to simulation code and implement required mocks
This commit is contained in:
Oleg Kalachev 2025-01-09 11:14:18 +03:00
parent 72033cdd75
commit 404ceed851
7 changed files with 14 additions and 11 deletions

View File

@ -8,6 +8,7 @@
extern PID rollRatePID, pitchRatePID, yawRatePID, rollPID, pitchPID;
extern LowPassFilter<Vector> ratesFilter;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
const char* motd =
"\nWelcome to\n"

View File

@ -50,6 +50,8 @@ Vector ratesTarget;
Vector torqueTarget;
float thrustTarget;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
void control() {
interpretRC();
failsafe();

View File

@ -18,11 +18,6 @@
#define RC_CHANNEL_ARMED 4
#define RC_CHANNEL_MODE 5
#define MOTOR_REAR_LEFT 0
#define MOTOR_REAR_RIGHT 1
#define MOTOR_FRONT_RIGHT 2
#define MOTOR_FRONT_LEFT 3
#define ONE_G 9.80665
float t = NAN; // current step time, s

View File

@ -14,6 +14,12 @@
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
// Motors array indexes:
const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2;
const int MOTOR_FRONT_LEFT = 3;
void setupMotors() {
Serial.println("Setup Motors");

View File

@ -150,6 +150,9 @@ void delay(uint32_t ms) {
std::this_thread::sleep_for(std::chrono::milliseconds(ms));
}
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
unsigned long __micros;
unsigned long __resetTime = 0;

View File

@ -12,11 +12,6 @@
#define RC_CHANNELS 16
#define MOTOR_REAR_LEFT 0
#define MOTOR_FRONT_LEFT 3
#define MOTOR_FRONT_RIGHT 2
#define MOTOR_REAR_RIGHT 1
#define WIFI_ENABLED 1
#define ONE_G 9.80665
@ -43,6 +38,7 @@ void controlAttitude();
void controlRate();
void controlTorque();
void showTable();
void sendMotors();
bool motorsActive();
void cliTestMotor(uint8_t n);
String stringToken(char* str, const char* delim);
@ -61,7 +57,6 @@ inline Quaternion FLU2FRD(const Quaternion &q);
void setLED(bool on) {};
void calibrateGyro() { printf("Skip gyro calibrating\n"); };
void calibrateAccel() { printf("Skip accel calibrating\n"); };
void sendMotors() {};
void printIMUCal() { printf("cal: N/A\n"); };
void printIMUInfo() {};
Vector accBias, gyroBias, accScale(1, 1, 1);

View File

@ -20,6 +20,7 @@
#include "util.ino"
#include "rc.ino"
#include "time.ino"
#include "motors.ino"
#include "estimate.ino"
#include "control.ino"
#include "log.ino"