Skip to content
Open
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: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ See the [examples/](examples/) directory for more.
```
This installs the `dev` dependency group which provides `maturin`, `pre-commit`, `pytest`, and other development tools. Commands prefixed with `uv run` below require this group.

It also triggers maturin to build Rust libraries used by Python.

2. **Install pre-commit hooks:**
```bash
uv run pre-commit install
Expand Down
31 changes: 26 additions & 5 deletions cflib2/_rust.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -779,10 +779,7 @@ class LedRingColor:
Intensity percentage (0-100); values above 100 are clamped to 100
"""
@intensity.setter
def intensity(self, value: builtins.int) -> None:
r"""
Intensity percentage (0-100); values above 100 are clamped to 100
"""
def intensity(self, value: builtins.int) -> None: ...
def __new__(
cls,
r: builtins.int = 0,
Expand All @@ -797,7 +794,7 @@ class LedRingColor:
* `r` - Red component (0-255, default 0)
* `g` - Green component (0-255, default 0)
* `b` - Blue component (0-255, default 0)
* `intensity` - Intensity percentage (0-100, default 100); clamped to 100 if higher
* `intensity` - Intensity percentage (0-100, default 100); values above 100 are clamped to 100
"""
def set(
self,
Expand Down Expand Up @@ -1352,6 +1349,16 @@ class Param:
# Returns
The default value (int or float depending on parameter type)
"""
async def watch_change(self) -> ParamChangeStream:
r"""
Watch for parameter value changes

Returns an async iterator that yields `(name, value)` tuples whenever
any parameter value changes. Each call creates an independent stream.

# Returns
An async iterator yielding `(str, int | float)` tuples
"""
async def persistent_get_state(self, name: builtins.str) -> PersistentParamState:
r"""
Get the persistent storage state of a parameter
Expand Down Expand Up @@ -1389,6 +1396,20 @@ class Param:
* `name` - Parameter name in format "group.name"
"""

@typing.final
class ParamChangeStream:
r"""
Async iterator that yields `(name, value)` tuples when parameters change
"""
def __aiter__(self) -> ParamChangeStream:
r"""
Return self (async iterator protocol)
"""
async def __anext__(self) -> tuple[str, int | float]:
r"""
Return the next `(name, value)` tuple, or raise StopAsyncIteration
"""

class ParamError(CrazyflieError):
r"""
Parameter subsystem error.
Expand Down
93 changes: 57 additions & 36 deletions examples/param.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,53 +45,74 @@ class Args:
"""Crazyflie URI"""


async def get_and_set_values(cf: Crazyflie, param_name: str) -> None:
param = cf.param()

# Get original value
print(f"\n1. Getting original value of '{param_name}'...")
original_value: int | float = await param.get(param_name)
print(f" Original value: {original_value}V")

# Set new value
new_value: float = 3.8
print(f"\n2. Setting '{param_name}' to {new_value}V...")
await param.set(param_name, new_value)
print(f" Set complete!")

# Get new value to confirm
print(f"\n3. Reading back '{param_name}'...")
current_value: int | float = await param.get(param_name)
print(f" Current value: {current_value}V")

# Restore original value
print(f"\n4. Restoring '{param_name}' to original value ({original_value}V)...")
await param.set(param_name, float(original_value))
print(f" Restored!")

# Get final value to confirm restoration
print(f"\n5. Verifying restoration of '{param_name}'...")
final_value: int | float = await param.get(param_name)
print(f" Final value: {final_value}V")

if final_value == original_value:
print("\n✓ Parameter successfully restored to original value!")
else:
print(
f"\n⚠ Warning: Final value ({final_value}) differs from original ({original_value})"
)


async def watch_param_changes(cf: Crazyflie) -> None:
param = cf.param()
param_change_stream = await param.watch_change()

async for name, value in param_change_stream:
print("--------------------")
print(f"Watched change: {name}: {value}")
print("--------------------")


async def main() -> None:
# Test config
param_name = "pm.lowVoltage"

args = tyro.cli(Args)

print(f"Connecting to {args.uri}...")
context = LinkContext()
cf = await Crazyflie.connect_from_uri(context, args.uri)
print("Connected!")

param = cf.param()
param_name = "pm.lowVoltage"

try:
# Get original value
print(f"\n1. Getting original value of '{param_name}'...")
original_value: int | float = await param.get(param_name)
print(f" Original value: {original_value}V")

# Set new value
new_value: float = 3.8
print(f"\n2. Setting '{param_name}' to {new_value}V...")
await param.set(param_name, new_value)
print(f" Set complete!")

# Get new value to confirm
print(f"\n3. Reading back '{param_name}'...")
current_value: int | float = await param.get(param_name)
print(f" Current value: {current_value}V")

# Restore original value
print(f"\n4. Restoring '{param_name}' to original value ({original_value}V)...")
await param.set(param_name, float(original_value))
print(f" Restored!")

# Get final value to confirm restoration
print(f"\n5. Verifying restoration of '{param_name}'...")
final_value: int | float = await param.get(param_name)
print(f" Final value: {final_value}V")

if final_value == original_value:
print("\n✓ Parameter successfully restored to original value!")
else:
print(
f"\n⚠ Warning: Final value ({final_value}) differs from original ({original_value})"
)
# Let watch changes run in the background
_ = asyncio.create_task(watch_param_changes(cf))
await get_and_set_values(cf, param_name)

except Exception as e:
print(f"\nError: {e}")

finally:
print("\nDisconnecting...")
print("Disconnect...")
await cf.disconnect()
print("Done!")

Expand Down
3 changes: 2 additions & 1 deletion rust/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ pub mod value;
use crazyflie::Crazyflie;
use link_context::LinkContext;
use subsystems::{
Commander, Console, Log, LogBlock, LogData, LogStream, Param, PersistentParamState, Platform, AppChannel,
Commander, Console, Log, LogBlock, LogData, LogStream, Param, PersistentParamState, ParamChangeStream, Platform, AppChannel,
Localization, EmergencyControl, ExternalPose, Lighthouse, LocoPositioning,
LighthouseAngleData, LighthouseAngles,
Memory, Poly, Poly4D, CompressedStart, CompressedSegment, LedRingColor,
Expand All @@ -55,6 +55,7 @@ fn _rust(m: &Bound<'_, PyModule>) -> PyResult<()> {
m.add_class::<LogStream>()?;
m.add_class::<Param>()?;
m.add_class::<PersistentParamState>()?;
m.add_class::<ParamChangeStream>()?;
m.add_class::<Platform>()?;
m.add_class::<AppChannel>()?;
m.add_class::<Localization>()?;
Expand Down
2 changes: 1 addition & 1 deletion rust/src/subsystems/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -36,5 +36,5 @@ pub use high_level_commander::HighLevelCommander;
pub use localization::{Localization, EmergencyControl, ExternalPose, Lighthouse, LocoPositioning, LighthouseAngleData, LighthouseAngles};
pub use log::{Log, LogBlock, LogData, LogStream};
pub use memory::{Memory, Poly, Poly4D, CompressedStart, CompressedSegment, LedRingColor};
pub use param::{Param, PersistentParamState};
pub use param::{Param, ParamChangeStream, PersistentParamState};
pub use platform::{Platform, AppChannel};
54 changes: 54 additions & 0 deletions rust/src/subsystems/param.rs
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,10 @@

//! Parameter subsystem - read and write configuration parameters

use futures::StreamExt;
use pyo3::prelude::*;
use pyo3_stub_gen_derive::*;
use std::pin::Pin;
use std::sync::Arc;

use crate::error::to_pyerr;
Expand Down Expand Up @@ -62,6 +64,39 @@ impl PersistentParamState {
}
}

/// Async iterator that yields `(name, value)` tuples when parameters change
#[gen_stub_pyclass]
#[pyclass]
pub struct ParamChangeStream {
rx: Arc<tokio::sync::Mutex<Pin<Box<dyn futures::Stream<Item = (String, crazyflie_lib::Value)> + Send>>>>,
}

#[gen_stub_pymethods]
#[pymethods]
impl ParamChangeStream {
/// Return self (async iterator protocol)
fn __aiter__(slf: PyRef<'_, Self>) -> PyRef<'_, Self> {
slf
}

/// Return the next `(name, value)` tuple, or raise StopAsyncIteration
#[gen_stub(override_return_type(type_repr = "collections.abc.Coroutine[typing.Any, typing.Any, tuple[str, int | float]]"))]
fn __anext__<'py>(&mut self, py: Python<'py>) -> PyResult<Bound<'py, PyAny>> {
let rx = self.rx.clone();
pyo3_async_runtimes::tokio::future_into_py(py, async move {
let mut rx = rx.lock().await;
match rx.next().await {
Some((parameter_name, parameter_value)) => Python::attach(|py| {
let py_parameter_name: Bound<'_, pyo3::types::PyString> = parameter_name.into_pyobject(py)?;
let py_parameter_value = value_to_python(py, parameter_value)?;
(py_parameter_name, py_parameter_value).into_pyobject(py).map(|b: Bound<'_, pyo3::types::PyTuple>| b.into_any().unbind())
}),
None => Err(pyo3::exceptions::PyStopAsyncIteration::new_err(())),
}
})
}
}

/// Access to the Crazyflie Param Subsystem
///
/// This struct provides methods to interact with the parameter subsystem.
Expand Down Expand Up @@ -250,6 +285,25 @@ impl Param {
})
}

/// Watch for parameter value changes
///
/// Returns an async iterator that yields `(name, value)` tuples whenever
/// any parameter value changes. Each call creates an independent stream.
///
/// # Returns
/// An async iterator yielding `(str, int | float)` tuples
#[gen_stub(override_return_type(type_repr = "collections.abc.Coroutine[typing.Any, typing.Any, ParamChangeStream]"))]
fn watch_change<'py>(&self, py: Python<'py>) -> PyResult<Bound<'py, PyAny>> {
let cf = self.cf.clone();
pyo3_async_runtimes::tokio::future_into_py(py, async move {
let stream = cf.param.watch_change().await.map_err(to_pyerr)?;
let rx = Arc::new(tokio::sync::Mutex::new(Box::pin(stream) as Pin<Box<dyn futures::Stream<Item = (String, crazyflie_lib::Value)> + Send>>));
Python::attach(|py| {
Ok(Py::new(py, ParamChangeStream { rx })?.into_any())
})
})
}

/// Get the persistent storage state of a parameter
///
/// Returns a PersistentParamState with:
Expand Down
Loading