Crazyflie Interfaces Python - Package
The package provides Server and Client classes which can be implemented.
E.g. the crazyflie_webots
implementation uses the server
and implements the functionality when the topics are called.
For coding your own application logic the client classes should be used, which create the appropriate publishers.
Crazyflie Interfaces Python Clients
These clients are used to translate the ros2 topics to python functionality. They represent an access point to the different components of the crazyflie interface. The modules represent the different CRTP ports of the Crazyflie CRTP protocol.
All classes are instantiated with a Node (rclpy.node.Node
) and a Prefix (str
).
The modules will each create a rclpy.callback_group
to which they add publishers and subscriptions.
The user is repsonsible for spinning the node.
The Prefix is needed in order to map to the correct Crazyflie namespace. In most cases this is just /cfXX
, where XX is the id.
Console
This module has no functionality at the moment. You might be able to receive the crazyflies console with this module in the future.
- class crazyflie_interfaces_python.client.console.ConsoleClient(node, prefix, callback=None)
The console functionality of the crazyflie.
Console: https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/functional-areas/crtp/crtp_console/ The console messages from crazyflie are processed and sent as lines to the console topic. Add a callback in constructor to acces the messages.
- Parameters:
node (rclpy.node.Node)
prefix (str)
callback (Callable[[str], None])
Emergency
Generic Commander
This is the entry point to the Crazyflie’s low level commander.
The commands are sent directly to Crazyflie’s controller.
Sending position setpoints to far away points will crash the Crazyflie.
Also, be sure to call notify_setpoints_stop
before sending high level commands again.
- class crazyflie_interfaces_python.client.generic_commander.GenericCommanderClient(node, prefix)
Send control setpoints to the Crazyflie. For more information on the functionality of the setpoints visit the official bitcraze website: https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/api/cflib/crazyflie/commander/
This commander sends low-level setpoints directly to the PID/Mellinger controller of the Crazyflie. Sending setpoints to far from current state can crash the crazyflie. All low-level commands must be sent out regulary (>= 5Hz) in order not to trigger fail safe mechanisms in the Crazyflie.
- Parameters:
node (rclpy.node.Node)
prefix (str)
- cmd_full_state(position, velocity, acceleration, orientation, angular_rate)
Send a full-state setpoint to controller (low-level)
Can be used for aggressive maneuvers
- Parameters:
position (List[float]) – Position [x, y, z] in m
velocity (List[float]) – Velocity [vx, vy, vz] in m/s
acceleration (List[float]) – Acceleration [ax, ay, az] in m/s^2
orientation (List[float]) – Orientation in quaternion components [qx, qy, qz, qw]
omega (List[float]) – Angular rates [Rollrate, Pitchrate, Yawrate] in degrees/s (TODO: rad/s ???)
angular_rate (List[float])
- Return type:
None
- cmd_hover(z_distance, velocity_x=0.0, velocity_y=0.0, yawrate=0.0)
Send a hover setpoint to controller (low-level)
Sets the crazyflie absolute height and velocity in body coordinate system.
- Parameters:
z_distance (float) – Absolute height in m
velocity_x (float, optional) – Velocity in x direction (body coordinates) in m/s. Defaults to 0.0.
velocity_y (float, optional) – Velocity in y direction (body coordinates) in m/s. Defaults to 0.0.
yawrate (float, optional) – Angular velocity in deg/s. Defaults to 0.0.
- Return type:
None
- cmd_position(position, yaw)
Send a position setpoint to controller (low-level)
- Parameters:
position (List[float]) – Position [x, y, z] in m
yaw (float) – Orientation in degrees
- Return type:
None
- cmd_velocity_world(velocity, yawrate=0.0)
Send a velocity world setpoint to controller (low-level)
This control-command does not work with Mellinger controller. Switch to PID controller if you are using this setpoint command.
- Parameters:
velocity (List[float]) – Velocity in m/s in world coordinates (vx, vy, vz).
yawrate (float, optional) – Angular velocity in degrees/s . Defaults to 0.0.
- Return type:
None
- notify_setpoints_stop(remain_valid_milliseconds=100, group_mask=0)
Send a notify setpoints command Informs that streaming low-level setpoint packets are about to stop. A common use case is to send this after the last low-level setpoint is sent but before the first high-level setpoint is sent.
- Parameters:
remain_valid_milliseconds (int, optional) – Artefact of pull-based hl-commander architecture no longer needed. Defaults to 100.
group_mask (int, optional) – The group this should apply to. Deprecated Dec2024. Defaults to 0.
- Return type:
None
High Level Commander
- class crazyflie_interfaces_python.client.high_level_commander.HighLevelCommanderClient(node, prefix)
Send high level commands to the Crazyflie. For more information visit the official bitcraze website: https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/api/cflib/crazyflie/high_level_commander/
These high level commands get processed onboard the Crazyflie. Polynomials are calculated in order to fly smooth trajectories between the commanded setpoints. Before switching from low-level to high-level commands the low-level command notify setpoints stop should be called.
- Parameters:
node (rclpy.node.Node)
prefix (str)
- go_to(x, y, z, yaw, duration_seconds, relative=False, linear=False, group_mask=0)
Move to x, y, z, yaw in duration_seconds amount of time (high-level)
The Crazyflie will hover indefinetely afterwards. Calling goTo rapidly (> 1Hz) can cause instability. Consider using the cmd_position() setpoint command from generic_commander instead.
- Parameters:
x (float) – x-position of goal in meters
y (float) – y-position of goal in meters
z (float) – z-position of goal in meters
yaw (float) – target yaw in radians
duration_seconds (float) – Time in seconds it should take the CF to move to goal
relative (bool, optional) – If true the goal and yaw are interpreted as relative to current position. Defaults to False.
linear (bool, optional) – If true a linear interpolation is used for trajectory instead of a smooth polynomial . Defaults to False.
group_mask (int, optional) – mask for which CFs this should apply to. Defaults to 0.
- Return type:
None
- land(target_height, duration_seconds, yaw=None, group_mask=0)
Vertical landing from current x-y position to given height (high-level)
The Crazyflie will hover indefinetely after target_height is reached. This should usually be followed by a stop command, but is not strictly required.
- Parameters:
target_height (float) – _description_
duration_seconds (float) – _description_
yaw (float, optional) – _description_. Defaults to None.
group_mask (int, optional) – _description_. Defaults to 0.
- Return type:
None
- land_with_velocity(height, yaw, velocity, height_is_relative=False, use_current_yaw=False, group_mask=0)
Vertical landing with given velocity (high-level) Only supported in newer firmware versions.
- Parameters:
height (float) – Height to land to in m (absolute unless height_is_relative is set)
yaw (float) – Target orientation in radians
velocity (float) – Average velocity during takeoff m/s
height_is_relative (bool, optional) – If true height is relative to current zHeight. Defaults to False.
use_current_yaw (bool, optional) – If true ignores yaw parameter and use current orientation. Defaults to False.
group_mask (int, optional) – mask for which CFs this should apply to. Defaults to 0.
- Return type:
None
- set_group_mask(group_mask)
Sets the group mask of the crazyflie
Deprecated will be removed December 2024 This can be used to split a swarm of Crazyflies into groups and then send high level commands via broadcasting messages.
- Parameters:
group_mask (int) – the group ID this CF belongs to
- spiral(sideways, clockwise, phi, r0, rf, dz, duration_seconds, group_mask=0)
Fly along a spiral path (high-level)
- Parameters:
sideways (bool) – Set to true if Crazyflie shoud spiral sideways instead of forward
clockwise (bool) – Set to true if Crazyflie shoudl spiral clockwise instead of counter-clockwise
phi (float) – Spiral angle in radians, limited to +- 2 PI
r0 (float) – Inital radius in m, must be positive
rf (float) – Final radius in m, must be positive
dz (float) – Altitude gain in , if positive climb else descent
duration_seconds (float) – The time it should take to reach the end of the spiral in seconds
group_mask (int, optional) – mask for which crazyflies this should apply to. Defaults to 0.
- Return type:
None
- start_trajectory(trajectory_id, timescale=1.0, reversed=False, relative=True, group_mask=0)
Begin executing an uploaded trajectory (high-level)
- Parameters:
trajectory_id (int) – ID of trajectory as uploaded
timescale (float, optional) – Scales the duration of trajectory by this factor (if 2.0, trajectory twice as long). Defaults to 1.0.
reversed (bool, optional) – Execute the trajectory in reverse order. Defaults to False.
relative (bool, optional) – Of true, the position of the trajectory is shifted such that it begins at the current position setpoint. Defaults to True.
group_mask (int, optional) – mask for which Crazyflies this should apply to. Defaults to 0.
- Return type:
None
- stop(group_mask=0)
Turns off the motors (high-level)
- Parameters:
group_mask (int, optional) – mask for which CFs this should apply to. Defaults to 0.
- Return type:
None
- takeoff(target_height, duration_seconds, yaw=None, use_current_yaw=False, group_mask=0)
Vertical takeoff from current x-y position to given height (high-level)
The Crazyflie will hover indefinetely after target_height is reached.
- Parameters:
target_height (float) – height to takeoff to (absolute) in meters
duration_seconds (float) – time it should take until target_height is reached in seconds
yaw (float) – Target orientation in radians
use_current_yaw (bool) – If true use ignore yaw parameter. Defaults to False.
group_mask (int, optional) – mask for which CFs this should apply to. Defaults to 0.
- Return type:
None
- takeoff_with_velocity(height, yaw, velocity, height_is_relative=False, use_current_yaw=False, group_mask=0)
Vertical takeoff with given velocity (high-level) Only supported in newer firmware versions.
- Parameters:
height (float) – Height to takeoff to in m (absolute unless height_is_relative is set)
yaw (float) – Target orientation in radians
velocity (float) – Average velocity during takeoff m/s
height_is_relative (bool, optional) – If true height is relative to current zHeight. Defaults to False.
use_current_yaw (bool, optional) – If true ignore yaw parameter and use current orientation. Defaults to False.
group_mask (int, optional) – mask for which CFs this should apply to. Defaults to 0.
- Return type:
None
- upload_trajectory(trajectory_id, piece_offset, pieces)
Uploads a piecewise polynomial trajectory for later execution.
This feature is currently not fully supported.
TODO: How do poly pieces work, should we also use uav_trajectory.py See https://crazyswarm.readthedocs.io/en/latest/api.html or ask whoenig for further information.
- Parameters:
trajectory_id (int) – The trajectory id to reference in start_trajectory
piece_offset (int) – TODO
pieces (List) – TODO
- Return type:
None
Logging
- class crazyflie_interfaces_python.client.logging.LoggingClient(node, prefix)
The logging functionality of the crazyflie. https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/functional-areas/crtp/crtp_log/
The logging on the crazyflie is segemented into log blocks. Create a log block with variables from: (other implementations (webots or older crazyflie version) might not have all logging variables available) https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/api/logs/
This creates a LogBlockClient, on which you can start and stop the log block.
- Parameters:
node (rclpy.node.Node)
prefix (str)
- create_log_block(variables, name, callback)
Create a log block with given variables.
The created topic will have the specified name
- Parameters:
variables (List[str]) – The logging variables (e.g. [“range.zrange”, ])
name (str) – The name of the rostopic
callback (Callable[[List[float]], None]) – A callback function for data beeing received
- Returns:
A LogBlockClient object with which the block can be started/stopped
- Return type:
- class crazyflie_interfaces_python.client.logblock.LogBlockClient(node, prefix, name, callback)
If a log block was created you can use this to start and stop log blocks.
- Parameters:
node (rclpy.node.Node)
prefix (str)
name (str)
callback (Callable[[List[float]], None])
- start_log_block(period_ms)
Start the log block with specified period.
- Parameters:
period_ms (int) – The period in ms in which log gets querried
- Return type:
None
- stop_log_block()
Stops the log block.
- Return type:
None
RPYT Commander
- class crazyflie_interfaces_python.client.rpyt_commander.RPYTCommanderClient(node, prefix)
- Parameters:
node (rclpy.node.Node)
prefix (str)
- send_rpyt_setpoint(roll, pitch, yawrate, thrust)
Send a roll pitch yawrate thrust command
This is typically used for manual flying (easy mode) as the angles correspond to stick positions.
- Parameters:
roll (float) – The roll angle, positive rolls to right
pitch (float) – The pitch angle, positive pitch forward
yawrate (float) – The angular velocity of yaw, positive turn counter clockwise
thrust (int) – Thrust magnitude. Non meaningfull units corresponds to a uint16_t 0-100% [0, 2^16]
- Raises:
NotImplementedError – Will always return this error because it is not implemented in this library.
- Return type:
None