Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Manually arm Crazyflies in all examples #501

Merged
merged 1 commit into from
Dec 5, 2024
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
5 changes: 5 additions & 0 deletions examples/aideck/fpv.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
import struct
import sys
import threading
from time import time

import numpy as np

Expand Down Expand Up @@ -185,6 +186,10 @@ def __init__(self, URI):

self.hover = {'x': 0.0, 'y': 0.0, 'z': 0.0, 'yaw': 0.0, 'height': 0.3}

# Arm the Crazyflie
self.cf.platform.send_arming_request(True)
time.sleep(1.0)

self.hoverTimer = QtCore.QTimer()
self.hoverTimer.timeout.connect(self.sendHoverCommand)
self.hoverTimer.setInterval(100)
Expand Down
4 changes: 4 additions & 0 deletions examples/autonomy/autonomousSequence.py
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,10 @@ def start_position_printing(scf):
def run_sequence(scf, sequence):
cf = scf.cf

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

for position in sequence:
print('Setting position {}'.format(position))
for i in range(50):
Expand Down
4 changes: 4 additions & 0 deletions examples/autonomy/autonomous_sequence_high_level.py
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,10 @@ def upload_trajectory(cf, trajectory_id, trajectory):
def run_sequence(cf, trajectory_id, duration):
commander = cf.high_level_commander

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

commander.takeoff(1.0, 2.0)
time.sleep(3.0)
relative = True
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,10 @@ def upload_trajectory(cf, trajectory_id, trajectory):
def run_sequence(cf, trajectory_id, duration):
commander = cf.high_level_commander

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

commander.takeoff(1.0, 2.0)
time.sleep(3.0)
relative = True
Expand Down
4 changes: 4 additions & 0 deletions examples/autonomy/circling_square_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,10 @@ def turn_off_leds(scf):


def run_sequence(scf, alpha, r):
# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

commander = scf.cf.high_level_commander
trajectory_id = 1
duration = 4*t
Expand Down
4 changes: 4 additions & 0 deletions examples/autonomy/full_state_setpoint_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,10 @@ def run_sequence(scf):
# Set to mellinger controller
# cf.param.set_value('stabilizer.controller', '2')

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

print('takeoff')
send_setpoint(cf, 4.0,
[0.0, 0.0, 1.0],
Expand Down
4 changes: 4 additions & 0 deletions examples/autonomy/motion_commander_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,10 @@
cflib.crtp.init_drivers()

with SyncCrazyflie(URI, cf=Crazyflie(rw_cache='./cache')) as scf:
# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

# We take off when the commander is created
with MotionCommander(scf) as mc:
time.sleep(1)
Expand Down
14 changes: 14 additions & 0 deletions examples/autonomy/position_commander_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@

Change the URI variable to your Crazyflie configuration.
"""
from time import time

import cflib.crtp
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
Expand All @@ -41,6 +43,10 @@

def slightly_more_complex_usage():
with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

with PositionHlCommander(
scf,
x=0.0, y=0.0, z=0.0,
Expand All @@ -67,6 +73,10 @@ def slightly_more_complex_usage():

def land_on_elevated_surface():
with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

with PositionHlCommander(scf,
default_height=0.5,
default_velocity=0.2,
Expand All @@ -80,6 +90,10 @@ def land_on_elevated_surface():

def simple_sequence():
with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

with PositionHlCommander(scf, controller=PositionHlCommander.CONTROLLER_PID) as pc:
pc.forward(1.0)
pc.left(1.0)
Expand Down
5 changes: 5 additions & 0 deletions examples/lighthouse/lighthouse_openvr_grab.py
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,11 @@ def run_sequence(scf):

with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
reset_estimator(scf)

# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

run_sequence(scf)

openvr.shutdown()
5 changes: 5 additions & 0 deletions examples/lighthouse/lighthouse_openvr_grab_color.py
Original file line number Diff line number Diff line change
Expand Up @@ -203,6 +203,11 @@ def run_sequence(scf):
with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
reset_estimator(scf)
# start_position_printing(scf)

# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

run_sequence(scf)

openvr.shutdown()
6 changes: 6 additions & 0 deletions examples/lighthouse/lighthouse_openvr_multigrab.py
Original file line number Diff line number Diff line change
Expand Up @@ -199,6 +199,12 @@ def run_sequence(scf0, scf1):
reset_estimator(scf0)
with SyncCrazyflie(uri1, cf=Crazyflie(rw_cache='./cache')) as scf1:
reset_estimator(scf1)

# Arm the Crazyflies
scf0.cf.platform.send_arming_request(True)
scf1.cf.platform.send_arming_request(True)
time.sleep(1.0)

run_sequence(scf0, scf1)

openvr.shutdown()
5 changes: 5 additions & 0 deletions examples/mocap/mocap_hl_commander.py
Original file line number Diff line number Diff line change
Expand Up @@ -233,6 +233,11 @@ def run_sequence(cf, trajectory_id, duration):
duration = upload_trajectory(cf, trajectory_id, figure8)
print('The sequence is {:.1f} seconds long'.format(duration))
reset_estimator(cf)

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

run_sequence(cf, trajectory_id, duration)

mocap_wrapper.close()
5 changes: 5 additions & 0 deletions examples/mocap/qualisys_hl_commander.py
Original file line number Diff line number Diff line change
Expand Up @@ -296,6 +296,11 @@ def run_sequence(cf, trajectory_id, duration):
duration = upload_trajectory(cf, trajectory_id, figure8)
print('The sequence is {:.1f} seconds long'.format(duration))
reset_estimator(cf)

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

run_sequence(cf, trajectory_id, duration)

qtm_wrapper.close()
4 changes: 4 additions & 0 deletions examples/motors/multiramp.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,10 @@ def _connected(self, link_uri):
""" This callback is called form the Crazyflie API when a Crazyflie
has been connected and the TOCs have been downloaded."""

# Arm the Crazyflie
self._cf.platform.send_arming_request(True)
time.sleep(1.0)

# Start a separate thread to do the motor test.
# Do not hijack the calling thread!
Thread(target=self._ramp_motors).start()
Expand Down
6 changes: 5 additions & 1 deletion examples/motors/ramp.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,10 @@ def _connected(self, link_uri):
""" This callback is called form the Crazyflie API when a Crazyflie
has been connected and the TOCs have been downloaded."""

# Arm the Crazyflie
self._cf.platform.send_arming_request(True)
time.sleep(1.0)

# Start a separate thread to do the motor test.
# Do not hijack the calling thread!
Thread(target=self._ramp_motors).start()
Expand Down Expand Up @@ -98,7 +102,7 @@ def _ramp_motors(self):
self._cf.commander.send_setpoint(0, 0, 0, 0)
# Make sure that the last packet leaves before the link is closed
# since the message queue is not flushed before closing
time.sleep(0.1)
time.sleep(1)
self._cf.close_link()


Expand Down
5 changes: 5 additions & 0 deletions examples/multiranger/multiranger_pointcloud.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
import logging
import math
import sys
from time import time

import numpy as np
from vispy import scene
Expand Down Expand Up @@ -111,6 +112,10 @@ def __init__(self, URI):
# Connect to the Crazyflie
self.cf.open_link(URI)

# Arm the Crazyflie
self.cf.platform.send_arming_request(True)
time.sleep(1.0)

self.hover = {'x': 0.0, 'y': 0.0, 'z': 0.0, 'yaw': 0.0, 'height': 0.3}

self.hoverTimer = QtCore.QTimer()
Expand Down
4 changes: 4 additions & 0 deletions examples/multiranger/multiranger_push.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,10 @@ def is_close(range):

cf = Crazyflie(rw_cache='./cache')
with SyncCrazyflie(URI, cf=cf) as scf:
# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

with MotionCommander(scf) as motion_commander:
with Multiranger(scf) as multiranger:
keep_flying = True
Expand Down
4 changes: 4 additions & 0 deletions examples/multiranger/multiranger_wall_following.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,10 @@ def handle_range_measurement(range):

cf = Crazyflie(rw_cache='./cache')
with SyncCrazyflie(URI, cf=cf) as scf:
# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

with MotionCommander(scf) as motion_commander:
with Multiranger(scf) as multiranger:
with SyncLogger(scf, lg_stab) as logger:
Expand Down
4 changes: 4 additions & 0 deletions examples/positioning/flowsequenceSync.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@
cf.param.set_value('kalman.resetEstimation', '0')
time.sleep(2)

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

for y in range(10):
cf.commander.send_hover_setpoint(0, 0, 0, y / 25)
time.sleep(0.1)
Expand Down
4 changes: 4 additions & 0 deletions examples/positioning/initial_position.py
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,10 @@ def reset_estimator(scf):
def run_sequence(scf, sequence, base_x, base_y, base_z, yaw):
cf = scf.cf

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

for position in sequence:
print('Setting position {}'.format(position))

Expand Down
4 changes: 4 additions & 0 deletions examples/positioning/matrix_light_printer.py
Original file line number Diff line number Diff line change
Expand Up @@ -110,5 +110,9 @@ def matrix_print(cf, pc, image_def):
image_def = ImageDef('monalisa.png')

with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
# Arm the Crazyflie
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)

with PositionHlCommander(scf, default_height=0.5, controller=PositionHlCommander.CONTROLLER_PID) as pc:
matrix_print(scf.cf, pc, image_def)
6 changes: 6 additions & 0 deletions examples/step-by-step/sbs_swarm.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,11 @@ def light_check(scf: SyncCrazyflie):
time.sleep(2)


def arm(scf: SyncCrazyflie):
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)


def take_off(scf: SyncCrazyflie):
commander = scf.cf.high_level_commander

Expand Down Expand Up @@ -161,6 +166,7 @@ def run_sequence(scf: SyncCrazyflie, sequence):
swarm.reset_estimators()
print('Estimators have been reset')

swarm.parallel_safe(arm)
swarm.parallel_safe(take_off)
# swarm.parallel_safe(run_square_sequence)
swarm.parallel_safe(run_sequence, args_dict=seq_args)
Expand Down
6 changes: 6 additions & 0 deletions examples/swarm/hl-commander-swarm.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,11 @@ def activate_mellinger_controller(scf, use_mellinger):
scf.cf.param.set_value('stabilizer.controller', controller)


def arm(scf):
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)


def run_shared_sequence(scf):
activate_mellinger_controller(scf, False)

Expand Down Expand Up @@ -84,4 +89,5 @@ def run_shared_sequence(scf):
factory = CachedCfFactory(rw_cache='./cache')
with Swarm(uris, factory=factory) as swarm:
swarm.reset_estimators()
swarm.parallel_safe(arm)
swarm.parallel_safe(run_shared_sequence)
6 changes: 6 additions & 0 deletions examples/swarm/swarmSequence.py
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,11 @@ def wait_for_param_download(scf):
print('Parameters downloaded for', scf.cf.link_uri)


def arm(scf):
scf.cf.platform.send_arming_request(True)
time.sleep(1.0)


def take_off(cf, position):
take_off_time = 1.0
sleep_time = 0.1
Expand Down Expand Up @@ -209,6 +214,7 @@ def run_sequence(scf, sequence):
try:
cf = scf.cf

arm(cf)
take_off(cf, sequence[0])
for position in sequence:
print('Setting position {}'.format(position))
Expand Down
4 changes: 4 additions & 0 deletions examples/swarm/swarmSequenceCircle.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,10 @@ def poshold(cf, t, z):
def run_sequence(scf, params):
cf = scf.cf

# Arm the Crazyflie
cf.platform.send_arming_request(True)
time.sleep(1.0)

# Number of setpoints sent per second
fs = 4
fsi = 1.0 / fs
Expand Down
Loading
Loading