mirror of
https://github.com/okalachev/flix.git
synced 2026-01-11 05:26:53 +00:00
Compare commits
12 Commits
dfceb8a6b2
...
robolager
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
d180a5d809 | ||
|
|
8762ae0b38 | ||
|
|
2fcf35289e | ||
|
|
af86699eb3 | ||
|
|
496888903f | ||
|
|
3cde9e69c4 | ||
|
|
310b48f856 | ||
|
|
ce3e47d1ec | ||
|
|
cc362c1d4b | ||
|
|
fc4feb8503 | ||
|
|
3bbace6a1e | ||
|
|
a090e3543c |
10
flix/cli.ino
10
flix/cli.ino
@@ -32,14 +32,15 @@ const char* motd =
|
|||||||
"ps - show pitch/roll/yaw\n"
|
"ps - show pitch/roll/yaw\n"
|
||||||
"psq - show attitude quaternion\n"
|
"psq - show attitude quaternion\n"
|
||||||
"imu - show IMU data\n"
|
"imu - show IMU data\n"
|
||||||
"arm - arm the drone (when no mode switch)\n"
|
"arm - arm the drone (when no armed switch)\n"
|
||||||
"disarm - disarm the drone (when no mode switch)\n"
|
"disarm - disarm the drone (when no armed switch)\n"
|
||||||
"rc - show RC data\n"
|
"rc - show RC data\n"
|
||||||
"mot - show motor output\n"
|
"mot - show motor output\n"
|
||||||
"log - dump in-RAM log\n"
|
"log - dump in-RAM log\n"
|
||||||
"cr - calibrate RC\n"
|
"cr - calibrate RC\n"
|
||||||
"ca - calibrate accel\n"
|
"ca - calibrate accel\n"
|
||||||
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
|
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
|
||||||
|
"wifi - show Wi-Fi info\n"
|
||||||
"sys - show system info\n"
|
"sys - show system info\n"
|
||||||
"reset - reset drone's state\n"
|
"reset - reset drone's state\n"
|
||||||
"reboot - reboot the drone\n";
|
"reboot - reboot the drone\n";
|
||||||
@@ -124,6 +125,7 @@ void doCommand(String str, bool echo = false) {
|
|||||||
print("\nroll: %g pitch: %g yaw: %g throttle: %g armed: %g mode: %g\n",
|
print("\nroll: %g pitch: %g yaw: %g throttle: %g armed: %g mode: %g\n",
|
||||||
controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode);
|
controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode);
|
||||||
print("mode: %s\n", getModeName());
|
print("mode: %s\n", getModeName());
|
||||||
|
print("armed: %d\n", armed);
|
||||||
} else if (command == "mot") {
|
} else if (command == "mot") {
|
||||||
print("front-right %g front-left %g rear-right %g rear-left %g\n",
|
print("front-right %g front-left %g rear-right %g rear-left %g\n",
|
||||||
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
|
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
|
||||||
@@ -141,6 +143,10 @@ void doCommand(String str, bool echo = false) {
|
|||||||
testMotor(MOTOR_REAR_RIGHT);
|
testMotor(MOTOR_REAR_RIGHT);
|
||||||
} else if (command == "mrl") {
|
} else if (command == "mrl") {
|
||||||
testMotor(MOTOR_REAR_LEFT);
|
testMotor(MOTOR_REAR_LEFT);
|
||||||
|
} else if (command == "wifi") {
|
||||||
|
#if WIFI_ENABLED
|
||||||
|
printWiFiInfo();
|
||||||
|
#endif
|
||||||
} else if (command == "sys") {
|
} else if (command == "sys") {
|
||||||
#ifdef ESP32
|
#ifdef ESP32
|
||||||
print("Chip: %s\n", ESP.getChipModel());
|
print("Chip: %s\n", ESP.getChipModel());
|
||||||
|
|||||||
@@ -79,7 +79,7 @@ void interpretControls() {
|
|||||||
|
|
||||||
if (mode == STAB) {
|
if (mode == STAB) {
|
||||||
float yawTarget = attitudeTarget.getYaw();
|
float yawTarget = attitudeTarget.getYaw();
|
||||||
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or yaw rate is set
|
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or pilot commands yaw rate
|
||||||
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
|
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
|
||||||
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
|
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
|
||||||
}
|
}
|
||||||
@@ -139,7 +139,7 @@ void controlTorque() {
|
|||||||
if (!torqueTarget.valid()) return; // skip torque control
|
if (!torqueTarget.valid()) return; // skip torque control
|
||||||
|
|
||||||
if (!armed || thrustTarget < 0.05) {
|
if (!armed || thrustTarget < 0.05) {
|
||||||
memset(motors, 0, sizeof(motors));
|
memset(motors, 0, sizeof(motors)); // stop motors if no thrust
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -3,7 +3,9 @@
|
|||||||
|
|
||||||
// Fail-safe functions
|
// Fail-safe functions
|
||||||
|
|
||||||
#define RC_LOSS_TIMEOUT 0.2
|
#include "util.h"
|
||||||
|
|
||||||
|
#define RC_LOSS_TIMEOUT 0.5
|
||||||
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
|
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
|
||||||
|
|
||||||
extern double controlTime;
|
extern double controlTime;
|
||||||
@@ -28,8 +30,7 @@ void autoFailsafe() {
|
|||||||
static float roll, pitch, yaw, throttle;
|
static float roll, pitch, yaw, throttle;
|
||||||
|
|
||||||
if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) {
|
if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) {
|
||||||
if (mode == AUTO && !isfinite(controlMode)) {
|
if (mode == AUTO && invalid(controlMode)) {
|
||||||
print("Failsafe: regain control to pilot\n");
|
|
||||||
mode = STAB; // regain control to the pilot
|
mode = STAB; // regain control to the pilot
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -12,7 +12,7 @@
|
|||||||
#define PERIOD_FAST 0.1
|
#define PERIOD_FAST 0.1
|
||||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
||||||
|
|
||||||
float mavlinkControlScale = 0.7;
|
float mavlinkControlScale = 1;
|
||||||
String mavlinkPrintBuffer;
|
String mavlinkPrintBuffer;
|
||||||
|
|
||||||
extern double controlTime;
|
extern double controlTime;
|
||||||
@@ -231,6 +231,12 @@ void handleMavlink(const void *_msg) {
|
|||||||
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
|
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
|
||||||
sendMessage(&ack);
|
sendMessage(&ack);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (m.command == MAV_CMD_COMPONENT_ARM_DISARM) {
|
||||||
|
armed = m.param1 == 1;
|
||||||
|
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
|
||||||
|
sendMessage(&ack);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -42,7 +42,7 @@ void normalizeRC() {
|
|||||||
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
|
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
|
||||||
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
|
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
|
||||||
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
|
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
|
||||||
controlArmed = armedChannel >= 0 ? controls[(int)armedChannel] : 1; // assume armed by default
|
controlArmed = armedChannel >= 0 ? controls[(int)armedChannel] : NAN;
|
||||||
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
|
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -19,6 +19,14 @@ float mapff(float x, float in_min, float in_max, float out_min, float out_max) {
|
|||||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool invalid(float x) {
|
||||||
|
return !isfinite(x);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool valid(float x) {
|
||||||
|
return isfinite(x);
|
||||||
|
}
|
||||||
|
|
||||||
// Wrap angle to [-PI, PI)
|
// Wrap angle to [-PI, PI)
|
||||||
float wrapAngle(float angle) {
|
float wrapAngle(float angle) {
|
||||||
angle = fmodf(angle, 2 * PI);
|
angle = fmodf(angle, 2 * PI);
|
||||||
|
|||||||
@@ -13,6 +13,7 @@
|
|||||||
#define WIFI_PASSWORD "flixwifi"
|
#define WIFI_PASSWORD "flixwifi"
|
||||||
#define WIFI_UDP_PORT 14550
|
#define WIFI_UDP_PORT 14550
|
||||||
#define WIFI_UDP_REMOTE_PORT 14550
|
#define WIFI_UDP_REMOTE_PORT 14550
|
||||||
|
#define WIFI_UDP_ALWAYS_BROADCAST 1
|
||||||
|
|
||||||
WiFiUDP udp;
|
WiFiUDP udp;
|
||||||
|
|
||||||
@@ -24,7 +25,9 @@ void setupWiFi() {
|
|||||||
|
|
||||||
void sendWiFi(const uint8_t *buf, int len) {
|
void sendWiFi(const uint8_t *buf, int len) {
|
||||||
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
|
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
|
||||||
udp.beginPacket(WiFi.softAPBroadcastIP(), WIFI_UDP_REMOTE_PORT);
|
IPAddress remote = WiFi.softAPBroadcastIP();
|
||||||
|
if (!WIFI_UDP_ALWAYS_BROADCAST && udp.remoteIP()) remote = udp.remoteIP();
|
||||||
|
udp.beginPacket(remote, WIFI_UDP_REMOTE_PORT);
|
||||||
udp.write(buf, len);
|
udp.write(buf, len);
|
||||||
udp.endPacket();
|
udp.endPacket();
|
||||||
}
|
}
|
||||||
@@ -34,4 +37,13 @@ int receiveWiFi(uint8_t *buf, int len) {
|
|||||||
return udp.read(buf, len);
|
return udp.read(buf, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void printWiFiInfo() {
|
||||||
|
print("SSID: %s\n", WiFi.softAPSSID().c_str());
|
||||||
|
print("Clients: %d\n", WiFi.softAPgetStationNum());
|
||||||
|
print("Status: %d\n", WiFi.status());
|
||||||
|
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
|
||||||
|
print("Remote IP: %s\n", udp.remoteIP().toString().c_str());
|
||||||
|
print("Broadcast IP: %s\n", WiFi.softAPBroadcastIP().toString().c_str());
|
||||||
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -72,4 +72,5 @@ void calibrateGyro() { print("Skip gyro calibrating\n"); };
|
|||||||
void calibrateAccel() { print("Skip accel calibrating\n"); };
|
void calibrateAccel() { print("Skip accel calibrating\n"); };
|
||||||
void printIMUCalibration() { print("cal: N/A\n"); };
|
void printIMUCalibration() { print("cal: N/A\n"); };
|
||||||
void printIMUInfo() {};
|
void printIMUInfo() {};
|
||||||
|
void printWiFiInfo() {};
|
||||||
Vector accBias, gyroBias, accScale(1, 1, 1);
|
Vector accBias, gyroBias, accScale(1, 1, 1);
|
||||||
|
|||||||
@@ -173,6 +173,10 @@ class Flix:
|
|||||||
self.motors = msg.controls[:4] # type: ignore
|
self.motors = msg.controls[:4] # type: ignore
|
||||||
self._trigger('motors', self.motors)
|
self._trigger('motors', self.motors)
|
||||||
|
|
||||||
|
# TODO: to be removed: the old way of passing motor outputs
|
||||||
|
if isinstance(msg, mavlink.MAVLink_actuator_output_status_message):
|
||||||
|
self.motors = msg.actuator[:4] # type: ignore
|
||||||
|
|
||||||
if isinstance(msg, mavlink.MAVLink_scaled_imu_message):
|
if isinstance(msg, mavlink.MAVLink_scaled_imu_message):
|
||||||
self.acc = self._mavlink_to_flu([msg.xacc / 1000, msg.yacc / 1000, msg.zacc / 1000])
|
self.acc = self._mavlink_to_flu([msg.xacc / 1000, msg.yacc / 1000, msg.zacc / 1000])
|
||||||
self.gyro = self._mavlink_to_flu([msg.xgyro / 1000, msg.ygyro / 1000, msg.zgyro / 1000])
|
self.gyro = self._mavlink_to_flu([msg.xgyro / 1000, msg.ygyro / 1000, msg.zgyro / 1000])
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
[project]
|
[project]
|
||||||
name = "pyflix"
|
name = "pyflix"
|
||||||
version = "0.5"
|
version = "0.6"
|
||||||
description = "Python API for Flix drone"
|
description = "Python API for Flix drone"
|
||||||
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
||||||
license = "MIT"
|
license = "MIT"
|
||||||
|
|||||||
Reference in New Issue
Block a user