mirror of
https://github.com/okalachev/flix.git
synced 2026-03-29 19:43:31 +00:00
Compare commits
2 Commits
0730ceeffa
...
c434107eaf
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
c434107eaf | ||
|
|
814427dbfd |
@@ -13,7 +13,7 @@ Do the following:
|
||||
Do the following:
|
||||
|
||||
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
|
||||
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 startup output.
|
||||
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button or `reboot` command to see the whole startup output.
|
||||
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200.
|
||||
* **Make sure correct IMU model is chosen**. If using ICM-20948/MPU-6050 board, change `MPU9250` to `ICM20948`/`MPU6050` in the `imu.ino` file.
|
||||
* **Check if the console is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the console using QGroundControl *(Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console)*.
|
||||
@@ -35,5 +35,7 @@ Do the following:
|
||||
* **Check the propeller directions are correct**. Make sure your propeller types (A or B) are installed as on the picture:
|
||||
<img src="img/user/peter_ukhov-2/1.jpg" width="200">
|
||||
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
|
||||
* If using SBUS receiver, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions.
|
||||
* **If using SBUS receiver**:
|
||||
* **Define the used GPIO pin** in `RC_RX_PIN` parameter.
|
||||
* **Calibrate the RC** using `cr` command in the console.
|
||||
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -195,11 +193,13 @@ There are several ways to control the drone's flight: using **smartphone** (Wi-F
|
||||
|
||||
### Control with a remote control
|
||||
|
||||
Before using remote SBUS-connected remote control, you need to calibrate it:
|
||||
Before using SBUS-connected remote control you need to enable SBUS and calibrate it:
|
||||
|
||||
1. Access the console using QGroundControl (recommended) or Serial Monitor.
|
||||
2. Type `cr` command and follow the instructions.
|
||||
3. Use the remote control to fly the drone!
|
||||
1. Connect to the drone using QGroundControl.
|
||||
2. In parameters, set the `RC_RX_PIN` parameter to the GPIO pin number where the SBUS signal is connected, for example: 4. Negative value disables SBUS.
|
||||
3. Reboot the drone to apply changes.
|
||||
4. Open the console, type `cr` command and follow the instructions to calibrate the remote control.
|
||||
5. Use the remote control to fly the drone!
|
||||
|
||||
### Control with a USB remote control
|
||||
|
||||
|
||||
@@ -9,6 +9,7 @@
|
||||
extern int channelZero[16];
|
||||
extern int channelMax[16];
|
||||
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||
extern int rcRxPin;
|
||||
extern int wifiMode, udpLocalPort, udpRemotePort;
|
||||
extern float rcLossTimeout, descendTime;
|
||||
|
||||
@@ -78,6 +79,7 @@ Parameter parameters[] = {
|
||||
{"MOT_PWM_MIN", &pwmMin},
|
||||
{"MOT_PWM_MAX", &pwmMax},
|
||||
// rc
|
||||
{"RC_RX_PIN", &rcRxPin},
|
||||
{"RC_ZERO_0", &channelZero[0]},
|
||||
{"RC_ZERO_1", &channelZero[1]},
|
||||
{"RC_ZERO_2", &channelZero[2]},
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
#include "util.h"
|
||||
|
||||
SBUS rc(Serial2);
|
||||
int rcRxPin = -1; // -1 means disabled
|
||||
|
||||
uint16_t channels[16]; // raw rc channels
|
||||
int channelZero[16]; // calibration zero values
|
||||
@@ -19,11 +20,13 @@ float controlTime = NAN; // time of the last controls update
|
||||
int rollChannel = -1, pitchChannel = -1, throttleChannel = -1, yawChannel = -1, modeChannel = -1; // channel mapping
|
||||
|
||||
void setupRC() {
|
||||
if (rcRxPin < 0) return;
|
||||
print("Setup RC\n");
|
||||
rc.begin();
|
||||
rc.begin(rcRxPin);
|
||||
}
|
||||
|
||||
bool readRC() {
|
||||
if (rcRxPin < 0) return false;
|
||||
if (rc.read()) {
|
||||
SBUSData data = rc.data();
|
||||
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
|
||||
@@ -48,6 +51,10 @@ void normalizeRC() {
|
||||
}
|
||||
|
||||
void calibrateRC() {
|
||||
if (rcRxPin < 0) {
|
||||
print("RC_RX_PIN = %d, set the RC pin!\n", rcRxPin);
|
||||
return;
|
||||
}
|
||||
uint16_t zero[16];
|
||||
uint16_t center[16];
|
||||
uint16_t max[16];
|
||||
|
||||
@@ -13,7 +13,7 @@ class SBUS {
|
||||
public:
|
||||
SBUS(HardwareSerial& bus, const bool inv = true) {};
|
||||
SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {};
|
||||
void begin() {};
|
||||
void begin(int rxpin = -1, int txpin = -1, bool inv = true, bool fast = false) {};
|
||||
bool read() { return joystickInit(); };
|
||||
SBUSData data() {
|
||||
SBUSData data;
|
||||
|
||||
Reference in New Issue
Block a user