This is a structured hands-on lab for controlling Crazyflie drones using Python and Crazyradio v2.
Both Brushed and Brushless versions of the Crazyflie 2.1 are supported.
- Crazyflie Python Lab – Brushed & Brushless
Install the following tools:
- Python 3.10 or newer
- Visual Studio Code
- Crazyflie Client (
cfclient) - Crazyradio PA v2 USB dongle
Get the installer from:
Install and verify that CFClient opens correctly.
In VS Code or terminal:
mkdir crazyflie-lab
cd crazyflie-lab
# Optitonal: Creat Virtual Environment
python -m venv venv
source venv/bin/activate
# Windows: venv\Scripts\activate
pip install --upgrade pip
pip install cflib- Connect drone via USB
- Open CFClient → "Bootloader"
- Select correct firmware:
- Brushed: Crazyflie 2.1
- Brushless: Crazyflie 2.1 Brushless
- Flash and reboot
- CFClient → Connect via USB
- Go to "Configure 2.x"
- Set:
- Channel:
80 - Datarate:
2M - Address:
Brushed: E7E7E7E7E7
Brushless: E7E7E7E7AA
- Write config and reboot
- Disconnect USB and use radio
Use the following constants in all examples:
URI_BRUSHED = "radio://0/33/2M/E7E7E7E7E7"
URI_BRUSHLESS = "radio://0/80/2M/E7E7E7E7AA"Never run CFClient and Python scripts simultaneously.
This is a link to our command cheat-sheet: Our MRB CF Cheat Sheet
Here, we just test if your python setup is ready and allows to connect to the drone.
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
import cflib.crtp
import time
# Brushed drone URI (adjust if needed)
URI = "radio://0/33/2M/E7E7E7E7AA"
def main():
cflib.crtp.init_drivers()
with SyncCrazyflie(URI, cf=Crazyflie()) as scf:
print("Connected")
time.sleep(5)
print("Disconnected")
if __name__ == '__main__':
main()For the brushless crazyDrone, bitcraze disarmed the controlling of the motors for security reason. With this small "hack" we circumvent that for further testing:
import time
import cflib.crtp
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
import cfMRB
URI = "radio://0/33/2M/E7E7E7E7AA" # Brushless URI
duration = 10
def main():
cflib.crtp.init_drivers()
with SyncCrazyflie(URI, cf=Crazyflie(rw_cache="./cache")) as scf:
print("Connected to drone.")
cfMRB.start_motors(scf)
time.sleep(duration)
cfMRB.stop_motors(scf)
print("Disconnected.")
if __name__ == '__main__':
main()Where the additional functions, that actually start and stop the propellers are located in the cfMRB folder.
We have the possibility to move user-created lib functions to a separated folder.
import time
def start_motors(scf, pwm):
"""
Start the brushless motors at a given PWM value.
:param scf: SyncCrazyflie instance
:param pwm: PWM value between 0 and 65535
"""
print(f"Starting motors with PWM = {pwm}")
scf.cf.param.set_value("motorPowerSet.m1", str(pwm))
scf.cf.param.set_value("motorPowerSet.m2", str(pwm))
scf.cf.param.set_value("motorPowerSet.m3", str(pwm))
scf.cf.param.set_value("motorPowerSet.m4", str(pwm))
time.sleep(0.5)
scf.cf.param.set_value("motorPowerSet.enable", "1")
def stop_motors(scf):
"""
Stop all motors safely.
:param scf: SyncCrazyflie instance
"""
print("Stopping motors...")
scf.cf.param.set_value("motorPowerSet.m1", "0")
scf.cf.param.set_value("motorPowerSet.m2", "0")
scf.cf.param.set_value("motorPowerSet.m3", "0")
scf.cf.param.set_value("motorPowerSet.m4", "0")
time.sleep(0.5)
scf.cf.param.set_value("motorPowerSet.enable", "0")import time
import cflib.crtp
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
import cfMRB
# Open-loop thrust ramp using low-level RPYT setpoints (send_setpoint).
# - BRUSHED: works open-loop (no sensors), but height is NOT stable.
# - BRUSHLESS: same ramp, but we add an "arm/disarm" step via parameters
# (matching your working hover test behavior).
URI_BRUSHED = "radio://0/80/2M/E7E7E7E7E7"
URI_BRUSHLESS = "radio://0/33/2M/E7E7E7E7AA"
IS_BRUSHLESS = True
URI = URI_BRUSHLESS if IS_BRUSHLESS else URI_BRUSHED
RATE_HZ = 50
DT = 1.0 / RATE_HZ
THRUST_START = 8000
THRUST_STEP = 2000
THRUST_MAX = 22000
HOLD_TIME = 1.0
def send_rpyt_for(scf, roll, pitch, yawrate, thrust, seconds):
"""Send the same RPYT setpoint repeatedly for 'seconds'."""
n = int(seconds * RATE_HZ)
for _ in range(n):
scf.cf.commander.send_setpoint(roll, pitch, yawrate, thrust)
time.sleep(DT)
def open_loop_ramp_test(scf):
"""
Open-loop ramp test:
- Slowly increases thrust in steps
- Holds each level for HOLD_TIME
- Then ramps down and stops
"""
print("Open-loop RPYT ramp test starting.")
print("Keep roll/pitch/yawrate at 0. This is thrust-only.")
# Small pre-stream (helps some setups avoid immediate timeout behavior)
send_rpyt_for(scf, 0.0, 0.0, 0.0, 0, 0.2)
# Ramp up
thrust = THRUST_START
while thrust <= THRUST_MAX:
print(f"Thrust = {thrust}")
send_rpyt_for(scf, 0.0, 0.0, 0.0, thrust, HOLD_TIME)
thrust += THRUST_STEP
# Ramp down
thrust -= THRUST_STEP
while thrust >= THRUST_START:
print(f"Thrust = {thrust}")
send_rpyt_for(scf, 0.0, 0.0, 0.0, thrust, HOLD_TIME)
thrust -= THRUST_STEP
# Stop cleanly
print("Stopping (thrust=0, stop setpoint).")
send_rpyt_for(scf, 0.0, 0.0, 0.0, 0, 0.3)
scf.cf.commander.send_stop_setpoint()
time.sleep(0.1)
if __name__ == "__main__":
cflib.crtp.init_drivers()
with SyncCrazyflie(URI, cf=Crazyflie(rw_cache="./cache")) as scf:
try:
if IS_BRUSHLESS:
cfMRB.start_motors(scf,6000)
open_loop_ramp_test(scf)
except KeyboardInterrupt:
print("\n[CTRL+C] Emergency stop ...")
# Best-effort stop
try:
send_rpyt_for(scf, 0.0, 0.0, 0.0, 0, 0.2)
scf.cf.commander.send_stop_setpoint()
except Exception:
pass
finally:
# Always stop setpoints
try:
send_rpyt_for(scf, 0.0, 0.0, 0.0, 0, 0.2)
scf.cf.commander.send_stop_setpoint()
except Exception:
pass
if IS_BRUSHLESS:
try:
cfMRB.stop_motors(scf)
except Exception:
pass-
Find a way to let the drone hover at a certain height position (just using THRUST for the crazyflie without sensors)
- For the brushless drone you could use
scf.cf.commander.send_hover_setpoint(0, 0, 0, 0.5)to hover. Where the last input is the height you want to achieve. But therefore, sensors are needed
- For the brushless drone you could use
-
You can also use the
aiMotionCamera system in order to get the information of the height, measure the height of the drone objects and use theTHRUSTto stabilize the height.
Hovering however, will be our most powerfull move, if this works in a stable way. We are fine for every single upcoming task we want to implement.
- Observe Phase 1 (Hover): drone should try to reach/hold 1 m or more for ~2 s.
scf.cf.commander.send_setpoint(0.0, 0.0, 0.0, THRUST_HOVER)
- Observe Phase 2 (Forward): drone should move forward for ~2 s (open-loop tilt) while keeping roughly similar thrust.
scf.cf.commander.send_setpoint(0.0, PITCH_FWD_DEG, 0.0, THRUST_HOVER)
- Observe Phase 3 (Stop/Level): stop forward tilt for ~2 s.
scf.cf.commander.send_setpoint(0.0, 0.0, 0.0, THRUST_HOVER)
- Observe Phase 4 (Ramp Down): stop forward tilt for ~2 s.
scf.cf.commander.send_setpoint(0.0, 0.0, 0.0, THRUST_REDUCTION)
- Finish: cut thrust and stop setpoints.
scf.cf.commander.send_setpoint(0.0, 0.0, 0.0, 0)scf.cf.commander.send_stop_setpoint()
### 4.4 Rotate Yaw in Air
- [ ] Observe **Phase 1 (Hover / Stabilize)**: drone should try to reach/hold **1 m or more** for **~2 s**.
- `scf.cf.commander.send_setpoint(0.0, 0.0, 0.0, THRUST_HOVER)`
- [ ] Observe **Phase 2 (Rotate CW)**: drone should rotate for **~2 s** at constant thrust.
- `scf.cf.commander.send_setpoint(0.0, 0.0, YAWRATE_CW_DEG_S, THRUST_HOVER)`
- [ ] Observe **Phase 3 (Rotate CCW)**: drone should rotate in the opposite direction for **~2 s**.
- `scf.cf.commander.send_setpoint(0.0, 0.0, YAWRATE_CCW_DEG_S, THRUST_HOVER)`
- [ ] Observe **Phase 4 (Stop Rotation / Level)**: stop yaw rotation for **~2 s**.
- `scf.cf.commander.send_setpoint(0.0, 0.0, 0.0, THRUST_HOVER)`
- [ ] Observe **Phase 5 (Ramp Down)**: reduce thrust for **~2 s** to descend.
- `scf.cf.commander.send_setpoint(0.0, 0.0, 0.0, THRUST_REDUCTION)`
- [ ] Finish: cut thrust and stop setpoints.
- `scf.cf.commander.send_setpoint(0.0, 0.0, 0.0, 0)`
- `scf.cf.commander.send_stop_setpoint()`import time
import cflib.crtp
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
from cflib.crazyflie.log import LogConfig
from cflib.crazyflie.syncLogger import SyncLogger
URI_BRUSHED = "radio://0/80/2M/E7E7E7E7E7E7"
URI_BRUSHLESS = "radio://0/33/2M/E7E7E7E7E7AA"
IS_BRUSHLESS = True
URI = URI_BRUSHLESS if IS_BRUSHLESS else URI_BRUSHED
ESTIMATOR_VALUE = "2" # firmware-dependent (often Kalman)
CONTROLLER_VALUE = "1" # firmware-dependent (often PID)
def safe_set_param(scf, name, value):
try:
scf.cf.param.set_value(name, value)
return True
except Exception:
return False
def configure_estimator(scf):
safe_set_param(scf, "stabilizer.estimator", ESTIMATOR_VALUE)
safe_set_param(scf, "stabilizer.controller", CONTROLLER_VALUE)
time.sleep(0.5)
def read_estimator_into_variables(scf, duration_s=5.0, period_ms=50):
"""
Cyclically reads stateEstimate.* for duration_s and writes into variables.
Prints the variables each cycle.
Returns the last values after the loop.
"""
logconf = LogConfig(name="state", period_in_ms=period_ms)
logconf.add_variable("stateEstimate.x", "float")
logconf.add_variable("stateEstimate.y", "float")
logconf.add_variable("stateEstimate.z", "float")
logconf.add_variable("stateEstimate.yaw", "float")
est_x = 0.0
est_y = 0.0
est_z = 0.0
est_yaw = 0.0
t0 = time.time()
with SyncLogger(scf, logconf) as logger:
for _, data, _ in logger:
est_x = float(data["stateEstimate.x"])
est_y = float(data["stateEstimate.y"])
est_z = float(data["stateEstimate.z"])
est_yaw = float(data["stateEstimate.yaw"])
print(f"x={est_x:.3f} y={est_y:.3f} z={est_z:.3f} yaw={est_yaw:.1f}")
if time.time() - t0 >= duration_s:
break
return est_x, est_y, est_z, est_yaw
if __name__ == "__main__":
cflib.crtp.init_drivers()
with SyncCrazyflie(URI, cf=Crazyflie(rw_cache="./cache")) as scf:
configure_estimator(scf)
x, y, z, yaw = read_estimator_into_variables(scf, duration_s=5.0, period_ms=50)
print("LAST VALUES:")
print(f"x={x:.3f} y={y:.3f} z={z:.3f} yaw={yaw:.1f}")- cflib documentation (home): https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/
- cflib API reference (auto-generated): https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/api/
- cflib API:
cflib.crazyflie.commander(send_setpoint / send_hover_setpoint etc.): https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/api/cflib/crazyflie/commander/ - cflib API:
motion_commanderclass reference: https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/api/cflib/positioning/motion_commander/ - User guides overview: https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/user-guides/
- Step-by-Step: Connect + Logging + Parameters: https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/user-guides/sbs_connect_log_param/
- Step-by-Step: Motion Commander: https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/user-guides/sbs_motion_commander/
- “Python API explanation” (high-level overview): https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/user-guides/python_api/
- Downloads & Install (Bitcraze): https://www.bitcraze.io/support/downloads/
- cfclient installation guide: https://www.bitcraze.io/documentation/repository/crazyflie-clients-python/master/installation/install/
- cfclient user guide (GUI overview): https://www.bitcraze.io/documentation/repository/crazyflie-clients-python/master/userguides/userguide_client/
- cflib repo (Crazyflie python library): https://github.com/bitcraze/crazyflie-lib-python
- cfclient repo (PC client & tools): https://github.com/bitcraze/crazyflie-clients-python
- MotionCommander demo script (repo example): https://github.com/bitcraze/crazyflie-lib-python/blob/master/examples/autonomy/motion_commander_demo.py