Wrote logging documentation authored by Colton Glick's avatar Colton Glick
To track a variable's value while the Crazyflie is running we use the built in logging feature. This consists of the Crazyflie sending the values of predetermined variables back to the ground station.
To track a variable's value while the Crazyflie is running we use the built in logging feature. This consists of the Crazyflie sending the values of predetermined variables back to the ground station. Note the logging bandwidth is limited to 26 bytes so only a handful of values can be logged simultaneously.
# Firmware Setup
The variables that can be logged are determined at compile time and is setup through a C macro. These macros are defined under the [`src/modules/interface/log.h`](/../blob/master/crazyflie_software/crazyflie-firmware-2021%2E06/src/modules/interface/log%2Eh) file so be sure this is included where you want to use logging. These logging macros are typically placed at the end of the relevant .c file outside of any function definition. They read the value of static global variables.
A logging variable is defined by its logging group and it's name, with the naming convention `group.name`. If you would like to log the _roll_ variable in the _stabilizer_ group it's access by _stabilizer.roll_.
Note that this definition is limited to *25 characters* (including the period), so be concise with your naming.
Example:
```c
/**
* [Documentation for the stabilizer group ...]
*/
LOG_GROUP_START(stabilizer)
/**
* @brief [Documentation for variable below ...]
*/
LOG_ADD(LOG_FLOAT, roll, &eulerRollActual)
/**
* @brief [Documentation for variable below ...]
*/
LOG_ADD(LOG_FLOAT, pitch, &eulerPitchActual)
/**
* @brief [Documentation for variable below ...]
*/
LOG_ADD(LOG_FLOAT, yaw, &eulerYawActual)
/**
* @brief [Documentation for variable below ...]
*/
LOG_ADD(LOG_UINT16, thrust, &actuatorThrust)
LOG_GROUP_STOP(stabilizer)
```
## Logging groups
Each variable to log belongs to a logging group. A logging group is defined as a section between the logging group start macro and the logging group stop macro:
```c
LOG_GROUP_START(NAME)
```
```c
LOG_GROUP_STOP(NAME)
```
The name of the group is given as the only parameter to the group stop and group start macros. Ensure that both names match for correct formatting.
**Nested groups are not supported by Crazyflie**
## Logging variables
A variable is added to a logging group when it is within the scope of that group's definition.
```c
LOG_ADD(TYPE, NAME, ADDRESS)
```
`LOG_ADD_CORE` serves the same purpose as `LOG_ADD` but is intended for use on core variables that will persist between Crazyflie versions and requires documentation ([example of LOG_ADD_CORE](https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/userguides/logparam/#:~:text=LOG_ADD_CORE(LOG_FLOAT%2C%20roll%2C%20%26eulerRollActual))). For the MicroCART project, we prefer `LOG_ADD`.
```c
LOG_ADD_CORE(TYPE, NAME, ADDRESS)
```
The `TYPE` defines how the data is sent over the network and read by the client, possible types are:
- `LOG_UINT8` unsigned 8 bit integer
- `LOG_UINT16` unsigned 16 bit integer
- `LOG_UINT32` unsigned 32 bit integer
- `LOG_INT8` signed 8 bit integer
- `LOG_INT16` signed 16 bit integer
- `LOG_INT32` signed 32 bit integer
- `LOG_FLOAT` standard 32 bit floating point number
- `LOG_FP16` 16 bit floating point number
The `NAME` parameter defines the log variable name. The `ADDRESS` is the memory location which the data is stored (passed as a pointer). Note, this must be a global static memory location for the logging system to read the value.
# Ground Station Setup
The second half of the logging equation is the ground station. The Crazyflie streams a small amount of data (limited to 26 bytes) to the ground station.
First we will cover how to setup logging on the [official Crazyflie Python client](https://github.com/bitcraze/crazyflie-clients-python), then cover the underlying process that it uses.
## Crazyflie Python Client
After the variables that you want to log are setup in the firmware, we can begin setting up the ground station.
1. Open the Crazyflie client.
2. Plug in the Crazyflie USB radio.
3. Power on the Crazyflie quadcopter.
4. Scan for your quad.
5. Connect to the appropriate quad, pay attention to the channel you're connecting to.
6. If not already visible, under the `view > tabs` menu, enable the `Log Blocks`, `Log TOC`, and `Plotter` tabs.
1. The `Log TOC` tab shows all available logging variables provided by the Crazyflie firmware.
2. The `Log Blocks` tab shows the log blocks that have been configured on the client. A log block specifies what variables should be sent from the quad.
3. The `Plotter` tab helps visualize the data being sent from the quad.
7. Setup a new log block
1. Open `Settings > Logging configurations`
2. On the far left is the list of existing log blocks, sorted by category. In the middle is the logging table of contents (TOC), listing all available variables to log. The far right shows the new working log block.
3. Create a new config, name it whatever you like.
4. Add variables to the new log block by selecting them in the TOC and pressing the left arrow button.
5. Notice the bar at the bottom shows the percent utilization of the log block, a maximum of 26 bytes can be transmitted.
6. Set the logging period, this is how often the data block will be transmitted
7. Click save
8. Go to the `Log Blocks` tab. This will display all log blocks that have been created for this quad.
9. Uncheck all boxes in the start column that may be enabled by default
10. Start your new log block
11. Switch to the plotter tab
12. Under the top drop down, select the log block you just started
13. The plotter will start displaying the data received from the log block, in this example It is displaying the roll angle of the quad
## Low Level
The ground station can instruct the Crazyflie to report back specific logging data, known as a *log block*. First the ground station queries the Crazyflie for available log variables, known as the *[Table of Contents (TOC)](https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/functional-areas/crtp/crtp_log/)*
The ground station then [sends a command](https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/functional-areas/crtp/crtp_log/#:~:text=variable%20retrieval%20programming-,Log%20control,-The%20log%20control) on port 5 channel 1 to enable log block transmission.
The ground station then listens on port 5 channel 2 for data sent by the Crazyflie quad. The packet format is described in the [Crazyflie documentation](https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/functional-areas/crtp/crtp_log/#:~:text=Stop%20block-,Log%20data,-The%20log%20data),
>The log data channel is used by the copter to send the log blocks at the programmed rate. The packet format is
>```
>Answer (Copter to PC):
> +----------+------------+---------//----------+
> | BLOCK_ID | TIME_STAMP | LOG VARIABLE VALUES |
> +----------+------------+---------//----------+
>Length 1 3 0 to 26
>```
>
>
>|Byte|Answer fields|Content|
>|----|-------------|-------|
>|0 |BLOCK_ID |ID of the block|
>|1 |ID |Timestamp in ms from the copter startup as a little-endian 3 bytes integer|
>|4.. |Log variable values|Packed log values in little endian format|
# Saving Data
----------------------------------------
Relevant sources:
- [Crazyflie Logging and parameter frameworks](https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/userguides/logparam/)
References:
- [Crazyflie logging and parameter frameworks](https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/userguides/logparam/)
- [Logging communication protocol](https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/functional-areas/crtp/crtp_log/)
- [Crazyflie python client logging](https://www.bitcraze.io/documentation/repository/crazyflie-clients-python/master/userguides/userguide_client/#:~:text=2.X%20EEPROM.-,Logging,-The%20Crazyflie%20logging)
\ No newline at end of file