Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
.pio
.vscode
.private
src/main.cpp
src/main*.cpp
src/madflight_config.h
28 changes: 11 additions & 17 deletions examples/00.HelloWorld/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,33 +6,27 @@ Upload, connect Serial Monitor at 115200 baud and send 'help' to see available c

See http://madflight.com for detailed description

MIT license
Copyright (c) 2023-2025 https://madflight.com
MIT license - Copyright (c) 2023-2026 https://madflight.com
##########################################################################################################################*/

#include <Arduino.h>
#include "madflight_config.h" //Edit this header file to setup the pins, hardware, radio, etc. for madflight
#include <madflight.h>
#include "madflight_config.h" // Edit this header file to setup the pins, hardware, radio, etc. for madflight
#include <madflight.h> // Include the library, do this after madflight_config

void setup() {
madflight_setup(); //setup madflight modules
// Setup madflight modules and start IMU, BBX, RCL, CLI, and SENSORS rtos tasks
madflight_setup();
}

void loop() {
rcl.update(); // get rc radio commands
bar.update(); // barometer
mag.update(); // magnetometer
gps.update(); // gps
bat.update(); // battery consumption
rdr.update(); // radar
ofl.update(); // optical flow
cli.update(); // process CLI commands
// Nothing to do here for madflight, delay() yields to Idle Task for clearer CPU usage statistics
delay(10);
}

//This is __MAIN__ function of this program. It is called when new IMU data is available.
// This function is called from the IMU task when fresh IMU data is available.
void imu_loop() {
//toggle led on every 1000 samples (normally 1 second)
// Toggle led on every 1000 samples (E.g. 1 second peroid at 1000Hz sample rate)
if(imu.update_cnt % 1000 == 0) led.toggle();

ahr.update(); //Sensor fusion: update ahr.roll, ahr.pitch, and ahr.yaw angle estimates (degrees) from IMU data
// AHRS sensor fusion - type 'pahr' in CLI to see results
ahr.update();
}
16 changes: 6 additions & 10 deletions examples/10.Quadcopter/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,9 @@ Blinking long ON short OFF (red) ARMED
Blink interval longer than 1 second imu_loop() is taking too much time
Fast blinking Something is wrong, connect USB serial for info

MIT license
Copyright (c) 2023-2025 https://madflight.com
MIT license - Copyright (c) 2023-2026 https://madflight.com
##########################################################################################################################*/

#include <Arduino.h>
#include "madflight_config.h" //Edit this header file to setup the pins, hardware, radio, etc. for madflight
#include <madflight.h>

Expand Down Expand Up @@ -84,9 +82,9 @@ const float Kd_yaw_angle = 0.1; //Yaw D-gain
const float Kp_ro_pi_rate = 0.15; //Roll/Pitch rate P-gain
const float Ki_ro_pi_rate = 0.2; //Roll/Pitch rate I-gain
const float Kd_ro_pi_rate = 0.0002; //Roll/Pitch rate D-gain (be careful when increasing too high, motors will begin to overheat!)
const float Kp_yaw_rate = 0.3; //Yaw rate P-gain
const float Ki_yaw_rate = 0.05; //Yaw rate I-gain
const float Kd_yaw_rate = 0.00015; //Yaw rate D-gain (be careful when increasing too high, motors will begin to overheat!)
const float Kp_yaw_rate = 0.3; //Yaw rate P-gain
const float Ki_yaw_rate = 0.05; //Yaw rate I-gain
const float Kd_yaw_rate = 0.00015; //Yaw rate D-gain (be careful when increasing too high, motors will begin to overheat!)

//Yaw to keep in ANGLE mode when yaw stick is centered
float yaw_desired = 0;
Expand Down Expand Up @@ -120,7 +118,8 @@ void setup() {
//========================================================================================================================//

void loop() {
cli.update(); //process CLI commands
// Nothing to do here for madflight, delay() yields to Idle Task for clearer CPU usage statistics
delay(10);
}

//========================================================================================================================//
Expand All @@ -135,9 +134,6 @@ void imu_loop() {
//Sensor fusion: update ahr.roll, ahr.pitch, and ahr.yaw angle estimates (degrees) from IMU data
ahr.update();

//Get radio commands - Note: don't do this in loop() because loop() is a lower priority task than imu_loop(), so in worst case loop() will not get any processor time.
rcl.update();

//PID Controller RATE or ANGLE
#ifdef FLIGHTMODE_ANGLE
control_Angle(rcl.throttle == 0); //Stabilize on pitch/roll angle setpoint, stabilize yaw on rate setpoint //control_Angle2(rcin_thro_is_low); //Stabilize on pitch/roll setpoint using cascaded method. Rate controller must be tuned well first!
Expand Down
43 changes: 7 additions & 36 deletions examples/11.QuadcopterAdvanced/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ Blink interval longer than 1 second imu_loop() is taking too much time
Fast blinking Something is wrong, connect USB serial for info

MIT license
Copyright (c) 2023-2025 https://madflight.com
MIT license - Copyright (c) 2023-2026 https://madflight.com
##########################################################################################################################*/

//Vehicle specific madflight configuration
Expand Down Expand Up @@ -127,50 +127,23 @@ void setup() {
//========================================================================================================================//

void loop() {
//update battery, and log if battery was updated.
if(bat.update()) {
bbx.log_bat();
}

alt.updateAccelUp(ahr.getAccelUp(), ahr.ts); //NOTE: do this here and not in imu_loop() because `alt` object is not thread safe. - Update altitude estimator with current earth-frame up acceleration measurement

if(bar.update()) {
alt.updateBarAlt(bar.alt, bar.ts); //update altitude estimator with current altitude measurement
bbx.log_bar(); //log if pressure updated
}

mag.update();

//update gps (and log GPS and ATT for plot.ardupilot.org visualization)
if(gps.update()) {
bbx.log_gps();
bbx.log_att();
}

//logging
static uint32_t log_ts = 0;
if(millis() - log_ts > 100) {
log_ts = millis();
bbx.log_sys();
}

cli.update(); //process CLI commands
// Nothing to do here for madflight, delay() yields to Idle Task for clearer CPU usage statistics
delay(10);
}

//========================================================================================================================//
// IMU UPDATE LOOP //
//========================================================================================================================//

//This is the __MAIN__ part of this program. It is called when new IMU data is available, and runs as high priority FreeRTOS task.
// This is the __MAIN__ part of this program. It is called from the IMU FreeRTOS task when new IMU data is available.
void imu_loop() {
//Blink LED
// Blink LED
led_Blink();

//Sensor fusion: update ahr.roll, ahr.pitch, and ahr.yaw angle estimates (degrees) from IMU data
// Sensor fusion: update ahr.roll, ahr.pitch, and ahr.yaw angle estimates (degrees) from IMU data
ahr.update();

//Get radio commands - Note: don't do this in loop() because loop() is a lower priority task than imu_loop(), so in worst case loop() will not get any processor time.
rcl.update();
// Update flight mode
if(rcl.connected() && veh.setFlightmode( rcl_to_flightmode_map[rcl.flightmode] )) { //map rcl.flightmode (0 to 5) to vehicle flightmode
Serial.printf("Flightmode:%s\n",veh.flightmode_name());
}
Expand All @@ -189,8 +162,6 @@ void imu_loop() {

//Actuator mixing
out_Mixer(); //Mixes PID outputs and sends command pulses to the motors, if mot.arm == true

//bbx.log_imu(); //uncomment for full speed black box logging of IMU data, but memory will fill up quickly...
}

//========================================================================================================================
Expand Down
24 changes: 4 additions & 20 deletions examples/20.Plane/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ Blink interval longer than 1 second imu_loop() is taking too much time
Fast blinking Something is wrong, connect USB serial for info

MIT license
Copyright (c) 2024-2025 https://madflight.com
MIT license - Copyright (c) 2023-2026 https://madflight.com
##########################################################################################################################*/

//Vehicle specific madflight configuration
Expand Down Expand Up @@ -153,21 +153,8 @@ void setup() {
//========================================================================================================================//

void loop() {
//update all I2C sensors
if(bat.update()) bbx.log_bat(); //update battery, and log if battery was updated.
if(bar.update()) bbx.log_bar(); //log if pressure updated
mag.update();

if(gps.update()) {bbx.log_gps(); bbx.log_att();} //update gps (and log GPS and ATT for plot.ardupilot.org visualization)

//logging
static uint32_t log_ts = 0;
if(millis() - log_ts > 100) {
log_ts = millis();
bbx.log_sys();
}

cli.update(); //process CLI commands
// Nothing to do here for madflight, delay() yields to Idle Task for clearer CPU usage statistics
delay(10);
}

//========================================================================================================================//
Expand All @@ -182,8 +169,7 @@ void imu_loop() {
//Sensor fusion: update ahr.roll, ahr.pitch, and ahr.yaw angle estimates (degrees) from IMU data
ahr.update();

//Get radio commands - Note: don't do this in loop() because loop() is a lower priority task than imu_loop(), so in worst case loop() will not get any processor time.
rcl.update();
// Update flight mode.
veh.setFlightmode( rcin_to_flightmode_map[rcl.flightmode] ); //map rcl.flightmode (0 to 5) to vehicle flightmode

//PID Controller
Expand All @@ -203,8 +189,6 @@ void imu_loop() {

//Actuator mixing
out_Mixer(); //Mixes PID outputs and sends command pulses to the motors, if mot.arm == true

//bbx.log_imu(); //full speed black box logging of IMU data, memory fills up quickly...
}

//========================================================================================================================
Expand Down

This file was deleted.

166 changes: 0 additions & 166 deletions examples/90.RTOS_HelloWorld_Experimental/madflight_config.h

This file was deleted.

Loading