mirror of
https://github.com/okalachev/flix.git
synced 2026-03-30 20:13:44 +00:00
Compare commits
1 Commits
67430c7aac
...
motor-conf
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
6c41f65ef9 |
Binary file not shown.
|
Before Width: | Height: | Size: 62 KiB |
Binary file not shown.
|
Before Width: | Height: | Size: 48 KiB |
Binary file not shown.
|
Before Width: | Height: | Size: 50 KiB |
Binary file not shown.
|
Before Width: | Height: | Size: 17 KiB |
@@ -143,8 +143,6 @@ 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.
|
||||
|
||||
|
||||
11
docs/user.md
11
docs/user.md
@@ -4,17 +4,6 @@ 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>
|
||||
|
||||
<img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>
|
||||
|
||||
@@ -52,7 +52,6 @@ PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
|
||||
PID yawPID(YAW_P, 0, 0);
|
||||
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
|
||||
float tiltMax = TILT_MAX;
|
||||
int flightModes[] = {STAB, STAB, STAB}; // map for rc mode switch
|
||||
|
||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||
@@ -66,9 +65,9 @@ void control() {
|
||||
}
|
||||
|
||||
void interpretControls() {
|
||||
if (controlMode < 0.25) mode = flightModes[0];
|
||||
else if (controlMode < 0.75) mode = flightModes[1];
|
||||
else if (controlMode > 0.75) mode = flightModes[2];
|
||||
if (controlMode < 0.25) mode = STAB;
|
||||
if (controlMode < 0.75) mode = STAB;
|
||||
if (controlMode > 0.75) mode = STAB;
|
||||
|
||||
if (mode == AUTO) return; // pilot is not effective in AUTO mode
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Attitude estimation using gyro and accelerometer
|
||||
// Attitude estimation from gyro and accelerometer
|
||||
|
||||
#include "quaternion.h"
|
||||
#include "vector.h"
|
||||
|
||||
@@ -21,8 +21,8 @@ void setup() {
|
||||
disableBrownOut();
|
||||
setupParameters();
|
||||
setupLED();
|
||||
setLED(true);
|
||||
setupMotors();
|
||||
setLED(true);
|
||||
setupWiFi();
|
||||
setupIMU();
|
||||
setupRC();
|
||||
|
||||
@@ -8,13 +8,12 @@
|
||||
|
||||
extern float controlTime;
|
||||
|
||||
bool mavlinkConnected = false;
|
||||
String mavlinkPrintBuffer;
|
||||
int mavlinkSysId = 1;
|
||||
Rate telemetryFast(10);
|
||||
Rate telemetrySlow(2);
|
||||
|
||||
bool mavlinkConnected = false;
|
||||
String mavlinkPrintBuffer;
|
||||
|
||||
void processMavlink() {
|
||||
sendMavlink();
|
||||
receiveMavlink();
|
||||
@@ -42,9 +41,9 @@ void sendMavlink() {
|
||||
}
|
||||
|
||||
if (telemetryFast && mavlinkConnected) {
|
||||
const float offset[] = {0, 0, 0, 0};
|
||||
const float zeroQuat[] = {0, 0, 0, 0};
|
||||
mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, offset); // convert to frd
|
||||
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
|
||||
sendMessage(&msg);
|
||||
|
||||
mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,
|
||||
|
||||
@@ -24,6 +24,7 @@ void setupMotors() {
|
||||
// configure pins
|
||||
for (int i = 0; i < 4; i++) {
|
||||
ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
|
||||
pwmFrequency = ledcChangeFrequency(motorPins[i], pwmFrequency, pwmResolution); // if re-initializing
|
||||
}
|
||||
sendMotors();
|
||||
print("Motors initialized\n");
|
||||
|
||||
@@ -15,9 +15,9 @@ extern float rcLossTimeout, descendTime;
|
||||
Preferences storage;
|
||||
|
||||
struct Parameter {
|
||||
const char *name; // max length is 15
|
||||
const char *name; // max length is 15 (Preferences key limit)
|
||||
bool integer;
|
||||
union { float *f; int *i; }; // pointer to the variable
|
||||
union { float *f; int *i; }; // pointer to variable
|
||||
float cache; // what's stored in flash
|
||||
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
|
||||
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
|
||||
@@ -49,9 +49,6 @@ Parameter parameters[] = {
|
||||
{"CTL_R_RATE_MAX", &maxRate.x},
|
||||
{"CTL_Y_RATE_MAX", &maxRate.z},
|
||||
{"CTL_TILT_MAX", &tiltMax},
|
||||
{"CTL_FLT_MODE_0", &flightModes[0]},
|
||||
{"CTL_FLT_MODE_1", &flightModes[1]},
|
||||
{"CTL_FLT_MODE_2", &flightModes[2]},
|
||||
// imu
|
||||
{"IMU_ROT_ROLL", &imuRotation.x},
|
||||
{"IMU_ROT_PITCH", &imuRotation.y},
|
||||
@@ -112,7 +109,6 @@ Parameter parameters[] = {
|
||||
};
|
||||
|
||||
void setupParameters() {
|
||||
print("Setup parameters\n");
|
||||
storage.begin("flix", false);
|
||||
// Read parameters from storage
|
||||
for (auto ¶meter : parameters) {
|
||||
@@ -124,6 +120,11 @@ void setupParameters() {
|
||||
}
|
||||
}
|
||||
|
||||
void afterParameterChange(String name, const float value) {
|
||||
if (name == "MOT_PWM_FREQ" || name == "MOT_PWM_RES") setupMotors();
|
||||
if (name == "MOT_PIN_FL" || name == "MOT_PIN_FR" || name == "MOT_PIN_RL" || name == "MOT_PIN_RR") setupMotors();
|
||||
}
|
||||
|
||||
int parametersCount() {
|
||||
return sizeof(parameters) / sizeof(parameters[0]);
|
||||
}
|
||||
@@ -152,6 +153,7 @@ bool setParameter(const char *name, const float value) {
|
||||
if (strcasecmp(parameter.name, name) == 0) {
|
||||
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
|
||||
parameter.setValue(value);
|
||||
afterParameterChange(name, value);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -165,6 +165,7 @@ void delay(uint32_t ms) {
|
||||
|
||||
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { 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 __resetTime = 0;
|
||||
|
||||
@@ -9,7 +9,6 @@
|
||||
#include "quaternion.h"
|
||||
#include "Arduino.h"
|
||||
#include "wifi.h"
|
||||
#include "lpf.h"
|
||||
|
||||
extern float t, dt;
|
||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||
@@ -20,7 +19,6 @@ extern float motors[4];
|
||||
|
||||
Vector gyro, acc, imuRotation;
|
||||
Vector accBias, gyroBias, accScale(1, 1, 1);
|
||||
LowPassFilter<Vector> gyroBiasFilter(0);
|
||||
|
||||
// declarations
|
||||
void step();
|
||||
|
||||
@@ -11,10 +11,9 @@
|
||||
#include <sys/poll.h>
|
||||
#include <gazebo/gazebo.hh>
|
||||
|
||||
int wifiMode = 1; // mock
|
||||
int udpLocalPort = 14580;
|
||||
int udpRemotePort = 14550;
|
||||
const char *udpRemoteIP = "255.255.255.255";
|
||||
#define WIFI_UDP_PORT 14580
|
||||
#define WIFI_UDP_REMOTE_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
||||
|
||||
int wifiSocket;
|
||||
|
||||
@@ -23,22 +22,22 @@ void setupWiFi() {
|
||||
sockaddr_in addr; // local address
|
||||
addr.sin_family = AF_INET;
|
||||
addr.sin_addr.s_addr = INADDR_ANY;
|
||||
addr.sin_port = htons(udpLocalPort);
|
||||
addr.sin_port = htons(WIFI_UDP_PORT);
|
||||
if (bind(wifiSocket, (sockaddr *)&addr, sizeof(addr))) {
|
||||
gzerr << "Failed to bind WiFi UDP socket on port " << udpLocalPort << std::endl;
|
||||
gzerr << "Failed to bind WiFi UDP socket on port " << WIFI_UDP_PORT << std::endl;
|
||||
return;
|
||||
}
|
||||
int broadcast = 1;
|
||||
setsockopt(wifiSocket, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)); // enable broadcast
|
||||
gzmsg << "WiFi UDP socket initialized on port " << udpLocalPort << " (remote port " << udpRemotePort << ")" << std::endl;
|
||||
gzmsg << "WiFi UDP socket initialized on port " << WIFI_UDP_PORT << " (remote port " << WIFI_UDP_REMOTE_PORT << ")" << std::endl;
|
||||
}
|
||||
|
||||
void sendWiFi(const uint8_t *buf, int len) {
|
||||
if (wifiSocket == 0) setupWiFi();
|
||||
sockaddr_in addr; // remote address
|
||||
addr.sin_family = AF_INET;
|
||||
addr.sin_addr.s_addr = inet_addr(udpRemoteIP);
|
||||
addr.sin_port = htons(udpRemotePort);
|
||||
addr.sin_addr.s_addr = inet_addr(WIFI_UDP_REMOTE_ADDR);
|
||||
addr.sin_port = htons(WIFI_UDP_REMOTE_PORT);
|
||||
sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr));
|
||||
}
|
||||
|
||||
|
||||
@@ -138,7 +138,7 @@ class Flix:
|
||||
while True:
|
||||
try:
|
||||
msg: Optional[mavlink.MAVLink_message] = self.connection.recv_match(blocking=True)
|
||||
if msg is None or msg.get_srcSystem() != self.system_id:
|
||||
if msg is None:
|
||||
continue
|
||||
self._connected()
|
||||
msg_dict = msg.to_dict()
|
||||
|
||||
Reference in New Issue
Block a user