mirror of
https://github.com/okalachev/flix.git
synced 2026-03-29 19:43:31 +00:00
Compare commits
3 Commits
a8c25d8ac0
...
0730ceeffa
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
0730ceeffa | ||
|
|
a687303062 | ||
|
|
b2daf2587f |
BIN
docs/img/user/fanby0ru/1.jpg
Normal file
BIN
docs/img/user/fanby0ru/1.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 44 KiB |
BIN
docs/img/user/fanby0ru/2.jpg
Normal file
BIN
docs/img/user/fanby0ru/2.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 55 KiB |
BIN
docs/img/user/phalko/1.jpg
Normal file
BIN
docs/img/user/phalko/1.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 105 KiB |
BIN
docs/img/user/phalko/2.jpg
Normal file
BIN
docs/img/user/phalko/2.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 34 KiB |
BIN
docs/img/user/phalko/3.jpg
Normal file
BIN
docs/img/user/phalko/3.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 36 KiB |
16
docs/user.md
16
docs/user.md
@@ -4,6 +4,22 @@ This page contains user-built drones based on the Flix project. Publish your pro
|
|||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
Author: [FanBy0ru](https://https://github.com/FanBy0ru).<br>
|
||||||
|
Description: custom 3D-printed frame.<br>
|
||||||
|
Frame STLs and flight validation: https://cults3d.com/en/3d-model/gadget/armature-pour-flix-drone.
|
||||||
|
|
||||||
|
<img src="img/user/fanby0ru/1.jpg" height=200> <img src="img/user/fanby0ru/2.jpg" height=200>
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
Author: Ivan44 Phalko.<br>
|
||||||
|
Description: custom PCB, cusom test bench.<br>
|
||||||
|
[Flight validation](https://drive.google.com/file/d/17DNDJ1gPmCmDRAwjedCbJ9RXAyqMqqcX/view?usp=sharing).
|
||||||
|
|
||||||
|
<img src="img/user/phalko/1.jpg" height=200> <img src="img/user/phalko/2.jpg" height=200> <img src="img/user/phalko/3.jpg" height=200>
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
Author: **Arkadiy "Arky" Matsekh**, Foucault Dynamics, Gold Coast, Australia.<br>
|
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.
|
The drone was built for the University of Queensland industry-led Master's capstone project.
|
||||||
|
|
||||||
|
|||||||
@@ -24,6 +24,7 @@ void setupMotors() {
|
|||||||
// configure pins
|
// configure pins
|
||||||
for (int i = 0; i < 4; i++) {
|
for (int i = 0; i < 4; i++) {
|
||||||
ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
|
ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
|
||||||
|
pwmFrequency = ledcChangeFrequency(motorPins[i], pwmFrequency, pwmResolution); // when reconfiguring
|
||||||
}
|
}
|
||||||
sendMotors();
|
sendMotors();
|
||||||
print("Motors initialized\n");
|
print("Motors initialized\n");
|
||||||
|
|||||||
@@ -19,8 +19,9 @@ struct Parameter {
|
|||||||
bool integer;
|
bool integer;
|
||||||
union { float *f; int *i; }; // pointer to the variable
|
union { float *f; int *i; }; // pointer to the variable
|
||||||
float cache; // what's stored in flash
|
float cache; // what's stored in flash
|
||||||
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
|
void (*callback)(); // called after parameter change
|
||||||
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
|
Parameter(const char *name, float *variable, void (*callback)() = nullptr) : name(name), integer(false), f(variable), callback(callback) {};
|
||||||
|
Parameter(const char *name, int *variable, void (*callback)() = nullptr) : name(name), integer(true), i(variable), callback(callback) {};
|
||||||
float getValue() const { return integer ? *i : *f; };
|
float getValue() const { return integer ? *i : *f; };
|
||||||
void setValue(const float value) { if (integer) *i = value; else *f = value; };
|
void setValue(const float value) { if (integer) *i = value; else *f = value; };
|
||||||
};
|
};
|
||||||
@@ -67,12 +68,12 @@ Parameter parameters[] = {
|
|||||||
{"EST_ACC_WEIGHT", &accWeight},
|
{"EST_ACC_WEIGHT", &accWeight},
|
||||||
{"EST_RATES_LPF_A", &ratesFilter.alpha},
|
{"EST_RATES_LPF_A", &ratesFilter.alpha},
|
||||||
// motors
|
// motors
|
||||||
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT]},
|
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT], setupMotors},
|
||||||
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT]},
|
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT], setupMotors},
|
||||||
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT]},
|
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT], setupMotors},
|
||||||
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT]},
|
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT], setupMotors},
|
||||||
{"MOT_PWM_FREQ", &pwmFrequency},
|
{"MOT_PWM_FREQ", &pwmFrequency, setupMotors},
|
||||||
{"MOT_PWM_RES", &pwmResolution},
|
{"MOT_PWM_RES", &pwmResolution, setupMotors},
|
||||||
{"MOT_PWM_STOP", &pwmStop},
|
{"MOT_PWM_STOP", &pwmStop},
|
||||||
{"MOT_PWM_MIN", &pwmMin},
|
{"MOT_PWM_MIN", &pwmMin},
|
||||||
{"MOT_PWM_MAX", &pwmMax},
|
{"MOT_PWM_MAX", &pwmMax},
|
||||||
@@ -113,7 +114,7 @@ Parameter parameters[] = {
|
|||||||
|
|
||||||
void setupParameters() {
|
void setupParameters() {
|
||||||
print("Setup parameters\n");
|
print("Setup parameters\n");
|
||||||
storage.begin("flix", false);
|
storage.begin("flix");
|
||||||
// Read parameters from storage
|
// Read parameters from storage
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
if (!storage.isKey(parameter.name)) {
|
if (!storage.isKey(parameter.name)) {
|
||||||
@@ -152,6 +153,7 @@ bool setParameter(const char *name, const float value) {
|
|||||||
if (strcasecmp(parameter.name, name) == 0) {
|
if (strcasecmp(parameter.name, name) == 0) {
|
||||||
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
|
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
|
||||||
parameter.setValue(value);
|
parameter.setValue(value);
|
||||||
|
if (parameter.callback) parameter.callback();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -165,8 +167,7 @@ void syncParameters() {
|
|||||||
|
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
if (parameter.getValue() == parameter.cache) continue; // no change
|
if (parameter.getValue() == parameter.cache) continue; // no change
|
||||||
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NaN
|
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NAN
|
||||||
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf
|
|
||||||
|
|
||||||
storage.putFloat(parameter.name, parameter.getValue());
|
storage.putFloat(parameter.name, parameter.getValue());
|
||||||
parameter.cache = parameter.getValue(); // update cache
|
parameter.cache = parameter.getValue(); // update cache
|
||||||
|
|||||||
@@ -165,6 +165,7 @@ void delay(uint32_t ms) {
|
|||||||
|
|
||||||
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
|
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
|
||||||
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
|
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
|
||||||
|
uint32_t ledcChangeFrequency(uint8_t pin, uint32_t freq, uint8_t resolution) { return freq; }
|
||||||
|
|
||||||
unsigned long __micros;
|
unsigned long __micros;
|
||||||
unsigned long __resetTime = 0;
|
unsigned long __resetTime = 0;
|
||||||
|
|||||||
Reference in New Issue
Block a user