mirror of
https://github.com/okalachev/flix.git
synced 2026-03-29 19:43:31 +00:00
Compare commits
3 Commits
7d74f3d5cd
...
1ac443d6f8
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
1ac443d6f8 | ||
|
|
964c0f7bc1 | ||
|
|
40bdaacedb |
BIN
docs/img/user/arkymatsekh/1.jpg
Normal file
BIN
docs/img/user/arkymatsekh/1.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 62 KiB |
BIN
docs/img/user/arkymatsekh/2.jpg
Normal file
BIN
docs/img/user/arkymatsekh/2.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 48 KiB |
BIN
docs/img/user/arkymatsekh/3.jpg
Normal file
BIN
docs/img/user/arkymatsekh/3.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 50 KiB |
BIN
docs/img/user/arkymatsekh/video.jpg
Normal file
BIN
docs/img/user/arkymatsekh/video.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 17 KiB |
@@ -134,6 +134,20 @@ Before flight you need to calibrate the accelerometer:
|
|||||||
1. Access the console using QGroundControl (recommended) or Serial Monitor.
|
1. Access the console using QGroundControl (recommended) or Serial Monitor.
|
||||||
2. Type `ca` command there and follow the instructions.
|
2. Type `ca` command there and follow the instructions.
|
||||||
|
|
||||||
|
### Setup motors
|
||||||
|
|
||||||
|
If using non-default motor pins, set the pin numbers using the parameters: `MOTOR_PIN_FL`, `MOTOR_PIN_FR`, `MOTOR_PIN_RL`, `MOTOR_PIN_RR` (front-left, front-right, rear-left, rear-right respectively).
|
||||||
|
|
||||||
|
If using brushless motors and ESCs:
|
||||||
|
|
||||||
|
1. Set the appropriate PWM using the parameters: `MOT_PWM_STOP`, `MOT_PWM_MIN`, and `MOT_PWM_MAX` (1000, 1000, and 2000 is typical).
|
||||||
|
2. Decrease the PWM frequency using the `MOT_PWM_FREQ` parameter (400 is typical).
|
||||||
|
|
||||||
|
Reboot the drone to apply the changes.
|
||||||
|
|
||||||
|
> [!CAUTION]
|
||||||
|
> **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them.
|
||||||
|
|
||||||
### Check everything works
|
### Check everything works
|
||||||
|
|
||||||
1. Check the IMU is working: perform `imu` command and check its output:
|
1. Check the IMU is working: perform `imu` command and check its output:
|
||||||
|
|||||||
11
docs/user.md
11
docs/user.md
@@ -4,6 +4,17 @@ This page contains user-built drones based on the Flix project. Publish your pro
|
|||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
Author: **Arkadiy "Arky" Matsekh**, Foucault Dynamics, Gold Coast, Australia.<br>
|
||||||
|
The drone was built for the University of Queensland industry-led Master's capstone project.
|
||||||
|
|
||||||
|
**Flight video:**
|
||||||
|
|
||||||
|
<a href="https://drive.google.com/file/d/1NNYSVXBY-w0JjCo07D8-PgnVq3ca9plj/view?usp=sharing"><img height=300 src="img/user/arkymatsekh/video.jpg"></a>
|
||||||
|
|
||||||
|
<img src="img/user/arkymatsekh/1.jpg" height=150> <img src="img/user/arkymatsekh/2.jpg" height=150> <img src="img/user/arkymatsekh/3.jpg" height=150>
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
Author: [goldarte](https://t.me/goldarte).<br>
|
Author: [goldarte](https://t.me/goldarte).<br>
|
||||||
|
|
||||||
<img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>
|
<img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>
|
||||||
|
|||||||
@@ -94,7 +94,7 @@ void doCommand(String str, bool echo = false) {
|
|||||||
} else if (command == "p") {
|
} else if (command == "p") {
|
||||||
bool success = setParameter(arg0.c_str(), arg1.toFloat());
|
bool success = setParameter(arg0.c_str(), arg1.toFloat());
|
||||||
if (success) {
|
if (success) {
|
||||||
print("%s = %g\n", arg0.c_str(), arg1.toFloat());
|
print("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
|
||||||
} else {
|
} else {
|
||||||
print("Parameter not found: %s\n", arg0.c_str());
|
print("Parameter not found: %s\n", arg0.c_str());
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,24 +1,19 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
// Repository: https://github.com/okalachev/flix
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
// Motors output control using MOSFETs
|
// PWM control for motors
|
||||||
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
|
|
||||||
|
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define MOTOR_0_PIN 12 // rear left
|
|
||||||
#define MOTOR_1_PIN 13 // rear right
|
|
||||||
#define MOTOR_2_PIN 14 // front right
|
|
||||||
#define MOTOR_3_PIN 15 // front left
|
|
||||||
|
|
||||||
#define PWM_FREQUENCY 78000
|
|
||||||
#define PWM_RESOLUTION 10
|
|
||||||
#define PWM_STOP 0
|
|
||||||
#define PWM_MIN 0
|
|
||||||
#define PWM_MAX 1000000 / PWM_FREQUENCY
|
|
||||||
|
|
||||||
float motors[4]; // normalized motor thrusts in range [0..1]
|
float motors[4]; // normalized motor thrusts in range [0..1]
|
||||||
|
|
||||||
|
int motorPins[4] = {12, 13, 14, 15}; // default pin numbers
|
||||||
|
int pwmFrequency = 78000;
|
||||||
|
int pwmResolution = 10;
|
||||||
|
int pwmStop = 0;
|
||||||
|
int pwmMin = 0;
|
||||||
|
int pwmMax = -1; // -1 means duty cycle mode
|
||||||
|
|
||||||
const int MOTOR_REAR_LEFT = 0;
|
const int MOTOR_REAR_LEFT = 0;
|
||||||
const int MOTOR_REAR_RIGHT = 1;
|
const int MOTOR_REAR_RIGHT = 1;
|
||||||
const int MOTOR_FRONT_RIGHT = 2;
|
const int MOTOR_FRONT_RIGHT = 2;
|
||||||
@@ -26,30 +21,30 @@ const int MOTOR_FRONT_LEFT = 3;
|
|||||||
|
|
||||||
void setupMotors() {
|
void setupMotors() {
|
||||||
print("Setup Motors\n");
|
print("Setup Motors\n");
|
||||||
|
|
||||||
// configure pins
|
// configure pins
|
||||||
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
for (int i = 0; i < 4; i++) {
|
||||||
ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
|
||||||
ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
}
|
||||||
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
|
||||||
|
|
||||||
sendMotors();
|
sendMotors();
|
||||||
print("Motors initialized\n");
|
print("Motors initialized\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
int getDutyCycle(float value) {
|
void sendMotors() {
|
||||||
value = constrain(value, 0, 1);
|
for (int i = 0; i < 4; i++) {
|
||||||
float pwm = mapf(value, 0, 1, PWM_MIN, PWM_MAX);
|
ledcWrite(motorPins[i], getDutyCycle(motors[i]));
|
||||||
if (value == 0) pwm = PWM_STOP;
|
}
|
||||||
float duty = mapf(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
|
|
||||||
return round(duty);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendMotors() {
|
int getDutyCycle(float value) {
|
||||||
ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
|
value = constrain(value, 0, 1);
|
||||||
ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
|
if (pwmMax >= 0) { // pwm mode
|
||||||
ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
|
float pwm = mapf(value, 0, 1, pwmMin, pwmMax);
|
||||||
ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
|
if (value == 0) pwm = pwmStop;
|
||||||
|
float duty = mapf(pwm, 0, 1000000 / pwmFrequency, 0, (1 << pwmResolution) - 1);
|
||||||
|
return round(duty);
|
||||||
|
} else { // duty cycle mode
|
||||||
|
return round(value * ((1 << pwmResolution) - 1));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool motorsActive() {
|
bool motorsActive() {
|
||||||
|
|||||||
@@ -63,6 +63,16 @@ Parameter parameters[] = {
|
|||||||
// estimate
|
// estimate
|
||||||
{"EST_ACC_WEIGHT", &accWeight},
|
{"EST_ACC_WEIGHT", &accWeight},
|
||||||
{"EST_RATES_LPF_A", &ratesFilter.alpha},
|
{"EST_RATES_LPF_A", &ratesFilter.alpha},
|
||||||
|
// motors
|
||||||
|
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT]},
|
||||||
|
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT]},
|
||||||
|
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT]},
|
||||||
|
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT]},
|
||||||
|
{"MOT_PWM_FREQ", &pwmFrequency},
|
||||||
|
{"MOT_PWM_RES", &pwmResolution},
|
||||||
|
{"MOT_PWM_STOP", &pwmStop},
|
||||||
|
{"MOT_PWM_MIN", &pwmMin},
|
||||||
|
{"MOT_PWM_MAX", &pwmMax},
|
||||||
// rc
|
// rc
|
||||||
{"RC_ZERO_0", &channelZero[0]},
|
{"RC_ZERO_0", &channelZero[0]},
|
||||||
{"RC_ZERO_1", &channelZero[1]},
|
{"RC_ZERO_1", &channelZero[1]},
|
||||||
|
|||||||
@@ -32,6 +32,7 @@ void controlRates();
|
|||||||
void controlTorque();
|
void controlTorque();
|
||||||
const char* getModeName();
|
const char* getModeName();
|
||||||
void sendMotors();
|
void sendMotors();
|
||||||
|
int getDutyCycle(float value);
|
||||||
bool motorsActive();
|
bool motorsActive();
|
||||||
void testMotor(int n);
|
void testMotor(int n);
|
||||||
void print(const char* format, ...);
|
void print(const char* format, ...);
|
||||||
|
|||||||
Reference in New Issue
Block a user