crazyflie_lib/subsystems/commander.rs
1//! # Low level setpoint subsystem
2//!
3//! This subsystem allows to send low-level setpoint. The setpoints are described as low-level in the sense that they
4//! are setting the instant target state. As such they likely need to be send very often to have the crazyflie
5//! follow the wanted flight profile.
6//!
7//! The Crazyflie has a couple of safety mechanisms that one needs to be aware of in order to send setpoints:
8//! - When using the [Commander::setpoint_rpyt()] function, a setpoint with thrust=0 must be sent once to unlock the thrust
9//! - There is a priority for setpoints in the Crazyflie, this allows app and other internal subsystem like the high-level
10//! commander to set setpoints in parallel, only the higher priority setpoint is taken into account.
11//! - In no setpoint are received for 1 seconds, the Crazyflie will reset roll/pitch/yawrate to 0/0/0 and after 2 seconds
12//! will fallback fallback to a lower-priority setpoint which in most case will cut the motors.
13//!
14//! The following example code would drive the motors in a ramp and then stop:
15//! ``` no_run
16//! # use tokio::time::{sleep, Duration};
17//! # async fn ramp(crazyflie: crazyflie_lib::Crazyflie) -> Result<(), Box<dyn std::error::Error>> {
18//! // Unlock the commander
19//! crazyflie.commander.setpoint_rpyt(0.0, 0.0, 0.0, 0).await?;
20//!
21//! // Ramp!
22//! for thrust in (0..20_000).step_by(1_000) {
23//! crazyflie.commander.setpoint_rpyt(0.0, 0.0, 0.0, thrust).await?;
24//! sleep(Duration::from_millis(100)).await;
25//! }
26//!
27//! // Stop the motors
28//! crazyflie.commander.setpoint_rpyt(0.0, 0.0, 0.0, 0).await?;
29//! # Ok(())
30//! # }
31//! ```
32
33use crazyflie_link::Packet;
34use flume::Sender;
35
36use crate::{Error, Result};
37
38use crate::crazyflie::COMMANDER_PORT;
39use crate::crazyflie::GENERIC_SETPOINT_PORT;
40
41
42// Channels
43const RPYT_CHANNEL: u8 = 0;
44const GENERIC_SETPOINT_CHANNEL: u8 = 0;
45const GENERIC_CMD_CHANNEL: u8 = 1;
46
47// Setpoint type identifiers
48const TYPE_POSITION: u8 = 7;
49const TYPE_VELOCITY_WORLD: u8 = 8;
50const TYPE_ZDISTANCE: u8 = 9;
51const TYPE_HOVER: u8 = 10;
52const TYPE_MANUAL: u8 = 11;
53const TYPE_STOP: u8 = 0;
54const TYPE_META_COMMAND_NOTIFY_SETPOINT_STOP: u8 = 0;
55
56/// # Low level setpoint subsystem
57///
58/// This struct implements methods to send low level setpoints to the Crazyflie.
59/// See the [commander module documentation](crate::subsystems::commander) for more context and information.
60#[derive(Debug)]
61pub struct Commander {
62 uplink: Sender<Packet>,
63}
64
65impl Commander {
66 pub(crate) fn new(uplink: Sender<Packet>) -> Self {
67 Self { uplink }
68 }
69}
70
71/// # Legacy RPY+ setpoint
72///
73/// This setpoint was originally the only one present in the Crazyflie and has been (ab)used to
74/// implement the early position control and other assisted and semi-autonomous mode.
75impl Commander {
76 /// Sends a Roll, Pitch, Yawrate, and Thrust setpoint to the Crazyflie.
77 ///
78 /// By default, unless modified by [parameters](crate::subsystems::param::Param), the arguments are interpreted as:
79 /// * `roll` - Desired roll angle (degrees)
80 /// * `pitch` - Desired pitch angle (degrees)
81 /// * `yawrate` - Desired yaw rate (degrees/second)
82 /// * `thrust` - Thrust as a 16-bit value (0 = 0% thrust, 65535 = 100% thrust)
83 ///
84 /// Note: Thrust is locked by default for safety. To unlock, send a setpoint with `thrust = 0` once before sending nonzero thrust values.
85 ///
86 /// Example:
87 /// ```no_run
88 /// # fn spin(cf: crazyflie_lib::Crazyflie) {
89 /// cf.commander.setpoint_rpyt(0.0, 0.0, 0.0, 0); // Unlocks thrust
90 /// cf.commander.setpoint_rpyt(0.0, 0.0, 0.0, 1000); // Sets thrust to 1000
91 /// # }
92 /// ```
93 pub async fn setpoint_rpyt(&self, roll: f32, pitch: f32, yawrate: f32, thrust: u16) -> Result<()> {
94 let mut payload = Vec::new();
95 payload.append(&mut roll.to_le_bytes().to_vec());
96 // Pitch is negated for compatibility with crazyflie-lib-python
97 payload.append(&mut (-pitch).to_le_bytes().to_vec());
98 payload.append(&mut yawrate.to_le_bytes().to_vec());
99 payload.append(&mut thrust.to_le_bytes().to_vec());
100
101 let pk = Packet::new(COMMANDER_PORT, RPYT_CHANNEL, payload);
102
103 self.uplink
104 .send_async(pk)
105 .await
106 .map_err(|_| Error::Disconnected)?;
107
108 Ok(())
109 }
110}
111
112/// # Generic setpoints
113///
114/// These setpoints are implemented in such a way that they are easy to add in the Crazyflie firmware
115/// and in libs like this one. So if you have a use-case not covered by any of the existing setpoint
116/// do not hesitate to implement and contribute your dream setpoint :-).
117impl Commander {
118 /// Sends an absolute position setpoint in world coordinates, with yaw as an absolute orientation.
119 ///
120 /// # Arguments
121 /// * `x` - Target x position (meters, world frame)
122 /// * `y` - Target y position (meters, world frame)
123 /// * `z` - Target z position (meters, world frame)
124 /// * `yaw` - Target yaw angle (degrees, absolute)
125 pub async fn setpoint_position(&self, x: f32, y: f32, z: f32, yaw: f32) -> Result<()> {
126 let mut payload = Vec::with_capacity(1 + 4 * 4);
127 payload.push(TYPE_POSITION);
128 payload.extend_from_slice(&x.to_le_bytes());
129 payload.extend_from_slice(&y.to_le_bytes());
130 payload.extend_from_slice(&z.to_le_bytes());
131 payload.extend_from_slice(&yaw.to_le_bytes());
132 let pk = Packet::new(GENERIC_SETPOINT_PORT, GENERIC_SETPOINT_CHANNEL, payload);
133 self.uplink.send_async(pk).await.map_err(|_| Error::Disconnected)?;
134 Ok(())
135 }
136
137 /// Sends a velocity setpoint in the world frame, with yaw rate control.
138 ///
139 /// # Arguments
140 /// * `vx` - Target velocity in x (meters/second, world frame)
141 /// * `vy` - Target velocity in y (meters/second, world frame)
142 /// * `vz` - Target velocity in z (meters/second, world frame)
143 /// * `yawrate` - Target yaw rate (degrees/second)
144 pub async fn setpoint_velocity_world(&self, vx: f32, vy: f32, vz: f32, yawrate: f32) -> Result<()> {
145 let mut payload = Vec::with_capacity(1 + 4 * 4);
146 payload.push(TYPE_VELOCITY_WORLD);
147 payload.extend_from_slice(&vx.to_le_bytes());
148 payload.extend_from_slice(&vy.to_le_bytes());
149 payload.extend_from_slice(&vz.to_le_bytes());
150 payload.extend_from_slice(&yawrate.to_le_bytes());
151 let pk = Packet::new(GENERIC_SETPOINT_PORT, GENERIC_SETPOINT_CHANNEL, payload);
152 self.uplink.send_async(pk).await.map_err(|_| Error::Disconnected)?;
153 Ok(())
154 }
155
156 /// Sends a setpoint with absolute height (distance to the surface below), roll, pitch, and yaw rate commands.
157 ///
158 /// # Arguments
159 /// * `roll` - Desired roll angle (degrees)
160 /// * `pitch` - Desired pitch angle (degrees)
161 /// * `yawrate` - Desired yaw rate (degrees/second)
162 /// * `zdistance` - Target height above ground (meters)
163 pub async fn setpoint_zdistance(&self, roll: f32, pitch: f32, yawrate: f32, zdistance: f32) -> Result<()> {
164 let mut payload = Vec::with_capacity(1 + 4 * 4);
165 payload.push(TYPE_ZDISTANCE);
166 payload.extend_from_slice(&roll.to_le_bytes());
167 payload.extend_from_slice(&pitch.to_le_bytes());
168 payload.extend_from_slice(&yawrate.to_le_bytes());
169 payload.extend_from_slice(&zdistance.to_le_bytes());
170 let pk = Packet::new(GENERIC_SETPOINT_PORT, GENERIC_SETPOINT_CHANNEL, payload);
171 self.uplink.send_async(pk).await.map_err(|_| Error::Disconnected)?;
172 Ok(())
173 }
174
175 /// Sends a setpoint with absolute height (distance to the surface below), and x/y velocity commands in the body-fixed frame.
176 ///
177 /// # Arguments
178 /// * `vx` - Target velocity in x (meters/second, body frame)
179 /// * `vy` - Target velocity in y (meters/second, body frame)
180 /// * `yawrate` - Target yaw rate (degrees/second)
181 /// * `zdistance` - Target height above ground (meters)
182 pub async fn setpoint_hover(&self, vx: f32, vy: f32, yawrate: f32, zdistance: f32) -> Result<()> {
183 let mut payload = Vec::with_capacity(1 + 4 * 4);
184 payload.push(TYPE_HOVER);
185 payload.extend_from_slice(&vx.to_le_bytes());
186 payload.extend_from_slice(&vy.to_le_bytes());
187 payload.extend_from_slice(&yawrate.to_le_bytes());
188 payload.extend_from_slice(&zdistance.to_le_bytes());
189 let pk = Packet::new(GENERIC_SETPOINT_PORT, GENERIC_SETPOINT_CHANNEL, payload);
190 self.uplink.send_async(pk).await.map_err(|_| Error::Disconnected)?;
191 Ok(())
192 }
193
194 /// Sends a manual control setpoint for roll, pitch, yaw rate, and thrust percentage.
195 ///
196 /// If `rate` is false, roll and pitch are interpreted as angles (degrees). If `rate` is true, they are interpreted as rates (degrees/second).
197 ///
198 /// # Arguments
199 /// * `roll` - Desired roll (degrees or degrees/second, depending on `rate`)
200 /// * `pitch` - Desired pitch (degrees or degrees/second, depending on `rate`)
201 /// * `yawrate` - Desired yaw rate (degrees/second)
202 /// * `thrust_percentage` - Thrust as a percentage (0 to 100)
203 /// * `rate` - If true, use rate mode; if false, use angle mode
204 pub async fn setpoint_manual(&self, roll: f32, pitch: f32, yawrate: f32, thrust_percentage: f32, rate: bool) -> Result<()> {
205 // Map thrust percentage to Crazyflie thrust value (10001 to 60000)
206 let thrust = 10001.0 + 0.01 * thrust_percentage * (60000.0 - 10001.0);
207 let thrust_16 = thrust as u16;
208 let mut payload = Vec::with_capacity(1 + 4 * 3 + 2 + 1);
209 payload.push(TYPE_MANUAL);
210 payload.extend_from_slice(&roll.to_le_bytes());
211 payload.extend_from_slice(&pitch.to_le_bytes());
212 payload.extend_from_slice(&yawrate.to_le_bytes());
213 payload.extend_from_slice(&thrust_16.to_le_bytes());
214 payload.push(rate as u8);
215 let pk = Packet::new(GENERIC_SETPOINT_PORT, GENERIC_SETPOINT_CHANNEL, payload);
216 self.uplink.send_async(pk).await.map_err(|_| Error::Disconnected)?;
217 Ok(())
218 }
219
220 /// Sends a STOP setpoint, immediately stopping the motors. The Crazyflie will lose lift and may fall.
221 pub async fn setpoint_stop(&self) -> Result<()> {
222 let payload = vec![TYPE_STOP];
223 let pk = Packet::new(GENERIC_SETPOINT_PORT, GENERIC_SETPOINT_CHANNEL, payload);
224 self.uplink.send_async(pk).await.map_err(|_| Error::Disconnected)?;
225 Ok(())
226 }
227
228 /// Notify the firmware that low-level setpoints have stopped.
229 ///
230 /// This tells the Crazyflie to drop the current low-level setpoint priority,
231 /// allowing the High-level commander (or other sources) to take control again.
232 ///
233 /// # Arguments
234 /// * `remain_valid_milliseconds` - How long (in ms) the last low-level setpoint
235 /// should remain valid before it is considered stale. Use `0` to make the
236 /// hand-off immediate; small non-zero values can smooth transitions if needed.
237 ///
238 /// # Examples
239 /// Hand control back to the High-level commander after a manual low-level burst:
240 /// ```no_run
241 /// # use crazyflie_lib::subsystems::commander::Commander;
242 /// # use crazyflie_lib::Result;
243 /// # async fn demo(cmd: &Commander) -> Result<()> {
244 /// // ... you were sending low-level setpoints here ...
245 /// cmd.notify_setpoint_stop(0).await?; // allow HL commander to resume
246 /// # Ok(()) }
247 /// ```
248 pub async fn notify_setpoint_stop(&self, remain_valid_milliseconds: u32) -> Result<()> {
249 let mut payload = Vec::with_capacity(1 + 4);
250 payload.push(TYPE_META_COMMAND_NOTIFY_SETPOINT_STOP);
251 payload.extend_from_slice(&remain_valid_milliseconds.to_le_bytes());
252 let pk = Packet::new(GENERIC_SETPOINT_PORT, GENERIC_CMD_CHANNEL, payload);
253 self.uplink.send_async(pk).await.map_err(|_| Error::Disconnected)?;
254 Ok(())
255 }
256}