pub struct HighLevelCommander { /* private fields */ }Expand description
High-level commander interface for a Crazyflie.
The high-level commander is a firmware module that generates smooth position setpoints from high-level actions such as take-off, go-to, spiral, and land. Internally it plans trajectories (polynomial-based) that are executed by the Crazyflie.
This Rust type provides an asynchronous, remote client for that module: it builds and sends the required packets over the high-level commander port, exposing a small set of ergonomic methods. When using trajectory functions, ensure the trajectory data has been uploaded to the Crazyflie’s memory first.
§Command execution model
Movement commands (take_off, land,
go_to, spiral) immediately trigger execution
on the Crazyflie and then block for their duration to simplify command sequencing.
The Crazyflie executes these commands autonomously—if the Rust future is cancelled
or the connection drops, the drone will continue executing the command until completion.
§Notes
The high-level commander can be preempted at any time by setpoints from the commander.
To return control to the high-level commander, see crate::subsystems::commander::Commander::notify_setpoint_stop.
A HighLevelCommander is typically obtained from a crate::Crazyflie instance.
§Safe usage pattern
// Continue flight sequence even if commands fail
if let Err(e) = cf.high_level_commander.take_off(0.5, None, 2.0, None).await {
eprintln!("Take-off failed: {e}");
}
if let Err(e) = cf.high_level_commander.land(0.0, None, 2.0, None).await {
eprintln!("Landing failed: {e}");
}Implementations§
Source§impl HighLevelCommander
Constructor methods.
impl HighLevelCommander
Constructor methods.
Source§impl HighLevelCommander
Group mask related commands.
impl HighLevelCommander
Group mask related commands.
Source§impl HighLevelCommander
High-level movement commands.
impl HighLevelCommander
High-level movement commands.
§Warning
Avoid overlapping movement commands. When a command is sent to a Crazyflie while another is currently executing, the generated polynomial can take unexpected routes and have high peaks.
Sourcepub async fn take_off(
&self,
height: f32,
yaw: Option<f32>,
duration: f32,
group_mask: Option<u8>,
) -> Result<()>
pub async fn take_off( &self, height: f32, yaw: Option<f32>, duration: f32, group_mask: Option<u8>, ) -> Result<()>
Take off vertically from the current x-y position to the given target height.
§Arguments
height- Target height (meters) above the world origin.yaw- Target yaw (radians). UseNoneto maintain the current yaw.duration- Time (seconds) to reach the target height. This method blocks for this duration.group_mask- Bitmask selecting which Crazyflies to command. UseNonefor all Crazyflies.
Sourcepub async fn land(
&self,
height: f32,
yaw: Option<f32>,
duration: f32,
group_mask: Option<u8>,
) -> Result<()>
pub async fn land( &self, height: f32, yaw: Option<f32>, duration: f32, group_mask: Option<u8>, ) -> Result<()>
Land vertically from the current x-y position to the given target height.
§Arguments
height- Target height (meters) above the world origin.yaw- Target yaw (radians). UseNoneto maintain the current yaw.duration- Time (seconds) to reach the target height. This method blocks for this duration.group_mask- Bitmask selecting which Crazyflies to command. UseNonefor all Crazyflies.
Sourcepub async fn stop(&self, group_mask: Option<u8>) -> Result<()>
pub async fn stop(&self, group_mask: Option<u8>) -> Result<()>
Stop the current high-level command and disable motors.
This immediately halts any active high-level command (takeoff, land, go_to, spiral, or trajectory execution) and stops motor output.
§Arguments
group_mask- Bitmask selecting which Crazyflies to command. UseNonefor all Crazyflies.
Sourcepub async fn go_to(
&self,
x: f32,
y: f32,
z: f32,
yaw: f32,
duration: f32,
relative: bool,
linear: bool,
group_mask: Option<u8>,
) -> Result<()>
pub async fn go_to( &self, x: f32, y: f32, z: f32, yaw: f32, duration: f32, relative: bool, linear: bool, group_mask: Option<u8>, ) -> Result<()>
Move to an absolute or relative position with smooth path planning.
The path is designed to transition smoothly from the current state to the target position, gradually decelerating at the goal with minimal overshoot. When the system is at hover, the path will be a straight line, but if there is any initial velocity, the path will be a smooth curve.
The trajectory is derived by solving for a unique 7th-degree polynomial that satisfies the initial conditions of position, velocity, and acceleration, and ends at the goal with zero velocity and acceleration. Additionally, the jerk (derivative of acceleration) is constrained to be zero at both the starting and ending points.
§Arguments
x- Target x-position in metersy- Target y-position in metersz- Target z-position in metersyaw- Target yaw angle in radiansduration- Time in seconds to reach the target position. This method blocks for this duration.relative- Iftrue, positions and yaw are relative to current position; iffalse, absolutelinear- Iftrue, use linear interpolation; iffalse, use polynomial trajectorygroup_mask- Bitmask selecting which Crazyflies to command. UseNonefor all Crazyflies.
Sourcepub async fn spiral(
&self,
angle: f32,
initial_radius: f32,
final_radius: f32,
altitude_gain: f32,
duration: f32,
sideways: bool,
clockwise: bool,
group_mask: Option<u8>,
) -> Result<()>
pub async fn spiral( &self, angle: f32, initial_radius: f32, final_radius: f32, altitude_gain: f32, duration: f32, sideways: bool, clockwise: bool, group_mask: Option<u8>, ) -> Result<()>
Fly a spiral segment.
The Crazyflie moves along an arc around a computed center point, sweeping
through an angle of up to ±2π (one full turn). While sweeping, the radius
changes linearly from initial_radius to final_radius. If the radii are
equal, the path is a circular arc; if they differ, the path spirals inward
or outward accordingly. Altitude changes linearly by altitude_gain over
the duration.
§Center placement
The spiral center is placed differently depending on sideways and clockwise:
sideways = falseclockwise = true→ center lies to the right of the current heading.clockwise = false→ center lies to the left of the current heading.
sideways = trueclockwise = true→ center lies ahead of the current heading.clockwise = false→ center lies behind the current heading.
§Orientation
sideways = false: the Crazyflie’s heading follows the tangent of the spiral (flies forward along the path).sideways = true: the Crazyflie’s heading points toward the spiral center while circling around it (flies sideways along the path).
§Direction conventions
clockwisechooses on which side the center is placed.- The sign of
anglesets the travel direction along the arc:angle > 0sweeps one way;angle < 0traverses the arc in the opposite direction (i.e., “backwards”). This can make some combinations appear counterintuitive—for example,sideways = false,clockwise = true,angle < 0will look counter-clockwise from above.
§Arguments
angle- Total spiral angle in radians (limited to ±2π).initial_radius- Starting radius in meters (≥ 0).final_radius- Ending radius in meters (≥ 0).altitude_gain- Vertical displacement in meters (positive = climb, negative = descent).duration- Time in seconds to complete the spiral. This method blocks for this duration.sideways- Iftrue, heading points toward the spiral center; iffalse, heading follows the spiral tangent.clockwise- Iftrue, fly clockwise; otherwise counter-clockwise.group_mask- Bitmask selecting which Crazyflies this applies to.
§Errors
Returns Error::InvalidArgument if any parameters are out of range,
or Error::Disconnected if the command cannot be sent.
Source§impl HighLevelCommander
Trajectory implementations
impl HighLevelCommander
Trajectory implementations
Sourcepub async fn define_trajectory(
&self,
trajectory_id: u8,
memory_offset: u32,
num_pieces: u8,
trajectory_type: Option<u8>,
) -> Result<()>
pub async fn define_trajectory( &self, trajectory_id: u8, memory_offset: u32, num_pieces: u8, trajectory_type: Option<u8>, ) -> Result<()>
Define a trajectory previously uploaded to memory.
§Arguments
trajectory_id- Identifier used to reference this trajectory later.memory_offset- Byte offset into trajectory memory where the data begins.piece_count- Number of segments (pieces) in the trajectory.trajectory_type- Type of the trajectory data (e.g. Poly4D).
§Errors
Returns Error::Disconnected if the command cannot be sent.
Sourcepub async fn start_trajectory(
&self,
trajectory_id: u8,
time_scale: f32,
relative_position: bool,
relative_yaw: bool,
reversed: bool,
group_mask: Option<u8>,
) -> Result<()>
pub async fn start_trajectory( &self, trajectory_id: u8, time_scale: f32, relative_position: bool, relative_yaw: bool, reversed: bool, group_mask: Option<u8>, ) -> Result<()>
Start executing a previously defined trajectory.
The trajectory is identified by trajectory_id and can be modified
at execution time by scaling its speed, shifting its position, aligning
its yaw, or running it in reverse.
§Arguments
trajectory_id- Identifier of the trajectory (as defined withHighLevelCommander::define_trajectory).time_scale- Time scaling factor;1.0= original speed, values >1.0 slow down, values <1.0 speed up.relative_position- Iftrue, shift trajectory to the current setpoint position.relative_yaw- Iftrue, align trajectory yaw to the current yaw.reversed- Iftrue, execute the trajectory in reverse.group_mask- Mask selecting which Crazyflies this applies to. IfNone, defaults to all Crazyflies.
§Errors
Returns Error::Disconnected if the command cannot be sent.