Showing preview only (319K chars total). Download the full file or copy to clipboard to get everything.
Repository: PX4/pyulog
Branch: main
Commit: 4379a77cc6d4
Files: 55
Total size: 302.1 KB
Directory structure:
gitextract_xzoh4fzy/
├── .github/
│ └── workflows/
│ ├── deploy.yml
│ └── test.yml
├── .gitignore
├── .gitmodules
├── LICENSE.md
├── MANIFEST.in
├── README.ko-KR.md
├── README.md
├── gen_expected_output.sh
├── pylintrc
├── pyproject.toml
├── pyulog/
│ ├── __init__.py
│ ├── core.py
│ ├── db.py
│ ├── extract_gps_dump.py
│ ├── extract_message.py
│ ├── info.py
│ ├── messages.py
│ ├── migrate_db.py
│ ├── params.py
│ ├── px4.py
│ ├── px4_events.py
│ ├── sql/
│ │ ├── pyulog.1.sql
│ │ ├── pyulog.2.sql
│ │ ├── pyulog.3.sql
│ │ ├── pyulog.4.sql
│ │ └── pyulog.5.sql
│ ├── ulog2csv.py
│ ├── ulog2kml.py
│ └── ulog2rosbag.py
├── run_tests.sh
├── setup.py
└── test/
├── __init__.py
├── sample.ulg
├── sample_appended.ulg
├── sample_appended_info.txt
├── sample_appended_messages.txt
├── sample_appended_multiple.ulg
├── sample_appended_multiple_info.txt
├── sample_appended_multiple_messages.txt
├── sample_info.txt
├── sample_log_small.ulg
├── sample_log_small_messages.txt
├── sample_logging_tagged_and_default_params.ulg
├── sample_logging_tagged_and_default_params_messages.txt
├── sample_messages.txt
├── sample_px4_events.ulg
├── sample_px4_events_messages.txt
├── test_cli.py
├── test_db.py
├── test_extract_message.py
├── test_migration.py
├── test_px4.py
├── test_px4_events.py
└── test_ulog.py
================================================
FILE CONTENTS
================================================
================================================
FILE: .github/workflows/deploy.yml
================================================
name: Deploy
on:
workflow_dispatch:
pull_request:
push:
branches:
- main
release:
types:
- published
jobs:
build_dist:
name: Build Dist
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
with:
submodules: true
- name: Build Dist
run: pipx run build
- name: Check Metadata
run: pipx run twine check --strict dist/*
- uses: actions/upload-artifact@v4
with:
path: dist/
upload_all:
name: Upload if release
needs: [build_dist]
runs-on: ubuntu-latest
if: github.event_name == 'release' && github.event.action == 'published'
environment:
name: pypi
url: https://pypi.org/p/pyulog
permissions:
id-token: write
steps:
- uses: actions/setup-python@v4
with:
python-version: "3.x"
- uses: actions/download-artifact@v4
with:
name: artifact
path: dist/
- name: Publish to PyPI
uses: pypa/gh-action-pypi-publish@v1.13.0
================================================
FILE: .github/workflows/test.yml
================================================
name: Run Tests
on:
push:
branches:
- 'main'
pull_request:
branches:
- '*'
jobs:
build:
runs-on: ubuntu-latest
strategy:
fail-fast: false # don't cancel if a job from the matrix fails
matrix: # https://devguide.python.org/versions
python-version: ["3.9", "3.10", "3.11", "3.12", "3.13", "3.14"]
steps:
- uses: actions/checkout@v4
with:
submodules: 'recursive'
- name: Set up Python ${{ matrix.python-version }}
uses: actions/setup-python@v5
with:
python-version: ${{ matrix.python-version }}
allow-prereleases: true
- name: Install Dependencies and pyulog
run: |
pip install pylint
pip install --verbose .[test]
- name: Running Tests
run: |
./run_tests.sh
================================================
FILE: .gitignore
================================================
__pycache__
*.pyc
build/
dist/
*.egg-info
.eggs/
*.sqlite3
venv/
================================================
FILE: .gitmodules
================================================
[submodule "3rd_party/libevents"]
path = 3rd_party/libevents
url = https://github.com/mavlink/libevents.git
================================================
FILE: LICENSE.md
================================================
Copyright (c) 2016, PX4 Pro Drone Autopilot
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the name of GpsDrivers nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
================================================
FILE: MANIFEST.in
================================================
include LICENSE.md
recursive-include pyulog/sql *
recursive-exclude test *.ulg
================================================
FILE: README.ko-KR.md
================================================
# pyulog
이 레포지토리에는 ULog 파일 및 스크립트를 파싱하는 python 패키지가 포함되어 있습니다.
ULog는 self-describing 형식을 따르며, 해당 관련 문서는 다음과 같습니다(https://docs.px4.io/main/en/dev_log/ulog_file_format.html).
제공되는 명령어 스크립트는(command line scripts)는 아래와 같습니다:
- `ulog_info`: ULog 파일의 정보를 나타냅니다.
- `ulog_messages`: ULog 파일에 기록된 로그 메시지(logged messages)를 출력합니다.
- `ulog_params`: ULog 파일에 저장된 파라미터들을 추출합니다.
- `ulog2csv`: ULog 파일을 CSV 파일로 변환합니다.
- `ulog2kml`: ULog 파일을 KML 파일로 변환합니다.
## 설치
패키지 설치:
```bash
pip install pyulog
```
소스코드를 통한 설치:
```bash
python setup.py build install
```
## 추가 개발
코드를 쉽게 변경 및 편집할 수 있는 형식으로 설치하려면 다음 명령 사용(해당 명령은 패키지를 Repo에 대한 링크로 설치합니다):
```bash
pip install -e .
```
## 테스트
```bash
pytest test
```
또는,
```bash
python setup.py test
```
## 코드 검사(Code Checking)
```bash
pylint pyulog/*.py
```
<span id="scripts"></span>
## 명령어 스크립트
모든 스크립트는 시스템 전체 어플리케이션단에서 설치되며(Python 또는 시스템 경로를 지정하지 않고
커맨드 라인에서 호출), `-h` 플래그를 통해 각 스크립트의 사용법을 확인할 수 있습니다.
아래 섹션에서는 사용 구문 및 샘플 출력을 나타냅니다. (from [test/sample.ulg](test/sample.ulg)):
### ULog 파일로부터 정보 출력 (ulog_info)
사용:
```bash
usage: ulog_info [-h] [-v] file.ulg
Display information from an ULog file
positional arguments:
file.ulg ULog input file
optional arguments:
-h, --help show this help message and exit
-v, --verbose Verbose output
```
결과 예시:
```bash
$ ulog_info sample.ulg
Logging start time: 0:01:52, duration: 0:01:08
Dropouts: count: 4, total duration: 0.1 s, max: 62 ms, mean: 29 ms
Info Messages:
sys_name: PX4
time_ref_utc: 0
ver_hw: AUAV_X21
ver_sw: fd483321a5cf50ead91164356d15aa474643aa73
Name (multi id, message size in bytes) number of data points, total bytes
actuator_controls_0 (0, 48) 3269 156912
actuator_outputs (0, 76) 1311 99636
commander_state (0, 9) 678 6102
control_state (0, 122) 3268 398696
cpuload (0, 16) 69 1104
ekf2_innovations (0, 140) 3271 457940
estimator_status (0, 309) 1311 405099
sensor_combined (0, 72) 17070 1229040
sensor_preflight (0, 16) 17072 273152
telemetry_status (0, 36) 70 2520
vehicle_attitude (0, 36) 6461 232596
vehicle_attitude_setpoint (0, 55) 3272 179960
vehicle_local_position (0, 123) 678 83394
vehicle_rates_setpoint (0, 24) 6448 154752
vehicle_status (0, 45) 294 13230
```
### ULog 파일에 기록된 로그 메시지 출력 (ulog_messages)
사용:
```
usage: ulog_messages [-h] file.ulg
Display logged messages from an ULog file
positional arguments:
file.ulg ULog input file
optional arguments:
-h, --help show this help message and exit
```
결과 예시:
```
ubuntu@ubuntu:~/github/pyulog/test$ ulog_messages sample.ulg
0:02:38 ERROR: [sensors] no barometer found on /dev/baro0 (2)
0:02:42 ERROR: [sensors] no barometer found on /dev/baro0 (2)
0:02:51 ERROR: [sensors] no barometer found on /dev/baro0 (2)
0:02:56 ERROR: [sensors] no barometer found on /dev/baro0 (2)
```
### ULog 파일에 저장된 파라미터 추출 (ulog_params)
사용:
```
usage: ulog_params [-h] [-d DELIMITER] [-i] [-o] file.ulg [params.txt]
Extract parameters from an ULog file
positional arguments:
file.ulg ULog input file
params.txt Output filename (default=stdout)
optional arguments:
-h, --help show this help message and exit
-d DELIMITER, --delimiter DELIMITER
Use delimiter in CSV (default is ',')
-i, --initial Only extract initial parameters
-o, --octave Use Octave format
```
결과 예시 (콘솔 출력):
```
ubuntu@ubuntu:~/github/pyulog/test$ ulog_params sample.ulg
ATT_ACC_COMP,1
ATT_BIAS_MAX,0.0500000007451
ATT_EXT_HDG_M,0
...
VT_OPT_RECOV_EN,0
VT_TYPE,0
VT_WV_LND_EN,0
VT_WV_LTR_EN,0
VT_WV_YAWR_SCL,0.15000000596
```
### ULog 파일을 CSV 파일로 변환 (ulog2csv)
사용:
```
usage: ulog2csv [-h] [-m MESSAGES] [-d DELIMITER] [-o DIR] file.ulg
Convert ULog to CSV
positional arguments:
file.ulg ULog input file
optional arguments:
-h, --help show this help message and exit
-m MESSAGES, --messages MESSAGES
Only consider given messages. Must be a comma-
separated list of names, like
'sensor_combined,vehicle_gps_position'
-d DELIMITER, --delimiter DELIMITER
Use delimiter in CSV (default is ',')
-o DIR, --output DIR Output directory (default is same as input file)
```
### ULog 파일을 KML 파일로 변환 (ulog2kml)
> **Note** 모듈 `simplekml` 이 사용자의 PC에 설치되어 있어야 합니다. 만약 설치되어 있지 않다면, 아래 명령어를 통해 설치하십시오.
```
pip install simplekml
```
사용:
```
usage: ulog2kml [-h] [-o OUTPUT_FILENAME] [--topic TOPIC_NAME]
[--camera-trigger CAMERA_TRIGGER]
file.ulg
Convert ULog to KML
positional arguments:
file.ulg ULog input file
optional arguments:
-h, --help show this help message and exit
-o OUTPUT_FILENAME, --output OUTPUT_FILENAME
output filename
--topic TOPIC_NAME topic name with position data
(default=vehicle_gps_position)
--camera-trigger CAMERA_TRIGGER
Camera trigger topic name (e.g. camera_capture)
```
### ULog 파일을 rosbag 파일로 변환 (ulog2rosbag)
> **Note** `px4_msgs`가 설치된 ROS 환경이 필요합니다.
사용:
```
usage: ulog2rosbag [-h] [-m MESSAGES] file.ulg result.bag
Convert ULog to rosbag
positional arguments:
file.ulg ULog input file
result.ulg rosbag output file
optional arguments:
-h, --help show this help message and exit
-m MESSAGES, --messages MESSAGES
Only consider given messages. Must be a comma-
separated list of names, like
'sensor_combined,vehicle_gps_position'
```
### Migrate/setup the database for use with the DatabaseULog class (ulog_migratedb)
사용:
```
usage: ulog_migratedb [-h] [-d DB_PATH] [-n] [-s SQL_DIR] [-f]
Setup the database for DatabaseULog
optional arguments:
-h, --help show this help message and exit
-d DB_PATH, --database DB_PATH
Path to the database file
-n, --noop Only print results, do not execute migration scripts.
-s SQL_DIR, --sql SQL_DIR
Directory with migration SQL files
-f, --force Run the migration script even if the database is not
created with this script.
```
결과 예시 (콘솔 출력):
```
ubuntu@ubuntu:~/github/pyulog$ ulog_migratedb
Using migration files in /home/ubuntu/github/pyulog/pyulog/sql.
Database file pyulog.sqlite3 not found, creating it from scratch.
Current schema version: 0 (database) and 1 (code).
Executing /home/ubuntu/github/pyulog/pyulog/sql/pyulog.1.sql.
Migration done.
```
================================================
FILE: README.md
================================================
# pyulog
This repository contains a python package to parse ULog files and scripts to
convert and display them. ULog is a self-describing logging format which is
documented [here](https://docs.px4.io/main/en/dev_log/ulog_file_format.html).
The provided [command line scripts](#scripts) are:
- `ulog_info`: display information from an ULog file.
- `ulog_messages`: display logged messages from an ULog file.
- `ulog_params`: extract parameters from an ULog file.
- `ulog2csv`: convert ULog to CSV files.
- `ulog2kml`: convert ULog to KML files.
## Installation
Installation with package manager:
```bash
pip install pyulog
```
Installation from source:
```bash
python setup.py build install
```
## Development
To install the code in a format so that it can be easily edited use the
following command (this will install the package as a link to the repo):
```bash
pip install -e .
```
## Testing
```bash
pytest test
```
or
```bash
python setup.py test
```
## Code Checking
```bash
pylint pyulog/*.py
```
<span id="scripts"></span>
## Command Line Scripts
All scripts are installed as system-wide applications (i.e. they be called on the command line without specifying Python or a system path), and support the `-h` flag for getting usage instructions.
The sections below show the usage syntax and sample output (from [test/sample.ulg](test/sample.ulg)):
### Display information from an ULog file (ulog_info)
Usage:
```bash
usage: ulog_info [-h] [-v] file.ulg
Display information from an ULog file
positional arguments:
file.ulg ULog input file
optional arguments:
-h, --help show this help message and exit
-v, --verbose Verbose output
```
Example output:
```bash
$ ulog_info sample.ulg
Logging start time: 0:01:52, duration: 0:01:08
Dropouts: count: 4, total duration: 0.1 s, max: 62 ms, mean: 29 ms
Info Messages:
sys_name: PX4
time_ref_utc: 0
ver_hw: AUAV_X21
ver_sw: fd483321a5cf50ead91164356d15aa474643aa73
Name (multi id, message size in bytes) number of data points, total bytes
actuator_controls_0 (0, 48) 3269 156912
actuator_outputs (0, 76) 1311 99636
commander_state (0, 9) 678 6102
control_state (0, 122) 3268 398696
cpuload (0, 16) 69 1104
ekf2_innovations (0, 140) 3271 457940
estimator_status (0, 309) 1311 405099
sensor_combined (0, 72) 17070 1229040
sensor_preflight (0, 16) 17072 273152
telemetry_status (0, 36) 70 2520
vehicle_attitude (0, 36) 6461 232596
vehicle_attitude_setpoint (0, 55) 3272 179960
vehicle_local_position (0, 123) 678 83394
vehicle_rates_setpoint (0, 24) 6448 154752
vehicle_status (0, 45) 294 13230
```
### Display logged messages from an ULog file (ulog_messages)
Usage:
```
usage: ulog_messages [-h] file.ulg
Display logged messages from an ULog file
positional arguments:
file.ulg ULog input file
optional arguments:
-h, --help show this help message and exit
```
Example output:
```
ubuntu@ubuntu:~/github/pyulog/test$ ulog_messages sample.ulg
0:02:38 ERROR: [sensors] no barometer found on /dev/baro0 (2)
0:02:42 ERROR: [sensors] no barometer found on /dev/baro0 (2)
0:02:51 ERROR: [sensors] no barometer found on /dev/baro0 (2)
0:02:56 ERROR: [sensors] no barometer found on /dev/baro0 (2)
```
### Extract parameters from an ULog file (ulog_params)
Usage:
```
usage: ulog_params [-h] [-d DELIMITER] [-i] [-o] file.ulg [params.txt]
Extract parameters from an ULog file
positional arguments:
file.ulg ULog input file
params.txt Output filename (default=stdout)
optional arguments:
-h, --help show this help message and exit
-d DELIMITER, --delimiter DELIMITER
Use delimiter in CSV (default is ',')
-i, --initial Only extract initial parameters
-o, --octave Use Octave format
```
Example output (to console):
```
ubuntu@ubuntu:~/github/pyulog/test$ ulog_params sample.ulg
ATT_ACC_COMP,1
ATT_BIAS_MAX,0.0500000007451
ATT_EXT_HDG_M,0
...
VT_OPT_RECOV_EN,0
VT_TYPE,0
VT_WV_LND_EN,0
VT_WV_LTR_EN,0
VT_WV_YAWR_SCL,0.15000000596
```
### Convert ULog to CSV files (ulog2csv)
Usage:
```
usage: ulog2csv [-h] [-m MESSAGES] [-d DELIMITER] [-o DIR] file.ulg
Convert ULog to CSV
positional arguments:
file.ulg ULog input file
optional arguments:
-h, --help show this help message and exit
-m MESSAGES, --messages MESSAGES
Only consider given messages. Must be a comma-
separated list of names, like
'sensor_combined,vehicle_gps_position'
-d DELIMITER, --delimiter DELIMITER
Use delimiter in CSV (default is ',')
-o DIR, --output DIR Output directory (default is same as input file)
```
### Convert ULog to KML files (ulog2kml)
> **Note** The `simplekml` module must be installed on your computer. If not already present, you can install it with:
```
pip install simplekml
```
Usage:
```
usage: ulog2kml [-h] [-o OUTPUT_FILENAME] [--topic TOPIC_NAME]
[--camera-trigger CAMERA_TRIGGER]
file.ulg
Convert ULog to KML
positional arguments:
file.ulg ULog input file
optional arguments:
-h, --help show this help message and exit
-o OUTPUT_FILENAME, --output OUTPUT_FILENAME
output filename
--topic TOPIC_NAME topic name with position data
(default=vehicle_gps_position)
--camera-trigger CAMERA_TRIGGER
Camera trigger topic name (e.g. camera_capture)
```
### Convert ULog to rosbag files (ulog2rosbag)
> **Note** You need a ROS environment with `px4_msgs` built and sourced.
Usage:
```
usage: ulog2rosbag [-h] [-m MESSAGES] file.ulg result.bag
Convert ULog to rosbag
positional arguments:
file.ulg ULog input file
result.ulg rosbag output file
optional arguments:
-h, --help show this help message and exit
-m MESSAGES, --messages MESSAGES
Only consider given messages. Must be a comma-
separated list of names, like
'sensor_combined,vehicle_gps_position'
```
### Migrate/setup the database for use with the DatabaseULog class (ulog_migratedb)
> **Warning** This command must be run whenever the schema changes, otherwise DatabaseULog won't function.
> **Warning** Even if you store logs in the database, you should keep the original .ulg files. Otherwise you may lose your data.
Usage:
```
usage: ulog_migratedb [-h] [-d DB_PATH] [-n] [-s SQL_DIR] [-f]
Setup the database for DatabaseULog.
optional arguments:
-h, --help show this help message and exit
-d DB_PATH, --database DB_PATH
Path to the database file
-n, --noop Only print results, do not execute migration scripts.
-s SQL_DIR, --sql SQL_DIR
Directory with migration SQL files
-f, --force Run the migration script even if the database is not
created with this script.
```
Example output (to console):
```
ubuntu@ubuntu:~/github/pyulog$ ulog_migratedb
Using migration files in /home/ubuntu/github/pyulog/pyulog/sql.
Database file pyulog.sqlite3 not found, creating it from scratch.
Current schema version: 0 (database) and 1 (code).
Executing /home/ubuntu/github/pyulog/pyulog/sql/pyulog.1.sql.
Migration done.
```
================================================
FILE: gen_expected_output.sh
================================================
#! /bin/bash
# generate the expected output for the unittests
for f in test/*.ulg; do
echo "Processing $f"
ulog_info -v "$f" > "${f%.*}"_info.txt
ulog_messages "$f" > "${f%.*}"_messages.txt
#ulog_params "$f" > "${f%.*}"_params.txt
done
================================================
FILE: pylintrc
================================================
[MAIN]
# Analyse import fallback blocks. This can be used to support both Python 2 and
# 3 compatible code, which means that the block might have code that exists
# only in one or another interpreter, leading to false positives when analysed.
analyse-fallback-blocks=no
# Clear in-memory caches upon conclusion of linting. Useful if running pylint
# in a server-like mode.
clear-cache-post-run=no
# Load and enable all available extensions. Use --list-extensions to see a list
# all available extensions.
#enable-all-extensions=
# In error mode, messages with a category besides ERROR or FATAL are
# suppressed, and no reports are done by default. Error mode is compatible with
# disabling specific errors.
#errors-only=
# Always return a 0 (non-error) status code, even if lint errors are found.
# This is primarily useful in continuous integration scripts.
#exit-zero=
# A comma-separated list of package or module names from where C extensions may
# be loaded. Extensions are loading into the active Python interpreter and may
# run arbitrary code.
extension-pkg-allow-list=
# A comma-separated list of package or module names from where C extensions may
# be loaded. Extensions are loading into the active Python interpreter and may
# run arbitrary code. (This is an alternative name to extension-pkg-allow-list
# for backward compatibility.)
extension-pkg-whitelist=
# Return non-zero exit code if any of these messages/categories are detected,
# even if score is above --fail-under value. Syntax same as enable. Messages
# specified are enabled, while categories only check already-enabled messages.
fail-on=
# Specify a score threshold under which the program will exit with error.
fail-under=10
# Interpret the stdin as a python script, whose filename needs to be passed as
# the module_or_package argument.
#from-stdin=
# Files or directories to be skipped. They should be base names, not paths.
ignore=CVS
# Add files or directories matching the regular expressions patterns to the
# ignore-list. The regex matches against paths and can be in Posix or Windows
# format. Because '\\' represents the directory delimiter on Windows systems,
# it can't be used as an escape character.
ignore-paths=
# Files or directories matching the regular expression patterns are skipped.
# The regex matches against base names, not paths. The default value ignores
# Emacs file locks
ignore-patterns=
# List of module names for which member attributes should not be checked and
# will not be imported (useful for modules/projects where namespaces are
# manipulated during runtime and thus existing member attributes cannot be
# deduced by static analysis). It supports qualified module names, as well as
# Unix pattern matching.
ignored-modules=numpy
# Python code to execute, usually for sys.path manipulation such as
# pygtk.require().
#init-hook=
# Use multiple processes to speed up Pylint. Specifying 0 will auto-detect the
# number of processors available to use, and will cap the count on Windows to
# avoid hangs.
jobs=1
# Control the amount of potential inferred values when inferring a single
# object. This can help the performance when dealing with large functions or
# complex, nested conditions.
limit-inference-results=100
# List of plugins (as comma separated values of python module names) to load,
# usually to register additional checkers.
load-plugins=
# Pickle collected data for later comparisons.
persistent=yes
# Resolve imports to .pyi stubs if available. May reduce no-member messages and
# increase not-an-iterable messages.
prefer-stubs=no
# Minimum Python version to use for version dependent checks. Will default to
# the version used to run pylint.
py-version=3.13
# Discover python modules and packages in the file system subtree.
recursive=no
# Add paths to the list of the source roots. Supports globbing patterns. The
# source root is an absolute path or a path relative to the current working
# directory used to determine a package namespace for modules located under the
# source root.
source-roots=
# When enabled, pylint would attempt to guess common misconfiguration and emit
# user-friendly hints instead of false-positive error messages.
suggestion-mode=yes
# Allow loading of arbitrary C extensions. Extensions are imported into the
# active Python interpreter and may run arbitrary code.
unsafe-load-any-extension=no
# In verbose mode, extra non-checker-related info will be displayed.
#verbose=
[BASIC]
# Naming style matching correct argument names.
argument-naming-style=snake_case
# Regular expression matching correct argument names. Overrides argument-
# naming-style. If left empty, argument names will be checked with the set
# naming style.
argument-rgx=[a-z_][a-z0-9_]{2,30}$
# Naming style matching correct attribute names.
attr-naming-style=snake_case
# Regular expression matching correct attribute names. Overrides attr-naming-
# style. If left empty, attribute names will be checked with the set naming
# style.
attr-rgx=[a-z_][a-z0-9_]{2,30}$
# Bad variable names which should always be refused, separated by a comma.
bad-names=foo,
bar,
baz,
toto,
tutu,
tata
# Bad variable names regexes, separated by a comma. If names match any regex,
# they will always be refused
bad-names-rgxs=
# Naming style matching correct class attribute names.
class-attribute-naming-style=any
# Regular expression matching correct class attribute names. Overrides class-
# attribute-naming-style. If left empty, class attribute names will be checked
# with the set naming style.
class-attribute-rgx=([A-Za-z_][A-Za-z0-9_]{2,30}|(__.*__))$
# Naming style matching correct class constant names.
class-const-naming-style=UPPER_CASE
# Regular expression matching correct class constant names. Overrides class-
# const-naming-style. If left empty, class constant names will be checked with
# the set naming style.
#class-const-rgx=
# Naming style matching correct class names.
class-naming-style=PascalCase
# Regular expression matching correct class names. Overrides class-naming-
# style. If left empty, class names will be checked with the set naming style.
class-rgx=[A-Z_][a-zA-Z0-9]+$
# Naming style matching correct constant names.
const-naming-style=UPPER_CASE
# Regular expression matching correct constant names. Overrides const-naming-
# style. If left empty, constant names will be checked with the set naming
# style.
const-rgx=(([A-Z_][A-Z0-9_]*)|(__.*__))$
# Minimum line length for functions/classes that require docstrings, shorter
# ones are exempt.
docstring-min-length=-1
# Naming style matching correct function names.
function-naming-style=snake_case
# Regular expression matching correct function names. Overrides function-
# naming-style. If left empty, function names will be checked with the set
# naming style.
function-rgx=[a-z_][a-z0-9_]{2,30}$
# Good variable names which should always be accepted, separated by a comma.
good-names=i,
j,
k,
ex,
Run,
_,
t,
x,
q
# Good variable names regexes, separated by a comma. If names match any regex,
# they will always be accepted
good-names-rgxs=
# Include a hint for the correct naming format with invalid-name.
include-naming-hint=no
# Naming style matching correct inline iteration names.
inlinevar-naming-style=any
# Regular expression matching correct inline iteration names. Overrides
# inlinevar-naming-style. If left empty, inline iteration names will be checked
# with the set naming style.
inlinevar-rgx=[A-Za-z_][A-Za-z0-9_]*$
# Naming style matching correct method names.
method-naming-style=snake_case
# Regular expression matching correct method names. Overrides method-naming-
# style. If left empty, method names will be checked with the set naming style.
method-rgx=[a-z_][a-z0-9_]{2,40}$
# Naming style matching correct module names.
module-naming-style=snake_case
# Regular expression matching correct module names. Overrides module-naming-
# style. If left empty, module names will be checked with the set naming style.
module-rgx=(([a-z_][a-z0-9_]*)|([A-Z][a-zA-Z0-9]+))$
# Colon-delimited sets of names that determine each other's naming style when
# the name regexes allow several styles.
name-group=
# Regular expression which should only match function or class names that do
# not require a docstring.
no-docstring-rgx=^_
# List of decorators that produce properties, such as abc.abstractproperty. Add
# to this list to register other decorators that produce valid properties.
# These decorators are taken in consideration only for invalid-name.
property-classes=abc.abstractproperty
# Regular expression matching correct type alias names. If left empty, type
# alias names will be checked with the set naming style.
#typealias-rgx=
# Regular expression matching correct type variable names. If left empty, type
# variable names will be checked with the set naming style.
#typevar-rgx=
# Naming style matching correct variable names.
variable-naming-style=snake_case
# Regular expression matching correct variable names. Overrides variable-
# naming-style. If left empty, variable names will be checked with the set
# naming style.
variable-rgx=[a-z_][a-z0-9_]{2,30}$
[CLASSES]
# Warn about protected attribute access inside special methods
check-protected-access-in-special-methods=no
# List of method names used to declare (i.e. assign) instance attributes.
defining-attr-methods=__init__,
__new__,
setUp
# List of member names, which should be excluded from the protected access
# warning.
exclude-protected=_asdict,
_fields,
_replace,
_source,
_make
# List of valid names for the first argument in a class method.
valid-classmethod-first-arg=cls
# List of valid names for the first argument in a metaclass class method.
valid-metaclass-classmethod-first-arg=mcs
[DESIGN]
# List of regular expressions of class ancestor names to ignore when counting
# public methods (see R0903)
exclude-too-few-public-methods=
# List of qualified class names to ignore when counting class parents (see
# R0901)
ignored-parents=
# Maximum number of arguments for function / method.
max-args=7
# Maximum number of attributes for a class (see R0902).
max-attributes=7
# Maximum number of boolean expressions in an if statement (see R0916).
max-bool-expr=5
# Maximum number of branch for function / method body.
max-branches=12
# Maximum number of locals for function / method body.
max-locals=20
# Maximum number of parents for a class (see R0901).
max-parents=7
# Maximum number of positional arguments for function / method.
max-positional-arguments=10
# Maximum number of public methods for a class (see R0904).
max-public-methods=25
# Maximum number of return / yield for function / method body.
max-returns=6
# Maximum number of statements in function / method body.
max-statements=100
# Minimum number of public methods for a class (see R0903).
min-public-methods=2
[EXCEPTIONS]
# Exceptions that will emit a warning when caught.
overgeneral-exceptions=builtins.Exception
[FORMAT]
# Expected format of line ending, e.g. empty (any line ending), LF or CRLF.
expected-line-ending-format=
# Regexp for a line that is allowed to be longer than the limit.
ignore-long-lines=^\s*(# )?<?https?://\S+>?$
# Number of spaces of indent required inside a hanging or continued line.
indent-after-paren=4
# String used as indentation unit. This is usually " " (4 spaces) or "\t" (1
# tab).
indent-string=' '
# Maximum number of characters on a single line.
max-line-length=100
# Maximum number of lines in a module.
max-module-lines=1200
# Allow the body of a class to be on the same line as the declaration if body
# contains single statement.
single-line-class-stmt=no
# Allow the body of an if to be on the same line as the test if there is no
# else.
single-line-if-stmt=no
[IMPORTS]
# List of modules that can be imported at any level, not just the top level
# one.
allow-any-import-level=
# Allow explicit reexports by alias from a package __init__.
allow-reexport-from-package=no
# Allow wildcard imports from modules that define __all__.
allow-wildcard-with-all=no
# Deprecated modules which should not be used, separated by a comma.
deprecated-modules=regsub,
TERMIOS,
Bastion,
rexec
# Output a graph (.gv or any supported image format) of external dependencies
# to the given file (report RP0402 must not be disabled).
ext-import-graph=
# Output a graph (.gv or any supported image format) of all (i.e. internal and
# external) dependencies to the given file (report RP0402 must not be
# disabled).
import-graph=
# Output a graph (.gv or any supported image format) of internal dependencies
# to the given file (report RP0402 must not be disabled).
int-import-graph=
# Force import order to recognize a module as part of the standard
# compatibility libraries.
known-standard-library=
# Force import order to recognize a module as part of a third party library.
known-third-party=enchant
# Couples of modules and preferred modules, separated by a comma.
preferred-modules=
[LOGGING]
# The type of string formatting that logging methods do. `old` means using %
# formatting, `new` is for `{}` formatting.
logging-format-style=old
# Logging modules to check that the string format arguments are in logging
# function parameter format.
logging-modules=logging
[MESSAGES CONTROL]
# Only show warnings with the listed confidence levels. Leave empty to show
# all. Valid levels: HIGH, CONTROL_FLOW, INFERENCE, INFERENCE_FAILURE,
# UNDEFINED.
confidence=HIGH,
CONTROL_FLOW,
INFERENCE,
INFERENCE_FAILURE,
UNDEFINED
# Disable the message, report, category or checker with the given id(s). You
# can either give multiple identifiers separated by comma (,) or put this
# option multiple times (only on the command line, not in the configuration
# file where it should appear only once). You can also use "--disable=all" to
# disable everything first and then re-enable specific checks. For example, if
# you want to run only the similarities checker, you can use "--disable=all
# --enable=similarities". If you want to run only the classes checker, but have
# no Warning level messages displayed, use "--disable=all --enable=classes
# --disable=W".
disable=raw-checker-failed,
bad-inline-option,
locally-disabled,
file-ignored,
suppressed-message,
useless-suppression,
deprecated-pragma,
use-symbolic-message-instead,
use-implicit-booleaness-not-comparison-to-string,
use-implicit-booleaness-not-comparison-to-zero,
fixme,
trailing-newlines,
multiple-statements,
too-few-public-methods,
use-implicit-booleaness-not-len,
useless-object-inheritance,
consider-using-f-string,
unused-argument
# Enable the message, report, category or checker with the given id(s). You can
# either give multiple identifier separated by comma (,) or put this option
# multiple time (only on the command line, not in the configuration file where
# it should appear only once). See also the "--disable" option for examples.
enable=
[METHOD_ARGS]
# List of qualified names (i.e., library.method) which require a timeout
# parameter e.g. 'requests.api.get,requests.api.post'
timeout-methods=requests.api.delete,requests.api.get,requests.api.head,requests.api.options,requests.api.patch,requests.api.post,requests.api.put,requests.api.request
[MISCELLANEOUS]
# List of note tags to take in consideration, separated by a comma.
notes=FIXME,
XXX,
TODO
# Regular expression of note tags to take in consideration.
notes-rgx=
[REFACTORING]
# Maximum number of nested blocks for function / method body
max-nested-blocks=6
# Complete name of functions that never returns. When checking for
# inconsistent-return-statements if a never returning function is called then
# it will be considered as an explicit return statement and no message will be
# printed.
never-returning-functions=sys.exit,argparse.parse_error
# Let 'consider-using-join' be raised when the separator to join on would be
# non-empty (resulting in expected fixes of the type: ``"- " + " -
# ".join(items)``)
suggest-join-with-non-empty-separator=yes
[REPORTS]
# Python expression which should return a score less than or equal to 10. You
# have access to the variables 'fatal', 'error', 'warning', 'refactor',
# 'convention', and 'info' which contain the number of messages in each
# category, as well as 'statement' which is the total number of statements
# analyzed. This score is used by the global evaluation report (RP0004).
evaluation=10.0 - ((float(5 * error + warning + refactor + convention) / statement) * 10)
# Template used to display messages. This is a python new-style format string
# used to format the message information. See doc for all details.
msg-template=
# Set the output format. Available formats are: text, parseable, colorized,
# json2 (improved json format), json (old json format) and msvs (visual
# studio). You can also give a reporter class, e.g.
# mypackage.mymodule.MyReporterClass.
#output-format=
# Tells whether to display a full report or only the messages.
reports=no
# Activate the evaluation score.
score=yes
[SIMILARITIES]
# Comments are removed from the similarity computation
ignore-comments=yes
# Docstrings are removed from the similarity computation
ignore-docstrings=yes
# Imports are removed from the similarity computation
ignore-imports=yes
# Signatures are removed from the similarity computation
ignore-signatures=yes
# Minimum lines number of a similarity.
min-similarity-lines=5
[SPELLING]
# Limits count of emitted suggestions for spelling mistakes.
max-spelling-suggestions=4
# Spelling dictionary name. No available dictionaries : You need to install
# both the python package and the system dependency for enchant to work.
spelling-dict=
# List of comma separated words that should be considered directives if they
# appear at the beginning of a comment and should not be checked.
spelling-ignore-comment-directives=fmt: on,fmt: off,noqa:,noqa,nosec,isort:skip,mypy:
# List of comma separated words that should not be checked.
spelling-ignore-words=
# A path to a file that contains the private dictionary; one word per line.
spelling-private-dict-file=
# Tells whether to store unknown words to the private dictionary (see the
# --spelling-private-dict-file option) instead of raising a message.
spelling-store-unknown-words=no
[STRING]
# This flag controls whether inconsistent-quotes generates a warning when the
# character used as a quote delimiter is used inconsistently within a module.
check-quote-consistency=no
# This flag controls whether the implicit-str-concat should generate a warning
# on implicit string concatenation in sequences defined over several lines.
check-str-concat-over-line-jumps=no
[TYPECHECK]
# List of decorators that produce context managers, such as
# contextlib.contextmanager. Add to this list to register other decorators that
# produce valid context managers.
contextmanager-decorators=contextlib.contextmanager
# List of members which are set dynamically and missed by pylint inference
# system, and so shouldn't trigger E1101 when accessed. Python regular
# expressions are accepted.
generated-members=
# Tells whether to warn about missing members when the owner of the attribute
# is inferred to be None.
ignore-none=yes
# This flag controls whether pylint should warn about no-member and similar
# checks whenever an opaque object is returned when inferring. The inference
# can return multiple potential results while evaluating a Python object, but
# some branches might not be evaluated, which results in partial inference. In
# that case, it might be useful to still emit no-member and other checks for
# the rest of the inferred objects.
ignore-on-opaque-inference=yes
# List of symbolic message names to ignore for Mixin members.
ignored-checks-for-mixins=no-member,
not-async-context-manager,
not-context-manager,
attribute-defined-outside-init
# List of class names for which member attributes should not be checked (useful
# for classes with dynamically set attributes). This supports the use of
# qualified names.
ignored-classes=optparse.Values,thread._local,_thread._local
# Show a hint with possible names when a member name was not found. The aspect
# of finding the hint is based on edit distance.
missing-member-hint=yes
# The minimum edit distance a name should have in order to be considered a
# similar match for a missing member name.
missing-member-hint-distance=1
# The total number of similar names that should be taken in consideration when
# showing a hint for a missing member.
missing-member-max-choices=1
# Regex pattern to define which classes are considered mixins.
mixin-class-rgx=.*[Mm]ixin
# List of decorators that change the signature of a decorated function.
signature-mutators=
[VARIABLES]
# List of additional names supposed to be defined in builtins. Remember that
# you should avoid defining new builtins when possible.
additional-builtins=
# Tells whether unused global variables should be treated as a violation.
allow-global-unused-variables=yes
# List of names allowed to shadow builtins
allowed-redefined-builtins=
# List of strings which can identify a callback function by name. A callback
# name must start or end with one of those strings.
callbacks=cb_,
_cb
# A regular expression matching the name of dummy variables (i.e. expected to
# not be used).
dummy-variables-rgx=(_+[a-zA-Z0-9]*?$)|dummy
# Argument names that match this expression will be ignored.
ignored-argument-names=_.*
# Tells whether we should check for unused import in __init__ files.
init-import=no
# List of qualified module names which can have objects that can redefine
# builtins.
redefining-builtins-modules=six.moves,future.builtins
================================================
FILE: pyproject.toml
================================================
[build-system]
requires = ["setuptools>=77.0.3", "setuptools-scm>=8"]
build-backend = "setuptools.build_meta"
[project]
name = "pyulog"
description = "Python log parser for ULog"
license = "BSD-3-Clause"
dependencies = [
"numpy < 1.25; python_version < '3.9'",
"numpy >= 1.25; python_version >= '3.9'",
]
dynamic = [
"version",
"readme",
]
maintainers = [
{ name = "James Goppert", email = "james.goppert@gmail.com" },
{ name = "Beat Kueng", email = "beat-kueng@gmx.net" },
]
classifiers = [
"Development Status :: 5 - Production/Stable",
"Intended Audience :: Science/Research",
"Intended Audience :: Developers",
"Programming Language :: Python",
"Programming Language :: Python :: 3",
"Programming Language :: Other",
"Topic :: Software Development",
"Topic :: Scientific/Engineering :: Artificial Intelligence",
"Topic :: Scientific/Engineering :: Mathematics",
"Topic :: Scientific/Engineering :: Physics",
"Operating System :: Microsoft :: Windows",
"Operating System :: POSIX",
"Operating System :: Unix",
"Operating System :: MacOS",
]
[project.scripts]
ulog_extract_gps_dump = "pyulog.extract_gps_dump:main"
ulog_info = "pyulog.info:main"
ulog_messages = "pyulog.messages:main"
ulog_params = "pyulog.params:main"
ulog2csv = "pyulog.ulog2csv:main"
ulog2kml = "pyulog.ulog2kml:main"
ulog2rosbag = "pyulog.ulog2rosbag:main"
ulog_migratedb = "pyulog.migrate_db:main"
[project.urls]
Homepage = "https://github.com/PX4/pyulog"
Repository = "https://github.com/PX4/pyulog"
[project.optional-dependencies]
test = ['pytest', 'ddt']
[tool.setuptools_scm]
================================================
FILE: pyulog/__init__.py
================================================
""" Wrapper to include the main library modules """
from .core import ULog
from . import px4
================================================
FILE: pyulog/core.py
================================================
""" Main Module to load and parse an ULog file """
import struct
import copy
import sys
import contextlib
import numpy as np
#pylint: disable=too-many-instance-attributes, unused-argument, missing-docstring
#pylint: disable=protected-access, too-many-branches
__author__ = "Beat Kueng"
# check python version
if sys.hexversion >= 0x030000F0:
_RUNNING_PYTHON3 = True
def _parse_string(cstr, errors='strict'):
return str(cstr, 'utf-8', errors)
else:
_RUNNING_PYTHON3 = False
def _parse_string(cstr):
return str(cstr)
class ULog(object):
"""
This class parses an ulog file
"""
## constants ##
HEADER_BYTES = b'\x55\x4c\x6f\x67\x01\x12\x35'
SYNC_BYTES = b'\x2F\x73\x13\x20\x25\x0C\xBB\x12'
# message types
MSG_TYPE_FORMAT = ord('F')
MSG_TYPE_DATA = ord('D')
MSG_TYPE_INFO = ord('I')
MSG_TYPE_INFO_MULTIPLE = ord('M')
MSG_TYPE_PARAMETER = ord('P')
MSG_TYPE_PARAMETER_DEFAULT = ord('Q')
MSG_TYPE_ADD_LOGGED_MSG = ord('A')
MSG_TYPE_REMOVE_LOGGED_MSG = ord('R')
MSG_TYPE_SYNC = ord('S')
MSG_TYPE_DROPOUT = ord('O')
MSG_TYPE_LOGGING = ord('L')
MSG_TYPE_LOGGING_TAGGED = ord('C')
MSG_TYPE_FLAG_BITS = ord('B')
_UNPACK_TYPES = {
'int8_t': ['b', 1, np.int8],
'uint8_t': ['B', 1, np.uint8],
'int16_t': ['h', 2, np.int16],
'uint16_t': ['H', 2, np.uint16],
'int32_t': ['i', 4, np.int32],
'uint32_t': ['I', 4, np.uint32],
'int64_t': ['q', 8, np.int64],
'uint64_t': ['Q', 8, np.uint64],
'float': ['f', 4, np.float32],
'double': ['d', 8, np.float64],
'bool': ['?', 1, np.int8],
'char': ['c', 1, np.int8]
}
@staticmethod
def get_field_size(type_str):
"""
get the field size in bytes.
:param type_str: type string, eg. 'int8_t'
"""
return ULog._UNPACK_TYPES[type_str][1]
# pre-init unpack structs for quicker use
_unpack_ushort_byte = struct.Struct('<HB').unpack
_unpack_ushort = struct.Struct('<H').unpack
_unpack_uint64 = struct.Struct('<Q').unpack
# when set to True disables string parsing exceptions
_disable_str_exceptions = False
@staticmethod
def parse_string(cstr):
"""
wrapper for _parse_string with
parametrized exception handling
"""
ret = ''
if _RUNNING_PYTHON3 and ULog._disable_str_exceptions:
ret = _parse_string(cstr, 'ignore')
else:
ret = _parse_string(cstr)
return ret
def __init__(self, log_file, message_name_filter_list=None, disable_str_exceptions=True,
parse_header_only=False):
"""
Initialize the object & load the file.
:param log_file: a file name (str) or a readable file object
:param message_name_filter_list: list of strings, to only load messages
with the given names. If None, load everything.
:param disable_str_parser_exceptions: If True, ignore string parsing errors
"""
self._debug = False
self._file_corrupt = False
self._start_timestamp = 0
self._last_timestamp = 0
self._msg_info_dict = {}
self._msg_info_dict_types = {}
self._msg_info_multiple_dict = {}
self._msg_info_multiple_dict_types = {}
self._initial_parameters = {}
self._default_parameters = {}
self._changed_parameters = []
self._message_formats = {}
self._logged_messages = []
self._logged_messages_tagged = {}
self._dropouts = []
self._data_list = []
self._subscriptions = {} # dict of key=msg_id, value=_MessageAddLogged
self._filtered_message_ids = set() # _MessageAddLogged id's that are filtered
self._missing_message_ids = set() # _MessageAddLogged id's that could not be found
self._file_version = 0
self._compat_flags = [0] * 8
self._incompat_flags = [0] * 8
self._appended_offsets = [] # file offsets for appended data
self._has_sync = True # set to false when first file search for sync fails
self._sync_seq_cnt = 0 # number of sync packets found in file
ULog._disable_str_exceptions = disable_str_exceptions
if log_file is not None:
self._load_file(log_file, message_name_filter_list, parse_header_only)
## parsed data
@property
def start_timestamp(self):
""" timestamp of file start """
return self._start_timestamp
@property
def last_timestamp(self):
""" timestamp of last message """
return self._last_timestamp
@property
def msg_info_dict(self):
""" dictionary of all information messages (key is a string, value
depends on the type, usually string or int) """
return self._msg_info_dict
@property
def msg_info_multiple_dict(self):
""" dictionary of all information multiple messages (key is a string, value
is a list of lists that contains the messages) """
return self._msg_info_multiple_dict
@property
def initial_parameters(self):
""" dictionary of all initially set parameters (key=param name) """
return self._initial_parameters
def get_default_parameters(self, default_type):
""" dictionary of all default parameters (key=param name).
Note that defaults are generally only stored for parameters where
the default is different from the configured value
:param default_type: 0: system, 1: current_setup
"""
return self._default_parameters.get(default_type, {})
@property
def changed_parameters(self):
""" list of all changed parameters (tuple of (timestamp, name, value))"""
return self._changed_parameters
@property
def message_formats(self):
""" dictionary with key = format name (MessageFormat.name),
value = MessageFormat object """
return self._message_formats
@property
def logged_messages(self):
""" list of MessageLogging objects """
return self._logged_messages
@property
def logged_messages_tagged(self):
""" dict of MessageLoggingTagged objects """
return self._logged_messages_tagged
@property
def dropouts(self):
""" list of MessageDropout objects """
return self._dropouts
@property
def data_list(self):
""" extracted data: list of Data objects """
return self._data_list
@property
def has_data_appended(self):
""" returns True if the log has data appended, False otherwise """
return self._incompat_flags[0] & 0x1
@property
def file_corruption(self):
""" True if a file corruption got detected """
return self._file_corrupt
@property
def has_default_parameters(self):
""" True if compat flag DEFAULT_PARAMETERS is set """
return self._compat_flags[0] & (0x1 << 0)
def get_dataset(self, name, multi_instance=0):
""" get a specific dataset.
example:
try:
gyro_data = ulog.get_dataset('sensor_gyro')
except (KeyError, IndexError, ValueError) as error:
print(type(error), "(sensor_gyro):", error)
:param name: name of the dataset
:param multi_instance: the multi_id, defaults to the first
:raises KeyError, IndexError, ValueError: if name or instance not found
"""
return [elem for elem in self._data_list
if elem.name == name and elem.multi_id == multi_instance][0]
def write_ulog(self, log_file):
""" write current data back into a ulog file """
if isinstance(log_file, str):
handle = open(log_file, "wb")
else:
handle = contextlib.nullcontext(log_file)
with handle as ulog_file:
# Definition section
self._write_file_header(ulog_file)
self._write_flags(ulog_file)
self._write_format_messages(ulog_file)
self._write_info_messages(ulog_file)
self._write_info_multiple_message(ulog_file)
self._write_initial_parameters(ulog_file)
self._write_default_parameters(ulog_file)
# Data section
self._write_logged_message_subscriptions(ulog_file)
self._write_data_section(ulog_file)
def _write_file_header(self, file):
header_data = bytearray()
header_data.extend(self.HEADER_BYTES)
header_data.extend(struct.pack('B', self._file_version))
header_data.extend(struct.pack('<Q', self._start_timestamp))
if len(header_data) != 16:
raise TypeError("Written header is too short")
file.write(header_data)
def _write_flags(self, file):
data = bytearray()
data.extend(struct.pack('<' + 'B' * 8, *self._compat_flags))
# When writing the log back to a .ulg file, don't mark data as appended
imcompat_flags = copy.deepcopy(self._incompat_flags)
imcompat_flags[0] = imcompat_flags[0] & 0xFE
data.extend(struct.pack('<' + 'B' * 8, *imcompat_flags))
offsets = [0, 0, 0]
data.extend(struct.pack('<' + 'Q' * 3, *offsets))
header = struct.pack('<HB', len(data), self.MSG_TYPE_FLAG_BITS)
file.write(header)
file.write(data)
def _write_info_messages(self, file):
for message in self._msg_info_dict.items():
value_type: str = self._msg_info_dict_types[message[0]]
key: str = value_type + ' ' + message[0]
value: str = message[1]
data = self._make_info_message_data(key, value, value_type)
header = struct.pack('<HB', len(data), self.MSG_TYPE_INFO)
file.write(header)
file.write(data)
def _write_info_multiple_message(self, file):
for base_key, value_sets in self._msg_info_multiple_dict.items():
value_type: str = self._msg_info_multiple_dict_types[base_key]
key: str = value_type + ' ' + base_key
for value_set in value_sets:
continued = False
for value in value_set:
data = self._make_info_message_data(key, value, value_type, continued)
header = struct.pack('<HB', len(data), self.MSG_TYPE_INFO_MULTIPLE)
file.write(header)
file.write(data)
continued = True
def _write_initial_parameters(self, file):
for parameter_name, value in self._initial_parameters.items():
data = self._make_parameter_data(parameter_name, value)
header = struct.pack('<HB', len(data), self.MSG_TYPE_PARAMETER)
file.write(header)
file.write(data)
def _write_default_parameters(self, file):
for bit, bit_dict in self._default_parameters.items():
bitfield = 1 << bit
for name, value in bit_dict.items():
data = bytearray()
data.extend(struct.pack('<B', bitfield))
data.extend(self._make_parameter_data(name, value))
header = struct.pack('<HB', len(data), self.MSG_TYPE_PARAMETER_DEFAULT)
file.write(header)
file.write(data)
def _make_parameter_data(self, name: str, value) -> bytes:
if isinstance(value, int):
value_type = "int32_t"
elif isinstance(value, float):
value_type = "float"
else:
raise TypeError("Found unknown parameter value type")
key: str = value_type + ' ' + name
return self._make_info_message_data(key, value, value_type)
def _make_info_message_data(self, key: str, value, value_type: str, continued=None) -> bytes:
key_bytes = bytes(key, 'utf-8')
data = bytearray()
if continued is not None:
data.extend(struct.pack('<B', continued))
data.extend(struct.pack('<B', len(key_bytes)))
data.extend(key_bytes)
if value_type.startswith('char['):
value_bytes = bytes(value, 'utf-8')
data.extend(value_bytes)
elif value_type.startswith('uint8_t['):
data.extend(value)
else:
code = self._UNPACK_TYPES[value_type][0]
data.extend(struct.pack('<' + code, value))
return data
def _write_format_messages(self, file):
for message_format in self._message_formats.values():
data = bytearray()
data.extend(bytes(message_format.name + ':', 'utf-8'))
for field in message_format.fields:
# Determine the field type (e.g. int16_t or float[8])
field_type: str = field[0]
array_size: int = field[1]
field_name: str = field[2]
if array_size > 0:
encoded_field = '%s[%d] %s;' % (field_type, array_size, field_name)
else:
encoded_field = '%s %s;' % (field_type, field_name)
data.extend(bytes(encoded_field, 'utf-8'))
header = struct.pack('<HB', len(data), self.MSG_TYPE_FORMAT)
file.write(header)
file.write(data)
def _write_logged_message_subscriptions(self, file):
data_sets = sorted(self._data_list, key=lambda x: x.msg_id)
for data_set in data_sets:
data = bytearray()
data.extend(struct.pack('<BH', data_set.multi_id, data_set.msg_id))
data.extend(bytes(data_set.name, 'utf-8'))
header = struct.pack('<HB', len(data), self.MSG_TYPE_ADD_LOGGED_MSG)
file.write(header)
file.write(data)
def _write_data_section(self, file):
# Reconstruct all messages in the data section except for those with the type A, S, I, M, Q.
items = self._make_data_items()
items = items + self._make_logged_message_items()
items = items + self._make_tagged_logged_message_items()
items = items + self._make_dropout_items()
items = items + self._make_changed_param_items()
# Sort items by timestamp
items.sort(key=lambda x: x[0])
for _, buffer in items:
file.write(buffer)
def _make_data_items(self):
data_sets = sorted(self._data_list, key=lambda x: x.msg_id)
data_items = []
for data_set in data_sets:
data_set_length = len(data_set.data[data_set.field_data[0].field_name])
for i_sample in range(data_set_length):
timestamp = data_set.data['timestamp'][i_sample]
msg_id = struct.pack('<H', data_set.msg_id)
data = bytearray()
data.extend(msg_id)
for field in data_set.field_data:
field_name = field.field_name
field_type = field.type_str
field_encoding = self._UNPACK_TYPES[field_type][0]
field_data = data_set.data[field_name][i_sample]
# For char type, convert np.int8 into single bytes() object
# so that struct.pack can handle it
if field_encoding == 'c':
field_data = bytes(chr(field_data), 'utf-8')
data.extend(struct.pack('<' + field_encoding, field_data))
header = struct.pack('<HB', len(data), self.MSG_TYPE_DATA)
data_items.append((timestamp, header + data))
return data_items
def _make_logged_message_items(self):
message_items = []
for message in self._logged_messages:
data = bytearray()
data.extend(struct.pack('<BQ', message.log_level, message.timestamp))
data.extend(bytes(message.message, 'utf-8'))
header = struct.pack('<HB', len(data), self.MSG_TYPE_LOGGING)
message_items.append((message.timestamp, header + data))
return message_items
def _make_tagged_logged_message_items(self):
message_items = []
for message_list in self._logged_messages_tagged.values():
for message in message_list:
data = bytearray()
data.extend(struct.pack('<BHQ', message.log_level, message.tag, message.timestamp))
data.extend(bytes(message.message, 'utf-8'))
header = struct.pack('<HB', len(data), self.MSG_TYPE_LOGGING_TAGGED)
message_items.append((message.timestamp, header + data))
return message_items
def _make_dropout_items(self):
dropout_items = []
for dropout in self._dropouts:
data = bytearray()
data.extend(struct.pack('<H', dropout.duration))
header = struct.pack('<HB', len(data), self.MSG_TYPE_DROPOUT)
dropout_items.append((dropout.timestamp, header + data))
return dropout_items
def _make_changed_param_items(self):
changed_param_items = []
for timestamp, name, value in self._changed_parameters:
data = self._make_parameter_data(name, value)
header = struct.pack('<HB', len(data), self.MSG_TYPE_PARAMETER)
changed_param_items.append((timestamp, header + data))
return changed_param_items
def __eq__(self, other):
"""
If the other object has all the same data as we have, we want to
consider them equal, even if the other object has extra fields, because
the user cares about the ULog contents.
"""
if not isinstance(other, ULog):
return NotImplemented
return all(
self_value == getattr(other, field)
for field, self_value in self.__dict__.items()
)
class Data(object):
""" contains the final topic data for a single topic and instance """
def __init__(self, message_add_logged_obj):
self.multi_id = message_add_logged_obj.multi_id
self.msg_id = message_add_logged_obj.msg_id
self.name = message_add_logged_obj.message_name
self.field_data = message_add_logged_obj.field_data
self.timestamp_idx = message_add_logged_obj.timestamp_idx
# get data as numpy.ndarray
np_array = np.frombuffer(message_add_logged_obj.buffer,
dtype=message_add_logged_obj.dtype)
# convert into dict of np.array (which is easier to handle)
self.data = {}
for name in np_array.dtype.names:
self.data[name] = np_array[name]
def __eq__(self, other):
if not isinstance(other, ULog.Data):
return NotImplemented
# Compare data arrays
arrays_equal = self.data.keys() == other.data.keys()
if arrays_equal:
for l_array, r_array in zip(self.data.values(), other.data.values()):
arrays_equal = arrays_equal and np.array_equal(l_array, r_array, equal_nan=True)
return (self.multi_id == other.multi_id and
self.msg_id == other.msg_id and
self.name == other.name and
self.field_data == other.field_data and
self.timestamp_idx == other.timestamp_idx and
arrays_equal)
def list_value_changes(self, field_name):
""" get a list of (timestamp, value) tuples, whenever the value
changes. The first data point with non-zero timestamp is always
included, messages with timestamp = 0 are ignored """
t = self.data['timestamp']
x = self.data[field_name]
indices = t != 0 # filter out 0 values
t = t[indices]
x = x[indices]
if len(t) == 0: return []
ret = [(t[0], x[0])]
indices = np.where(x[:-1] != x[1:])[0] + 1
ret.extend(zip(t[indices], x[indices]))
return ret
## Representations of the messages from the log file ##
class _MessageHeader(object):
""" 3 bytes ULog message header """
def __init__(self):
self.msg_size = 0
self.msg_type = 0
def initialize(self, data):
self.msg_size, self.msg_type = ULog._unpack_ushort_byte(data)
class _MessageInfo(object):
""" ULog info message representation """
def __init__(self, data, header, is_info_multiple=False):
if is_info_multiple: # INFO_MULTIPLE message
self.is_continued, = struct.unpack('<B', data[0:1])
data = data[1:]
key_len, = struct.unpack('<B', data[0:1])
type_key = ULog.parse_string(data[1:1+key_len])
type_key_split = type_key.split(' ')
self.type = type_key_split[0]
self.key = type_key_split[1]
if self.type.startswith('char['): # it's a string
self.value = ULog.parse_string(data[1+key_len:])
elif self.type in ULog._UNPACK_TYPES:
unpack_type = ULog._UNPACK_TYPES[self.type]
self.value, = struct.unpack('<'+unpack_type[0], data[1+key_len:])
else: # probably an array (or non-basic type)
self.value = data[1+key_len:]
class _MessageParameterDefault(object):
""" ULog parameter default message representation """
def __init__(self, data, header):
self.default_types, = struct.unpack('<B', data[0:1])
msg_info = ULog._MessageInfo(data[1:], header)
self.type = msg_info.type
self.key = msg_info.key
self.value = msg_info.value
class _MessageFlagBits(object):
""" ULog message flag bits """
def __init__(self, data, header):
if header.msg_size > 8 + 8 + 3*8:
# we can still parse it but might miss some information
print('Warning: Flags Bit message is longer than expected')
self.compat_flags = list(struct.unpack('<'+'B'*8, data[0:8]))
self.incompat_flags = list(struct.unpack('<'+'B'*8, data[8:16]))
self.appended_offsets = list(struct.unpack('<'+'Q'*3, data[16:16+3*8]))
# remove the 0's at the end
while len(self.appended_offsets) > 0 and self.appended_offsets[-1] == 0:
self.appended_offsets.pop()
class MessageFormat(object):
""" ULog message format representation """
def __init__(self, data, header):
format_arr = ULog.parse_string(data).split(':')
self.name = format_arr[0]
types_str = format_arr[1].split(';')
self.fields = [] # list of tuples (type, array_size, name)
for t in types_str:
if len(t) > 0:
self.fields.append(self._extract_type(t))
def __eq__(self, other):
if not isinstance(other, ULog.MessageFormat):
return NotImplemented
return self.name == other.name and self.fields == other.fields
@staticmethod
def _extract_type(field_str):
field_str_split = field_str.split(' ')
type_str = field_str_split[0]
name_str = field_str_split[1]
a_pos = type_str.find('[')
if a_pos == -1:
array_size = 0
type_name = type_str
else:
b_pos = type_str.find(']')
array_size = int(type_str[a_pos+1:b_pos])
type_name = type_str[:a_pos]
return type_name, array_size, name_str
class MessageLogging(object):
""" ULog logged string message representation """
def __init__(self, data, header):
self.log_level, = struct.unpack('<B', data[0:1])
self.timestamp, = struct.unpack('<Q', data[1:9])
self.message = ULog.parse_string(data[9:])
def __eq__(self, other):
if not isinstance(other, ULog.MessageLogging):
return NotImplemented
return (self.log_level == other.log_level and
self.timestamp == other.timestamp and
self.message == other.message)
def log_level_str(self):
return {ord('0'): 'EMERGENCY',
ord('1'): 'ALERT',
ord('2'): 'CRITICAL',
ord('3'): 'ERROR',
ord('4'): 'WARNING',
ord('5'): 'NOTICE',
ord('6'): 'INFO',
ord('7'): 'DEBUG'}.get(self.log_level, 'UNKNOWN')
class MessageLoggingTagged(object):
""" ULog tagged log string message representation """
def __init__(self, data, header):
self.log_level, = struct.unpack('<B', data[0:1])
self.tag, = struct.unpack('<H', data[1:3])
self.timestamp, = struct.unpack('<Q', data[3:11])
self.message = ULog.parse_string(data[11:])
def __eq__(self, other):
if not isinstance(other, ULog.MessageLoggingTagged):
return NotImplemented
return (self.log_level == other.log_level and
self.tag == other.tag and
self.timestamp == other.timestamp and
self.message == other.message)
def log_level_str(self):
return {ord('0'): 'EMERGENCY',
ord('1'): 'ALERT',
ord('2'): 'CRITICAL',
ord('3'): 'ERROR',
ord('4'): 'WARNING',
ord('5'): 'NOTICE',
ord('6'): 'INFO',
ord('7'): 'DEBUG'}.get(self.log_level, 'UNKNOWN')
class MessageDropout(object):
""" ULog dropout message representation """
def __init__(self, data, header, timestamp):
self.duration, = struct.unpack('<H', data)
self.timestamp = timestamp
def __eq__(self, other):
if not isinstance(other, ULog.MessageDropout):
return NotImplemented
return self.duration == other.duration and self.timestamp == other.timestamp
class _FieldData(object):
""" Type and name of a single ULog data field """
def __init__(self, field_name, type_str):
self.field_name = field_name
self.type_str = type_str
def __eq__(self, other):
if not isinstance(other, ULog._FieldData):
return NotImplemented
return self.field_name == other.field_name and self.type_str == other.type_str
class _MessageAddLogged(object):
""" ULog add logging data message representation """
def __init__(self, data, header, message_formats):
self.multi_id, = struct.unpack('<B', data[0:1])
self.msg_id, = struct.unpack('<H', data[1:3])
self.message_name = ULog.parse_string(data[3:])
self.field_data = [] # list of _FieldData
self.timestamp_idx = -1
self.max_data_size = 0 # Max size of each data point (including padding fields at end)
self._parse_format(message_formats)
self.timestamp_offset = 0
for field in self.field_data:
if field.field_name == 'timestamp':
break
self.timestamp_offset += ULog._UNPACK_TYPES[field.type_str][1]
self.buffer = bytearray() # accumulate all message data here
# construct types for numpy
dtype_list = []
for field in self.field_data:
numpy_type = ULog._UNPACK_TYPES[field.type_str][2]
self.max_data_size += ULog._UNPACK_TYPES[field.type_str][1]
dtype_list.append((field.field_name, numpy_type))
self.dtype = np.dtype(dtype_list).newbyteorder('<')
def _parse_format(self, message_formats):
self._parse_nested_type('', self.message_name, message_formats)
# remove padding fields at the end
while (len(self.field_data) > 0 and
self.field_data[-1].field_name.startswith('_padding')):
self.field_data.pop()
def _parse_nested_type(self, prefix_str, type_name, message_formats):
# we flatten nested types
message_format = message_formats[type_name]
for (type_name_fmt, array_size, field_name) in message_format.fields:
if type_name_fmt in ULog._UNPACK_TYPES:
if array_size > 0:
for i in range(array_size):
self.field_data.append(ULog._FieldData(
prefix_str+field_name+'['+str(i)+']', type_name_fmt))
else:
self.field_data.append(ULog._FieldData(
prefix_str+field_name, type_name_fmt))
if prefix_str+field_name == 'timestamp':
self.timestamp_idx = len(self.field_data) - 1
else: # nested type
if array_size > 0:
for i in range(array_size):
self._parse_nested_type(prefix_str+field_name+'['+str(i)+'].',
type_name_fmt, message_formats)
else:
self._parse_nested_type(prefix_str+field_name+'.',
type_name_fmt, message_formats)
class _MessageData(object):
def __init__(self):
self.timestamp = 0
def initialize(self, data, header, subscriptions, ulog_object) -> bool:
has_corruption = False
msg_id, = ULog._unpack_ushort(data[:2])
if msg_id in subscriptions:
subscription = subscriptions[msg_id]
min_data_size = subscription.dtype.itemsize
data_size = len(data) - 2
if data_size < min_data_size or data_size > subscription.max_data_size:
# Corrupt data: skip
self.timestamp = 0
has_corruption = True
else:
if data_size > min_data_size:
# Strip extra data (_padding bytes)
data = data[:2+min_data_size]
# accumulate data to a buffer, will be parsed later
subscription.buffer += data[2:]
t_off = subscription.timestamp_offset
# TODO: the timestamp can have another size than uint64
self.timestamp, = ULog._unpack_uint64(data[t_off+2:t_off+10])
else:
if not msg_id in ulog_object._filtered_message_ids:
# this is an error, but make it non-fatal
if not msg_id in ulog_object._missing_message_ids:
ulog_object._missing_message_ids.add(msg_id)
if ulog_object._debug:
print(ulog_object._file_handle.tell())
print('Warning: no subscription found for message id {:}. Continuing,'
' but file is most likely corrupt'.format(msg_id))
has_corruption = True
self.timestamp = 0
return has_corruption
def _add_parameter_default(self, msg_param):
""" add a _MessageParameterDefault object """
default_types = msg_param.default_types
while default_types: # iterate over each bit
def_type = default_types & (~default_types+1)
default_types ^= def_type
def_type -= 1
if def_type not in self._default_parameters:
self._default_parameters[def_type] = {}
self._default_parameters[def_type][msg_param.key] = msg_param.value
def _add_message_info_multiple(self, msg_info):
""" add a message info multiple to self._msg_info_multiple_dict """
if msg_info.key in self._msg_info_multiple_dict:
if msg_info.is_continued:
self._msg_info_multiple_dict[msg_info.key][-1].append(msg_info.value)
else:
self._msg_info_multiple_dict[msg_info.key].append([msg_info.value])
else:
self._msg_info_multiple_dict[msg_info.key] = [[msg_info.value]]
self._msg_info_multiple_dict_types[msg_info.key] = msg_info.type
def _load_file(self, log_file, message_name_filter_list, parse_header_only=False):
""" load and parse an ULog file into memory """
if isinstance(log_file, str):
self._file_handle = open(log_file, "rb") #pylint: disable=consider-using-with
else:
self._file_handle = log_file
# parse the whole file
self._read_file_header()
self._last_timestamp = self._start_timestamp
self._read_file_definitions()
if self._debug:
print("header end offset: {:}".format(self._file_handle.tell()))
if parse_header_only:
self._file_handle.close()
del self._file_handle
return
if self.has_data_appended and len(self._appended_offsets) > 0:
if self._debug:
print('This file has data appended')
for offset in self._appended_offsets:
self._read_file_data(message_name_filter_list, read_until=offset)
self._file_handle.seek(offset)
# read the whole file, or the rest if data appended
self._read_file_data(message_name_filter_list)
self._file_handle.close()
del self._file_handle
def _read_file_header(self):
header_data = self._file_handle.read(16)
if len(header_data) != 16:
raise TypeError("Invalid file format (Header too short)")
if header_data[:7] != self.HEADER_BYTES:
raise TypeError("Invalid file format (Failed to parse header)")
self._file_version, = struct.unpack('B', header_data[7:8])
if self._file_version > 1:
print("Warning: unknown file version. Will attempt to read it anyway")
# read timestamp
self._start_timestamp, = ULog._unpack_uint64(header_data[8:])
def _read_file_definitions(self):
header = self._MessageHeader()
while True:
data = self._file_handle.read(3)
if not data:
break
header.initialize(data)
data = self._file_handle.read(header.msg_size)
try:
if header.msg_type == self.MSG_TYPE_INFO:
msg_info = self._MessageInfo(data, header)
self._msg_info_dict[msg_info.key] = msg_info.value
self._msg_info_dict_types[msg_info.key] = msg_info.type
elif header.msg_type == self.MSG_TYPE_INFO_MULTIPLE:
msg_info = self._MessageInfo(data, header, is_info_multiple=True)
self._add_message_info_multiple(msg_info)
elif header.msg_type == self.MSG_TYPE_FORMAT:
msg_format = self.MessageFormat(data, header)
self._message_formats[msg_format.name] = msg_format
elif header.msg_type == self.MSG_TYPE_PARAMETER:
msg_info = self._MessageInfo(data, header)
self._initial_parameters[msg_info.key] = msg_info.value
elif header.msg_type == self.MSG_TYPE_PARAMETER_DEFAULT:
msg_param = self._MessageParameterDefault(data, header)
self._add_parameter_default(msg_param)
elif header.msg_type in (self.MSG_TYPE_ADD_LOGGED_MSG,
self.MSG_TYPE_LOGGING, self.MSG_TYPE_LOGGING_TAGGED):
self._file_handle.seek(-(3+header.msg_size), 1)
break # end of section
elif header.msg_type == self.MSG_TYPE_FLAG_BITS:
# make sure this is the first message in the log
if self._file_handle.tell() != 16 + 3 + header.msg_size:
print('Error: FLAGS_BITS message must be first message. Offset:',
self._file_handle.tell())
msg_flag_bits = self._MessageFlagBits(data, header)
self._compat_flags = msg_flag_bits.compat_flags
self._incompat_flags = msg_flag_bits.incompat_flags
self._appended_offsets = msg_flag_bits.appended_offsets
if self._debug:
print('compat flags: ', self._compat_flags)
print('incompat flags:', self._incompat_flags)
print('appended offsets:', self._appended_offsets)
# check if there are bits set that we don't know
unknown_incompat_flag_msg = \
"Unknown incompatible flag set: cannot parse the log"
if self._incompat_flags[0] & ~1:
raise ValueError(unknown_incompat_flag_msg)
for i in range(1, 8):
if self._incompat_flags[i]:
raise NotImplementedError(unknown_incompat_flag_msg)
else:
if self._debug:
print('read_file_definitions: unknown message type: %i (%s)' %
(header.msg_type, chr(header.msg_type)))
file_position = self._file_handle.tell()
print('file position: %i (0x%x) msg size: %i' % (
file_position, file_position, header.msg_size))
if self._check_packet_corruption(header):
# seek back to advance only by a single byte instead of
# skipping the message
self._file_handle.seek(-2-header.msg_size, 1)
except IndexError:
if not self._file_corrupt:
print("File corruption detected while reading file definitions!")
self._file_corrupt = True
def _find_sync(self, last_n_bytes=-1):
"""
read the file from a given location until the end of sync_byte sequence is found
or an end condition is met(reached EOF or searched all last_n_bytes).
:param last_n_bytes: optional arg to search only last_n_bytes for sync_bytes.
when provided, _find_sync searches for sync_byte sequence in the last_n_bytes
from current location, else, from current location till end of file.
return true if successful, else return false and seek back to initial position and
set _has_sync to false if searched till end of file
"""
sync_seq_found = False
initial_file_position = self._file_handle.tell()
current_file_position = initial_file_position
search_chunk_size = 512 # number of bytes that are searched at once
if last_n_bytes != -1:
current_file_position = self._file_handle.seek(-last_n_bytes, 1)
search_chunk_size = last_n_bytes
chunk = self._file_handle.read(search_chunk_size)
while len(chunk) >= len(ULog.SYNC_BYTES):
current_file_position += len(chunk)
chunk_index = chunk.find(ULog.SYNC_BYTES)
if chunk_index >= 0:
if self._debug:
print("Found sync at %i" % (current_file_position - len(chunk) + chunk_index))
# seek to end of sync sequence and break
current_file_position = self._file_handle.seek(current_file_position - len(chunk)\
+ chunk_index + len(ULog.SYNC_BYTES), 0)
sync_seq_found = True
break
if last_n_bytes != -1:
# we read the whole last_n_bytes and did not find sync
break
# seek back 7 bytes to handle boundary condition and read next chunk
current_file_position = self._file_handle.seek(-(len(ULog.SYNC_BYTES)-1), 1)
chunk = self._file_handle.read(search_chunk_size)
if not sync_seq_found:
current_file_position = self._file_handle.seek(initial_file_position, 0)
if last_n_bytes == -1:
self._has_sync = False
if self._debug:
print("Failed to find sync in file from %i" % initial_file_position)
else:
if self._debug:
print("Failed to find sync in (%i, %i)" %\
(initial_file_position - last_n_bytes, initial_file_position))
else:
# declare file corrupt if we skipped bytes to sync sequence
self._file_corrupt = True
return sync_seq_found
def _read_file_data(self, message_name_filter_list, read_until=None):
"""
read the file data section
:param read_until: an optional file offset: if set, parse only up to
this offset (smaller than)
"""
if read_until is None:
read_until = 1 << 50 # make it larger than any possible log file
try:
# pre-init reusable objects
header = self._MessageHeader()
msg_data = self._MessageData()
curr_file_pos = self._file_handle.tell()
while True:
data = self._file_handle.read(3)
curr_file_pos += len(data)
header.initialize(data)
data = self._file_handle.read(header.msg_size)
curr_file_pos += len(data)
if len(data) < header.msg_size:
break # less data than expected. File is most likely cut
if curr_file_pos > read_until:
if self._debug:
print('read until offset=%i done, current pos=%i' %
(read_until, curr_file_pos))
break
try:
if header.msg_type == self.MSG_TYPE_INFO:
msg_info = self._MessageInfo(data, header)
self._msg_info_dict[msg_info.key] = msg_info.value
self._msg_info_dict_types[msg_info.key] = msg_info.type
elif header.msg_type == self.MSG_TYPE_INFO_MULTIPLE:
msg_info = self._MessageInfo(data, header, is_info_multiple=True)
self._add_message_info_multiple(msg_info)
elif header.msg_type == self.MSG_TYPE_PARAMETER:
msg_info = self._MessageInfo(data, header)
self._changed_parameters.append((self._last_timestamp,
msg_info.key, msg_info.value))
elif header.msg_type == self.MSG_TYPE_PARAMETER_DEFAULT:
msg_param = self._MessageParameterDefault(data, header)
self._add_parameter_default(msg_param)
elif header.msg_type == self.MSG_TYPE_ADD_LOGGED_MSG:
msg_add_logged = self._MessageAddLogged(data, header,
self._message_formats)
if (message_name_filter_list is None or
msg_add_logged.message_name in message_name_filter_list):
self._subscriptions[msg_add_logged.msg_id] = msg_add_logged
else:
self._filtered_message_ids.add(msg_add_logged.msg_id)
elif header.msg_type == self.MSG_TYPE_LOGGING:
msg_logging = self.MessageLogging(data, header)
self._logged_messages.append(msg_logging)
elif header.msg_type == self.MSG_TYPE_LOGGING_TAGGED:
msg_log_tagged = self.MessageLoggingTagged(data, header)
if msg_log_tagged.tag in self._logged_messages_tagged:
self._logged_messages_tagged[msg_log_tagged.tag].append(msg_log_tagged)
else:
self._logged_messages_tagged[msg_log_tagged.tag] = [msg_log_tagged]
elif header.msg_type == self.MSG_TYPE_DATA:
has_corruption = msg_data.initialize(data, header, self._subscriptions,
self)
if has_corruption:
self._file_corrupt = True
elif msg_data.timestamp > self._last_timestamp:
self._last_timestamp = msg_data.timestamp
elif header.msg_type == self.MSG_TYPE_DROPOUT:
msg_dropout = self.MessageDropout(data, header,
self._last_timestamp)
self._dropouts.append(msg_dropout)
elif header.msg_type == self.MSG_TYPE_SYNC:
self._sync_seq_cnt = self._sync_seq_cnt + 1
else:
if self._debug:
print('_read_file_data: unknown message type: %i (%s)' %
(header.msg_type, chr(header.msg_type)))
print('file position: %i msg size: %i' % (
curr_file_pos, header.msg_size))
if self._check_packet_corruption(header):
# seek back to advance only by a single byte instead of
# skipping the message
curr_file_pos = self._file_handle.seek(-2-header.msg_size, 1)
# try recovery with sync sequence in case of unknown msg_type
if self._has_sync:
self._find_sync()
else:
# seek back msg_size to look for sync sequence in payload
if self._has_sync:
self._find_sync(header.msg_size)
except IndexError:
if not self._file_corrupt:
print("File corruption detected while reading file data!")
self._file_corrupt = True
except struct.error:
pass #we read past the end of the file
# convert into final representation
while self._subscriptions:
_, value = self._subscriptions.popitem()
if len(value.buffer) > 0: # only add if we have data
data_item = ULog.Data(value)
self._data_list.append(data_item)
# Sorting is necessary to be able to compare two ULogs correctly
self.data_list.sort(key=lambda ds: (ds.name, ds.multi_id))
def _check_packet_corruption(self, header):
"""
check for data corruption based on an unknown message type in the header
set _file_corrupt flag to true if a corrupt packet is found
We need to handle 2 cases:
- corrupt file (we do our best to read the rest of the file)
- new ULog message type got added (we just want to skip the message)
return true if packet associated with header is corrupt, else return false
"""
data_corrupt = False
if header.msg_type == 0 or header.msg_size == 0 or header.msg_size > 10000:
if not self._file_corrupt and self._debug:
print('File corruption detected')
data_corrupt = True
self._file_corrupt = True
return data_corrupt
def get_version_info(self, key_name='ver_sw_release'):
"""
get the (major, minor, patch, type) version information as tuple.
Returns None if not found
definition of type is:
>= 0: development
>= 64: alpha version
>= 128: beta version
>= 192: RC version
== 255: release version
"""
if key_name in self._msg_info_dict:
val = self._msg_info_dict[key_name]
return ((val >> 24) & 0xff, (val >> 16) & 0xff, (val >> 8) & 0xff, val & 0xff)
return None
def get_version_info_str(self, key_name='ver_sw_release'):
"""
get version information in the form 'v1.2.3 (RC)', or None if version
tag either not found or it's a development version
"""
version = self.get_version_info(key_name)
if not version is None and version[3] >= 64:
type_str = ''
if version[3] < 128: type_str = ' (alpha)'
elif version[3] < 192: type_str = ' (beta)'
elif version[3] < 255: type_str = ' (RC)'
return 'v{}.{}.{}{}'.format(version[0], version[1], version[2], type_str)
return None
================================================
FILE: pyulog/db.py
================================================
'''
Module containing the DatabaseULog class.
'''
import sqlite3
import hashlib
import contextlib
import numpy as np
from pyulog import ULog
# pylint: disable=too-many-instance-attributes
class DatabaseULog(ULog):
'''
This class can be used in place of a ULog, except that it reads from and
writes to a sqlite3 database instead of a file.
The first time you see a ulog file, instantiate a DatabaseULog directly
from a ulog file, and then call save() to write it to the database. Later
it can be accessed by providing the primary_key, upon which this class
loads all needed fields from the database. If you don't have the
primary_key value available, but you have the .ulg file and know it is in
the database, you can retrieve the hash with DatabaseULog.calc_sha256sum
and DatabaseULog.primary_key_from_sha256sum.
This class is currently designed to be write-once only, so you cannot
update existing database entries. To do so, first call delete() and then
save() again.
A weakness of the implementation is that there are some silently failing
states if you don't call save() immediately after instantiating from a ULog
object. The requirement of explicit save() is to prevent unexpected, sudden
side effects, which is considered worse than the current solution.
Example usage:
> from pyulog.db import DatabaseULog
>
> db_handle = DatabaseULog.get_db_handle('dbulog.sqlite3')
> dbulog = DatabaseULog(db_handle, log_file='example.ulg') # Slow
> dbulog.save()
> pk = dbulog.primary_key()
> # [...]
> dbulog = DatabaseULog(db_handle, primary_key=pk) # Fast
SCHEMA_VERSION specifies which version of the database schema (as read from
"PRAGMA user_version") this file is supposed to match. This is done to
ensure consistency between the database operations and the state of the
database. If SCHEMA_VERSION is higher than what is found in the database,
then it means that the datbaase is has not been updated, and the
contsructor will throw an exception. See the documentation of
"ulog_migratedb" for more information.
'''
SCHEMA_VERSION = 5
@staticmethod
def get_db_handle(db_path):
'''
Generate a database handle that can be used in subsequent database access.
'''
def db_handle():
con = sqlite3.connect(
db_path,
detect_types=sqlite3.PARSE_DECLTYPES|sqlite3.PARSE_COLNAMES
)
# The next line is necessary for sqlite3 to actually respect
# FOREIGN KEY constraints and ON DELETE CASCADE.
con.execute('PRAGMA foreign_keys=on')
return con
return db_handle
@staticmethod
def exists_in_db(db_handle, primary_key):
'''
Check whether an ULog row with Id=primary_key exists in the database
accessed with db_handle.
'''
with db_handle() as con:
cur = con.cursor()
cur.execute('''
SELECT COUNT(*)
FROM ULog
WHERE Id = ?
''', (primary_key,))
count, = cur.fetchone()
cur.close()
return count == 1
@staticmethod
def primary_key_from_sha256sum(db_handle, sha256sum):
'''
Search the database for a row with the given SHA256 digest and returns
the corresponding primary key. Returns None if not found.
'''
primary_key = None
with db_handle() as con:
cur = con.cursor()
cur.execute('''
SELECT Id
FROM ULog
WHERE SHA256Sum = ?
''', (sha256sum,))
row = cur.fetchone()
if row:
primary_key = row[0]
cur.close()
return primary_key
@staticmethod
def calc_sha256sum(log_file):
'''
Compute the SHA256 digest of a file, specified as a file or a valid file path.
'''
if log_file is None:
return None
if isinstance(log_file, str):
file_context = open(log_file, 'rb') # pylint: disable=consider-using-with
elif log_file.closed:
file_context = open(log_file.name, 'rb')
else:
file_context = contextlib.nullcontext(log_file)
file_hash = hashlib.sha256()
with file_context as open_file:
while True:
block = open_file.read(4096)
file_hash.update(block)
if block == b'':
break
return file_hash.hexdigest()
def __init__(self, db_handle, primary_key=None, log_file=None, lazy=True, **kwargs):
'''
You always need the database handle (which can be generated with
DatabaseULog.get_db_handle), but there are two options for the
parameters "primary_key" and "log_file":
- For storing a new log in the database, supply the corresponding
log_file parameter, but leave the primary_key field at None.
- For reading an existing log from the database, supply the desired
primary_key parameter, but leave the log_file parameter at None. If
you don't know the primary_key, you can try finding it with
DatabaseULog.primary_key_from_sha256sum.
You cannot supply both of these parameters.
Furthermore, the "lazy" parameter specifies whether all data fields
should be read on-demand when get_dataset is called, or if they should
all be read and populated into data_list when the object is
instantiated.
The constructor also checks that SCHEMA_VERSION matches the "PRAGMA
user_version" found in the database, see the documentation of "PRAGMA
user_version" for more information.
'''
with db_handle() as con:
cur = con.cursor()
cur.execute('PRAGMA user_version')
(db_version,) = cur.fetchone()
if db_version < DatabaseULog.SCHEMA_VERSION:
raise ValueError('Database version %d < schema version %d, migration needed.' % (
db_version,
DatabaseULog.SCHEMA_VERSION
))
if log_file is not None and primary_key is not None:
raise ValueError('You cannot provide both primary_key and log_file.')
if log_file is None and primary_key is None:
raise ValueError('You must provide either a primary_key or log_file.')
self._pk = primary_key
self._db = db_handle
self._lazy_loaded = lazy
if log_file is not None:
self._sha256sum = DatabaseULog.calc_sha256sum(log_file)
super().__init__(log_file, **kwargs)
if primary_key is not None:
self.load(lazy=lazy)
def __eq__(self, other):
"""
If the other object is a normal ULog, then we just want to compare ULog
data, not DatabaseULog specific fields, because we want to compare
theULog file contents.
"""
if type(other) is ULog: # pylint: disable=unidiomatic-typecheck
return other.__eq__(self)
return super().__eq__(other)
def write_ulog(self, log_file):
if self._lazy_loaded:
raise ValueError('Cannot write after lazy load because it has no datasets.')
super().write_ulog(log_file)
@property
def primary_key(self):
'''The primary key of the ulog, pointing to the correct "ULog" row in the database.'''
return self._pk
@property
def sha256sum(self):
'''The computed SHA256 digest of the file, stored for later use.'''
return self._sha256sum
# pylint: disable=too-many-locals,too-many-branches
def load(self, lazy=True):
'''
Load all necessary data from the database, possibly except for the data series
themselves, which can cost unnecessary resources.
If lazy=True, then the data series will be left unread, deferred until
get_dataset is called. If however lazy=False, then all data series will
be read at once.
Even if the log was originally saved with append_json=True, this
function will always use the faster BLOB column for retrieval.
'''
if not DatabaseULog.exists_in_db(self._db, self._pk):
raise KeyError(f'No ULog in database with Id={self._pk}')
with self._db() as con:
cur = con.cursor()
# ULog metadata
cur.execute('''
SELECT FileVersion,
StartTimestamp,
LastTimestamp,
CompatFlags,
IncompatFlags,
SyncCount,
HasSync,
SHA256Sum
FROM ULog
WHERE Id = ?
''', (self._pk,))
ulog_result = cur.fetchone()
self._file_version = ulog_result[0]
self._start_timestamp = ulog_result[1]
self._last_timestamp = ulog_result[2]
self._compat_flags = [ord(c) for c in ulog_result[3]]
self._incompat_flags = [ord(c) for c in ulog_result[4]]
self._sync_seq_cnt = ulog_result[5]
self._has_sync = ulog_result[6]
self._sha256sum = ulog_result[7]
# appended_offsets
cur.execute('''
SELECT Offset
FROM ULogAppendedOffsets
WHERE ULogId = ?
ORDER BY SeriesIndex
''', (self._pk,))
offsets_result = cur.fetchall()
for offset, in offsets_result:
self._appended_offsets.append(offset)
# data_list
self._data_list = []
cur.execute('''
SELECT DatasetName, MultiId
FROM ULogDataset
WHERE ULogId = ?
ORDER BY DatasetName, MultiId
''', (self._pk,))
dataset_results = cur.fetchall()
for dataset_name, multi_id in dataset_results:
dataset = self.get_dataset(dataset_name,
multi_instance=multi_id,
lazy=lazy,
db_cursor=cur,
caching=False)
self._data_list.append(dataset)
# dropouts
cur.execute('''
SELECT Timestamp, Duration
FROM ULogMessageDropout
WHERE ULogId = ?
''', (self._pk,))
for timestamp, duration in cur.fetchall():
self._dropouts.append(
DatabaseULog.DatabaseMessageDropout(
timestamp=timestamp,
duration=duration,
)
)
# logged_messages
cur.execute('''
SELECT LogLevel, Timestamp, Message
FROM ULogMessageLogging
WHERE ULogId = ?
''', (self._pk,))
for log_level, timestamp, message in cur.fetchall():
self._logged_messages.append(
DatabaseULog.DatabaseMessageLogging(
log_level=log_level,
timestamp=timestamp,
message=message,
)
)
# logged_messages_tagged
cur.execute('''
SELECT LogLevel, Tag, Timestamp, Message
FROM ULogMessageLoggingTagged
WHERE ULogId = ?
''', (self._pk,))
for log_level, tag, timestamp, message in cur.fetchall():
if tag not in self._logged_messages_tagged:
self._logged_messages_tagged[tag] = []
self._logged_messages_tagged[tag].append(
DatabaseULog.DatabaseMessageLoggingTagged(
log_level=log_level,
tag=tag,
timestamp=timestamp,
message=message,
)
)
# message_formats
cur.execute('''
SELECT
msg.Name,
field.FieldType,
field.ArraySize,
field.Name
FROM ULogMessageFormat msg JOIN ULogMessageFormatField field
ON field.MessageId = msg.Id
WHERE ULogId = ?
''', (self._pk,))
for row in cur.fetchall():
msg_name = row[0]
field_data = row[1:]
if msg_name in self._message_formats:
self._message_formats[msg_name].fields.append(field_data)
else:
self._message_formats[msg_name] = DatabaseULog.DatabaseMessageFormat(
name=msg_name,
fields=[field_data]
)
# msg_info_dict
cur.execute('''
SELECT Key, Typename, Value
FROM ULogMessageInfo
WHERE ULogId = ?
''', (self._pk,))
for key, typename, value in cur.fetchall():
self._msg_info_dict[key] = value
self._msg_info_dict_types[key] = typename
# msg_info_multiple_dict
cur.execute('''
SELECT Id, Key, Typename
FROM ULogMessageInfoMultiple
WHERE ULogId = ?
''', (self._pk,))
for message_id, key, typename in cur.fetchall():
self._msg_info_multiple_dict[key] = []
self._msg_info_multiple_dict_types[key] = typename
cur.execute('''
SELECT Id
FROM ULogMessageInfoMultipleList
WHERE MessageId = ?
ORDER BY SeriesIndex
''', (message_id,))
for (list_id,) in cur.fetchall():
cur.execute('''
SELECT Value
FROM ULogMessageInfoMultipleListElement
WHERE ListId = ?
ORDER BY SeriesIndex
''', (list_id,))
self._msg_info_multiple_dict[key].append([value for (value,) in cur.fetchall()])
# initial_parameters
cur.execute('''
SELECT Key, Value
FROM ULogInitialParameter
WHERE ULogId = ?
''', (self._pk,))
for key, value in cur.fetchall():
self._initial_parameters[key] = value
# _default_parameters
cur.execute('''
SELECT DefaultType, Key, Value
FROM ULogDefaultParameter
WHERE ULogId = ?
''', (self._pk,))
for default_type, key, value in cur.fetchall():
if default_type not in self._default_parameters:
self._default_parameters[default_type] = {}
self._default_parameters[default_type][key] = value
# changed_parameters
cur.execute('''
SELECT Timestamp, Key, Value
FROM ULogChangedParameter
WHERE ULogId = ?
''', (self._pk,))
for timestamp, key, value in cur.fetchall():
self._changed_parameters.append((timestamp, key, value))
cur.close()
self._lazy_loaded = lazy
def get_dataset(self, name, multi_instance=0, lazy=False, db_cursor=None, caching=True):
'''
Access a specific dataset and its data series from the database.
The "lazy" argument specifies whether only dataset metadata should be
retrieved from the database, or if the data series arrays should be
retrieved too.
The optional "db_cursor" argument can be used to avoid re-opening the
database connection each time get_dataset is called.
Since we don't expect the data to change often, we will normally use
self._data_list as a cache, and check there before reading from the
database. However, if caching=False, then we will always read anew
from the database.
'''
if db_cursor is None:
db_context = self._db()
cur = db_context.cursor()
else:
db_context = contextlib.nullcontext()
cur = db_cursor
existing_dataset = None
for dataset in self._data_list:
if dataset.name == name and dataset.multi_id == multi_instance:
existing_dataset = dataset
break
if (caching
and existing_dataset is not None
and (lazy or existing_dataset.data)):
return existing_dataset
with db_context:
cur.execute('''
SELECT Id, TimestampIndex, MessageId
FROM ULogDataset
WHERE DatasetName = ? AND MultiId = ? AND ULogId = ?
''', (name, multi_instance, self._pk))
dataset_result = cur.fetchone()
if dataset_result is None:
raise KeyError(f'Dataset with name {name} and multi id {multi_instance} not found.')
dataset_id, timestamp_idx, msg_id = dataset_result
fields = []
data = {}
if not lazy:
cur.execute('''
SELECT TopicName, DataType, ValueArray
FROM ULogField
WHERE DatasetId = ?
''', (dataset_id,))
field_results = cur.fetchall()
for field_name, data_type, value_bytes in field_results:
fields.append(DatabaseULog._FieldData(field_name=field_name,type_str=data_type))
dtype = DatabaseULog._UNPACK_TYPES[data_type][2]
data[field_name] = np.frombuffer(value_bytes, dtype=dtype)
# If caching=True but there is no existing dataset we could append a
# new one to self._data_list, but that could be considered a
# non-obvious side effect.
if caching and existing_dataset is not None:
existing_dataset.msg_id = msg_id
existing_dataset.timestamp_idx = timestamp_idx
existing_dataset.field_data = fields
existing_dataset.data = data
dataset = existing_dataset
else:
dataset = DatabaseULog.DatabaseData(
name=name,
multi_id=multi_instance,
msg_id=msg_id,
timestamp_idx=timestamp_idx,
field_data=fields,
data=data,
)
return dataset
def save(self, append_json=False):
'''
Save the DatabaseULog to the database. Throws a KeyError if the primary
key is already in the database.
The datasets are stored in a sqlite BLOB for fast retrieval, but if
append_json=True, then datasets are additionally stored in a JSON
field. This allows them to be directly queried using the sqlite
function json_each, but increases the writing time and database size.
'''
if self._pk is not None:
raise KeyError('Cannot save logs that are already in the database')
pk_from_hash = DatabaseULog.primary_key_from_sha256sum(self._db, self._sha256sum)
if pk_from_hash is not None:
self._pk = pk_from_hash
raise KeyError(f'Hash {self._sha256sum} already in database with Id={pk_from_hash}')
with self._db() as con:
cur = con.cursor()
# ULog metadata
cur.execute('''
INSERT INTO ULog
(FileVersion, StartTimestamp, LastTimestamp, CompatFlags, IncompatFlags, SyncCount, HasSync, SHA256Sum)
VALUES
(?, ?, ?, ?, ?, ?, ?, ?)
''', (
self._file_version,
self._start_timestamp,
self._last_timestamp,
''.join([chr(n) for n in self._compat_flags]),
''.join([chr(n) for n in self._incompat_flags]),
self._sync_seq_cnt,
self._has_sync,
self._sha256sum,
)
)
self._pk = cur.lastrowid
# appended_offsets
cur.executemany('''
INSERT INTO ULogAppendedOffsets
(SeriesIndex, Offset, ULogId)
VALUES
(?, ?, ?)
''', [(
list_index,
offset,
self._pk,
) for list_index, offset in enumerate(self._appended_offsets)])
# data_list
for dataset in self.data_list:
cur.execute('''
INSERT INTO ULogDataSet
(DatasetName, MultiId, MessageId, TimestampIndex, ULogId)
VALUES
(?, ?, ?, ?, ?)
''', (
dataset.name,
dataset.multi_id,
dataset.msg_id,
dataset.timestamp_idx,
self._pk,
)
)
dataset_id = cur.lastrowid
for field in dataset.field_data:
values = dataset.data[field.field_name]
values_bytes = values.tobytes()
if append_json:
# Precision is only good enough up to a few decimals,
# depending on the default float formatter. The
# function np.array2string was tested, but was slower.
# Also note that doing the slow json.dumps is also
# unnecessary since we know that the object to be
# formatted is an array.
timestamp_list = [str(s) for s in dataset.data['timestamp'].tolist()]
values_json = str(
dict(zip(timestamp_list, values.tolist()))
).replace('nan', 'null').replace('inf', 'null').replace("'", '"')
json_placeholder = 'json(?)' # Saves some space
else:
values_json = None
json_placeholder = '?'
cur.execute(f'''
INSERT INTO ULogField
(TopicName, DataType, ValueArray, ValueJson, DatasetId)
VALUES
(?, ?, ?, {json_placeholder}, ?)
''', (
field.field_name,
field.type_str,
values_bytes,
values_json,
dataset_id,
)
)
# dropouts
cur.executemany('''
INSERT INTO ULogMessageDropout
(Timestamp, Duration, ULogId)
VALUES
(?, ?, ?)
''', [(
dropout.timestamp,
dropout.duration,
self._pk,
) for dropout in self._dropouts])
# logged_messages
cur.executemany('''
INSERT INTO ULogMessageLogging
(LogLevel, Timestamp, Message, ULogId)
VALUES
(?, ?, ?, ?)
''', [(
message.log_level,
message.timestamp,
message.message,
self._pk,
) for message in self._logged_messages])
# logged_messages_tagged
for tag, messages in self._logged_messages_tagged.items():
cur.executemany('''
INSERT INTO ULogMessageLoggingTagged
(LogLevel, Timestamp, Tag, Message, ULogId)
VALUES
(?, ?, ?, ?, ?)
''', [(
message.log_level,
message.timestamp,
tag,
message.message,
self._pk,
) for message in messages])
# message_formats
for name, message_format in self._message_formats.items():
cur.execute('''
INSERT INTO ULogMessageFormat
(Name, ULogId)
VALUES
(?, ?)
''', (name, self._pk))
format_id = cur.lastrowid
cur.executemany('''
INSERT INTO ULogMessageFormatField
(FieldType, ArraySize, Name, MessageId)
VALUES
(?, ?, ?, ?)
''', [(*field, format_id) for field in message_format.fields])
# msg_info_dict
cur.executemany('''
INSERT INTO ULogMessageInfo
(Key, Value, Typename, ULogId)
VALUES
(?, ?, ?, ?)
''', [(
key,
value,
self._msg_info_dict_types[key],
self._pk,
) for key, value in self.msg_info_dict.items()])
# msg_info_multiple_dict
for key, lists in self.msg_info_multiple_dict.items():
cur.execute('''
INSERT INTO ULogMessageInfoMultiple
(Key, Typename, ULogId)
VALUES
(?, ?, ?)
''', (key, self._msg_info_multiple_dict_types[key], self._pk))
message_id = cur.lastrowid
for list_index, message_list in enumerate(lists):
cur.execute('''
INSERT INTO ULogMessageInfoMultipleList
(SeriesIndex, MessageId)
VALUES
(?, ?)
''', (list_index, message_id))
list_id = cur.lastrowid
cur.executemany('''
INSERT INTO ULogMessageInfoMultipleListElement
(SeriesIndex, Value, ListId)
VALUES
(?, ?, ?)
''', [(
series_index,
value,
list_id,
) for series_index, value in enumerate(message_list)])
# initial_parameters
cur.executemany('''
INSERT INTO ULogInitialParameter
(Key, Value, ULogId)
VALUES
(?, ?, ?)
''', [(
key,
value,
self._pk,
) for key, value in self.initial_parameters.items()])
# _default_parameters
for default_type, parameters in self._default_parameters.items():
cur.executemany('''
INSERT INTO ULogDefaultParameter
(DefaultType, Key, Value, ULogId)
VALUES
(?, ?, ?, ?)
''', [(
default_type,
key,
value,
self._pk,
) for key, value in parameters.items()])
# changed_parameters
cur.executemany('''
INSERT INTO ULogChangedParameter
(Timestamp, Key, Value, ULogId)
VALUES
(?, ?, ?, ?)
''', [(
timestamp,
key,
value,
self._pk,
) for timestamp, key, value in self.changed_parameters])
cur.close()
def delete(self):
'''
Deletes the ULog row and cascading rows from the database.
'''
if self._pk is None:
raise KeyError('Cannot delete logs that are not in the database')
with self._db() as con:
cur = con.cursor()
cur.execute('''
DELETE FROM ULog
WHERE Id = ?
''', (self._pk,)
)
cur.close()
self._pk = None
class DatabaseData(ULog.Data):
'''
Overrides the ULog.Data class since its constructor only
reads ULog.MessageLogAdded objects, and we want to specify
the fields directly.
'''
# pylint: disable=super-init-not-called,too-many-arguments
def __init__(self, name, multi_id, msg_id, timestamp_idx, field_data, data=None):
self.name = name
self.multi_id = multi_id
self.msg_id = msg_id
self.timestamp_idx = timestamp_idx
self.field_data = field_data
self.data = data
class DatabaseMessageDropout(ULog.MessageDropout):
'''
Overrides the ULog.MessageDropout class since its
constructor is not suitable for out purpose.
'''
# pylint: disable=super-init-not-called
def __init__(self, timestamp, duration):
self.timestamp = timestamp
self.duration = duration
class DatabaseMessageFormat(ULog.MessageFormat):
'''
Overrides the ULog.MessageFormat class since its
constructor is not suitable for out purpose.
'''
# pylint: disable=super-init-not-called
def __init__(self, name, fields):
self.name = name
self.fields = fields
class DatabaseMessageLogging(ULog.MessageLogging):
'''
Overrides the ULog.MessageLogging class since its
constructor is not suitable for out purpose.
'''
# pylint: disable=super-init-not-called
def __init__(self, log_level, timestamp, message):
self.log_level = log_level
self.timestamp = timestamp
self.message = message
class DatabaseMessageLoggingTagged(ULog.MessageLoggingTagged):
'''
Overrides the ULog.MessageLoggingTagged class since its
constructor is not suitable for our purpose.
'''
# pylint: disable=super-init-not-called
def __init__(self, log_level, tag, timestamp, message):
self.log_level = log_level
self.tag = tag
self.timestamp = timestamp
self.message = message
================================================
FILE: pyulog/extract_gps_dump.py
================================================
#! /usr/bin/env python
"""
Extract the raw gps communication from an ULog file.
"""
import argparse
import os
import sys
import numpy as np
from .core import ULog
#pylint: disable=too-many-locals, unused-wildcard-import, wildcard-import
def main():
"""
Command line interface
"""
parser = argparse.ArgumentParser(
description='Extract the raw gps communication from an ULog file')
parser.add_argument('filename', metavar='file.ulg', help='ULog input file')
def is_valid_directory(parser, arg):
"""Check if valid directory"""
if not os.path.isdir(arg):
parser.error('The directory {} does not exist'.format(arg))
# File exists so return the directory
return arg
parser.add_argument('-o', '--output', dest='output', action='store',
help='Output directory (default is CWD)',
metavar='DIR', type=lambda x: is_valid_directory(parser, x))
parser.add_argument('-x', '--ignore', dest='ignore', action='store_true',
help='Ignore string parsing exceptions', default=False)
parser.add_argument('-i', '--instance', dest='required_instance', action='store',
help='GPS instance. Use 0 (default)'
+ 'for main GPS, 1 for secondary GPS reciever.',
default=0)
args = parser.parse_args()
ulog_file_name = args.filename
disable_str_exceptions = args.ignore
required_instance = int(args.required_instance)
msg_filter = ['gps_dump']
ulog = ULog(ulog_file_name, msg_filter, disable_str_exceptions)
data = ulog.data_list
output_file_prefix = os.path.basename(ulog_file_name)
# strip '.ulg'
if output_file_prefix.lower().endswith('.ulg'):
output_file_prefix = output_file_prefix[:-4]
# write to different output path?
if args.output is not None:
output_file_prefix = os.path.join(args.output, output_file_prefix)
to_dev_filename = output_file_prefix + '_' + str(required_instance) + '_to_device.dat'
from_dev_filename = output_file_prefix + '_' + str(required_instance) + '_from_device.dat'
if len(data) == 0:
print("File {0} does not contain gps_dump messages!".format(ulog_file_name))
sys.exit(0)
gps_dump_data = data[0]
# message format check
field_names = [f.field_name for f in gps_dump_data.field_data]
if not 'len' in field_names or not 'data[0]' in field_names:
print('Error: gps_dump message has wrong format')
sys.exit(-1)
if len(ulog.dropouts) > 0:
print("Warning: file contains {0} dropouts".format(len(ulog.dropouts)))
print("Creating files {0} and {1}".format(to_dev_filename, from_dev_filename))
with open(to_dev_filename, 'wb') as to_dev_file:
with open(from_dev_filename, 'wb') as from_dev_file:
msg_lens = gps_dump_data.data['len']
instances = gps_dump_data.data.get('instance', [0]*len(msg_lens))
for i in range(len(gps_dump_data.data['timestamp'])):
instance = instances[i]
msg_len = msg_lens[i]
if instance == required_instance:
if msg_len & (1<<7):
msg_len = msg_len & ~(np.uint8(1) << 7)
file_handle = to_dev_file
else:
file_handle = from_dev_file
for k in range(msg_len):
file_handle.write(gps_dump_data.data['data['+str(k)+']'][i])
================================================
FILE: pyulog/extract_message.py
================================================
"""
Extract values from a ULog file message to use in scripting
"""
from typing import List
import numpy as np
from .core import ULog
def extract_message(ulog_file_name: str, message: str,
time_s: "int | None" = None, time_e: "int | None" = None,
disable_str_exceptions: bool = False) -> List[dict]:
"""
Extract values from a ULog file
:param ulog_file_name: (str) The ULog filename to open and read
:param message: (str) A ULog message to return values from
:param time_s: (int) Offset time for conversion in seconds
:param time_e: (int) Limit until time for conversion in seconds
:return: (List[dict]) A list of each record from the ULog as key-value pairs
"""
if not isinstance(message, str):
raise AttributeError("Must provide a message to pull from ULog file")
ulog = ULog(ulog_file_name, message, disable_str_exceptions)
try:
data = ulog.get_dataset(message)
except Exception as exc:
raise AttributeError("Provided message is not in the ULog file") from exc
values = []
# use same field order as in the log, except for the timestamp
data_keys = [f.field_name for f in data.field_data]
data_keys.remove('timestamp')
data_keys.insert(0, 'timestamp') # we want timestamp at first position
#get the index for row where timestamp exceeds or equals the required value
time_s_i = np.where(data.data['timestamp'] >= time_s * 1e6)[0][0] \
if time_s else 0
#get the index for row upto the timestamp of the required value
time_e_i = np.where(data.data['timestamp'] >= time_e * 1e6)[0][0] \
if time_e else len(data.data['timestamp'])
# write the data
for i in range(time_s_i, time_e_i):
row = {}
for key in data_keys:
row[key] = data.data[key][i]
values.append(row)
return values
================================================
FILE: pyulog/info.py
================================================
#! /usr/bin/env python
"""
Display information from an ULog file
"""
import argparse
from .core import ULog
#pylint: disable=too-many-locals, unused-wildcard-import, wildcard-import
#pylint: disable=invalid-name
def show_info(ulog, verbose):
"""Show general information from an ULog"""
if ulog.file_corruption:
print("Warning: file has data corruption(s)")
m1, s1 = divmod(int(ulog.start_timestamp/1e6), 60)
h1, m1 = divmod(m1, 60)
m2, s2 = divmod(int((ulog.last_timestamp - ulog.start_timestamp)/1e6), 60)
h2, m2 = divmod(m2, 60)
print("Logging start time: {:d}:{:02d}:{:02d}, duration: {:d}:{:02d}:{:02d}".format(
h1, m1, s1, h2, m2, s2))
dropout_durations = [dropout.duration for dropout in ulog.dropouts]
if len(dropout_durations) == 0:
print("No Dropouts")
else:
print("Dropouts: count: {:}, total duration: {:.1f} s, max: {:} ms, mean: {:} ms"
.format(len(dropout_durations), sum(dropout_durations)/1000.,
max(dropout_durations),
int(sum(dropout_durations)/len(dropout_durations))))
version = ulog.get_version_info_str()
if not version is None:
print('SW Version: {}'.format(version))
print("Info Messages:")
for k in sorted(ulog.msg_info_dict):
if not k.startswith('perf_') or verbose:
print(" {0}: {1}".format(k, ulog.msg_info_dict[k]))
if len(ulog.msg_info_multiple_dict) > 0:
if verbose:
print("Info Multiple Messages:")
for k in sorted(ulog.msg_info_multiple_dict):
print(" {0}: {1}".format(k, ulog.msg_info_multiple_dict[k]))
else:
print("Info Multiple Messages: {}".format(
", ".join(["[{}: {}]".format(k, len(ulog.msg_info_multiple_dict[k])) for k in
sorted(ulog.msg_info_multiple_dict)])))
print("")
print("{:<41} {:7}, {:10}".format("Name (multi id, message size in bytes)",
"number of data points", "total bytes"))
data_list_sorted = sorted(ulog.data_list, key=lambda d: d.name + str(d.multi_id))
for d in data_list_sorted:
message_size = sum(ULog.get_field_size(f.type_str) for f in d.field_data)
num_data_points = len(d.data['timestamp'])
name_id = "{:} ({:}, {:})".format(d.name, d.multi_id, message_size)
print(" {:<40} {:7d} {:10d}".format(name_id, num_data_points,
message_size * num_data_points))
def main():
"""Commande line interface"""
parser = argparse.ArgumentParser(description='Display information from an ULog file')
parser.add_argument('filename', metavar='file.ulg', help='ULog input file')
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
help='Verbose output', default=False)
parser.add_argument('-m', '--message', dest='message',
help='Show a specific Info Multiple Message')
parser.add_argument('-n', '--newline', dest='newline', action='store_true',
help='Add newline separators (only with --message)', default=False)
parser.add_argument('-i', '--ignore', dest='ignore', action='store_true',
help='Ignore string parsing exceptions', default=False)
args = parser.parse_args()
ulog_file_name = args.filename
disable_str_exceptions = args.ignore
ulog = ULog(ulog_file_name, None, disable_str_exceptions)
message = args.message
if message:
separator = ""
if args.newline: separator = "\n"
if len(ulog.msg_info_multiple_dict) > 0 and message in ulog.msg_info_multiple_dict:
message_info_multiple = ulog.msg_info_multiple_dict[message]
for i, m in enumerate(message_info_multiple):
if len(m) > 0 and isinstance(m[0], (bytes, bytearray)):
print("# {} {} (len: {:}):".format(message, i, sum(len(item) for item in m)))
print(separator.join(' '.join('{:02x}'.format(x) for x in item) for item in m))
else:
print("# {} {}:".format(message, i))
print(separator.join(m))
else:
print("message {} not found".format(message))
else:
show_info(ulog, args.verbose)
================================================
FILE: pyulog/messages.py
================================================
#! /usr/bin/env python
"""
Display logged messages from an ULog file
"""
import argparse
from .core import ULog
from .px4_events import PX4Events
#pylint: disable=invalid-name
def main():
"""Commande line interface"""
parser = argparse.ArgumentParser(description='Display logged messages from an ULog file')
parser.add_argument('filename', metavar='file.ulg', help='ULog input file')
parser.add_argument('-i', '--ignore', dest='ignore', action='store_true',
help='Ignore string parsing exceptions', default=False)
args = parser.parse_args()
ulog_file_name = args.filename
disable_str_exceptions = args.ignore
msg_filter = ['event']
ulog = ULog(ulog_file_name, msg_filter, disable_str_exceptions)
logged_messages = [(m.timestamp, m.log_level_str(), m.message) for m in ulog.logged_messages]
# If this is a PX4 log, try to get the events too
if ulog.msg_info_dict.get('sys_name', '') == 'PX4':
px4_events = PX4Events()
events = px4_events.get_logged_events(ulog)
for t, log_level, message in logged_messages:
# backwards compatibility: a string message with appended tab is output
# in addition to an event with the same message so we can ignore those
if message[-1] == '\t':
continue
events.append((t, log_level, message))
logged_messages = sorted(events, key=lambda m: m[0])
for t, log_level, message in logged_messages:
m1, s1 = divmod(int(t/1e6), 60)
h1, m1 = divmod(m1, 60)
print("{:d}:{:02d}:{:02d} {:}: {:}".format(h1, m1, s1, log_level, message))
================================================
FILE: pyulog/migrate_db.py
================================================
'''
Tool for handling changes in the database schema. This is necessary for
avoiding breaking backwards compatibility whenver bugs are discovered in the
database model, or if the ULog format changes.
There are some options available, such as "alembic" or "migrations', but these
seem like overkill for us. For instance, we don't really need to migrate both up and
down, just up.
'''
import os
import argparse
from pyulog.db import DatabaseULog
def main():
'''
Entry point for the console script.
'''
parser = argparse.ArgumentParser(description='Setup the database for DatabaseULog')
parser.add_argument('-d', '--database', dest='db_path', action='store',
help='Path to the database file',
default='pyulog.sqlite3')
# The noop flag actually has a side effect if it is called on an uncreated
# database, since the "PRAGMA user_version" command implicitly creates the
# database. The created database will have user_version = 0, which will
# later confuse the migration tool. however, this edge case will mostly be
# relevant for advanced users, and can be handled with the -f flag.
parser.add_argument('-n', '--noop', dest='noop', action='store_true',
help='Only print results, do not execute migration scripts.',
default=False)
parser.add_argument('-s', '--sql', dest='sql_dir', action='store',
help='Directory with migration SQL files',
default=None)
parser.add_argument('-f', '--force', dest='force', action='store_true',
help=('Run the migration script even if the database is not created'
'with this script.'),
default=False)
args = parser.parse_args()
migrate_db(args.db_path, sql_dir=args.sql_dir, noop=args.noop, force=args.force)
def _read_db_schema_version(db_path, force):
'''
Read and validate the schema version defined by the "PRAGMA user_version"
field in the database. If the database file exists and schema version is 0,
then this means that the database was not created with the migration tool.
This means that the database is in a state unknown to the migration tool,
and hence a migration could cause schema corruption. The default behavior
in this case is to reject the migration, but it can be overriden with
force=True.
'''
db_handle = DatabaseULog.get_db_handle(db_path)
if not os.path.isfile(db_path):
print(f'Database file {db_path} not found, creating it from scratch.')
return 0
print(f'Found database file {db_path}.')
with db_handle() as con:
cur = con.cursor()
cur.execute('PRAGMA user_version')
(db_schema_version,) = cur.fetchone()
cur.close()
if db_schema_version is None:
raise ValueError(f'Could not fetch database schema version for {db_path}.')
if db_schema_version == 0 and not force:
raise FileExistsError('Database has user_version = 0, rejecting migration.'
'Use the "force" flag to migrate anyway.')
if not isinstance(db_schema_version, int) or db_schema_version < 0:
raise ValueError(f'Invalid database schema version {db_schema_version}.')
return db_schema_version
def _read_migration_file(migration_id, sql_dir):
'''
Read the migration file with id "migration_id" in directory "sql_dir", and
check that it handles transactions strictly.
'''
migration_filename_format = os.path.join(sql_dir, 'pyulog.{migration_id}.sql')
migration_filename = migration_filename_format.format(migration_id=migration_id)
if not os.path.exists(migration_filename):
raise FileNotFoundError(f'Migration file {migration_filename} does not exist. '
f'Stopped after migration {migration_id}.')
with open(migration_filename, 'r', encoding='utf8') as migration_file:
migration_lines = migration_file.read()
if not migration_lines.strip().startswith('BEGIN;'):
raise ValueError(f'Migration file {migration_filename} must start with "BEGIN;"')
if not migration_lines.strip().endswith('COMMIT;'):
raise ValueError(f'Migration file {migration_filename} must end with "COMMIT;"')
migration_lines += f'\nPRAGMA user_version = {migration_id};'
return migration_filename, migration_lines
def migrate_db(db_path, sql_dir=None, noop=False, force=False):
'''
Apply database migrations that have not yet been applied.
Compares "PRAGMA user_version" from the sqlite3 database at "db_path" with
the SCHEMA_VERSION in the DatabaseULog class. If the former is larger than
the latter, then migration scripts will be read and executed from files in
"sql_dir", and the user_version will be incremented, until the database is
up to date.
'''
if sql_dir is None:
module_dir = os.path.dirname(os.path.realpath(os.path.abspath(__file__)))
sql_dir = os.path.join(module_dir, 'sql')
if not os.path.isdir(sql_dir):
raise NotADirectoryError(f'{sql_dir} is not a directory.')
print(f'Using migration files in {sql_dir}.')
db_schema_version = _read_db_schema_version(db_path, force)
class_schema_version = DatabaseULog.SCHEMA_VERSION
print('Current schema version: {} (database) and {} (code).'.format(
db_schema_version,
class_schema_version,
))
db_handle = DatabaseULog.get_db_handle(db_path)
with db_handle() as con:
cur = con.cursor()
for migration_id in range(db_schema_version+1,
DatabaseULog.SCHEMA_VERSION+1):
migration_filename, migration_lines = _read_migration_file(migration_id, sql_dir)
print(f'Executing {migration_filename}.')
if noop:
print(migration_lines)
else:
cur.executescript(migration_lines)
cur.close()
print('Migration done.')
return db_path
if __name__ == '__main__':
raise SystemExit(main())
================================================
FILE: pyulog/params.py
================================================
#! /usr/bin/env python
"""
Extract parameters from an ULog file
"""
import argparse
import sys
from .core import ULog
#pylint: disable=unused-variable, too-many-branches
def get_defaults(ulog, default):
""" get default params from ulog """
assert ulog.has_default_parameters, "Log does not contain default parameters"
if default == 'system': return ulog.get_default_parameters(0)
if default == 'current_setup': return ulog.get_default_parameters(1)
raise ValueError('invalid value \'{}\' for --default'.format(default))
def main():
"""Commande line interface"""
parser = argparse.ArgumentParser(description='Extract parameters from an ULog file')
parser.add_argument('filename', metavar='file.ulg', help='ULog input file')
parser.add_argument('-l', '--delimiter', dest='delimiter', action='store',
help='Use delimiter in CSV (default is \',\')', default=',')
parser.add_argument('-i', '--initial', dest='initial', action='store_true',
help='Only extract initial parameters. (octave|csv)', default=False)
parser.add_argument('-t', '--timestamps', dest='timestamps', action='store_true',
help='Extract changed parameters with timestamps. (csv)', default=False)
parser.add_argument('-f', '--format', dest='format', action='store', type=str,
help='csv|octave|qgc', default='csv')
parser.add_argument('output_filename', metavar='params.txt',
type=argparse.FileType('w'), nargs='?',
help='Output filename (default=stdout)', default=sys.stdout)
parser.add_argument('--ignore', dest='ignore', action='store_true',
help='Ignore string parsing exceptions', default=False)
parser.add_argument('-d', '--default', dest='default', action='store', type=str,
help='Select default param values instead of configured '
'values (implies --initial). Valid values: system|current_setup',
default=None)
args = parser.parse_args()
ulog_file_name = args.filename
disable_str_exceptions = args.ignore
message_filter = []
if not args.initial: message_filter = None
ulog = ULog(ulog_file_name, message_filter, disable_str_exceptions)
params = ulog.initial_parameters
if args.default is not None:
params = get_defaults(ulog, args.default)
args.initial = True
param_keys = sorted(params.keys())
delimiter = args.delimiter
output_file = args.output_filename
if args.format == "csv":
for param_key in param_keys:
output_file.write(param_key)
if args.timestamps:
output_file.write(delimiter)
output_file.write(str(params[param_key]))
for t, name, value in ulog.changed_parameters:
if name == param_key:
output_file.write(delimiter)
output_file.write(str(value))
output_file.write('\n')
output_file.write("timestamp")
output_file.write(delimiter)
output_file.write('0')
for t, name, value in ulog.changed_parameters:
if name == param_key:
output_file.write(delimiter)
output_file.write(str(t))
output_file.write('\n')
else:
output_file.write(delimiter)
output_file.write(str(params[param_key]))
if not args.initial:
for t, name, value in ulog.changed_parameters:
if name == param_key:
output_file.write(delimiter)
output_file.write(str(value))
output_file.write('\n')
elif args.format == "octave":
for param_key in param_keys:
output_file.write('# name ')
output_file.write(param_key)
values = [params[param_key]]
if not args.initial:
for t, name, value in ulog.changed_parameters:
if name == param_key:
values += [value]
if len(values) > 1:
output_file.write('\n# type: matrix\n')
output_file.write('# rows: 1\n')
output_file.write('# columns: ')
output_file.write(str(len(values)) + '\n')
for value in values:
output_file.write(str(value) + ' ')
else:
output_file.write('\n# type: scalar\n')
output_file.write(str(values[0]))
output_file.write('\n')
elif args.format == "qgc":
for param_key in param_keys:
sys_id = 1
comp_id = 1
delimiter = '\t'
param_value = params[param_key]
output_file.write(str(sys_id))
output_file.write(delimiter)
output_file.write(str(comp_id))
output_file.write(delimiter)
output_file.write(param_key)
output_file.write(delimiter)
output_file.write(str(param_value))
output_file.write(delimiter)
if isinstance(param_value, float):
# Float
param_type = 9
else:
# Int
param_type = 6
output_file.write(str(param_type))
output_file.write('\n')
================================================
FILE: pyulog/px4.py
================================================
"""
PX4-specific ULog helper
"""
import numpy as np
__author__ = "Beat Kueng"
class PX4ULog(object):
"""
This class contains PX4-specific ULog things (field names, etc.)
"""
def __init__(self, ulog_object):
"""
@param ulog_object: ULog instance
"""
self._ulog = ulog_object
def get_mav_type(self):
""" return the MAV type as string from initial parameters """
mav_type = self._ulog.initial_parameters.get('MAV_TYPE', None)
return {0: 'Generic',
1: 'Fixed Wing',
2: 'Quadrotor',
3: 'Coaxial helicopter',
4: 'Normal helicopter with tail rotor',
5: 'Ground installation',
6: 'Ground Control Station',
7: 'Airship, controlled',
8: 'Free balloon, uncontrolled',
9: 'Rocket',
10: 'Ground Rover',
11: 'Surface Vessel, Boat, Ship',
12: 'Submarine',
13: 'Hexarotor',
14: 'Octorotor',
15: 'Tricopter',
16: 'Flapping wing',
17: 'Kite',
18: 'Onboard Companion Controller',
19: 'Two-rotor VTOL (Tailsitter)',
20: 'Quad-rotor VTOL (Tailsitter)',
21: 'Tiltrotor VTOL',
22: 'VTOL Standard',
23: 'VTOL Tailsitter',
24: 'VTOL reserved 4',
25: 'VTOL reserved 5',
26: 'Onboard Gimbal',
27: 'Onboard ADSB Peripheral'}.get(mav_type, 'unknown type')
def get_estimator(self):
"""return the configured estimator as string from initial parameters"""
mav_type = self._ulog.initial_parameters.get('MAV_TYPE', None)
if mav_type == 1: # fixed wing always uses EKF2
return 'EKF2'
mc_est_group = self._ulog.initial_parameters.get('SYS_MC_EST_GROUP', 2)
return {0: 'INAV',
1: 'LPE',
2: 'EKF2',
3: 'Q'}.get(mc_est_group, 'unknown ({})'.format(mc_est_group))
def add_roll_pitch_yaw(self, messages=None):
""" convenience method to add the fields 'roll', 'pitch', 'yaw' to the
loaded data using the quaternion fields (does not update field_data).
By default, messages are: 'vehicle_attitude.q',
'vehicle_attitude_setpoint.q_d', 'vehicle_attitude_groundtruth.q' and
'vehicle_vision_attitude.q' """
if messages is None:
messages = ['vehicle_attitude',
'vehicle_vision_attitude',
'vehicle_attitude_groundtruth',
'vehicle_attitude_setpoint:_d']
for message in messages:
if message.endswith(':_d'):
suffix = '_d'
message = message[:-3]
else:
suffix = ''
self._add_roll_pitch_yaw_to_message(message, suffix)
def _add_roll_pitch_yaw_to_message(self, message_name, field_name_suffix=''):
message_data_all = [elem for elem in self._ulog.data_list if elem.name == message_name]
for message_data in message_data_all:
q = [message_data.data['q'+field_name_suffix+'['+str(i)+']'] for i in range(4)]
roll = np.arctan2(2.0 * (q[0] * q[1] + q[2] * q[3]),
1.0 - 2.0 * (q[1] * q[1] + q[2] * q[2]))
pitch = np.arcsin(2.0 * (q[0] * q[2] - q[3] * q[1]))
yaw = np.arctan2(2.0 * (q[0] * q[3] + q[1] * q[2]),
1.0 - 2.0 * (q[2] * q[2] + q[3] * q[3]))
message_data.data['roll'+field_name_suffix] = roll
message_data.data['pitch'+field_name_suffix] = pitch
message_data.data['yaw'+field_name_suffix] = yaw
def get_configured_rc_input_names(self, channel):
"""
find all RC mappings to a given channel and return their names
:param channel: input channel (0=first)
:return: list of strings or None
"""
ret_val = []
for key in self._ulog.initial_parameters:
param_val = self._ulog.initial_parameters[key]
if key.startswith('RC_MAP_') and param_val == channel + 1:
ret_val.append(key[7:].capitalize())
if len(ret_val) > 0:
return ret_val
return None
================================================
FILE: pyulog/px4_events.py
================================================
""" Event parsing """
import json
import lzma
import urllib.request
from typing import Optional, Callable, Any, List, Tuple
from .libevents_parse.parser import Parser
from .core import ULog
class PX4Events:
""" class to extract events from logs and combine them with metadata to get the messages """
DEFAULT_EVENTS_URL = \
'https://px4-travis.s3.amazonaws.com/Firmware/master/_general/all_events.json.xz'
def __init__(self):
self._events_profile = 'dev'
self._default_parser: Optional[Parser] = None
self._get_default_json_def_cb = self._get_default_json_definitions
@staticmethod
def _get_default_json_definitions(already_has_default_parser: bool) -> Optional[Any]:
""" Default implementation for retrieving the default json event definitions """
# If it already exists, return it to avoid re-downloading
if already_has_default_parser:
return None
with urllib.request.urlopen(PX4Events.DEFAULT_EVENTS_URL, timeout=4) as response:
data = response.read()
return json.loads(lzma.decompress(data))
def set_default_json_definitions_cb(self,
default_json_definitions_cb: Callable[[bool], Optional[Any]]):
""" Set the callback to retrieve the default event definitions json
data (can be used for caching) """
self._get_default_json_def_cb = default_json_definitions_cb
def _get_event_parser(self, ulog: ULog) -> Optional[Parser]:
""" get event parser instance or None on error """
if 'metadata_events' in ulog.msg_info_multiple_dict and \
'metadata_events_sha256' in ulog.msg_info_dict:
file_hash = ulog.msg_info_dict['metadata_events_sha256']
if len(file_hash) <= 64 and file_hash.isalnum():
events_metadata = ulog.msg_info_multiple_dict['metadata_events'][0]
event_definitions_json = json.loads(lzma.decompress(b''.join(events_metadata)))
parser = Parser()
parser.load_definitions(event_definitions_json)
parser.set_profile(self._events_profile)
return parser
# No json definitions in the log -> use default definitions
json_definitions = self._get_default_json_def_cb(
self._default_parser is not None)
if json_definitions is not None:
self._default_parser = Parser()
self._default_parser.load_definitions(json_definitions)
self._default_parser.set_profile(self._events_profile)
return self._default_parser
def get_logged_events(self, ulog: ULog) -> List[Tuple[int, str, str]]:
"""
Get the events as list of messages
:return: list of (timestamp, log level str, message) tuples
"""
def event_log_level_str(log_level: int):
return {0: 'EMERGENCY',
1: 'ALERT',
2: 'CRITICAL',
3: 'ERROR',
4: 'WARNING',
5: 'NOTICE',
6: 'INFO',
7: 'DEBUG',
8: 'PROTOCOL',
9: 'DISABLED'}.get(log_level, 'UNKNOWN')
# Parse events
messages = []
try:
events = ulog.get_dataset('event')
all_ids = events.data['id']
if len(all_ids) == 0:
return []
# Get the parser
try:
event_parser = self._get_event_parser(ulog)
except Exception as exception: # pylint: disable=broad-exception-caught
print('Failed to get event parser: {}'.format(exception))
return []
for event_idx, event_id in enumerate(all_ids):
log_level = (events.data['log_levels'][event_idx] >> 4) & 0xf
if log_level >= 8:
continue
args = []
i = 0
while True:
arg_str = 'arguments[{}]'.format(i)
if arg_str not in events.data:
break
arg = events.data[arg_str][event_idx]
args.append(arg)
i += 1
log_level_str = event_log_level_str(log_level)
t = events.data['timestamp'][event_idx]
event = None
if event_parser is not None:
event = event_parser.parse(event_id, bytes(args))
if event is None:
messages.append((t, log_level_str,
'[Unknown event with ID {:}]'.format(event_id)))
else:
# only show default group
if event.group() == "default":
messages.append((t, log_level_str, event.message()))
# we could expand this a bit for events:
# - show the description too
# - handle url's as link (currently it's shown as text, and all tags are escaped)
except (KeyError, IndexError, ValueError):
# no events in log
pass
return messages
================================================
FILE: pyulog/sql/pyulog.1.sql
================================================
BEGIN;
CREATE TABLE IF NOT EXISTS ULog (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
FileVersion INT,
StartTimestamp REAL,
LastTimestamp REAL,
CompatFlags TEXT,
IncompatFlags TEXT,
SyncCount INT,
HasSync BOOLEAN
);
CREATE TABLE IF NOT EXISTS ULogAppendedOffsets (
SeriesIndex INTEGER,
Offset INTEGER,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogDataset (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
DatasetName TEXT,
MultiId INT,
MessageId INT,
TimestampIndex INT,
ULogId INT REFERENCES ULog (Id),
UNIQUE (ULogId, DatasetName, MultiId)
);
CREATE TABLE IF NOT EXISTS ULogField (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
TopicName TEXT,
DataType TEXT,
ValueArray BLOB,
DatasetId INTEGER REFERENCES ULogDataset (Id)
);
CREATE INDEX IF NOT EXISTS btree_ulogfield_datasetid ON ULogField(DatasetId);
CREATE TABLE IF NOT EXISTS ULogMessageDropout (
Timestamp REAL,
Duration FLOAT,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogMessageFormat (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
Name TEXT,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogMessageFormatField (
FieldType TEXT,
ArraySize INT,
Name TEXT,
MessageId INT REFERENCES ULogMessageFormat (Id)
);
CREATE TABLE IF NOT EXISTS ULogMessageLogging (
LogLevel INT,
Timestamp REAL,
Message TEXT,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogMessageLoggingTagged (
LogLevel INT,
Timestamp REAL,
Tag INT,
Message TEXT,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogMessageInfo (
Key TEXT,
Typename TEXT,
Value BLOB,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogMessageInfoMultiple (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
Key TEXT,
Typename TEXT,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogMessageInfoMultipleList (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
SeriesIndex INTEGER,
MessageId TEXT REFERENCES ULogMessageInfoMultiple (Id)
);
CREATE TABLE IF NOT EXISTS ULogMessageInfoMultipleListElement (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
SeriesIndex INTEGER,
Value TEXT,
ListId TEXT REFERENCES ULogMessageInfoMultipleList (Id)
);
CREATE TABLE IF NOT EXISTS ULogInitialParameter (
Key TEXT,
Value BLOB,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogChangedParameter (
Timestamp REAL,
Key TEXT,
Value BLOB,
ULogId INT REFERENCES ULog (Id)
);
CREATE TABLE IF NOT EXISTS ULogDefaultParameter (
DefaultType INT,
Key TEXT,
Value BLOB,
ULogId INT REFERENCES ULog (Id)
);
COMMIT;
================================================
FILE: pyulog/sql/pyulog.2.sql
================================================
BEGIN;
PRAGMA foreign_keys=off;
CREATE TABLE IF NOT EXISTS ULog_tmp (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
SHA256Sum TEXT UNIQUE,
FileVersion INT,
StartTimestamp REAL,
LastTimestamp REAL,
CompatFlags TEXT,
IncompatFlags TEXT,
SyncCount INT,
HasSync BOOLEAN
);
INSERT OR IGNORE INTO ULog_tmp (Id, FileVersion, StartTimestamp, LastTimestamp, CompatFlags, IncompatFlags, SyncCount, HasSync) SELECT Id, FileVersion, StartTimestamp, LastTimestamp, CompatFlags, IncompatFlags, SyncCount, HasSync FROM ULog;
CREATE TABLE IF NOT EXISTS ULogAppendedOffsets_tmp (
SeriesIndex INTEGER,
Offset INTEGER,
ULogId INT REFERENCES ULog_tmp (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogAppendedOffsets_tmp SELECT * FROM ULogAppendedOffsets;
CREATE TABLE IF NOT EXISTS ULogDataset_tmp (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
DatasetName TEXT,
MultiId INT,
MessageId INT,
TimestampIndex INT,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE,
UNIQUE (ULogId, DatasetName, MultiId)
);
INSERT OR IGNORE INTO ULogDataset_tmp SELECT * FROM ULogDataset;
CREATE TABLE IF NOT EXISTS ULogField_tmp (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
TopicName TEXT,
DataType TEXT,
ValueArray BLOB,
DatasetId INTEGER REFERENCES ULogDataset (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogField_tmp SELECT * FROM ULogField;
CREATE INDEX IF NOT EXISTS btree_ulogfield_datasetid ON ULogField_tmp(DatasetId);
CREATE TABLE IF NOT EXISTS ULogMessageDropout_tmp (
Timestamp REAL,
Duration FLOAT,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageDropout_tmp SELECT * FROM ULogMessageDropout;
CREATE TABLE IF NOT EXISTS ULogMessageFormat_tmp (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
Name TEXT,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageFormat_tmp SELECT * FROM ULogMessageFormat;
CREATE TABLE IF NOT EXISTS ULogMessageFormatField_tmp (
FieldType TEXT,
ArraySize INT,
Name TEXT,
MessageId INT REFERENCES ULogMessageFormat (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageFormatField_tmp SELECT * FROM ULogMessageFormatField;
CREATE TABLE IF NOT EXISTS ULogMessageLogging_tmp (
LogLevel INT,
Timestamp REAL,
Message TEXT,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageLogging_tmp SELECT * FROM ULogMessageLogging;
CREATE TABLE IF NOT EXISTS ULogMessageLoggingTagged_tmp (
LogLevel INT,
Timestamp REAL,
Tag INT,
Message TEXT,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageLoggingTagged_tmp SELECT * FROM ULogMessageLoggingTagged;
CREATE TABLE IF NOT EXISTS ULogMessageInfo_tmp (
Key TEXT,
Typename TEXT,
Value BLOB,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageInfo_tmp SELECT * FROM ULogMessageInfo;
CREATE TABLE IF NOT EXISTS ULogMessageInfoMultiple_tmp (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
Key TEXT,
Typename TEXT,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageInfoMultiple_tmp SELECT * FROM ULogMessageInfoMultiple;
CREATE TABLE IF NOT EXISTS ULogMessageInfoMultipleList_tmp (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
SeriesIndex INTEGER,
MessageId TEXT REFERENCES ULogMessageInfoMultiple (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageInfoMultipleList_tmp SELECT * FROM ULogMessageInfoMultipleList;
CREATE TABLE IF NOT EXISTS ULogMessageInfoMultipleListElement_tmp (
Id INTEGER PRIMARY KEY AUTOINCREMENT,
SeriesIndex INTEGER,
Value TEXT,
ListId TEXT REFERENCES ULogMessageInfoMultipleList (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogMessageInfoMultipleListElement_tmp SELECT * FROM ULogMessageInfoMultipleListElement;
CREATE TABLE IF NOT EXISTS ULogInitialParameter_tmp (
Key TEXT,
Value BLOB,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogInitialParameter_tmp SELECT * FROM ULogInitialParameter;
CREATE TABLE IF NOT EXISTS ULogChangedParameter_tmp (
Timestamp REAL,
Key TEXT,
Value BLOB,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogChangedParameter_tmp SELECT * FROM ULogChangedParameter;
CREATE TABLE IF NOT EXISTS ULogDefaultParameter_tmp (
DefaultType INT,
Key TEXT,
Value BLOB,
ULogId INT REFERENCES ULog (Id) ON DELETE CASCADE
);
INSERT OR IGNORE INTO ULogDefaultParameter_tmp SELECT * FROM ULogDefaultParameter;
DROP TABLE IF EXISTS ULog;
DROP TABLE IF EXISTS ULogAppendedOffsets;
DROP TABLE IF EXISTS ULogDataset;
DROP TABLE IF EXISTS ULogField;
DROP TABLE IF EXISTS ULogMessageDropout;
DROP TABLE IF EXISTS ULogMessageFormat;
DROP TABLE IF EXISTS ULogMessageFormatField;
DROP TABLE IF EXISTS ULogMessageLogging;
DROP TABLE IF EXISTS ULogMessageLoggingTagged;
DROP TABLE IF EXISTS ULogMessageInfo;
DROP TABLE IF EXISTS ULogMessageInfoMultiple;
DROP TABLE IF EXISTS ULogMessageInfoMultipleList;
DROP TABLE IF EXISTS ULogMessageInfoMultipleListElement;
DROP TABLE IF EXISTS ULogInitialParameter;
DROP TABLE IF EXISTS ULogChangedParameter;
DROP TABLE IF EXISTS ULogDefaultParameter;
ALTER TABLE ULog_tmp RENAME TO ULog;
ALTER TABLE ULogAppendedOffsets_tmp RENAME TO ULogAppendedOffsets;
ALTER TABLE ULogDataset_tmp RENAME TO ULogDataset;
ALTER TABLE ULogField_tmp RENAME TO ULogField;
ALTER TABLE ULogMessageDropout_tmp RENAME TO ULogMessageDropout;
ALTER TABLE ULogMessageFormat_tmp RENAME TO ULogMessageFormat;
ALTER TABLE ULogMessageFormatField_tmp RENAME TO ULogMessageFormatField;
ALTER TABLE ULogMessageLogging_tmp RENAME TO ULogMessageLogging;
ALTER TABLE ULogMessageLoggingTagged_tmp RENAME TO ULogMessageLoggingTagged;
ALTER TABLE ULogMessageInfo_tmp RENAME TO ULogMessageInfo;
ALTER TABLE ULogMessageInfoMultiple_tmp RENAME TO ULogMessageInfoMultiple;
ALTER TABLE ULogMessageInfoMultipleList_tmp RENAME TO ULogMessageInfoMultipleList;
ALTER TABLE ULogMessageInfoMultipleListElement_tmp RENAME TO ULogMessageInfoMultipleListElement;
ALTER TABLE ULogInitialParameter_tmp RENAME TO ULogInitialParameter;
ALTER TABLE ULogChangedParameter_tmp RENAME TO ULogChangedParameter;
ALTER TABLE ULogDefaultParameter_tmp RENAME TO ULogDefaultParameter;
PRAGMA foreign_keys=on;
COMMIT;
================================================
FILE: pyulog/sql/pyulog.3.sql
================================================
BEGIN;
ALTER TABLE ULogField ADD COLUMN ValueJson JSON;
COMMIT;
================================================
FILE: pyulog/sql/pyulog.4.sql
================================================
BEGIN;
PRAGMA foreign_keys=off;
-- Change REAL timestamps to INT. SQLITE only supports INT64, but ULog -- changed from REAL
-- timestamps are UINT64. We accept losing 1 bit at the top end, since 2^63
-- microseconds = 400,000 years. which should be enough.
ALTER TABLE ULog RENAME COLUMN StartTimestamp TO StartTimestamp_old;
ALTER TABLE ULog ADD COLUMN StartTimestamp INT;
UPDATE ULog SET StartTimestamp = CAST(StartTimestamp_old AS INT);
ALTER TABLE ULog RENAME COLUMN LastTimestamp TO LastTimestamp_old;
ALTER TABLE ULog ADD COLUMN LastTimestamp INT;
UPDATE ULog SET LastTimestamp = CAST(LastTimestamp_old AS INT);
ALTER TABLE ULogMessageDropout RENAME COLUMN Timestamp TO Timestamp_old;
ALTER TABLE ULogMessageDropout ADD COLUMN Timestamp INT;
UPDATE ULogMessageDropout SET Timestamp = CAST(Timestamp_old AS INT);
ALTER TABLE ULogMessageDropout RENAME COLUMN Duration TO Duration_old;
ALTER TABLE ULogMessageDropout ADD COLUMN Duration INT;
UPDATE ULogMessageDropout SET Duration = CAST(Duration_old AS INT);
ALTER TABLE ULogMessageLogging RENAME COLUMN Timestamp TO Timestamp_old;
ALTER TABLE ULogMessageLogging ADD COLUMN Timestamp INT;
UPDATE ULogMessageLogging SET Timestamp = CAST(Timestamp_old AS INT);
ALTER TABLE ULogMessageLoggingTagged RENAME COLUMN Timestamp TO Timestamp_old;
ALTER TABLE ULogMessageLoggingTagged ADD COLUMN Timestamp INT;
UPDATE ULogMessageLoggingTagged SET Timestamp = CAST(Timestamp_old AS INT);
ALTER TABLE ULogChangedParameter RENAME COLUMN Timestamp TO Timestamp_old;
ALTER TABLE ULogChangedParameter ADD COLUMN Timestamp INT;
UPDATE ULogChangedParameter SET Timestamp = CAST(Timestamp_old AS INT);
PRAGMA foreign_keys=on;
COMMIT;
================================================
FILE: pyulog/sql/pyulog.5.sql
================================================
BEGIN;
CREATE INDEX IF NOT EXISTS btree_ULogAppendedOffsets_ULogId ON ULogAppendedOffsets(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogDataset_ULogId ON ULogDataset(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogField_DatasetId ON ULogField(DatasetId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageDropout_ULogId ON ULogMessageDropout(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageFormat_ULogId ON ULogMessageFormat(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageFormatField_MessageId ON ULogMessageFormatField(MessageId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageLogging_ULogId ON ULogMessageLogging(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageLoggingTagged_ULogId ON ULogMessageLoggingTagged(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageInfo_ULogId ON ULogMessageInfo(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageInfoMultiple_ULogId ON ULogMessageInfoMultiple(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageInfoMultipleList_MessageId ON ULogMessageInfoMultipleList(MessageId);
CREATE INDEX IF NOT EXISTS btree_ULogMessageInfoMultipleListElement_ListId ON ULogMessageInfoMultipleListElement(ListId);
CREATE INDEX IF NOT EXISTS btree_ULogInitialParameter_ULogId ON ULogInitialParameter(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogChangedParameter_ULogId ON ULogChangedParameter(ULogId);
CREATE INDEX IF NOT EXISTS btree_ULogDefaultParameter_ULogId ON ULogDefaultParameter(ULogId);
COMMIT;
================================================
FILE: pyulog/ulog2csv.py
================================================
#! /usr/bin/env python
"""
Convert a ULog file into CSV file(s)
"""
import argparse
import os
import re
import numpy as np
from .core import ULog
#pylint: disable=too-many-locals, invalid-name, consider-using-enumerate
def main():
"""Command line interface"""
parser = argparse.ArgumentParser(description='Convert ULog to CSV')
parser.add_argument('filename', metavar='file.ulg', help='ULog input file')
parser.add_argument(
'-m', '--messages', dest='messages',
help=("Only consider given messages. Must be a comma-separated list of"
" names, like 'sensor_combined,vehicle_gps_position'"))
parser.add_argument('-d', '--delimiter', dest='delimiter', action='store',
help="Use delimiter in CSV (default is ',')", default=',')
parser.add_argument('-o', '--output', dest='output', action='store',
help='Output directory (default is same as input file)',
metavar='DIR')
parser.add_argument('-i', '--ignore', dest='ignore', action='store_true',
help='Ignore string parsing exceptions', default=False)
parser.add_argument(
'-ts', '--time_s', dest='time_s', type = int,
help="Only convert data after this timestamp (in seconds)")
parser.add_argument(
'-te', '--time_e', dest='time_e', type=int,
help="Only convert data upto this timestamp (in seconds)")
args = parser.parse_args()
if args.output and not os.path.isdir(args.output):
print('Creating output directory {:}'.format(args.output))
os.mkdir(args.output)
convert_ulog2csv(args.filename, args.messages, args.output, args.delimiter,
args.time_s, args.time_e, args.ignore)
def read_string_data(data: ULog.Data, field_name: str, array_size: int, data_index: int) -> str:
""" Parse a data field as string """
s = ''
for index in range(array_size):
character = data.data[f'{field_name}[{index}]'][data_index]
if character == 0:
break
s += chr(character)
return s
def convert_ulog2csv(ulog_file_name, messages, output, delimiter, time_s, time_e,
disable_str_exceptions=False):
"""
Coverts and ULog file to a CSV file.
:param ulog_file_name: The ULog filename to open and read
:param messages: A list of message names
:param output: Output file path
:param delimiter: CSV delimiter
:param time_s: Offset time for conversion in seconds
:param time_e: Limit until time for conversion in seconds
:return: None
"""
msg_filter = messages.split(',') if messages else None
ulog = ULog(ulog_file_name, msg_filter, disable_str_exceptions)
data = ulog.data_list
output_file_prefix = ulog_file_name
# strip '.ulg'
if output_file_prefix.lower().endswith('.ulg'):
output_file_prefix = output_file_prefix[:-4]
# write to different output path?
if output:
base_name = os.path.basename(output_file_prefix)
output_file_prefix = os.path.join(output, base_name)
array_pattern = re.compile(r"(.*)\[(.*?)\]")
def get_fields(data: ULog.Data) -> tuple[list[str], dict[str, int]]:
# use same field order as in the log, except for the timestamp
data_keys = []
string_array_sizes = {}
for f in data.field_data:
if f.field_name.startswith('_padding'):
continue
result = array_pattern.fullmatch(f.field_name)
if result and f.type_str == 'char': # string (array of char's)
field, array_index = result.groups()
array_index = int(array_index)
string_array_sizes[field] = max(array_index + 1, string_array_sizes.get(field, 0))
if array_index == 0:
data_keys.append(field)
else:
data_keys.append(f.field_name)
data_keys.remove('timestamp')
data_keys.insert(0, 'timestamp') # we want timestamp at first position
return data_keys, string_array_sizes
for d in data:
name_without_slash = d.name.replace('/', '_')
output_file_name = f'{output_file_prefix}_{name_without_slash}_{d.multi_id}.csv'
num_data_points = len(d.data['timestamp'])
print(f'Writing {output_file_name} ({num_data_points} data points)')
with open(output_file_name, 'w', encoding='utf-8') as csvfile:
data_keys, string_array_sizes = get_fields(d)
# we don't use np.savetxt, because we have multiple arrays with
# potentially different data types. However the following is quite
# slow...
# write the header
csvfile.write(delimiter.join(data_keys) + '\n')
#get the index for row where timestamp exceeds or equals the required value
time_s_i = np.where(d.data['timestamp'] >= time_s * 1e6)[0][0] \
if time_s else 0
#get the index for row upto the timestamp of the required value
time_e_i = np.where(d.data['timestamp'] >= time_e * 1e6)[0][0] \
if time_e else len(d.data['timestamp'])
# write the data
last_elem = len(data_keys)-1
for i in range(time_s_i, time_e_i):
for k in range(len(data_keys)):
if data_keys[k] in string_array_sizes: # string
s = read_string_data(d, data_keys[k], string_array_sizes[data_keys[k]], i)
csvfile.write(s)
else:
csvfile.write(str(d.data[data_keys[k]][i]))
if k != last_elem:
csvfile.write(delimiter)
csvfile.write('\n')
================================================
FILE: pyulog/ulog2kml.py
================================================
#! /usr/bin/env python
"""
Convert a ULog file into a KML file (positioning information)
"""
import argparse
import simplekml # pylint: disable=import-error
from .core import ULog
#pylint: disable=too-many-locals, invalid-name, consider-using-enumerate, too-many-arguments
#pylint: disable=unused-variable
def main():
"""Command line interface"""
parser = argparse.ArgumentParser(description='Convert ULog to KML')
parser.add_argument('filename', metavar='file.ulg', help='ULog input file')
parser.add_argument('-o', '--output', dest='output_filename',
help="output filename", default='track.kml')
parser.add_argument('--topic', dest='topic_name',
help="topic name with position data (default=vehicle_gps_position)",
default='vehicle_gps_position')
parser.add_argument('--camera-trigger', dest='camera_trigger',
help="Camera trigger topic name (e.g. camera_capture)",
default=None)
parser.add_argument('-i', '--ignore', dest='ignore', action='store_true',
help='Ignore string parsing exceptions', default=False)
args = parser.parse_args()
convert_ulog2kml(args.filename, args.output_filename,
position_topic_name=args.topic_name,
camera_trigger_topic_name=args.camera_trigger,
disable_str_exceptions=args.ignore)
# alternative example call:
# convert_ulog2kml(args.filename, 'test.kml', ['vehicle_global_position',
# 'vehicle_gps_position'], [_kml_default_colors, lambda x: simplekml.Color.green])
def _kml_default_colors(x):
""" flight mode to color conversion """
x = max([x, 0])
colors_arr = [simplekml.Color.red, simplekml.Color.green, simplekml.Color.blue,
simplekml.Color.violet, simplekml.Color.yellow, simplekml.Color.orange,
simplekml.Color.burlywood, simplekml.Color.azure, simplekml.Color.lightblue,
simplekml.Color.lawngreen, simplekml.Color.indianred, simplekml.Color.hotpink,
simplekml.Color.bisque, simplekml.Color.cyan, simplekml.Color.darksalmon,
simplekml.Color.deepskyblue, simplekml.Color.lime, simplekml.Color.orchid]
return colors_arr[x]
def convert_ulog2kml(ulog_file_name, output_file_name, position_topic_name=
'vehicle_gps_position', colors=_kml_default_colors, altitude_offset=0,
minimum_interval_s=0.1, style=None, camera_trigger_topic_name=None,
disable_str_exceptions=False):
"""
Coverts and ULog file to a CSV file.
:param ulog_file_name: The ULog filename to open and read
:param output_file_name: KML Output file name
:param position_topic_name: either name of a topic (must have 'lon', 'lat' &
'alt' fields), or a list of topic names
:param colors: lambda function with flight mode (int) (or -1) as input and
returns a color (eg 'fffff8f0') (or list of lambda functions if
multiple position_topic_name's)
:param altitude_offset: add this offset to the altitude [m]
:param minimum_interval_s: minimum time difference between two datapoints
(drop if more points)
:param style: dictionary with rendering options:
'extrude': Bool
'line_width': int
:param camera_trigger_topic_name: name of the camera trigger topic (must
have 'lon', 'lat' & 'seq')
:return: None
"""
default_style = {
'extrude': False,
'line_width': 3
}
used_style = default_style
if style is not None:
for key in style:
used_style[key] = style[key]
if not isinstance(position_topic_name, list):
position_topic_name = [position_topic_name]
colors = [colors]
kml = simplekml.Kml()
load_topic_names = position_topic_name + ['vehicle_status']
if camera_trigger_topic_name is not None:
load_topic_names.append(camera_trigger_topic_name)
ulog = ULog(ulog_file_name, load_topic_names, disable_str_exceptions)
# get flight modes
try:
cur_dataset = ulog.get_dataset('vehicle_status')
flight_mode_changes = cur_dataset.list_value_changes('nav_state')
flight_mode_changes.append((ulog.last_timestamp, -1))
except (KeyError, IndexError) as error:
flight_mode_changes = []
# add the graphs
for topic, cur_colors in zip(position_topic_name, colors):
_kml_add_position_data(kml, ulog, topic, cur_colors, used_style,
altitude_offset, minimum_interval_s, flight_mode_changes)
# camera triggers
_kml_add_camera_triggers(kml, ulog, camera_trigger_topic_name, altitude_offset)
kml.save(output_file_name)
def _kml_add_camera_triggers(kml, ulog, camera_trigger_topic_name, altitude_offset):
"""
Add camera trigger points to the map
"""
data = ulog.data_list
topic_instance = 0
cur_dataset = [elem for elem in data
if elem.name == camera_trigger_topic_name and elem.multi_id == topic_instance]
if len(cur_dataset) > 0:
cur_dataset = cur_dataset[0]
pos_lon = cur_dataset.data['lon']
pos_lat = cur_dataset.data['lat']
pos_alt = cur_dataset.data['alt']
sequence = cur_dataset.data['seq']
for i in range(len(pos_lon)):
pnt = kml.newpoint(name='Camera Trigger '+str(sequence[i]))
pnt.coords = [(pos_lon[i], pos_lat[i], pos_alt[i] + altitude_offset)]
# Balloons instead of text does not work
#pnt.style.balloonstyle.text = 'Camera Trigger '+str(sequence[i])
def _kml_add_position_data(kml, ulog, position_topic_name, colors, style,
altitude_offset=0, minimum_interval_s=0.1,
flight_mode_changes=None):
data = ulog.data_list
topic_instance = 0
if flight_mode_changes is None:
flight_mode_changes = []
cur_dataset = [elem for elem in data
if elem.name == position_topic_name and elem.multi_id == topic_instance]
if len(cur_dataset) == 0:
raise KeyError(position_topic_name+' not found in data')
cur_dataset = cur_dataset[0]
pos_lon = cur_dataset.data['lon']
pos_lat = cur_dataset.data['lat']
pos_alt = cur_dataset.data['alt']
pos_t = cur_dataset.data['timestamp']
if 'fix_type' in cur_dataset.data:
indices = cur_dataset.data['fix_type'] > 2 # use only data with a fix
pos_lon = pos_lon[indices]
pos_lat = pos_lat[indices]
pos_alt = pos_alt[indices]
pos_t = pos_t[indices]
# scale if it's an integer type
lon_type = [f.type_str for f in cur_dataset.field_data if f.field_name == 'lon']
if len(lon_type) > 0 and lon_type[0] == 'int32_t':
pos_lon = pos_lon / 1e7 # to degrees
pos_lat = pos_lat / 1e7
pos_alt = pos_alt / 1e3 # to meters
current_flight_mode = 0
current_flight_mode_idx = 0
if len(flight_mode_changes) > 0:
current_flight_mode = flight_mode_changes[0][1]
def create_linestring():
""" create a new kml linestring and set rendering options """
name = position_topic_name + ":" + str(current_flight_mode)
new_linestring = kml.newlinestring(name=name, altitudemode='absolute')
# set rendering options
if style['extrude']:
new_linestring.extrude = 1
new_linestring.style.linestyle.color = colors(current_flight_mode)
new_linestring.style.linestyle.width = style['line_width']
return new_linestring
current_kml_linestring = create_linestring()
last_t = 0
for i in range(len(pos_lon)):
cur_t = pos_t[i]
if (cur_t - last_t)/1e6 > minimum_interval_s: # assume timestamp is in [us]
pos_data = [pos_lon[i], pos_lat[i], pos_alt[i] + altitude_offset]
current_kml_linestring.coords.addcoordinates([pos_data])
last_t = cur_t
# flight mode change?
while current_flight_mode_idx < len(flight_mode_changes)-1 and \
flight_mode_changes[current_flight_mode_idx+1][0] <= cur_t:
current_flight_mode_idx += 1
current_flight_mode = flight_mode_changes[current_flight_mode_idx][1]
current_kml_linestring = create_linestring()
current_kml_linestring.coords.addcoordinates([pos_data])
================================================
FILE: pyulog/ulog2rosbag.py
================================================
#! /usr/bin/env python
"""
Convert a ULog file into rosbag file(s)
"""
from collections import defaultdict
import argparse
import re
import rospy # pylint: disable=import-error
import rosbag # pylint: disable=import-error
from px4_msgs import msg as px4_msgs # pylint: disable=import-error
from .core import ULog
#pylint: disable=too-many-locals, invalid-name
def main():
"""Command line interface"""
parser = argparse.ArgumentParser(description='Convert ULog to rosbag')
parser.add_argument('filename', metavar='file.ulg', help='ULog input file')
parser.add_argument('bag', metavar='file.bag', help='rosbag output file')
parser.add_argument(
'-m', '--messages', dest='messages',
help=("Only consider given messages. Must be a comma-separated list of"
" names, like 'sensor_combined,vehicle_gps_position'"))
parser.add_argument('-i', '--ignore', dest='ignore', action='store_true',
help='Ignore string parsing exceptions', default=False)
args = parser.parse_args()
convert_ulog2rosbag(args.filename, args.bag, args.messages, args.ignore)
# https://stackoverflow.com/questions/19053707/converting-snake-case-to-lower-camel-case-lowercamelcase
def to_camel_case(snake_str):
""" Convert snake case string to camel case """
components = snake_str.split("_")
return ''.join(x.title() for x in components)
def convert_ulog2rosbag(ulog_file_name, rosbag_file_name, messages, disable_str_exceptions=False):
"""
Coverts and ULog file to a CSV file.
:param ulog_file_name: The ULog filename to open and read
:param rosbag_file_name: The rosbag filename to open and write
:param messages: A list of message names
:return: No
"""
array_pattern = re.compile(r"(.*?)\[(.*?)\]")
msg_filter = messages.split(',') if messages else None
ulog = ULog(ulog_file_name, msg_filter, disable_str_exceptions)
data = ulog.data_list
multiids = defaultdict(set)
for d in data:
multiids[d.name].add(d.multi_id)
with rosbag.Bag(rosbag_file_name, 'w') as bag:
items = []
for d in data:
if multiids[d.name] == {0}:
topic = "/px4/{}".format(d.name)
else:
topic = "/px4/{}_{}".format(d.name, d.multi_id)
msg_type = getattr(px4_msgs, to_camel_case(d.name))
for i in range(len(d.data['timestamp'])):
msg = msg_type()
for f in d.field_data:
result = array_pattern.match(f.field_name)
value = d.data[f.field_name][i]
if result:
field, array_index = result.groups()
array_index = int(array_index)
if isinstance(getattr(msg, field), bytes):
attr = bytearray(getattr(msg, field))
attr[array_index] = value
setattr(msg, field, bytes(attr))
else:
getattr(msg, field)[array_index] = value
else:
setattr(msg, f.field_name, value)
ts = rospy.Time(nsecs=d.data['timestamp'][i]*1000)
items.append((topic, msg, ts))
items.sort(key=lambda x: x[2])
for topic, msg, ts in items:
bag.write(topic, msg, ts)
================================================
FILE: run_tests.sh
================================================
#! /bin/bash
pytest test && pylint pyulog/*.py test/*.py
================================================
FILE: setup.py
================================================
#!/usr/bin/env python
"""
This module allows you to parse ULog files, which are used within the PX4
autopilot middleware.
The file format is documented on https://docs.px4.io/main/en/dev_log/ulog_file_format.html
"""
from setuptools import setup
DOCLINES = __doc__.split("\n")
# pylint: disable=invalid-name
setup(
long_description="\n".join(DOCLINES),
long_description_content_type='text/x-rst',
platforms=["Windows", "Linux", "Solaris", "Mac OS-X", "Unix"],
)
================================================
FILE: test/__init__.py
================================================
================================================
FILE: test/sample_appended_info.txt
================================================
Logging start time: 0:00:05, duration: 0:01:54
Dropouts: count: 1, total duration: 0.0 s, max: 10 ms, mean: 10 ms
Info Messages:
perf_counter_preflight-00: navigator: 3 events, 80us elapsed, 26us avg, min 25us max 28us 1.528us rms
perf_counter_preflight-01: mc_att_control: 766 events, 38087us elapsed, 49us avg, min 23us max 395us 32.174us rms
perf_counter_preflight-02: logger_sd_fsync: 0 events, 0us elapsed, 0us avg, min 0us max 0us 0.000us rms
perf_counter_preflight-03: logger_sd_write: 3 events, 72442us elapsed, 24147us avg, min 10us max 36356us 20904.014us rms
perf_counter_preflight-04: mavlink_txe: 226 events
perf_counter_preflight-05: mavlink_el: 1016 events, 163693us elapsed, 161us avg, min 84us max 2478us 191.598us rms
perf_counter_preflight-06: mavlink_txe: 0 events
perf_counter_preflight-07: mavlink_el: 286 events, 33394us elapsed, 116us avg, min 46us max 1851us 166.045us rms
perf_counter_preflight-08: mavlink_txe: 0 events
perf_counter_preflight-09: mavlink_el: 318 events, 48587us elapsed, 152us avg, min 66us max 2327us 259.293us rms
perf_counter_preflight-10: mavlink_txe: 0 events
perf_counter_preflight-11: mavlink_el: 1030 events, 214017us elapsed, 207us avg, min 79us max 4163us 310.871us rms
perf_counter_preflight-12: ctl_lat: 321 events, 13187us elapsed, 41us avg, min 38us max 111us 11.183us rms
perf_counter_preflight-13: stack_check: 7 events, 69us elapsed, 9us avg, min 2us max 16us 4.488us rms
perf_counter_preflight-14: sensors: 826 events, 93853us elapsed, 113us avg, min 65us max 5118us 179.764us rms
perf_counter_preflight-15: ctrl_latency: 321 events, 40037us elapsed, 124us avg, min 103us max 3022us 166.815us rms
perf_counter_preflight-16: mpu9250_dupe: 898 events
perf_counter_preflight-17: mpu9250_reset: 0 events
perf_counter_preflight-18: mpu9250_good_trans: 3443 events
perf_counter_preflight-19: mpu9250_bad_reg: 0 events
perf_counter_preflight-20: mpu9250_bad_trans: 0 events
perf_counter_preflight-21: mpu9250_read: 4342 events, 269357us elapsed, 62us avg, min 41us max 91us 13.632us rms
perf_counter_preflight-22: mpu9250_gyro_read: 0 events
perf_counter_preflight-23: mpu9250_acc_read: 2 events
perf_counter_preflight-24: mpu9250_mag_duplicates: 3066 events
perf_counter_preflight-25: mpu9250_mag_overflows: 0 events
perf_counter_preflight-26: mpu9250_mag_overruns: 51 events
perf_counter_preflight-27: mpu9250_mag_errors: 0 events
perf_counter_preflight-28: mpu9250_mag_reads: 0 events
perf_counter_preflight-29: adc_samples: 3024 events, 8046us elapsed, 2us avg, min 2us max 3us 0.474us rms
perf_counter_preflight-30: ms5611_com_err: 0 events
perf_counter_preflight-31: ms5611_measure: 321 events, 5603us elapsed, 17us avg, min 8us max 679us 54.355us rms
perf_counter_preflight-32: ms5611_read: 320 events, 23168us elapsed, 72us avg, min 13us max 543us 49.197us rms
perf_counter_preflight-33: dma_alloc: 4 events
perf_top_preflight-00: PID COMMAND CPU(ms) CPU(%) USED/STACK PRIO(BASE) STATE
perf_top_preflight-01: 0 Idle Task 2922 53.339 596/ 748 0 ( 0) READY
perf_top_preflight-02: 1 hpwork 207 4.486 928/ 1780 192 (192) w:sig
perf_top_preflight-03: 2 lpwork 3 0.099 640/ 1780 50 ( 50) w:sig
perf_top_preflight-04: 3 init 4816 0.000 1720/ 2580 100 (100) w:sem
perf_top_preflight-05: 228 px4flow 1 0.000 728/ 1164 100 (100) w:sig
perf_top_preflight-06: 104 gps 10 0.099 1032/ 1524 220 (220) w:sem
perf_top_preflight-07: 108 dataman 1 0.000 720/ 1180 90 ( 90) w:sem
perf_top_preflight-08: 152 sensors 161 3.389 1440/ 1980 250 (250) READY
perf_top_preflight-09: 154 commander 59 2.093 2776/ 3652 140 (140) w:sig
perf_top_preflight-10: 169 mavlink_if0 261 6.281 1648/ 2380 100 (100) READY
perf_top_preflight-11: 170 mavlink_rcv_if0 14 0.299 1320/ 2140 175 (175) w:sem
perf_top_preflight-12: 175 mavlink_if1 63 1.395 1616/ 2420 100 (100) w:sig
perf_top_preflight-13: 176 mavlink_rcv_if1 16 0.398 1496/ 2140 175 (175) w:sem
perf_top_preflight-14: 187 mavlink_if2 48 1.096 1632/ 2388 100 (100) w:sig
perf_top_preflight-15: 188 mavlink_rcv_if2 15 0.299 1316/ 2140 175 (175) w:sem
perf_top_preflight-16: 217 frsky_telemetry 0 0.000 544/ 1188 200 (200) w:sem
perf_top_preflight-17: 254 log_writer_file 13 0.997 544/ 1060 60 ( 60) w:sem
perf_top_preflight-18: 235 mavlink_if3 249 4.287 1576/ 2388 100 (100) READY
perf_top_preflight-19: 237 mavlink_rcv_if3 62 2.093 1316/ 2140 175 (175) READY
perf_top_preflight-20: 253 logger 115 6.779 3104/ 3532 250 (250) RUN
perf_top_preflight-21: 341 commander_low_prio 0 0.000 592/ 2996 50 ( 50) w:sem
perf_top_preflight-22: 295 ekf2 331 9.870 5056/ 5780 250 (250) w:sem
perf_top_preflight-23: 305 mc_att_control 97 2.991 1136/ 1676 250 (250) READY
perf_top_preflight-24: 307 mc_pos_control 12 0.299 552/ 1876 250 (250) w:sem
perf_top_preflight-25: 310 navigator 4 0.000 904/ 1772 105 (105) w:sem
perf_top_preflight-26:
perf_top_preflight-27: Processes: 25 total, 7 running, 18 sleeping
perf_top_preflight-28: CPU usage: 46.66% tasks, 0.00% sched, 53.34% idle
perf_top_preflight-29: DMA Memory: 5120 total, 1536 used 1536 peak
perf_top_preflight-30: Uptime: 6.236s total, 2.922s idle
sys_mcu: STM32F42x, rev. 3
sys_name: PX4
sys_os_name: NuttX
sys_os_ver: 8b81cf5c7ece0c228eaaea3e9d8e667fc4d21a06
sys_os_ver_release: 192
sys_toolchain: GNU GCC
sys_toolchain_ver: 5.4.1 20160919 (release) [ARM/embedded-5-branch revision 240496]
sys_uuid: 004F00413335510D30383336
time_ref_utc: 0
ver_hw: PX4FMU_V4
ver_sw: f54a6c2999e1e2fcbf56dd89de06b615b4186a6e
ver_sw_branch: ulog_crash_dump
ver_sw_release: 17170432
Info Multiple Messages:
hardfault_plain: [['[hardfault_log] -- 2000-01-01-00:06:01 Begin Fault Log --\nSystem fault Occurred on: 2000-01-01-00:06:01\n Type:Hard Fault in file:armv7-m/up_hardfault.c at line: 171 running task: hardfault_log\n FW git-hash: f54a6c2999e1e2fcbf56dd89de06b615b4186a6e\n Build datetime: Jul 3 2017 17:04:33\n Build url: localhost \n Processor registers: from 0x2002b8e4\n r0:0x00000000 r1:0x00000000 r2:0x00000001 r3:0xe000ed14 r4:0x00000000 r5:0x20002854 r6:0x2002bba6 r7:0x2002bb8c\n r8:0x00000000 r9:0x00000000 r10:0x00000000 r11:0x00000000 r12:0x00000000 sp:0x2002b9b8 lr:0x080353ad pc:0x080353dc\n xpsr:0x21000000 basepri:0x000000f0 control:0x00000004\n exe return:0xffffffe9\n IRQ stack: \n top: 0x200068f0\n sp: 0x200068a0 Valid\n bottom: 0x20006604\n size: 0x000002ec\n used: 000000e0\n User stack: \n top: 0x2002bb88\n sp: 0x2002b9b8 Valid\n bottom: 0x2002b3ac\n size: 0x000007dc\n used: 000007dc\nInterrupt sp memory region, stack pointer lies within stack\n0x20006952 0x00000000\n0x20006951 0x00000000\n0x20006950 0x00000000\n0x2000694f 0x00000000\n0x2000694e 0x00000000\n0x2000694d 0x00000000\n0x2000694c 0x00000000\n0x2000694b 0x00000000\n0x2000694a 0x00000000\n0x20006949 0x00000000\n0x20006948 0x00000000\n0x20006947 0x00000000\n0x20006946 0x00000000\n0x20006945 0x00000000\n0x20006944 0x00000000\n0x20006943 0x00000000\n0x20006942 0x00000000\n0x20006941 0x00000000\n0x20006940 0x00000000\n0x2000693f 0x00000000\n0x2000693e 0x00000000\n0x2000693d 0x00000000\n0x2000693c 0x00000000\n0x2000693b 0x00000000\n0x2000693a 0x00000000\n0x20006939 0x2001ba90\n0x20006938 0x00000000\n0x20006937 0x00000000\n0x20006936 0x2001bac0\n0x20006935 0x00000000\n0x20006934 0x20007758\n0x20006933 0x20007640\n0x20006932 0x20007608\n0x20006931 0x20007590\n0x20006930 0x20007790\n0x2000692f 0x20007790\n0x2000692e 0x200078a8\n0x2000692d 0x20007794\n0x2000692c 0x00000000\n0x2000692b 0x00000603\n0x2000692a 0x100061b0\n0x20006929 0x10006060\n0x20006928 0x20006990\n0x20006927 0x10005460\n0x20006926 0x00400003\n0x20006925 0x0813b450\n0x20006924 0x00000002\n0x20006923 0x00000000\n0x20006922 0x00000000\n0x20006921 0x20006990\n0x20006920 0x00000000\n0x2000691f 0x00400002\n0x2000691e 0x0813b450\n0x2000691d 0x00000001\n
gitextract_xzoh4fzy/
├── .github/
│ └── workflows/
│ ├── deploy.yml
│ └── test.yml
├── .gitignore
├── .gitmodules
├── LICENSE.md
├── MANIFEST.in
├── README.ko-KR.md
├── README.md
├── gen_expected_output.sh
├── pylintrc
├── pyproject.toml
├── pyulog/
│ ├── __init__.py
│ ├── core.py
│ ├── db.py
│ ├── extract_gps_dump.py
│ ├── extract_message.py
│ ├── info.py
│ ├── messages.py
│ ├── migrate_db.py
│ ├── params.py
│ ├── px4.py
│ ├── px4_events.py
│ ├── sql/
│ │ ├── pyulog.1.sql
│ │ ├── pyulog.2.sql
│ │ ├── pyulog.3.sql
│ │ ├── pyulog.4.sql
│ │ └── pyulog.5.sql
│ ├── ulog2csv.py
│ ├── ulog2kml.py
│ └── ulog2rosbag.py
├── run_tests.sh
├── setup.py
└── test/
├── __init__.py
├── sample.ulg
├── sample_appended.ulg
├── sample_appended_info.txt
├── sample_appended_messages.txt
├── sample_appended_multiple.ulg
├── sample_appended_multiple_info.txt
├── sample_appended_multiple_messages.txt
├── sample_info.txt
├── sample_log_small.ulg
├── sample_log_small_messages.txt
├── sample_logging_tagged_and_default_params.ulg
├── sample_logging_tagged_and_default_params_messages.txt
├── sample_messages.txt
├── sample_px4_events.ulg
├── sample_px4_events_messages.txt
├── test_cli.py
├── test_db.py
├── test_extract_message.py
├── test_migration.py
├── test_px4.py
├── test_px4_events.py
└── test_ulog.py
SYMBOL INDEX (242 symbols across 23 files)
FILE: pyulog/core.py
function _parse_string (line 17) | def _parse_string(cstr, errors='strict'):
function _parse_string (line 21) | def _parse_string(cstr):
class ULog (line 25) | class ULog(object):
method get_field_size (line 66) | def get_field_size(type_str):
method parse_string (line 83) | def parse_string(cstr):
method __init__ (line 95) | def __init__(self, log_file, message_name_filter_list=None, disable_st...
method start_timestamp (line 143) | def start_timestamp(self):
method last_timestamp (line 148) | def last_timestamp(self):
method msg_info_dict (line 153) | def msg_info_dict(self):
method msg_info_multiple_dict (line 159) | def msg_info_multiple_dict(self):
method initial_parameters (line 165) | def initial_parameters(self):
method get_default_parameters (line 169) | def get_default_parameters(self, default_type):
method changed_parameters (line 179) | def changed_parameters(self):
method message_formats (line 184) | def message_formats(self):
method logged_messages (line 190) | def logged_messages(self):
method logged_messages_tagged (line 195) | def logged_messages_tagged(self):
method dropouts (line 200) | def dropouts(self):
method data_list (line 205) | def data_list(self):
method has_data_appended (line 210) | def has_data_appended(self):
method file_corruption (line 215) | def file_corruption(self):
method has_default_parameters (line 220) | def has_default_parameters(self):
method get_dataset (line 224) | def get_dataset(self, name, multi_instance=0):
method write_ulog (line 240) | def write_ulog(self, log_file):
method _write_file_header (line 261) | def _write_file_header(self, file):
method _write_flags (line 271) | def _write_flags(self, file):
method _write_info_messages (line 288) | def _write_info_messages(self, file):
method _write_info_multiple_message (line 300) | def _write_info_multiple_message(self, file):
method _write_initial_parameters (line 316) | def _write_initial_parameters(self, file):
method _write_default_parameters (line 324) | def _write_default_parameters(self, file):
method _make_parameter_data (line 337) | def _make_parameter_data(self, name: str, value) -> bytes:
method _make_info_message_data (line 349) | def _make_info_message_data(self, key: str, value, value_type: str, co...
method _write_format_messages (line 370) | def _write_format_messages(self, file):
method _write_logged_message_subscriptions (line 392) | def _write_logged_message_subscriptions(self, file):
method _write_data_section (line 405) | def _write_data_section(self, file):
method _make_data_items (line 419) | def _make_data_items(self):
method _make_logged_message_items (line 448) | def _make_logged_message_items(self):
method _make_tagged_logged_message_items (line 461) | def _make_tagged_logged_message_items(self):
method _make_dropout_items (line 475) | def _make_dropout_items(self):
method _make_changed_param_items (line 487) | def _make_changed_param_items(self):
method __eq__ (line 497) | def __eq__(self, other):
class Data (line 510) | class Data(object):
method __init__ (line 513) | def __init__(self, message_add_logged_obj):
method __eq__ (line 528) | def __eq__(self, other):
method list_value_changes (line 545) | def list_value_changes(self, field_name):
class _MessageHeader (line 565) | class _MessageHeader(object):
method __init__ (line 568) | def __init__(self):
method initialize (line 572) | def initialize(self, data):
class _MessageInfo (line 575) | class _MessageInfo(object):
method __init__ (line 578) | def __init__(self, data, header, is_info_multiple=False):
class _MessageParameterDefault (line 595) | class _MessageParameterDefault(object):
method __init__ (line 598) | def __init__(self, data, header):
class _MessageFlagBits (line 605) | class _MessageFlagBits(object):
method __init__ (line 608) | def __init__(self, data, header):
class MessageFormat (line 621) | class MessageFormat(object):
method __init__ (line 624) | def __init__(self, data, header):
method __eq__ (line 633) | def __eq__(self, other):
method _extract_type (line 640) | def _extract_type(field_str):
class MessageLogging (line 654) | class MessageLogging(object):
method __init__ (line 657) | def __init__(self, data, header):
method __eq__ (line 662) | def __eq__(self, other):
method log_level_str (line 670) | def log_level_str(self):
class MessageLoggingTagged (line 680) | class MessageLoggingTagged(object):
method __init__ (line 683) | def __init__(self, data, header):
method __eq__ (line 689) | def __eq__(self, other):
method log_level_str (line 698) | def log_level_str(self):
class MessageDropout (line 708) | class MessageDropout(object):
method __init__ (line 710) | def __init__(self, data, header, timestamp):
method __eq__ (line 714) | def __eq__(self, other):
class _FieldData (line 720) | class _FieldData(object):
method __init__ (line 722) | def __init__(self, field_name, type_str):
method __eq__ (line 726) | def __eq__(self, other):
class _MessageAddLogged (line 732) | class _MessageAddLogged(object):
method __init__ (line 734) | def __init__(self, data, header, message_formats):
method _parse_format (line 761) | def _parse_format(self, message_formats):
method _parse_nested_type (line 769) | def _parse_nested_type(self, prefix_str, type_name, message_formats):
class _MessageData (line 792) | class _MessageData(object):
method __init__ (line 793) | def __init__(self):
method initialize (line 796) | def initialize(self, data, header, subscriptions, ulog_object) -> bool:
method _add_parameter_default (line 829) | def _add_parameter_default(self, msg_param):
method _add_message_info_multiple (line 840) | def _add_message_info_multiple(self, msg_info):
method _load_file (line 851) | def _load_file(self, log_file, message_name_filter_list, parse_header_...
method _read_file_header (line 884) | def _read_file_header(self):
method _read_file_definitions (line 897) | def _read_file_definitions(self):
method _find_sync (line 966) | def _find_sync(self, last_n_bytes=-1):
method _read_file_data (line 1024) | def _read_file_data(self, message_name_filter_list, read_until=None):
method _check_packet_corruption (line 1138) | def _check_packet_corruption(self, header):
method get_version_info (line 1156) | def get_version_info(self, key_name='ver_sw_release'):
method get_version_info_str (line 1172) | def get_version_info_str(self, key_name='ver_sw_release'):
FILE: pyulog/db.py
class DatabaseULog (line 12) | class DatabaseULog(ULog):
method get_db_handle (line 55) | def get_db_handle(db_path):
method exists_in_db (line 71) | def exists_in_db(db_handle, primary_key):
method primary_key_from_sha256sum (line 90) | def primary_key_from_sha256sum(db_handle, sha256sum):
method calc_sha256sum (line 110) | def calc_sha256sum(log_file):
method __init__ (line 133) | def __init__(self, db_handle, primary_key=None, log_file=None, lazy=Tr...
method __eq__ (line 182) | def __eq__(self, other):
method write_ulog (line 192) | def write_ulog(self, log_file):
method primary_key (line 198) | def primary_key(self):
method sha256sum (line 203) | def sha256sum(self):
method load (line 208) | def load(self, lazy=True):
method get_dataset (line 412) | def get_dataset(self, name, multi_instance=0, lazy=False, db_cursor=No...
method save (line 491) | def save(self, append_json=False):
method delete (line 731) | def delete(self):
class DatabaseData (line 748) | class DatabaseData(ULog.Data):
method __init__ (line 755) | def __init__(self, name, multi_id, msg_id, timestamp_idx, field_data...
class DatabaseMessageDropout (line 763) | class DatabaseMessageDropout(ULog.MessageDropout):
method __init__ (line 769) | def __init__(self, timestamp, duration):
class DatabaseMessageFormat (line 773) | class DatabaseMessageFormat(ULog.MessageFormat):
method __init__ (line 779) | def __init__(self, name, fields):
class DatabaseMessageLogging (line 783) | class DatabaseMessageLogging(ULog.MessageLogging):
method __init__ (line 789) | def __init__(self, log_level, timestamp, message):
class DatabaseMessageLoggingTagged (line 794) | class DatabaseMessageLoggingTagged(ULog.MessageLoggingTagged):
method __init__ (line 800) | def __init__(self, log_level, tag, timestamp, message):
FILE: pyulog/extract_gps_dump.py
function main (line 15) | def main():
FILE: pyulog/extract_message.py
function extract_message (line 9) | def extract_message(ulog_file_name: str, message: str,
FILE: pyulog/info.py
function show_info (line 13) | def show_info(ulog, verbose):
function main (line 70) | def main():
FILE: pyulog/messages.py
function main (line 12) | def main():
FILE: pyulog/migrate_db.py
function main (line 15) | def main():
function _read_db_schema_version (line 41) | def _read_db_schema_version(db_path, force):
function _read_migration_file (line 72) | def _read_migration_file(migration_id, sql_dir):
function migrate_db (line 93) | def migrate_db(db_path, sql_dir=None, noop=False, force=False):
FILE: pyulog/params.py
function get_defaults (line 12) | def get_defaults(ulog, default):
function main (line 20) | def main():
FILE: pyulog/px4.py
class PX4ULog (line 9) | class PX4ULog(object):
method __init__ (line 14) | def __init__(self, ulog_object):
method get_mav_type (line 20) | def get_mav_type(self):
method get_estimator (line 53) | def get_estimator(self):
method add_roll_pitch_yaw (line 67) | def add_roll_pitch_yaw(self, messages=None):
method _add_roll_pitch_yaw_to_message (line 89) | def _add_roll_pitch_yaw_to_message(self, message_name, field_name_suff...
method get_configured_rc_input_names (line 104) | def get_configured_rc_input_names(self, channel):
FILE: pyulog/px4_events.py
class PX4Events (line 11) | class PX4Events:
method __init__ (line 17) | def __init__(self):
method _get_default_json_definitions (line 23) | def _get_default_json_definitions(already_has_default_parser: bool) ->...
method set_default_json_definitions_cb (line 34) | def set_default_json_definitions_cb(self,
method _get_event_parser (line 40) | def _get_event_parser(self, ulog: ULog) -> Optional[Parser]:
method get_logged_events (line 64) | def get_logged_events(self, ulog: ULog) -> List[Tuple[int, str, str]]:
FILE: pyulog/sql/pyulog.1.sql
type ULog (line 2) | CREATE TABLE IF NOT EXISTS ULog (
type ULogAppendedOffsets (line 13) | CREATE TABLE IF NOT EXISTS ULogAppendedOffsets (
type ULogDataset (line 19) | CREATE TABLE IF NOT EXISTS ULogDataset (
type ULogField (line 29) | CREATE TABLE IF NOT EXISTS ULogField (
type btree_ulogfield_datasetid (line 37) | CREATE INDEX IF NOT EXISTS btree_ulogfield_datasetid ON ULogField(Datase...
type ULogMessageDropout (line 39) | CREATE TABLE IF NOT EXISTS ULogMessageDropout (
type ULogMessageFormat (line 45) | CREATE TABLE IF NOT EXISTS ULogMessageFormat (
type ULogMessageFormatField (line 51) | CREATE TABLE IF NOT EXISTS ULogMessageFormatField (
type ULogMessageLogging (line 58) | CREATE TABLE IF NOT EXISTS ULogMessageLogging (
type ULogMessageLoggingTagged (line 65) | CREATE TABLE IF NOT EXISTS ULogMessageLoggingTagged (
type ULogMessageInfo (line 73) | CREATE TABLE IF NOT EXISTS ULogMessageInfo (
type ULogMessageInfoMultiple (line 80) | CREATE TABLE IF NOT EXISTS ULogMessageInfoMultiple (
type ULogMessageInfoMultipleList (line 86) | CREATE TABLE IF NOT EXISTS ULogMessageInfoMultipleList (
type ULogMessageInfoMultipleListElement (line 91) | CREATE TABLE IF NOT EXISTS ULogMessageInfoMultipleListElement (
type ULogInitialParameter (line 98) | CREATE TABLE IF NOT EXISTS ULogInitialParameter (
type ULogChangedParameter (line 104) | CREATE TABLE IF NOT EXISTS ULogChangedParameter (
type ULogDefaultParameter (line 111) | CREATE TABLE IF NOT EXISTS ULogDefaultParameter (
FILE: pyulog/sql/pyulog.2.sql
type ULog_tmp (line 4) | CREATE TABLE IF NOT EXISTS ULog_tmp (
type ULogAppendedOffsets_tmp (line 18) | CREATE TABLE IF NOT EXISTS ULogAppendedOffsets_tmp (
type ULogDataset_tmp (line 25) | CREATE TABLE IF NOT EXISTS ULogDataset_tmp (
type ULogField_tmp (line 36) | CREATE TABLE IF NOT EXISTS ULogField_tmp (
type btree_ulogfield_datasetid (line 44) | CREATE INDEX IF NOT EXISTS btree_ulogfield_datasetid ON ULogField_tmp(Da...
type ULogMessageDropout_tmp (line 46) | CREATE TABLE IF NOT EXISTS ULogMessageDropout_tmp (
type ULogMessageFormat_tmp (line 53) | CREATE TABLE IF NOT EXISTS ULogMessageFormat_tmp (
type ULogMessageFormatField_tmp (line 60) | CREATE TABLE IF NOT EXISTS ULogMessageFormatField_tmp (
type ULogMessageLogging_tmp (line 68) | CREATE TABLE IF NOT EXISTS ULogMessageLogging_tmp (
type ULogMessageLoggingTagged_tmp (line 76) | CREATE TABLE IF NOT EXISTS ULogMessageLoggingTagged_tmp (
type ULogMessageInfo_tmp (line 85) | CREATE TABLE IF NOT EXISTS ULogMessageInfo_tmp (
type ULogMessageInfoMultiple_tmp (line 93) | CREATE TABLE IF NOT EXISTS ULogMessageInfoMultiple_tmp (
type ULogMessageInfoMultipleList_tmp (line 101) | CREATE TABLE IF NOT EXISTS ULogMessageInfoMultipleList_tmp (
type ULogMessageInfoMultipleListElement_tmp (line 108) | CREATE TABLE IF NOT EXISTS ULogMessageInfoMultipleListElement_tmp (
type ULogInitialParameter_tmp (line 116) | CREATE TABLE IF NOT EXISTS ULogInitialParameter_tmp (
type ULogChangedParameter_tmp (line 123) | CREATE TABLE IF NOT EXISTS ULogChangedParameter_tmp (
type ULogDefaultParameter_tmp (line 131) | CREATE TABLE IF NOT EXISTS ULogDefaultParameter_tmp (
FILE: pyulog/sql/pyulog.5.sql
type btree_ULogAppendedOffsets_ULogId (line 2) | CREATE INDEX IF NOT EXISTS btree_ULogAppendedOffsets_ULogId ON ULogAppen...
type btree_ULogDataset_ULogId (line 3) | CREATE INDEX IF NOT EXISTS btree_ULogDataset_ULogId ON ULogDataset(ULogId)
type btree_ULogField_DatasetId (line 4) | CREATE INDEX IF NOT EXISTS btree_ULogField_DatasetId ON ULogField(Datase...
type btree_ULogMessageDropout_ULogId (line 5) | CREATE INDEX IF NOT EXISTS btree_ULogMessageDropout_ULogId ON ULogMessag...
type btree_ULogMessageFormat_ULogId (line 6) | CREATE INDEX IF NOT EXISTS btree_ULogMessageFormat_ULogId ON ULogMessage...
type btree_ULogMessageFormatField_MessageId (line 7) | CREATE INDEX IF NOT EXISTS btree_ULogMessageFormatField_MessageId ON ULo...
type btree_ULogMessageLogging_ULogId (line 8) | CREATE INDEX IF NOT EXISTS btree_ULogMessageLogging_ULogId ON ULogMessag...
type btree_ULogMessageLoggingTagged_ULogId (line 9) | CREATE INDEX IF NOT EXISTS btree_ULogMessageLoggingTagged_ULogId ON ULog...
type btree_ULogMessageInfo_ULogId (line 10) | CREATE INDEX IF NOT EXISTS btree_ULogMessageInfo_ULogId ON ULogMessageIn...
type btree_ULogMessageInfoMultiple_ULogId (line 11) | CREATE INDEX IF NOT EXISTS btree_ULogMessageInfoMultiple_ULogId ON ULogM...
type btree_ULogMessageInfoMultipleList_MessageId (line 12) | CREATE INDEX IF NOT EXISTS btree_ULogMessageInfoMultipleList_MessageId O...
type btree_ULogMessageInfoMultipleListElement_ListId (line 13) | CREATE INDEX IF NOT EXISTS btree_ULogMessageInfoMultipleListElement_List...
type btree_ULogInitialParameter_ULogId (line 14) | CREATE INDEX IF NOT EXISTS btree_ULogInitialParameter_ULogId ON ULogInit...
type btree_ULogChangedParameter_ULogId (line 15) | CREATE INDEX IF NOT EXISTS btree_ULogChangedParameter_ULogId ON ULogChan...
type btree_ULogDefaultParameter_ULogId (line 16) | CREATE INDEX IF NOT EXISTS btree_ULogDefaultParameter_ULogId ON ULogDefa...
FILE: pyulog/ulog2csv.py
function main (line 17) | def main():
function read_string_data (line 55) | def read_string_data(data: ULog.Data, field_name: str, array_size: int, ...
function convert_ulog2csv (line 65) | def convert_ulog2csv(ulog_file_name, messages, output, delimiter, time_s...
FILE: pyulog/ulog2kml.py
function main (line 16) | def main():
function _kml_default_colors (line 45) | def _kml_default_colors(x):
function convert_ulog2kml (line 58) | def convert_ulog2kml(ulog_file_name, output_file_name, position_topic_name=
function _kml_add_camera_triggers (line 124) | def _kml_add_camera_triggers(kml, ulog, camera_trigger_topic_name, altit...
function _kml_add_position_data (line 149) | def _kml_add_position_data(kml, ulog, position_topic_name, colors, style,
FILE: pyulog/ulog2rosbag.py
function main (line 18) | def main():
function to_camel_case (line 38) | def to_camel_case(snake_str):
function convert_ulog2rosbag (line 43) | def convert_ulog2rosbag(ulog_file_name, rosbag_file_name, messages, disa...
FILE: test/test_cli.py
class TestCommandLineTools (line 24) | class TestCommandLineTools(unittest.TestCase):
method run_against_file (line 29) | def run_against_file(self, expected_output_file, test):
method test_ulog2csv (line 52) | def test_ulog2csv(self, test_case):
method test_pyulog_info_cli (line 73) | def test_pyulog_info_cli(self, test_case):
method test_extract_gps_dump_cli (line 86) | def test_extract_gps_dump_cli(self):
method test_messages_cli (line 98) | def test_messages_cli(self, test_case):
method test_params_cli (line 110) | def test_params_cli(self, test_case):
FILE: test/test_db.py
class TestDatabaseULog (line 19) | class TestDatabaseULog(unittest.TestCase):
method setUp (line 25) | def setUp(self):
method tearDown (line 34) | def tearDown(self):
method test_parsing (line 45) | def test_parsing(self, test_case):
method test_lazy (line 60) | def test_lazy(self):
method test_data_caching (line 86) | def test_data_caching(self):
method test_save (line 112) | def test_save(self):
method test_load (line 123) | def test_load(self):
method test_unapplied_migrations (line 128) | def test_unapplied_migrations(self):
method test_sha256sum (line 143) | def test_sha256sum(self, test_case):
method test_delete (line 170) | def test_delete(self):
method test_json (line 200) | def test_json(self):
method test_write_ulog (line 249) | def test_write_ulog(self, base_name):
FILE: test/test_extract_message.py
class TestExtractMessage (line 17) | class TestExtractMessage(unittest.TestCase):
method test_extract_message (line 23) | def test_extract_message(self, test_case):
FILE: test/test_migration.py
class TestMigration (line 19) | class TestMigration(unittest.TestCase):
method setUp (line 27) | def setUp(self):
method tearDown (line 36) | def tearDown(self):
method _make_migration_file (line 48) | def _make_migration_file(self, sql):
method _get_db_info (line 64) | def _get_db_info(self):
method test_good_migrations (line 79) | def test_good_migrations(self):
method test_transactions (line 100) | def test_transactions(self, sql_line):
method test_bad_migrations (line 110) | def test_bad_migrations(self):
method test_existing_db (line 137) | def test_existing_db(self):
method test_missing_migration_file (line 152) | def test_missing_migration_file(self):
method test_noop (line 165) | def test_noop(self):
method test_real_migrations (line 173) | def test_real_migrations(self):
method test_cli (line 182) | def test_cli(self):
FILE: test/test_px4.py
class TestPX4ULog (line 20) | class TestPX4ULog(unittest.TestCase):
method setUp (line 25) | def setUp(self):
method tearDown (line 34) | def tearDown(self):
method test_add_roll_pitch_yaw (line 44) | def test_add_roll_pitch_yaw(self, base_name):
method test_add_roll_pitch_yaw_db (line 62) | def test_add_roll_pitch_yaw_db(self, base_name):
FILE: test/test_px4_events.py
class TestPX4Events (line 18) | class TestPX4Events(unittest.TestCase):
method test_px4_events (line 24) | def test_px4_events(self, base_name):
FILE: test/test_ulog.py
class TestULog (line 19) | class TestULog(unittest.TestCase):
method test_comparison (line 25) | def test_comparison(self, base_name):
method test_write_ulog (line 44) | def test_write_ulog(self, base_name):
method test_write_ulog_memory (line 64) | def test_write_ulog_memory(self, base_name):
Condensed preview — 55 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (323K chars).
[
{
"path": ".github/workflows/deploy.yml",
"chars": 1020,
"preview": "name: Deploy\n\non:\n workflow_dispatch:\n pull_request:\n push:\n branches:\n - main\n release:\n types:\n - p"
},
{
"path": ".github/workflows/test.yml",
"chars": 840,
"preview": "name: Run Tests\n\non:\n push:\n branches:\n - 'main'\n pull_request:\n branches:\n - '*'\n\njobs:\n build:\n runs"
},
{
"path": ".gitignore",
"chars": 66,
"preview": "__pycache__\n*.pyc\nbuild/\ndist/\n*.egg-info\n.eggs/\n*.sqlite3\nvenv/\n\n"
},
{
"path": ".gitmodules",
"chars": 110,
"preview": "[submodule \"3rd_party/libevents\"]\n\tpath = 3rd_party/libevents\n\turl = https://github.com/mavlink/libevents.git\n"
},
{
"path": "LICENSE.md",
"chars": 1492,
"preview": "Copyright (c) 2016, PX4 Pro Drone Autopilot\nAll rights reserved.\n\nRedistribution and use in source and binary forms, wit"
},
{
"path": "MANIFEST.in",
"chars": 78,
"preview": "include LICENSE.md\nrecursive-include pyulog/sql *\nrecursive-exclude test *.ulg"
},
{
"path": "README.ko-KR.md",
"chars": 6951,
"preview": "# pyulog\n\n 이 레포지토리에는 ULog 파일 및 스크립트를 파싱하는 python 패키지가 포함되어 있습니다.\n ULog는 self-describing 형식을 따르며, 해당 관련 문서는 다음과 같습니다(http"
},
{
"path": "README.md",
"chars": 7752,
"preview": "# pyulog\n\nThis repository contains a python package to parse ULog files and scripts to\nconvert and display them. ULog is"
},
{
"path": "gen_expected_output.sh",
"chars": 242,
"preview": "#! /bin/bash\n\n# generate the expected output for the unittests\n\nfor f in test/*.ulg; do\n\techo \"Processing $f\"\n\tulog_info"
},
{
"path": "pylintrc",
"chars": 22273,
"preview": "[MAIN]\n\n# Analyse import fallback blocks. This can be used to support both Python 2 and\n# 3 compatible code, which means"
},
{
"path": "pyproject.toml",
"chars": 1639,
"preview": "[build-system]\nrequires = [\"setuptools>=77.0.3\", \"setuptools-scm>=8\"]\nbuild-backend = \"setuptools.build_meta\"\n\n[project]"
},
{
"path": "pyulog/__init__.py",
"chars": 93,
"preview": "\"\"\" Wrapper to include the main library modules \"\"\"\nfrom .core import ULog\nfrom . import px4\n"
},
{
"path": "pyulog/core.py",
"chars": 49394,
"preview": "\"\"\" Main Module to load and parse an ULog file \"\"\"\n\nimport struct\nimport copy\nimport sys\nimport contextlib\nimport numpy "
},
{
"path": "pyulog/db.py",
"chars": 31136,
"preview": "'''\nModule containing the DatabaseULog class.\n'''\n\nimport sqlite3\nimport hashlib\nimport contextlib\nimport numpy as np\nfr"
},
{
"path": "pyulog/extract_gps_dump.py",
"chars": 3573,
"preview": "#! /usr/bin/env python\n\"\"\"\nExtract the raw gps communication from an ULog file.\n\"\"\"\n\nimport argparse\nimport os\nimport sy"
},
{
"path": "pyulog/extract_message.py",
"chars": 1907,
"preview": "\"\"\"\nExtract values from a ULog file message to use in scripting\n\"\"\"\n\nfrom typing import List\nimport numpy as np\nfrom .co"
},
{
"path": "pyulog/info.py",
"chars": 4391,
"preview": "#! /usr/bin/env python\n\"\"\"\nDisplay information from an ULog file\n\"\"\"\n\nimport argparse\n\nfrom .core import ULog\n\n#pylint: "
},
{
"path": "pyulog/messages.py",
"chars": 1663,
"preview": "#! /usr/bin/env python\n\"\"\"\nDisplay logged messages from an ULog file\n\"\"\"\n\nimport argparse\n\nfrom .core import ULog\nfrom ."
},
{
"path": "pyulog/migrate_db.py",
"chars": 6149,
"preview": "'''\nTool for handling changes in the database schema. This is necessary for\navoiding breaking backwards compatibility wh"
},
{
"path": "pyulog/params.py",
"chars": 5574,
"preview": "#! /usr/bin/env python\n\"\"\"\nExtract parameters from an ULog file\n\"\"\"\n\nimport argparse\nimport sys\n\nfrom .core import ULog\n"
},
{
"path": "pyulog/px4.py",
"chars": 4433,
"preview": "\"\"\"\nPX4-specific ULog helper\n\"\"\"\nimport numpy as np\n\n__author__ = \"Beat Kueng\"\n\n\nclass PX4ULog(object):\n \"\"\"\n This"
},
{
"path": "pyulog/px4_events.py",
"chars": 5226,
"preview": "\"\"\" Event parsing \"\"\"\nimport json\nimport lzma\nimport urllib.request\nfrom typing import Optional, Callable, Any, List, Tu"
},
{
"path": "pyulog/sql/pyulog.1.sql",
"chars": 3017,
"preview": "BEGIN;\nCREATE TABLE IF NOT EXISTS ULog (\n Id INTEGER PRIMARY KEY AUTOINCREMENT,\n FileVersion INT,\n "
},
{
"path": "pyulog/sql/pyulog.2.sql",
"chars": 6660,
"preview": "BEGIN;\nPRAGMA foreign_keys=off;\n\nCREATE TABLE IF NOT EXISTS ULog_tmp (\n Id INTEGER PRIMARY KEY AUTOINCREMENT,\n "
},
{
"path": "pyulog/sql/pyulog.3.sql",
"chars": 64,
"preview": "BEGIN;\nALTER TABLE ULogField ADD COLUMN ValueJson JSON;\nCOMMIT;\n"
},
{
"path": "pyulog/sql/pyulog.4.sql",
"chars": 1678,
"preview": "BEGIN;\nPRAGMA foreign_keys=off;\n\n-- Change REAL timestamps to INT. SQLITE only supports INT64, but ULog -- changed from "
},
{
"path": "pyulog/sql/pyulog.5.sql",
"chars": 1437,
"preview": "BEGIN;\nCREATE INDEX IF NOT EXISTS btree_ULogAppendedOffsets_ULogId ON ULogAppendedOffsets(ULogId);\nCREATE INDEX IF NOT E"
},
{
"path": "pyulog/ulog2csv.py",
"chars": 5826,
"preview": "#! /usr/bin/env python\n\n\"\"\"\nConvert a ULog file into CSV file(s)\n\"\"\"\n\nimport argparse\nimport os\nimport re\n\nimport numpy "
},
{
"path": "pyulog/ulog2kml.py",
"chars": 8606,
"preview": "#! /usr/bin/env python\n\"\"\"\nConvert a ULog file into a KML file (positioning information)\n\"\"\"\n\nimport argparse\nimport sim"
},
{
"path": "pyulog/ulog2rosbag.py",
"chars": 3434,
"preview": "#! /usr/bin/env python\n\n\"\"\"\nConvert a ULog file into rosbag file(s)\n\"\"\"\n\nfrom collections import defaultdict\nimport argp"
},
{
"path": "run_tests.sh",
"chars": 59,
"preview": "#! /bin/bash\n\npytest test && pylint pyulog/*.py test/*.py\n\n"
},
{
"path": "setup.py",
"chars": 480,
"preview": "#!/usr/bin/env python\n\"\"\"\nThis module allows you to parse ULog files, which are used within the PX4\nautopilot middleware"
},
{
"path": "test/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "test/sample_appended_info.txt",
"chars": 25767,
"preview": "Logging start time: 0:00:05, duration: 0:01:54\nDropouts: count: 1, total duration: 0.0 s, max: 10 ms, mean: 10 ms\nInfo M"
},
{
"path": "test/sample_appended_messages.txt",
"chars": 82,
"preview": "0:00:11 WARNING: [commander_tests] Not ready to fly: Sensors not set up correctly\n"
},
{
"path": "test/sample_appended_multiple_info.txt",
"chars": 62892,
"preview": "Logging start time: 0:00:12, duration: 0:00:09\nNo Dropouts\nInfo Messages:\n perf_counter_preflight-00: navigator: 9 event"
},
{
"path": "test/sample_appended_multiple_messages.txt",
"chars": 82,
"preview": "0:00:11 WARNING: [commander_tests] Not ready to fly: Sensors not set up correctly\n"
},
{
"path": "test/sample_info.txt",
"chars": 1222,
"preview": "Logging start time: 0:01:52, duration: 0:01:08\nDropouts: count: 4, total duration: 0.1 s, max: 62 ms, mean: 29 ms\nInfo M"
},
{
"path": "test/sample_log_small_messages.txt",
"chars": 132,
"preview": "0:00:22 INFO: [commander] Takeoff detected\n0:00:23 INFO: [commander] Landing detected\n0:00:25 INFO: [commander] Disarmed"
},
{
"path": "test/sample_logging_tagged_and_default_params_messages.txt",
"chars": 245,
"preview": "0:00:00 INFO: [px4] Startup script returned successfully\n0:00:00 INFO: logging: opening log file 2022-4-29/8_45_27.ulg\n0"
},
{
"path": "test/sample_messages.txt",
"chars": 248,
"preview": "0:02:38 ERROR: [sensors] no barometer found on /dev/baro0 (2)\n0:02:42 ERROR: [sensors] no barometer found on /dev/baro0 "
},
{
"path": "test/sample_px4_events_messages.txt",
"chars": 991,
"preview": "475214:49:10 INFO: logging: opening log file 2024-3-18/14_49_10.ulg\n475214:49:10 INFO: [px4] Startup script returned suc"
},
{
"path": "test/test_cli.py",
"chars": 3570,
"preview": "'''\nTest command line tools\n'''\n\nimport sys\nimport os\nimport inspect\nimport unittest\nimport tempfile\n\nfrom ddt import dd"
},
{
"path": "test/test_db.py",
"chars": 11435,
"preview": "'''\nTest the DatabaseULog module.\n'''\n\nimport unittest\nimport os\nimport tempfile\nfrom unittest.mock import patch\nimport "
},
{
"path": "test/test_extract_message.py",
"chars": 851,
"preview": "'''\nTest extract_message module\n'''\n\nimport os\nimport inspect\nimport unittest\n\nfrom ddt import ddt, data\n\nfrom pyulog.ex"
},
{
"path": "test/test_migration.py",
"chars": 7214,
"preview": "'''\nTest that the migration module works correctly.\n'''\n\nimport unittest\nimport os\nimport re\nimport sqlite3\nimport subpr"
},
{
"path": "test/test_px4.py",
"chars": 2470,
"preview": "'''\nTests the PX4ULog class\n'''\n\nimport os\nimport inspect\nimport unittest\n\nfrom ddt import ddt, data\n\nfrom pyulog import"
},
{
"path": "test/test_px4_events.py",
"chars": 1577,
"preview": "\"\"\"\nTests the PX4Events class\n\"\"\"\n\nimport os\nimport inspect\nimport unittest\n\nfrom ddt import ddt, data\n\nimport pyulog\nfr"
},
{
"path": "test/test_ulog.py",
"chars": 3342,
"preview": "'''\nTests the ULog class\n'''\n\nimport os\nimport inspect\nimport unittest\nimport tempfile\nfrom io import BytesIO\n\nfrom ddt "
}
]
// ... and 6 more files (download for full content)
About this extraction
This page contains the full source code of the PX4/pyulog GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 55 files (302.1 KB), approximately 97.1k tokens, and a symbol index with 242 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.