Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • danc/MicroCART
  • snawerdt/MicroCART_17-18
  • bbartels/MicroCART_17-18
  • jonahu/MicroCART
4 results
Show changes
Showing
with 681 additions and 0 deletions
---
title: Lighthouse system overview
page_id: lh_system_overview
---
The lighthouse deck allows to use the HTC-Vive/SteamVR lighthouse tracking system to fly Crazyflies autonomously. The system works with one or two Lighthouse base stations (two recommended), both V1 and V2 are supported. It is not possible to mix V1 and V2 base stations in the same system.
After everything is setup, the computer is not required anymore: the Crazyflie will autonomously estimate its position from the lighthouse signals.
## The basics
The information obtained from a lighthouse system is essentially two angles describing the direction from the base station to each light sensor on the lighthouse deck. All measurements and position calculations are performed in the Crazyflie.
The Crayzflie needs two pieces of system information to be able to estimate its position. The first is calibration data for all base stations in the system, the second is geometry data.
The calibration data describes slight imperfections in the the manufacturing of the base stations. The calibration data is measured in the factory and is stored in each base station. The calibration data is required to calculate the angles with a high level of accuracy.
The geometry data describes the position and orientation of the base stations and is needed to understand how the measured angles relate to the global reference frame.
The geometry data is calculated by the client using raw angles corrected by calibration data.
Calibration and geometry data is stored in the Crazyflie to make it possible to take off and use the lighthouse system imediate after reboot.
The Crazyflie must know if the system is using V1 or V2 type base stations, this is set manually from the client.
## The number of base stations and frame synchronization
The lighthouse deck works with one or two basestations but the estimated position will be better and more stable with two basestations. When using two basestations, one of them may be occluded temporarily, and the Crazyflie will use the other one for positioning.
The protocol for the lighthouse V1 is composed of frames starting with sync pulses from the basestations. The sync pulses are used to identify which basestation the frame is originating from and this information is essential for correct positioning. When one basestation is occluded, only sync pulses from the visible basestation will be available to the system, which is fine as long as the the system can keep track of the frames. If we loose track of the frames, for instance if both basestations are occluded, the system has to re-synch again to function, but this is a quick process when the basestations are visible. Due to the design of the lighthouse protocol, visibility to both basestations is always required for synchronization or re-synchronization in a two basestation system.
The protocol in lighthouse 2 does not use the same frame concept and there is no need for frame sync.
The lighthouse V2 protocol supports more than 2 base stations and most of the Crazyflie firmware is designed for this as well but the tools currently only support two base stations.
The ```PULSE_PROCESSOR_N_BASE_STATIONS``` (in pulse_processor.h) determines the number of base stations that are handled by the system and can be increased by brave users. This feature is very much untested and there is currently no support to estimate the geometry of a 2+ system.
## Position estimation methods
There are currently two ways of calculating the position using the lighthouse.
The first method that was implemented calculates two vectors (or beams) from the basestations, based on the sweep angles measured by the sensors on the Crazyflie. The intersection point between the beams is the position of the Crazyflie, and this point is pushed into the estimator. We call this method the “crossing beam” method. A more recent implementation pushes the sweep angles from the base stations into the estimator and lets the kalman filter calculate the position based on this information. This method is called the “sweep angle” method and also works if only one basestation is available. It is possible to change positioning method “on the fly” by setting the lighthouse.method parameter. The sweep angle method is the default.
## V1 vs. V2
Crazyflie support two generation of lighthouse basestation called V1 and V2.
The main difference between the two versions is that lighthouse V1 is designed to work with 2 basestion sychonized either optically or via a cable, and V2 is design to work with any number of independent basestations setup on different channels.
---
title: Lighthouse terminology and definitions
page_id: lh_terminology
---
This page contains terminology and definitions for the lighthouse system to make it easier to
understand and discuss algorithms and code. Our definitions probably do not match the ones used
by other software packages, but we find these suitable for our setup.
## Reference frames
There are a number of different reference frames (or coordinate systems) used.
### Global reference frame
The global coordinate system is fixed in the room and shared by all parts of the system. This system
is used for absolute position references in set points and the kalman estimator.
### Crazyflie reference frame
The Crazyflie reference frame is defined with the X-axis pointing forward, the Y-axis pointing left when seen from behind
and the Z-axis pointing upwards.
### Base station reference frame
The base station coordinate system is defined as
* X-axis pointing forward through the glass
* Y-axis pointing right, when the base station is seen from the front.
* Z-axis pointing up (away from the screw mount)
![Base station reference frame](/docs/images/lighthouse/base_station_ref_frame.png)
### Rotor reference frame
There is one (LH2) or two rotors (LH1) in a base station. Each rotor is rotating around an axis of rotation, $$\vec{r}$$.
We define a coordinate system for the rotor where the Z-axis points along $$\vec{r}$$ and the X-axis is the same as the X-axis
of the base station.
![Rotor reference frame](/docs/images/lighthouse/rotor_ref_frame.png)
The axis of rotation is defined such that when $$\vec{r}$$ is pointing towards you, the drum is spinning counterclockwise.
## Geometry data
The geometry data (position $$\vec{p_{bs}}$$ and rotation matrix $$R_{bs}$$) describes the pose of a base station in the global coordinate system
such that a point $$\vec{q_{bs}}$$ in the base station reference frame is transformed to the global reference frame by $$\vec{q} = \vec{p_{bs}} + R_{bs} \cdot \vec{q_{bs}}$$.
## Rotors
In relation to the base station reference frame we have
| System type | rotor | $$\vec{r}$$ |
| ----------- | ---------------------------------------------------- | -------------- |
| LH 1 | horizontal sweep (left to right seen from the front) | $$(0, 0, 1)$$ |
| LH 1 | vertical sweep (down to up seen from the front) | $$(0, -1, 0)$$ |
| LH 2 | horizontal sweep (left to right seen from the front) | $$(0, 0, 1)$$ |
The coordinate systems for the horizontal LH1 rotor and the LH2 rotor are identical to the base station reference frame.
### Rotation angle
Rotation angle $$\alpha=0$$ is forward, along the X axis in the rotor (and base station) reference frame.
![Rotor rotation angle](/docs/images/lighthouse/rotor_rotaion_angle.png)
**Note:** In LH2 the two light planes are offset from each other on the rotor by 120 degrees, but this offset is compensated for in the decoding
part of the firmware. For a sensor placed along the X-axis, the measured $$\alpha = 0$$ for both light planes.
### Light plane tilt
There is a lens on the rotor spreading light in the form of a plane, rotating with the rotor. In LH1 the plane is oriented along the axis of rotation,
sweeping the room when the rotor spins, while LH2 has two light planes that are tilted by an angle $$\pm t$$. $$t$$ is defined such that the plane is
rotated counterclockwise with increasing $$t$$, seen from the front of the base station ($$\alpha = 0$$).
![Rotor rotation angle](/docs/images/lighthouse/light_plane_tilt.png "Rotor seen from the front, with the lens straight forward")
In the general form we have no tilt for the rotors of LH1, in LH2 the planes are tilted 30 degrees.
| System type | rotor / light plane | $$t$$ |
| ----------- | --------------------------------------------------------- | ------------------ |
| LH 1 | horizontal sweep (left to right seen from the front) | 0 |
| LH 1 | vertical sweep (down to up seen from the front) | 0 |
| LH 2 | horizontal sweep, first light plane | $$-\frac{\pi}{6}$$ |
| LH 2 | horizontal sweep, second light plane | $$\frac{\pi}{6}$$ |
---
title: The Loco Positioning System
page_id: loco_positioning
---
The Loco Positioning System is an absolute positioning system based on Ultra Wide Band (UWB) radios.
Most of the documentation for the Loco Positioning System can be found in the [lps-node-firmware repository documentation](https://www.bitcraze.io/documentation/repository/lps-node-firmware/master/), this is where protocols, principles and modes are described.
This section contains details specific to the implementation in the Crazyflie, mainly estimator related information.
## Position estimation
When using the Loco Positioning System the [Kalman estimator](/docs/functional-areas/sensor-to-control/state_estimators.md#extended-kalman-filter) is used for position estimation. The two main ranging schemes used for UWB localization are (i) two-way ranging (TWR) and (ii) time-difference-of-arrival (TDoA). In this page, we elaborate the measurement model, Kalman filter update and robust estimation for both TWR and TDoA.
### Two-way ranging (TWR)
In TWR, the UWB tag mounted on the Crazyflie communicates with fixed UWB anchors and acquires range measurements through two-way communication. The measurement model is as follows:
$$d_i = \sqrt{(x-x_i)^2 +(y-y_i)^2 + (z-z_i)^2}$$,
where $$(x, y, z)$$ is the position of the Crazyflie and $$(x_i, y_i, z_i)$$ is the position of the fixed anchor i. For the conventional extended Kalman filter, we have
$$g_x = (x-x_i) / d_i$$
$$g_y = (y-y_i) / d_i$$
$$g_z = (z-z_i) / d_i$$.
The H vector is
$$H = (g_x, g_y, g_z, 0, 0, 0, 0, 0, 0)$$.
Then, we call the function `kalmanCoreScalarUpdate()` in [kalman_core.c](https://github.com/bitcraze/crazyflie-firmware/blob/master/src/modules/src/kalman_core/kalman_core.c) to update the states and covariance matrix.
### Time-difference-of-arrival (TDoA)
In TDoA, UWB tags receive signals from anchors passively and compute the difference in distance beween two anchors as TDoA measurements. Since in TDoA scheme, UWB tags only listen to the messages from anchors, a TDoA-based localization system allows a theoretically unlimited number of robots to localize themselves with a small number of fixed anchors. However, TDoA measurements are more noisy than TWR measurements, leading to a less accurate localization performance. Two types of TDoA protocols ([TDoA2](https://www.bitcraze.io/documentation/repository/lps-node-firmware/master/protocols/tdoa2_protocol/) and [TDoA3](https://www.bitcraze.io/documentation/repository/lps-node-firmware/master/protocols/tdoa3_protocol/)) are implemented in LPS system. The main difference between the two TDoA protocols is that TDoA3 protocol achieves the scalability at the cost of localization accuracy. The readers are refer to [TDoA2 VS TDoA3](https://www.bitcraze.io/documentation/repository/lps-node-firmware/master/functional-areas/tdoa2-vs-tdoa3/) for detailed information.
The TDoA measurement model is as follows:
$$d_{ij} = d_j - d_i = \sqrt{(x-x_j)^2 +(y-y_j)^2 + (z-z_j)^2} - \sqrt{(x-x_i)^2 +(y-y_i)^2 + (z-z_i)^2}$$,
where $$(x, y, z)$$ is the position of the Crazyflie and $$(x_i, y_i, z_i)$$ and $$(x_j, y_j, z_j)$$ are the positions of fixed anchor i and j, respectively. For the conventional extended Kalman filter, we have
$$g_x = (x-x_j) / d_j - (x-x_i) / d_i$$
$$g_y = (y-y_j) / d_j - (y-y_i) / d_i$$
$$g_z = (z-z_j) / d_j - (z-z_i) / d_i$$.
The H vector is
$$H = (g_x, g_y, g_z, 0, 0, 0, 0, 0, 0)$$.
Then, we call the function `kalmanCoreScalarUpdate()` in [kalman_core.c](https://github.com/bitcraze/crazyflie-firmware/blob/master/src/modules/src/kalman_core/kalman_core.c) to update the states and covariance matrix.
### M-estimation based robust Kalman filter
UWB radio signal suffers from outlier measurements caused by radio multi-path reflection and non-line-of-sight propagation. The large erroneous measurements often deteriorate the accuracy of UWB localization. The conventional Kalman filter is sensitive to measurement outliers due to its intrinsic minimum mean-square-error (MMSE) criterion. Here, we provide a robust estiamtion approach based on M-estimation robust cost function. We will explain the general idea of the robust Kalman filter and readers are encouraged to look into the firmware [mm_distance_robust](https://github.com/bitcraze/crazyflie-firmware/blob/master/src/modules/src/kalman_core/mm_distance_robust.c) and [mm_tdoa_robust](https://github.com/bitcraze/crazyflie-firmware/blob/master/src/modules/src/kalman_core/mm_tdoa_robust.c). The implementation is based on paper [1] and please read the paper for implementation details.
From the Bayesian maximum a posteriori perspective, the Kalman filter state estimation framework can be derived by solving the following minimization problem:
![equation](/docs/images/rkf-eq1.png)
Therein, $$x_k$$ and $$y_k$$ are the system state and measurements at timestep k, $$P_k$$ and $$R_k$$ denote the prior covariance and measurement covariance, respectively. Through Cholesky factorization of $$P_k$$ and $$R_k$ $, the original optimization problem is equivalent to:
![equation](/docs/images/rkf-eq2.png)
where $$e_{x,k,i}$$ and $$e_{y,k,i}$$ are the elements of $$e_{x,k}$$ and $$e_{y,k}$$. To reduce the influence of outliers, we incorporate a robust cost function into the Kalman filter framework as follows:
![equation](/docs/images/rkf-eq3.png)
where $$\rho()$$ could be any robust function (e.g., G-M, SC-DCS, Huber, Cauchy, etc.)
By introducing a weight function for the process and measurement uncertainties---with e as input---we can translate the optimization problem into an Iterative Reweight Least-Square (IRLS) problem. Then, the optimal posterior estimate can be computed through iteratively solving the least-square problem using the robust weights computed from the previous solution. In our implementation, we use the G-M robust cost function and the maximum iteration is set to be two for computational frugality. Then, we call the function `kalmanCoreUpdateWithPKE()` in [kalman_core.c](https://github.com/bitcraze/crazyflie-firmware/blob/master/src/modules/src/kalman_core/kalman_core.c) with the weighted covariance matrix $P_w_m$, kalman gain Km, and innovation error to update the states and covariance matrix.
This functionality can be turned on through setting a parameter (robustTwr or robustTdoa) in [estimator_kalman.c](https://github.com/bitcraze/crazyflie-firmware/blob/master/src/modules/src/estimator_kalman.c).
## References
[1] Zhao, Wenda, Jacopo Panerati, and Angela P. Schoellig. "Learning-based Bias Correction for Time Difference of Arrival Ultra-wideband Localization of Resource-constrained Mobile Robots." IEEE Robotics and Automation Letters 6, no. 2 (2021): 3639-3646.
---
title: Generic application memory - MEM_TYPE_APP
page_id: mem_type_app
---
This memory can be used by applications and the memory
layout is application specific.
---
title: Deck memory - MEM_TYPE_DECK_MEM
page_id: mem_type_deck_mem
---
This memory is used to access memory on decks when available. Decks that have firmware may also
support firmware updates through write operations to the memory.
The information section contains information that allows a client to enumerate installed decks,
identify decks with firmware that needs to be updated and the address to write new firmware to.
The information in a `Deck memory info` record is only valid if the `Is valid` bit is set to 1. The `Is Valid` bit
is always valid, also when set to 0.
Some decks may take a while to boot, the `Is started` bit indicates if the deck has started and is ready.
Data in the `Deck memory info` record should only be used if both the `Is Valid` and the `Is started`
bits are set.
The firmware that is required by a deck is uniquely identified through the tuple `(required hash, required length, name)`.
A deck driver may implement read and/or write operations to data on a deck, a camera deck could for
instance proved image data through a memory read operation. The deck driver can freely choose the addresses
where data is mapped. From a client point of view the address will be relative to the base address of the deck,
the base address is aquired by a client from the information section.
If a deck has firmware upgrade capabilities, the write address for firmware upgrades must allways be at 0 (relative
to the base address). A deck is ready to receive FW if the `Bootloader active` flag is set.
## Memory layout
| Address | Type | Description |
|-------------------|--------------|----------------------------------------------------------|
| 0x0000 | Info section | Information on installed decks and the mapping to memory |
| deck 1 base addr | raw memory | Mapped to the memory on deck 1 |
| deck 2 base addr | raw memory | Mapped to the memory on deck 2 |
| deck 3 base addr | raw memory | Mapped to the memory on deck 3 |
| deck 4 base addr | raw memory | Mapped to the memory on deck 4 |
### Info section memory layout
| Address | Type | Description |
|---------|------------------|------------------------|
| 0x0000 | uint8 | Version, currently 1 |
| 0x0001 | Deck memory info | Information for deck 1 |
| 0x0021 | Deck memory info | Information for deck 2 |
| 0x0041 | Deck memory info | Information for deck 3 |
| 0x0061 | Deck memory info | Information for deck 4 |
### Deck memory info memory layout
Addresses relative to the deck memory info base address
| Address | Type | Description |
|---------|-------------|--------------------------------------------------------------------|
| 0x0000 | uint8 | A bitfield describing the properties of the deck memory, see below |
| 0x0001 | uint32 | required hash - the hash for the reuired firmware |
| 0x0005 | uint32 | required length - the length of the required firmware |
| 0x0009 | uint32 | base address - the start address of the deck memory |
| 0x000D | uint8\[19\] | name - zero terminated string, max 19 bytes in total. |
### Deck memory info bit field
| Bit | Property | 0 | 1 |
|-----|-------------------|------------------------------------------------------------|-----------------------------------------------------|
| 0 | Is valid | no deck is installed or does not support memory operations | a deck is installed and the data is valid |
| 1 | Is started | the deck is in start up mode, data is not reliable yet | deck has started, data is reliable |
| 3 | Supports write | write not supported | memory is writeable |
| 2 | Supports read | read not supported | memory is readable |
| 4 | Supports upgrade | no upgradable firmware | firmware upgrades possible |
| 5 | Upgrade required | the firmware is up to date | the firmware needs to be upgraded |
| 6 | Bootloader active | the deck is running FW | the deck is in bootloader mode, ready to receive FW |
| 7 | Reserved | | |
---
title: EEPROM - MEM_TYPE_EEPROM
page_id: mem_type_eeprom
---
TBD
---
title: LED ring - MEM_TYPE_LED12
page_id: mem_type_led12
---
TBD
---
title: LED ring timing - MEM_TYPE_LEDMEM
page_id: mem_type_ledmem
---
TBD
---
title: Lighthouse - MEM_TYPE_LH
page_id: mem_type_lh
---
The lighthouse memory mapping is used to communicate geometry and
calibration data. The implementation supports both read and write
operations.
## Memory layout
| Address | Type | Description |
|---------|------------------|-------------------------------------------------|
| 0x0000 | Geometry data | Geometry data for base station on channel 1 |
| 0x0100 | Geometry data | Geometry data for base station on channel 2 |
| ... | Geometry data | |
| 0x0f00 | Geometry data | Geometry data for base station on channel 16 |
| 0x1000 | Calibration data | Calibration data for base station on channel 1 |
| 0x1100 | Calibration data | Calibration data for base station on channel 2 |
| ... | Calibration data | |
| 0x1f00 | Calibration data | Calibration data for base station on channel 16 |
### Geometry data memory layout
| Address | Type | Description |
|---------|---------------------|------------------------------------------------------------------|
| 0x0X00 | float (4 bytes) x 3 | Base station position, 3 element vector of floats (4 bytes) |
| 0x0X0C | float (4 bytes) x 9 | Base station attitude, 3 x 3 rotation matrix of floats (4 bytes) |
| 0x0X18 | uint8 | Is valid : 0 = the data is not valid, 1 = data is valid |
### Calibration data memory layout
| Address | Type | Description |
|---------|------------------------|---------------------------------------------------------|
| 0x0X00 | Calibration sweep data | Calibration data for first sweep |
| 0x0X1C | Calibration sweep data | Calibration data for second sweep |
| 0x0X38 | uint32 | Base station UID |
| 0x0X3C | uint8 | Is valid : 0 = the data is not valid, 1 = data is valid |
#### Calibration sweep data memory layout
| Address | Type | Description |
|---------|------------------------------------------------|
| 0x0X00 | float (4 bytes) | phase |
| 0x0X04 | float (4 bytes) | tilt |
| 0x0X08 | float (4 bytes) | curve |
| 0x0X0C | float (4 bytes) | gibmag |
| 0x0X10 | float (4 bytes) | gibphase |
| 0x0X14 | float (4 bytes) | ogeemag (only used in LH2) |
| 0x0X18 | float (4 bytes) | ogeephase (only used in LH2) |
---
title: Loco Positioning System 1 - MEM_TYPE_LOCO
page_id: mem_type_loco
---
This implementation is obsolete and remains for backwards compatibility.
---
title: Loco Positioning System 2 - MEM_TYPE_LOCO2
page_id: mem_type_loco2
---
The Loco Positioning System memory implementation provides means to read information about the
Loco Positioning System. There is no write functionality.
## Memory layout
| Address | Type | Description |
|----------------------|-------------|----------------------------------------------------------------------------|
| 0x0000 | uint8 | number of anchors in the system (n) |
| 0x0001 - 0x0000 + n | uint8 | unordered list of anchor ids in the system |
| | | |
| 0x1000 | uint8 | number of active anchors in the system (na) |
| 0x1001 - 0x1000 + na | uint8 | unordered list of anchor ids for the anchors in the system that are active |
| | | |
| 0x2000 | Anchor data | Data for anchor id 0 (if available) |
| 0x2100 | Anchor data | Data for anchor id 1 (if available) |
| ... | Anchor data | |
| 0x2000 + 0x100 * i | Anchor data | Data for anchor id i (if available) |
| ... | Anchor data | |
| 0x11F00 | Anchor data | Data for anchor id 255 (if available) |
### Anchor data memory layout
Address relative to start address for the anchor data
| Address | Type | Description |
|---------|-----------------|---------------------------------------------------------|
| 0x0000 | float (4 bytes) | x coordinate of the anchor position |
| 0x0004 | float (4 bytes) | y coordinate of the anchor position |
| 0x0008 | float (4 bytes) | z coordinate of the anchor position |
| 0x000C | uint8 | Is valid : 0 = the data is not valid, 1 = data is valid |
---
title: One wire memory - MEM_TYPE_OW
page_id: mem_type_ow
---
TBD
---
title: Test - MEM_TYPE_TESTER
page_id: mem_type_tester
---
TBD
---
title: Trajectory - MEM_TYPE_TRAJ
page_id: mem_type_traj
---
TBD
---
title: uSD card - MEM_TYPE_USD
page_id: mem_type_usd
---
TBD
---
title: The memory subsystem
page_id: memory_subsystem
---
The memory subsystem is intended to be used for transfering larger chunks of data
between a Crazyflie and a client where real time characteristics are not important.
The memory subsystem uses the ```CRTP_PORT_MEM``` port for communication and supports basic read and write functionality of raw binary data. One packet on the CRTP level contains data for one read or write operation with information on address, size and type. A larger read or write is split up in multiple operations, where each sub-operation fits into one
CRTP packet. The sub-operations should be done in order (from lower address to higher) and
some read handlers may rely on this to update caches or similar when receiving the last part of a block.
The type can be seen as the highest level of abstraction and indicates which memory
the read/write operation will act on. There are a number of memory types (defined in ```MemoryType_t```) which each implements a read and/or write paradigm of selected parts of a virtual memory space, for a functional area of the system. A read/write
implementation may be mapped directly to a block of RAM in the Crazyflie, but it can
also be connected to other data structures through function calls where the
virtual memory map is simply a means of organaizing data for transfer.
A module in the Crazyflie firmware registeres handlers for read and/or write operations
and the framwork calls the handlers with appropriate values when memory operations are
initiated from a client.
## Memory types and mappings
* [EEPROM - MEM_TYPE_EEPROM](./MEM_TYPE_EEPROM.md)
* [One wire memory - MEM_TYPE_OW](MEM_TYPE_OW.md)
* [LED ring - MEM_TYPE_LED12](MEM_TYPE_LED12.md)
* [Loco Positioning System 1 - MEM_TYPE_LOCO](MEM_TYPE_LOCO.md)
* [Trajectory - MEM_TYPE_TRAJ](MEM_TYPE_TRAJ.md)
* [Loco Positioning System 2 - MEM_TYPE_LOCO2](MEM_TYPE_LOCO2.md)
* [Lighthouse - MEM_TYPE_LH](MEM_TYPE_LH.md)
* [Test - MEM_TYPE_TESTER](MEM_TYPE_TESTER.md)
* [uSD card - MEM_TYPE_USD](MEM_TYPE_USD.md)
* [LED ring timing - MEM_TYPE_LEDMEM](MEM_TYPE_LEDMEM.md)
* [Generic application memory - MEM_TYPE_APP](MEM_TYPE_APP.md)
* [Deck memory - MEM_TYPE_DECK_MEM](MEM_TYPE_DECK_MEM.md)
---
title: Peer to Peer API
page_id: p2p_api
---
## Introduction
Currently peer to peer communication on the crazyflie is **in development**. Now an API is made available to send P2P
messages in broadcast mode, and we are going to extend this to unicast.
P2P packets are sent and received on the same channel as the currently configured CRTP radio link. P2P packets are sent and received independently to regular CRTP packets. In order to allow for multiple appilication to use P2P communication at the same time a port number has been added to each packet, the intend being that independent service will use different P2P port. For the time being this port is not used by the API and keeping it to 0 unless otherwise needed is advised.
Furthermore, P2P packets are only sent and received from the 2.4GHz internal Crazyflie radio independently of where the CRTP link is connect (ex. the CRTP link can be connecte over USB).
The maximum data payload contained in a P2P packet is ```P2P_MAX_DATA_SIZE```. It is currently set to 60Bytes.
## Using the P2P API
Functions and structures are defined in the header file [src/hal/interface/radiolink.h](https://github.com/bitcraze/crazyflie-firmware/blob/master/src/hal/interface/radiolink.h). There is also an [app layer example](https://github.com/bitcraze/crazyflie-firmware/tree/master/examples/app_peer_to_peer) available in the example folder of the repository.
## Peer to Peer broadcast
#### Sending P2P broadcast
From the STM, a packet can be sent using the ```radiolinkSendP2PPacketBroadcast``` function. For example:
```c
static P2PPacket pk;
pk.port = 0;
pk.size = 11;
memcpy(pk.data, "Hello World", 11);
radiolinkSendP2PPacketBroadcast(&pk);
```
This function will trigger a single P2P packet to be transmitted by the radio.
#### Receiving P2P broadcast
If you want to receive packet in your function, you can register a callback with:
```c
p2pRegisterCB(p2pcallbackHandler);
```
with a function of the form of:
```c
void p2pcallbackHandler(P2PPacket *p)
{
// p->port: P2P Port
// p->size: Payload size
// p->data: Payload data
// p->rssi: RSSI of the packet. 40 means -40dBm.
}
```
The callback will be called by the task handling radio communication, it should then execute quickly (for example pushing data in a queue).
---
title: Persistent storage
page_id: persistent_storage
---
# Persistent storage
The crazyflie has a persistent storage subsystem that is intended to be used for configuration and other rarely written data.
The 7kB of the internal EEPROM is used for storage.
Fetching data should be fairly fast, storing data can be very slow if the storage space needs to be defragmented/garbage collected.
The API is documented in the [storage.h](https://github.com/bitcraze/crazyflie-firmware/blob/master/src/hal/interface/storage.h).
It currently only implements basic store/fetch/delete functions.
The data stored are buffers and are stored and fetched using a key string.
Care must be taken to not use generic keys in order to avoid collision.
## Embedded KV format
This is low level information about the format used to store data in the EEPROM.
These information are not needed to use the storage api but can be useful if one want to modify or port the memory storage.
The stored binary format is based on TLV (Type Length Value) but modified for the need of a dynamic storage.
The format assumes it is working on a EEPROM since it does not implement a proper wear leveling.
However, it can be noted that the format is already prepared to be used in flash allowing to append and discard entries without erasing the page: entries can be added and holes created by only writing zeros to a all-one memory. So, if modification are implemented using copy-on-write, this is effectively becoming a log-format and would fit a flash.
### Basic format
Each KV couple is written as:
- **Length** uint16_t: Length of the item, includes length, keylength, key and value.
- **KeyLength** uint8_t: Length of the key
- **Key** char*: Key
- **Value** void*: Data buffer
KV couples are writen one after each other. If one KV is at memory position *n*, the next one will be at memory position *n + length*.
If the key has a length of 0, it indicates a hole and the length indicates
the offset to the next entry.
A lenght of 0xffff means the end of the table.
Holes are created when an entry is deleted or modified entries.
New entries can be added either at the end of the table or in a hole that can fit the new buffer.
When there is no more space for new entries, the memory should be defragmented by moving all items into the holes, packing all the items at the begining of the table.
---
title: The Commander Framework
page_id: commanders_setpoints
---
This section will go into the commander framework, which handles the setpoint of the desired states, which the controllers will try to steer the estimated state to.
* [The Commander Module](#the-commander-module)
* [Setpoint Structure](#setpoint-structure)
* [High Level Commander](#high-level-commander)
## The Commander Module
![commander framework](/docs/images/commander_framework.png){:width="700"}
The commander module handles the incoming setpoints from several sources (src/modules/src/commander.c in the [firmware](https://github.com/bitcraze/crazyflie-firmware)). A setpoint can be set directly, either through a python script using the [cflib](https://github.com/bitcraze/crazyflie-lib-python)/ [cfclient](https://github.com/bitcraze/crazyflie-clients-python) or [the app layer](/docs/userguides/app_layer.md) (blue pathways in the figure), or by the high-level commander module (purple pathway). The High-level commander in turn, can be controlled remotely from the python library or from inside the Crazyflie.
It is important to realize that the commander module also checks how long ago a setpoint has been received. If it has been a little while (defined by threshold `COMMANDER_WDT_TIMEOUT_STABILIZE` in commander.c), it will set the attitude angles to 0 on order to keep the Crazyflie stabilized. If this takes longer than `COMMANDER_WDT_TIMEOUT_SHUTDOWN`, a null setpoint will be given which will result in the Crazyflie shutting down its motors and fall from the sky. This won’t happen if you are using the high level commander.
[go back to top](#)
## Setpoint Structure
In order to understand the commander module, you must be able to comprehend the setpoint structure. The specific implementation can be found in src/modules/interface/stabilizer_types.h as setpoint_t in the Crazyflie firmware.
There are 2 levels to control, which is:
Position (X, Y, Z)
Attitude (pitch, roll, yaw or in quaternions)
These can be controlled in different modes, namely:
Absolute mode (modeAbs)
Velocity mode (modeVelocity)
Disabled (modeDisable)
![commander framework](/docs/images/setpoint_structure.png){:width="700"}
So if absolute position control is desired (go to point (1,0,1) in x,y,z), the controller will obey values given setpoint.position.xyz if setpoint.mode.xyz is set to modeAbs. If you rather want to control velocity (go 0.5 m/s in the x-direction), the controller will listen to the values given in setpoint.velocity.xyz if setpoint.mode.xyz is set to modeVel. All the attitude setpoint modes will be set then to disabled (modeDisabled). If only the attitude should be controlled, then all the position modes are set to modeDisabled. This happens for instance when you are controlling the crazyflie with a controller through the cfclient in attitude mode.
[go back to top](#)
## High Level Commander
![high level commander](/docs/images/high_level_commander.png){:width="700"}
As already explained before: The high level commander handles the setpoints from within the firmware based on a predefined trajectory. This was merged as part of the [Crazyswarm](https://crazyswarm.readthedocs.io/en/latest/) project of the [USC ACT lab](https://act.usc.edu/). The high-level commander uses a planner to generate smooth trajectories based on actions like ‘take off’, ‘go to’ or ‘land’ with 7th order polynomials. The planner generates a group of setpoints, which will be handled by the High level commander and send one by one to the commander framework.
[go back to top](#)
## Support in the python lib (CFLib)
There are four main ways to interact with the commander framework from the [python library](https://github.com/bitcraze/crazyflie-lib-python)/.
* **autonomousSequence.py**: Send setpoints directly using the Commander class from the Crazyflie object.
* **motion_commander_demo.py**: The MotionCommander class exposes a simplified API and sends velocity setpoints continuously based on the methods called.
* **autonomous_sequence_high_level.py**: Use the high level commander directly using the HighLevelCommander class on the Crazyflie object.
* **position_commander_demo.py**: Use the PositionHlCommander class for a simplified API to send commands to the high level commander.
[go back to top](#)
---
title: Configure estimator and controller
page_id: config_est_ctrl
---
All the estimators and controllers are part of the standard firmware build and the active estimator and controller can be configured in runtime or compile time.
## Estimators
The available estimators are defined in the `StateEstimatorType` enum in `src/modules/interface/estimator.h`.
### Setting in runtime
To activate a specific estimator, set the `stabilizer.estimator` parameter to the appropriate value based on the `StateEstimatorType`.
The parameter can be set from the python client, the python lib or from an app in the Crazyflie.
### Default estimator
The complementary estimator is the default estimator.
Some decks require the kalman estimator and it is automatically activated when one of these decks are detected. The activated estimator is based on the .requiredEstimator member of the DeckDriver API.
### Setting default estimator at compile time
It is possible to force the use of a specific estimator at compile time by setting `ESTIMATOR`, see [Configure the build](/docs/building-and-flashing/build.md/#configmk).
Example:
`ESTIMATOR=kalman`
## Controller
The available controllers are defined in the `ControllerType` enum in `src/modules/interface/controller.h`.
### Setting in runtime
To activate a specific controller, set the `stabilizer.controller` parameter to the appropriate value based on the `ControllerType`.
The parameter can be set from the python client, the python lib or from an app in the Crazyflie.
### Default controller
The PID controller is the default controller.
### Setting at compile time
It is possible to force the use of a specific controller at compile time by setting `CONTROLLER`, see [Configure the build](/docs/building-and-flashing/build.md/#configmk).
Example:
`CONTROLLER=Mellinger`