mirror of
https://github.com/okalachev/flix.git
synced 2026-01-12 05:57:52 +00:00
Add parameters to config.h
This commit is contained in:
@@ -1 +1,55 @@
|
|||||||
|
// Wi-Fi
|
||||||
#define WIFI_ENABLED 1
|
#define WIFI_ENABLED 1
|
||||||
|
#define WIFI_SSID "flix"
|
||||||
|
#define WIFI_PASSWORD "flixwifi"
|
||||||
|
#define WIFI_UDP_PORT 14550
|
||||||
|
#define WIFI_UDP_REMOTE_PORT 14550
|
||||||
|
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
||||||
|
|
||||||
|
// Motors
|
||||||
|
#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
|
||||||
|
|
||||||
|
// Control
|
||||||
|
#define PITCHRATE_P 0.05
|
||||||
|
#define PITCHRATE_I 0.2
|
||||||
|
#define PITCHRATE_D 0.001
|
||||||
|
#define PITCHRATE_I_LIM 0.3
|
||||||
|
#define ROLLRATE_P PITCHRATE_P
|
||||||
|
#define ROLLRATE_I PITCHRATE_I
|
||||||
|
#define ROLLRATE_D PITCHRATE_D
|
||||||
|
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
|
||||||
|
#define YAWRATE_P 0.3
|
||||||
|
#define YAWRATE_I 0.0
|
||||||
|
#define YAWRATE_D 0.0
|
||||||
|
#define YAWRATE_I_LIM 0.3
|
||||||
|
#define ROLL_P 6
|
||||||
|
#define ROLL_I 0
|
||||||
|
#define ROLL_D 0
|
||||||
|
#define PITCH_P ROLL_P
|
||||||
|
#define PITCH_I ROLL_I
|
||||||
|
#define PITCH_D ROLL_D
|
||||||
|
#define YAW_P 3
|
||||||
|
#define PITCHRATE_MAX radians(360)
|
||||||
|
#define ROLLRATE_MAX radians(360)
|
||||||
|
#define YAWRATE_MAX radians(300)
|
||||||
|
#define TILT_MAX radians(30)
|
||||||
|
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||||
|
|
||||||
|
// Estimation
|
||||||
|
#define WEIGHT_ACC 0.003
|
||||||
|
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||||
|
|
||||||
|
// MAVLink
|
||||||
|
#define SYSTEM_ID 1
|
||||||
|
|
||||||
|
// Safety
|
||||||
|
#define RC_LOSS_TIMEOUT 1
|
||||||
|
#define DESCEND_TIME 10
|
||||||
|
|||||||
@@ -3,37 +3,13 @@
|
|||||||
|
|
||||||
// Flight control
|
// Flight control
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "pid.h"
|
#include "pid.h"
|
||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define PITCHRATE_P 0.05
|
|
||||||
#define PITCHRATE_I 0.2
|
|
||||||
#define PITCHRATE_D 0.001
|
|
||||||
#define PITCHRATE_I_LIM 0.3
|
|
||||||
#define ROLLRATE_P PITCHRATE_P
|
|
||||||
#define ROLLRATE_I PITCHRATE_I
|
|
||||||
#define ROLLRATE_D PITCHRATE_D
|
|
||||||
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
|
|
||||||
#define YAWRATE_P 0.3
|
|
||||||
#define YAWRATE_I 0.0
|
|
||||||
#define YAWRATE_D 0.0
|
|
||||||
#define YAWRATE_I_LIM 0.3
|
|
||||||
#define ROLL_P 6
|
|
||||||
#define ROLL_I 0
|
|
||||||
#define ROLL_D 0
|
|
||||||
#define PITCH_P ROLL_P
|
|
||||||
#define PITCH_I ROLL_I
|
|
||||||
#define PITCH_D ROLL_D
|
|
||||||
#define YAW_P 3
|
|
||||||
#define PITCHRATE_MAX radians(360)
|
|
||||||
#define ROLLRATE_MAX radians(360)
|
|
||||||
#define YAWRATE_MAX radians(300)
|
|
||||||
#define TILT_MAX radians(30)
|
|
||||||
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
|
||||||
|
|
||||||
extern const int MANUAL = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
extern const int MANUAL = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
||||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||||
|
|
||||||
|
|||||||
@@ -3,15 +3,13 @@
|
|||||||
|
|
||||||
// Attitude estimation from gyro and accelerometer
|
// Attitude estimation from gyro and accelerometer
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
#include "flix.h"
|
#include "flix.h"
|
||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define WEIGHT_ACC 0.003
|
|
||||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
|
||||||
|
|
||||||
Vector rates; // filtered angular rates, rad/s
|
Vector rates; // filtered angular rates, rad/s
|
||||||
Quaternion attitude; // estimated attitude
|
Quaternion attitude; // estimated attitude
|
||||||
bool landed; // are we landed and stationary
|
bool landed; // are we landed and stationary
|
||||||
|
|||||||
@@ -11,11 +11,8 @@
|
|||||||
|
|
||||||
MPU9250 imu(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
|
||||||
Vector gyro; // gyroscope data
|
Vector gyro, gyroBias;
|
||||||
Vector gyroBias; // gyroscope bias
|
Vector acc, accBias, accScale(1, 1, 1);
|
||||||
Vector acc; // accelerometer data, m/s/s
|
|
||||||
Vector accBias; // accelerometer bias
|
|
||||||
Vector accScale(1, 1, 1); // accelerometer scale
|
|
||||||
|
|
||||||
extern float loopRate;
|
extern float loopRate;
|
||||||
|
|
||||||
|
|||||||
@@ -4,14 +4,13 @@
|
|||||||
// MAVLink communication
|
// MAVLink communication
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "flix.h"
|
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
|
#include "flix.h"
|
||||||
|
|
||||||
#if WIFI_ENABLED
|
#if WIFI_ENABLED
|
||||||
|
|
||||||
#include <MAVLink.h>
|
#include <MAVLink.h>
|
||||||
|
|
||||||
#define SYSTEM_ID 1
|
|
||||||
#define PERIOD_SLOW 1.0
|
#define PERIOD_SLOW 1.0
|
||||||
#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
|
||||||
|
|||||||
@@ -5,20 +5,10 @@
|
|||||||
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
|
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
#include "config.h"
|
||||||
#include "flix.h"
|
#include "flix.h"
|
||||||
#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 motors thrust in range [0..1]
|
float motors[4]; // normalized motors thrust in range [0..1]
|
||||||
extern const int MOTOR_REAR_LEFT = 0;
|
extern const int MOTOR_REAR_LEFT = 0;
|
||||||
extern const int MOTOR_REAR_RIGHT = 1;
|
extern const int MOTOR_REAR_RIGHT = 1;
|
||||||
|
|||||||
@@ -3,11 +3,9 @@
|
|||||||
|
|
||||||
// Fail-safe functions
|
// Fail-safe functions
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
#include "flix.h"
|
#include "flix.h"
|
||||||
|
|
||||||
#define RC_LOSS_TIMEOUT 1
|
|
||||||
#define DESCEND_TIME 10
|
|
||||||
|
|
||||||
extern float controlTime;
|
extern float controlTime;
|
||||||
extern const int AUTO, STAB;
|
extern const int AUTO, STAB;
|
||||||
|
|
||||||
|
|||||||
@@ -12,12 +12,6 @@
|
|||||||
#include <WiFiAP.h>
|
#include <WiFiAP.h>
|
||||||
#include <WiFiUdp.h>
|
#include <WiFiUdp.h>
|
||||||
|
|
||||||
#define WIFI_SSID "flix"
|
|
||||||
#define WIFI_PASSWORD "flixwifi"
|
|
||||||
#define WIFI_UDP_PORT 14550
|
|
||||||
#define WIFI_UDP_REMOTE_PORT 14550
|
|
||||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
|
||||||
|
|
||||||
WiFiUDP udp;
|
WiFiUDP udp;
|
||||||
|
|
||||||
void setupWiFi() {
|
void setupWiFi() {
|
||||||
|
|||||||
Reference in New Issue
Block a user