Everything you need to know about FLYQ Air & FLYQ Vision
From unboxing to autonomous flight programming
Get flying in 30 minutes
Components & specifications
Arduino, Python, ESP-IDF
Installation & configuration
Safety, calibration & flying
Common issues & solutions
Complete function library
Inspiration & examples
Get help & connect
• Open-source hardware designs
• Firmware source code
• Circuit schematics
• 3D printable parts
• Authorized dealer
• Original products
• India-wide shipping
• Technical support
• Instant chat support
• Community group
• Quick troubleshooting
• +91 9137361474
From unboxing to your first flight in 30 minutes
Carefully open your FLYQ package and verify all components are present:
Important: Keep propellers away from motors until you're ready to fly. Store battery safely at room temperature.
Before your first flight, fully charge the LiPo battery:
DON'T:
DO:
Choose your preferred programming environment:
Easy-to-use IDE with extensive libraries
Crazyflie-compatible Python library
Professional development framework
git clone https://github.com/passion3d/flyq-firmwareidf.py menuconfigidf.py build flashEstablish connection and calibrate sensors:
FLYQ-XXXXflyq1234http://192.168.4.1Tip: Calibrate IMU before every flight session for best stability
Ready for takeoff? Follow these safety steps:
Follow along with our step-by-step video guide for a successful maiden flight
Watch on YouTubeCongratulations on your first flight! Now continue learning with our comprehensive documentation and project ideas below.
Arduino, Python, and ESP-IDF examples with step-by-step guides
Complete hardware specs, firmware flashing, and problem solutions
Beginner to advanced projects with examples and inspiration
Your FLYQ drone is ready to fly. Start with basic flights, then progress to autonomous missions. Join our community for support!
Complete technical reference for FLYQ Air & FLYQ Vision drone hardware
Basic Programmable Drone
| CPU | ESP32-S3 Dual-Core Xtensa LX7 @ 240MHz |
| SRAM | 512KB on-chip |
| Flash | 4MB external |
| Architecture | 32-bit with FPU |
| Wi-Fi | 802.11 b/g/n 2.4GHz |
| Bluetooth | BLE 5.0 Long Range |
| Range | 50m (open space) |
| USB | Type-C (data + charging) |
| IMU | MPU6050 6-axis (Gyro + Accel) |
| Gyroscope | ±250/500/1000/2000 °/s |
| Accelerometer | ±2/4/8/16 g |
| Sample Rate | 1kHz max |
| Motors | 4x 720 coreless DC motors |
| Max RPM | 38,000 RPM |
| Voltage | 3.7V nominal |
| Control | PWM via MOSFET H-bridge |
| Battery | 1S LiPo 3.7V 600mAh |
| Flight Time | 8-10 minutes |
| Charge Time | ~45 minutes (5V 1A) |
| Protection | Over-charge, over-discharge |
| Size | 92 x 92 x 20mm |
| Weight | ~45g (w/o battery) |
| Propellers | 4 x 45mm diameter |
| Frame | Lightweight plastic + PCB |
| Connector | 24-pin 2.54mm header |
| GPIO | 18 available pins |
| I2C | 1x bus (sensors) |
| SPI | 1x bus (expansion modules) |
| UART | 2x serial ports |
| ADC | 6x channels, 12-bit |
Camera & Vision AI Drone
| Sensor | OV2640 2MP CMOS |
| Resolution | 1280 x 720 (HD 720p) |
| Frame Rate | 30 FPS |
| FOV | 120° wide angle |
| Streaming | Real-time Wi-Fi MJPEG |
| PSRAM | 8MB for frame buffers |
| AI Accelerator | Vector instructions |
| Gesture Recognition | Hand tracking, poses |
| Latency | < 200ms streaming |
| CPU | ESP32-S3 Dual-Core @ 240MHz |
| SRAM | 512KB on-chip |
| PSRAM | 8MB external |
| Flash | 4MB SPI flash |
| Wi-Fi | 802.11 b/g/n dual antenna |
| Video Streaming | HD 720p @ 30fps |
| Range | 50m with video |
| Protocols | UDP, WebSocket, RTSP |
| Arduino IDE | ✓ Full support + camera libs |
| Python SDK | ✓ OpenCV integration |
| ESP-IDF | ✓ Advanced firmware |
| Mobile App | iOS & Android (WebRTC) |
| Battery | 1S LiPo 3.7V 600mAh |
| Flight Time | 7-9 min (with camera) |
| Weight | ~52g (w/ camera) |
| Power Draw | Higher due to camera |
Our technical team is here to help with any hardware questions
Professional drone engineering made accessible for education and development
FLYQ drones are designed with education in mind. Unlike expensive commercial drones, FLYQ provides professional-grade hardware at student-friendly prices. All components are clearly labeled, and assembly takes just 30 minutes with our step-by-step guide.
Snap-together components with clear markings - no soldering required for basic assembly
Starting at ₹8,999 - 10x cheaper than commercial alternatives like DJI Tello
Video tutorials, illustrated guides, and 24/7 community support
Assembly Time: 30 minutes for beginners
Control from any device with a web browser - no app installation required
Write autonomous flight programs using CrazyFlie Python API
Connect any USB gamepad for manual flight control
Build your own control apps using WebSocket API
FLYQ uses WiFi for control - eliminating the need for expensive radio transmitters. Connect your smartphone, tablet, or laptop to the drone's WiFi hotspot and control it through a web interface or Python scripts.
20-30ms response time - fast enough for manual flight and real-time control
Reliable 2.4GHz WiFi connection up to 50 meters (line of sight)
FLYQ Vision streams 720p video @ 30fps directly to your device (WiFi Vision model only)
FLYQ features a professional expansion connector supporting multiple communication protocols:
Expand your FLYQ with professional-grade sensors:
Use existing CrazyFlie Python scripts with FLYQ
Compatible with CrazyFlie Python library - no code changes needed
Run waypoint navigation, formations, and advanced maneuvers
Access thousands of example projects and tutorials
Complete guides for Arduino, Python, and ESP-IDF development
Perfect for beginners • Rapid prototyping • Extensive libraries
https://espressif.github.io/arduino-esp32/package_esp32_index.jsonSimple program to blink the onboard LED. Perfect first test!
// FLYQ Air - Blink LED Example
#define LED_PIN 2 // Onboard LED on GPIO2
void setup() {
pinMode(LED_PIN, OUTPUT);
Serial.begin(115200);
Serial.println("FLYQ Air - LED Blink Test");
}
void loop() {
digitalWrite(LED_PIN, HIGH); // Turn LED on
Serial.println("LED ON");
delay(1000); // Wait 1 second
digitalWrite(LED_PIN, LOW); // Turn LED off
Serial.println("LED OFF");
delay(1000); // Wait 1 second
}
Upload: Click the Upload button (→) in Arduino IDE. LED should blink once upload completes!
Read gyroscope and accelerometer data from MPU6050 IMU
// FLYQ Air - IMU Reader #include#include MPU6050 mpu; void setup() { Serial.begin(115200); Wire.begin(21, 22); // SDA=21, SCL=22 Serial.println("Initializing IMU..."); mpu.initialize(); if (mpu.testConnection()) { Serial.println("MPU6050 connected!"); } else { Serial.println("MPU6050 connection failed!"); } } void loop() { // Read accelerometer (in g) int16_t ax, ay, az; mpu.getAcceleration(&ax, &ay, &az); // Read gyroscope (in degrees/sec) int16_t gx, gy, gz; mpu.getRotation(&gx, &gy, &gz); // Print values Serial.print("Accel: "); Serial.print(ax/16384.0); Serial.print("g, "); Serial.print(ay/16384.0); Serial.print("g, "); Serial.print(az/16384.0); Serial.println("g"); Serial.print("Gyro: "); Serial.print(gx/131.0); Serial.print("°/s, "); Serial.print(gy/131.0); Serial.print("°/s, "); Serial.print(gz/131.0); Serial.println("°/s"); delay(100); }
Library Required: Install "MPU6050" library via Library Manager (Sketch → Include Library → Manage Libraries)
Control motor speed using PWM signals
// FLYQ Air - Motor Control
#define MOTOR1_PIN 25 // Front-left motor
#define MOTOR2_PIN 26 // Front-right motor
#define MOTOR3_PIN 27 // Rear-left motor
#define MOTOR4_PIN 33 // Rear-right motor
// PWM settings
const int freq = 20000; // 20 kHz
const int resolution = 8; // 8-bit (0-255)
void setup() {
Serial.begin(115200);
// Configure PWM channels
ledcSetup(0, freq, resolution);
ledcSetup(1, freq, resolution);
ledcSetup(2, freq, resolution);
ledcSetup(3, freq, resolution);
// Attach pins to channels
ledcAttachPin(MOTOR1_PIN, 0);
ledcAttachPin(MOTOR2_PIN, 1);
ledcAttachPin(MOTOR3_PIN, 2);
ledcAttachPin(MOTOR4_PIN, 3);
Serial.println("Motor control ready!");
}
void setMotorSpeed(int motor, int speed) {
// Speed: 0-255
ledcWrite(motor, speed);
}
void loop() {
// Gradual speed test
for(int speed = 0; speed <= 255; speed += 5) {
setMotorSpeed(0, speed); // Motor 1
setMotorSpeed(1, speed); // Motor 2
setMotorSpeed(2, speed); // Motor 3
setMotorSpeed(3, speed); // Motor 4
Serial.print("Speed: ");
Serial.println(speed);
delay(100);
}
// Stop motors
for(int i = 0; i < 4; i++) {
setMotorSpeed(i, 0);
}
delay(2000);
}
Safety Warning: Remove propellers before testing motors! Never test with propellers attached to bench.
Autonomous flight • Advanced missions • Crazyflie-compatible
# Install Python 3.8+ (check version)
python --version
# Install cflib (Crazyflie library)
pip install cflib
# Install additional dependencies
pip install numpy matplotlib
# Verify installation
python -c "import cflib; print('cflib version:', cflib.__version__)"
# connect_drone.py
import cflib.crtp
from cflib.crazyflie import Crazyflie
import time
# Initialize drivers
cflib.crtp.init_drivers()
# URI of the drone (radio://0/80/2M/E7E7E7E7E7)
URI = 'radio://0/80/2M'
def connected(link_uri):
print(f'Connected to {link_uri}')
def disconnected(link_uri):
print(f'Disconnected from {link_uri}')
def connection_failed(link_uri, msg):
print(f'Connection failed: {msg}')
# Create Crazyflie object
cf = Crazyflie()
# Add callbacks
cf.connected.add_callback(connected)
cf.disconnected.add_callback(disconnected)
cf.connection_failed.add_callback(connection_failed)
print('Connecting to drone...')
cf.open_link(URI)
# Keep connection alive
time.sleep(5)
# Disconnect
cf.close_link()
print('Connection closed')
# autonomous_flight.py
import cflib.crtp
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
from cflib.positioning.motion_commander import MotionCommander
import time
cflib.crtp.init_drivers()
URI = 'radio://0/80/2M'
def simple_flight():
with SyncCrazyflie(URI, cf=Crazyflie(rw_cache='./cache')) as scf:
with MotionCommander(scf) as mc:
print('Taking off...')
time.sleep(1)
print('Moving forward 0.5m')
mc.forward(0.5)
time.sleep(1)
print('Moving left 0.5m')
mc.left(0.5)
time.sleep(1)
print('Moving back 0.5m')
mc.back(0.5)
time.sleep(1)
print('Moving right 0.5m')
mc.right(0.5)
time.sleep(1)
print('Turning 360°')
mc.turn_right(360)
time.sleep(1)
print('Landing...')
# MotionCommander auto-lands on exit
if __name__ == '__main__':
simple_flight()
print('Flight complete!')
Run: python autonomous_flight.py
Professional firmware • RTOS • Advanced features
# Linux/macOS # Install prerequisites sudo apt-get install git wget flex bison gperf python3 python3-pip \ python3-setuptools cmake ninja-build ccache libffi-dev libssl-dev \ dfu-util libusb-1.0-0 # Download ESP-IDF mkdir -p ~/esp cd ~/esp git clone --recursive https://github.com/espressif/esp-idf.git # Install tools cd ~/esp/esp-idf ./install.sh esp32s3 # Setup environment (add to ~/.bashrc) . $HOME/esp/esp-idf/export.sh # Verify installation idf.py --version
// main.c - FreeRTOS Task Example #include#include "freertos/FreeRTOS.h" #include "freertos/task.h" #include "driver/gpio.h" #define LED_PIN GPIO_NUM_2 void blink_task(void *pvParameter) { gpio_set_direction(LED_PIN, GPIO_MODE_OUTPUT); while(1) { gpio_set_level(LED_PIN, 1); printf("LED ON\n"); vTaskDelay(1000 / portTICK_PERIOD_MS); gpio_set_level(LED_PIN, 0); printf("LED OFF\n"); vTaskDelay(1000 / portTICK_PERIOD_MS); } } void app_main(void) { printf("FLYQ Air - FreeRTOS Example\n"); xTaskCreate(&blink_task, "blink_task", 2048, NULL, 5, NULL); }
Build & Flash: idf.py build flash monitor
Step-by-step guide to flash firmware on your FLYQ drone
Connect your FLYQ to computer. LED should turn on.
File → Examples → FLYQ → BasicFlight
Wait for "Done uploading" message
# Install esptool pip install esptool # Download firmware.bin from GitHub releases wget https://github.com/passion3d/flyq-firmware/releases/latest/download/firmware.bin # Flash firmware esptool.py --chip esp32s3 --port /dev/ttyUSB0 write_flash 0x0 firmware.bin # Verify esptool.py --chip esp32s3 --port /dev/ttyUSB0 verify_flash 0x0 firmware.bin
sudo usermod -a -G dialout $USER (Linux)Complete safety procedures and flight operations guide
Solutions to common issues and problems
Our technical support team is ready to assist you
Complete function library documentation
Initialize FLYQ drone system
Returns: bool - true if successful
FLYQ.init(); // Initialize all sensors and motors
Calibrate IMU on flat surface
Returns: bool - true if successful
Set individual motor speed
Parameters: motor (0-3), speed (0-255)
FLYQ.setMotorSpeed(0, 150); // Motor 1 at 60% speed
Set all motors to same speed
Parameters: value (0-255)
Get IMU sensor data
Returns: IMUData struct with gyro and accel
IMUData data = FLYQ.getIMU();
Serial.print("Gyro X: "); Serial.println(data.gyro.x);
Take off to specified height
Parameters: height (meters, default 0.3)
mc.take_off(0.5) # Take off to 0.5m
Fly forward specified distance
Parameters: distance (meters)
Turn right by angle in degrees
Parameters: angle (degrees, 0-360)
mc.turn_right(90) # Turn 90° right
Land drone at current position
Returns: None
Inspiration and examples for your drone projects
Create custom LED light shows synchronized with flight
Arduino • 1 hourUse ToF sensor to detect and avoid obstacles
Arduino • 2 hoursImplement barometer-based altitude stabilization
Arduino • 3 hoursProgram autonomous flight to GPS waypoints
Python • 1 dayTrack and follow a moving target automatically
Python • 2 daysCoordinate multiple drones in formation flight
Python • 3 daysBuild 3D maps using camera and sensors
ESP-IDF • 1 weekPrecision landing on visual markers
Python + OpenCV • 1 weekReal-time object recognition and tracking
TensorFlow Lite • 2 weeksProgram your FLYQ to autonomously navigate a room, avoiding obstacles and creating a 2D floor plan map.
Join our growing community of makers, developers, and educators
Start typing to search...