mirror of
https://github.com/okalachev/flix.git
synced 2026-03-31 04:24:23 +00:00
Compare commits
4 Commits
robolager
...
8e043555c5
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
8e043555c5 | ||
|
|
c39e2ca998 | ||
|
|
f46842f341 | ||
|
|
3d72224b32 |
@@ -40,7 +40,6 @@ const char* motd =
|
|||||||
"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";
|
||||||
@@ -143,10 +142,6 @@ 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 pilot commands yaw rate
|
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or yaw rate is set
|
||||||
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)); // stop motors if no thrust
|
memset(motors, 0, sizeof(motors));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -3,9 +3,7 @@
|
|||||||
|
|
||||||
// Fail-safe functions
|
// Fail-safe functions
|
||||||
|
|
||||||
#include "util.h"
|
#define RC_LOSS_TIMEOUT 0.2
|
||||||
|
|
||||||
#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;
|
||||||
@@ -30,7 +28,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 && invalid(controlMode)) {
|
if (mode == AUTO && !isfinite(controlMode)) {
|
||||||
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 = 1;
|
float mavlinkControlScale = 0.7;
|
||||||
String mavlinkPrintBuffer;
|
String mavlinkPrintBuffer;
|
||||||
|
|
||||||
extern double controlTime;
|
extern double controlTime;
|
||||||
@@ -231,12 +231,6 @@ 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);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -13,7 +13,6 @@
|
|||||||
#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;
|
||||||
|
|
||||||
@@ -25,9 +24,7 @@ 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;
|
||||||
IPAddress remote = WiFi.softAPBroadcastIP();
|
udp.beginPacket(WiFi.softAPBroadcastIP(), WIFI_UDP_REMOTE_PORT);
|
||||||
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();
|
||||||
}
|
}
|
||||||
@@ -37,13 +34,4 @@ 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,5 +72,4 @@ 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,10 +173,6 @@ 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.6"
|
version = "0.5"
|
||||||
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