Skip to content

Commit

Permalink
Merge pull request #515 from bitcraze/Aris/Single_Drone_Reset_Estimator
Browse files Browse the repository at this point in the history
Replaced reset estimator in single drone examples
  • Loading branch information
ArisMorgens authored Feb 13, 2025
2 parents 2a97614 + 119ce20 commit 77b131f
Show file tree
Hide file tree
Showing 13 changed files with 74 additions and 573 deletions.
56 changes: 56 additions & 0 deletions cflib/utils/reset_estimator.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
import time

from cflib.crazyflie.log import LogConfig
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
from cflib.crazyflie.syncLogger import SyncLogger


def reset_estimator(crazyflie):
if isinstance(crazyflie, SyncCrazyflie):
cf = crazyflie.cf
else:
cf = crazyflie
cf.param.set_value('kalman.resetEstimation', '1')
time.sleep(0.1)
cf.param.set_value('kalman.resetEstimation', '0')

_wait_for_position_estimator(cf)


def _wait_for_position_estimator(cf):
print('Waiting for estimator to find position...', end='\r')

log_config = LogConfig(name='Kalman Variance', period_in_ms=500)
log_config.add_variable('kalman.varPX', 'float')
log_config.add_variable('kalman.varPY', 'float')
log_config.add_variable('kalman.varPZ', 'float')

var_y_history = [1000] * 10
var_x_history = [1000] * 10
var_z_history = [1000] * 10

threshold = 0.001

with SyncLogger(cf, log_config) as logger:
for log_entry in logger:
data = log_entry[1]

var_x_history.append(data['kalman.varPX'])
var_x_history.pop(0)
var_y_history.append(data['kalman.varPY'])
var_y_history.pop(0)
var_z_history.append(data['kalman.varPZ'])
var_z_history.pop(0)

min_x = min(var_x_history)
max_x = max(var_x_history)
min_y = min(var_y_history)
max_y = max(var_y_history)
min_z = min(var_z_history)
max_z = max(var_z_history)

if (max_x - min_x) < threshold and (
max_y - min_y) < threshold and (
max_z - min_z) < threshold:
print('Waiting for estimator to find position...success!')
break
54 changes: 2 additions & 52 deletions examples/autonomy/autonomousSequence.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.log import LogConfig
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
from cflib.crazyflie.syncLogger import SyncLogger
from cflib.utils import uri_helper
from cflib.utils.reset_estimator import reset_estimator

# URI to the Crazyflie to connect to
uri = uri_helper.uri_from_env(default='radio://0/80/2M/E7E7E7E7E7')
Expand All @@ -56,56 +56,6 @@
]


def wait_for_position_estimator(scf):
print('Waiting for estimator to find position...')

log_config = LogConfig(name='Kalman Variance', period_in_ms=500)
log_config.add_variable('kalman.varPX', 'float')
log_config.add_variable('kalman.varPY', 'float')
log_config.add_variable('kalman.varPZ', 'float')

var_y_history = [1000] * 10
var_x_history = [1000] * 10
var_z_history = [1000] * 10

threshold = 0.001

with SyncLogger(scf, log_config) as logger:
for log_entry in logger:
data = log_entry[1]

var_x_history.append(data['kalman.varPX'])
var_x_history.pop(0)
var_y_history.append(data['kalman.varPY'])
var_y_history.pop(0)
var_z_history.append(data['kalman.varPZ'])
var_z_history.pop(0)

min_x = min(var_x_history)
max_x = max(var_x_history)
min_y = min(var_y_history)
max_y = max(var_y_history)
min_z = min(var_z_history)
max_z = max(var_z_history)

# print("{} {} {}".
# format(max_x - min_x, max_y - min_y, max_z - min_z))

if (max_x - min_x) < threshold and (
max_y - min_y) < threshold and (
max_z - min_z) < threshold:
break


def reset_estimator(scf):
cf = scf.cf
cf.param.set_value('kalman.resetEstimation', '1')
time.sleep(0.1)
cf.param.set_value('kalman.resetEstimation', '0')

wait_for_position_estimator(cf)


def position_callback(timestamp, data, logconf):
x = data['kalman.stateX']
y = data['kalman.stateY']
Expand Down Expand Up @@ -154,5 +104,5 @@ def run_sequence(scf, sequence):

with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
reset_estimator(scf)
# start_position_printing(scf)
start_position_printing(scf)
run_sequence(scf, sequence)
52 changes: 1 addition & 51 deletions examples/autonomy/autonomous_sequence_high_level.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,11 @@

import cflib.crtp
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.log import LogConfig
from cflib.crazyflie.mem import MemoryElement
from cflib.crazyflie.mem import Poly4D
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
from cflib.crazyflie.syncLogger import SyncLogger
from cflib.utils import uri_helper
from cflib.utils.reset_estimator import reset_estimator

# URI to the Crazyflie to connect to
uri = uri_helper.uri_from_env(default='radio://0/80/2M/E7E7E7E7E7')
Expand All @@ -62,55 +61,6 @@
]


def wait_for_position_estimator(scf):
print('Waiting for estimator to find position...')

log_config = LogConfig(name='Kalman Variance', period_in_ms=500)
log_config.add_variable('kalman.varPX', 'float')
log_config.add_variable('kalman.varPY', 'float')
log_config.add_variable('kalman.varPZ', 'float')

var_y_history = [1000] * 10
var_x_history = [1000] * 10
var_z_history = [1000] * 10

threshold = 0.001

with SyncLogger(scf, log_config) as logger:
for log_entry in logger:
data = log_entry[1]

var_x_history.append(data['kalman.varPX'])
var_x_history.pop(0)
var_y_history.append(data['kalman.varPY'])
var_y_history.pop(0)
var_z_history.append(data['kalman.varPZ'])
var_z_history.pop(0)

min_x = min(var_x_history)
max_x = max(var_x_history)
min_y = min(var_y_history)
max_y = max(var_y_history)
min_z = min(var_z_history)
max_z = max(var_z_history)

# print("{} {} {}".
# format(max_x - min_x, max_y - min_y, max_z - min_z))

if (max_x - min_x) < threshold and (
max_y - min_y) < threshold and (
max_z - min_z) < threshold:
break


def reset_estimator(cf):
cf.param.set_value('kalman.resetEstimation', '1')
time.sleep(0.1)
cf.param.set_value('kalman.resetEstimation', '0')

wait_for_position_estimator(cf)


def activate_mellinger_controller(cf):
cf.param.set_value('stabilizer.controller', '2')

Expand Down
52 changes: 1 addition & 51 deletions examples/autonomy/autonomous_sequence_high_level_compressed.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,12 @@
import cflib.crtp
from cflib.crazyflie import Crazyflie
from cflib.crazyflie.high_level_commander import HighLevelCommander
from cflib.crazyflie.log import LogConfig
from cflib.crazyflie.mem import CompressedSegment
from cflib.crazyflie.mem import CompressedStart
from cflib.crazyflie.mem import MemoryElement
from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
from cflib.crazyflie.syncLogger import SyncLogger
from cflib.utils import uri_helper
from cflib.utils.reset_estimator import reset_estimator

# URI to the Crazyflie to connect to
uri = uri_helper.uri_from_env(default='radio://0/80/2M/E7E7E7E7E7')
Expand All @@ -58,55 +57,6 @@
]


def wait_for_position_estimator(scf):
print('Waiting for estimator to find position...')

log_config = LogConfig(name='Kalman Variance', period_in_ms=500)
log_config.add_variable('kalman.varPX', 'float')
log_config.add_variable('kalman.varPY', 'float')
log_config.add_variable('kalman.varPZ', 'float')

var_y_history = [1000] * 10
var_x_history = [1000] * 10
var_z_history = [1000] * 10

threshold = 0.001

with SyncLogger(scf, log_config) as logger:
for log_entry in logger:
data = log_entry[1]

var_x_history.append(data['kalman.varPX'])
var_x_history.pop(0)
var_y_history.append(data['kalman.varPY'])
var_y_history.pop(0)
var_z_history.append(data['kalman.varPZ'])
var_z_history.pop(0)

min_x = min(var_x_history)
max_x = max(var_x_history)
min_y = min(var_y_history)
max_y = max(var_y_history)
min_z = min(var_z_history)
max_z = max(var_z_history)

# print("{} {} {}".
# format(max_x - min_x, max_y - min_y, max_z - min_z))

if (max_x - min_x) < threshold and (
max_y - min_y) < threshold and (
max_z - min_z) < threshold:
break


def reset_estimator(cf):
cf.param.set_value('kalman.resetEstimation', '1')
time.sleep(0.1)
cf.param.set_value('kalman.resetEstimation', '0')

wait_for_position_estimator(cf)


def activate_mellinger_controller(cf):
cf.param.set_value('stabilizer.controller', '2')

Expand Down
52 changes: 1 addition & 51 deletions examples/autonomy/circling_square_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,11 @@

import cflib.crtp
from cflib.crazyflie.high_level_commander import HighLevelCommander
from cflib.crazyflie.log import LogConfig
from cflib.crazyflie.mem import CompressedSegment
from cflib.crazyflie.mem import CompressedStart
from cflib.crazyflie.mem import MemoryElement
from cflib.crazyflie.swarm import CachedCfFactory
from cflib.crazyflie.swarm import Swarm
from cflib.crazyflie.syncLogger import SyncLogger

URI1 = 'radio://0/60/2M/E7E7E7E710'
URI2 = 'radio://0/60/2M/E7E7E7E711'
Expand Down Expand Up @@ -72,55 +70,6 @@ def rotate_beizer_node(xl, yl, alpha):
return x_rot, y_rot


def wait_for_position_estimator(scf):
print('Waiting for estimator to find position...')

log_config = LogConfig(name='Kalman Variance', period_in_ms=500)
log_config.add_variable('kalman.varPX', 'float')
log_config.add_variable('kalman.varPY', 'float')
log_config.add_variable('kalman.varPZ', 'float')

var_y_history = [1000] * 10
var_x_history = [1000] * 10
var_z_history = [1000] * 10

threshold = 0.001

with SyncLogger(scf, log_config) as logger:
for log_entry in logger:
data = log_entry[1]

var_x_history.append(data['kalman.varPX'])
var_x_history.pop(0)
var_y_history.append(data['kalman.varPY'])
var_y_history.pop(0)
var_z_history.append(data['kalman.varPZ'])
var_z_history.pop(0)

min_x = min(var_x_history)
max_x = max(var_x_history)
min_y = min(var_y_history)
max_y = max(var_y_history)
min_z = min(var_z_history)
max_z = max(var_z_history)

# print("{} {} {}".
# format(max_x - min_x, max_y - min_y, max_z - min_z))

if (max_x - min_x) < threshold and (
max_y - min_y) < threshold and (
max_z - min_z) < threshold:
break


def reset_estimator(cf):
cf.param.set_value('kalman.resetEstimation', '1')
time.sleep(0.1)
cf.param.set_value('kalman.resetEstimation', '0')

wait_for_position_estimator(cf)


def activate_high_level_commander(cf):
cf.param.set_value('commander.enHighLevel', '1')

Expand Down Expand Up @@ -234,6 +183,7 @@ def upload_trajectories(scf, alpha, r):

factory = CachedCfFactory(rw_cache='./cache')
with Swarm(uris, factory=factory) as swarm:
swarm.reset_estimators()
swarm.parallel_safe(turn_off_leds)
swarm.parallel_safe(upload_trajectories, args_dict=position_params)
time.sleep(5)
Expand Down
Loading

0 comments on commit 77b131f

Please sign in to comment.