diff --git a/.github/runs-on.yml b/.github/runs-on.yml new file mode 100644 index 0000000000..f68d406c8a --- /dev/null +++ b/.github/runs-on.yml @@ -0,0 +1,24 @@ +runners: + x86-small-runner: + cpu: [1, 2] + ram: [1, 4] + disk: default + spot: price-capacity-optimized + image: ubuntu24-full-x64 + extras: s3-cache + x86-firmware-builder: + cpu: [4, 8] + ram: [8, 16] + disk: default + family: ["c7i", "m7i", "r7i"] + spot: price-capacity-optimized + image: ubuntu24-full-x64 + extras: s3-cache + arm64-firmware-builder: + cpu: [4, 8] + ram: [8, 16] + disk: default + family: ["c7g", "m7g", "r7g"] + spot: price-capacity-optimized + image: ubuntu24-full-arm64 + extras: s3-cache diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml index ef3b4d1470..56e6a6ee1a 100644 --- a/.github/workflows/build_all_targets.yml +++ b/.github/workflows/build_all_targets.yml @@ -26,11 +26,15 @@ concurrency: group: ${{ github.workflow }}-${{ github.ref }} cancel-in-progress: true +permissions: + contents: write + actions: read + jobs: group_targets: name: Scan for Board Targets # runs-on: ubuntu-latest - runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] outputs: matrix: ${{ steps.set-matrix.outputs.matrix }} timestamp: ${{ steps.set-timestamp.outputs.timestamp }} @@ -38,6 +42,14 @@ jobs: steps: - uses: actions/checkout@v4 + - name: Cache Python pip + uses: actions/cache@v4 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-${{ hashFiles('**./Tools/setup/requirements.txt') }} + restore-keys: | + ${{ runner.os }}-pip- + - name: Update python packaging to avoid canonicalize_version() error run: | pip3 install -U packaging @@ -48,12 +60,15 @@ jobs: path: "./Tools/setup/requirements.txt" - id: set-matrix - run: echo "::set-output name=matrix::$(./Tools/ci/generate_board_targets_json.py --group)" + name: Generate Build Matrix + run: echo "matrix=$(./Tools/ci/generate_board_targets_json.py --group)" >> $GITHUB_OUTPUT - id: set-timestamp - run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")" + name: Save Current Timestamp + run: echo "timestamp=$(date +"%Y%m%d%H%M%S")" >> $GITHUB_OUTPUT - id: set-branch + name: Save Current Branch Name run: | echo "branchname=${{ github.event_name == 'pull_request' && @@ -70,7 +85,7 @@ jobs: echo "$(./Tools/ci/generate_board_targets_json.py --group --verbose)" setup: - name: Build Group [${{ matrix.group }}][${{ matrix.arch == 'nuttx' && 'x86' || 'arm64' }}] + name: Build [${{ matrix.runner }}][${{ matrix.group }}] # runs-on: ubuntu-latest runs-on: [runs-on,"runner=8cpu-linux-${{ matrix.runner }}","image=ubuntu24-full-${{ matrix.runner }}","run-id=${{ github.run_id }}",spot=false] needs: group_targets @@ -80,6 +95,7 @@ jobs: container: image: ${{ matrix.container }} steps: + - uses: runs-on/action@v2 - uses: actions/checkout@v4 with: fetch-depth: 0 @@ -87,14 +103,24 @@ jobs: - name: Git ownership workaround run: git config --system --add safe.directory '*' - - name: Setup ccache - uses: actions/cache@v4 + # ccache key breakdown: + # ccache---- + # ccache---- + # ccache---- + - name: Cache Restore from Key + id: cc_restore + uses: actions/cache/restore@v4 with: path: ~/.ccache - key: ${{ matrix.group }}-ccache-${{ needs.group_targets.outputs.timestamp }} - restore-keys: ${{ matrix.group }}-ccache-${{ needs.group_targets.outputs.timestamp }} + key: ${{ format('ccache-{0}-{1}-{2}', runner.os, matrix.runner, matrix.group) }} + restore-keys: | + ccache-${{ runner.os }}-${{ matrix.runner }}-${{ matrix.group }}- + ccache-${{ runner.os }}-${{ matrix.runner }}- + ccache-${{ runner.os }}-${{ matrix.runner }}- + ccache-${{ runner.os }}- + ccache- - - name: Configure ccache + - name: Cache Config and Stats run: | mkdir -p ~/.ccache echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf @@ -102,10 +128,11 @@ jobs: echo "compression_level = 6" >> ~/.ccache/ccache.conf echo "max_size = 120M" >> ~/.ccache/ccache.conf echo "hash_dir = false" >> ~/.ccache/ccache.conf + echo "compiler_check = content" >> ~/.ccache/ccache.conf ccache -s ccache -z - - name: Building [${{ matrix.group }}] + - name: Building Artifacts for [${{ matrix.targets }}] run: | ./Tools/ci/build_all_runner.sh ${{matrix.targets}} ${{matrix.arch}} @@ -119,15 +146,27 @@ jobs: name: px4_${{matrix.group}}_build_artifacts path: artifacts/ + - name: Cache Post Build Stats + if: always() + run: | + ccache -s + ccache -z + - name: Cache Save - run: ccache -s + if: always() + uses: actions/cache/save@v4 + with: + path: ~/.ccache + key: ${{ steps.cc_restore.outputs.cache-primary-key }} artifacts: - name: Upload Artifacts to S3 + name: Upload Artifacts # runs-on: ubuntu-latest runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] needs: [setup, group_targets] - if: contains(fromJSON('["main", "stable", "beta"]'), needs.group_targets.outputs.branchname) + if: startsWith(github.ref, 'refs/tags/v') || contains(fromJSON('["main","stable","beta"]'), needs.group_targets.outputs.branchname) + outputs: + uploadlocation: ${{ steps.upload-location.outputs.uploadlocation }} steps: - name: Download Artifacts uses: actions/download-artifact@v4 @@ -135,11 +174,36 @@ jobs: path: artifacts/ merge-multiple: true - - name: Branch Name + - name: Choose Upload Location + id: upload-location run: | - echo "${{ needs.group_targets.outputs.branchname }}" + # Determine upload location based on branch or tag with the following considerations: + # Destination: AWS S3 bucket px4-travis in folder Firmware/ + # - If branch is main -> upload to master/ + # - Older versions of QGC are hardocded to look for master/ + # - If branch is stable or beta -> upload to stable/ or beta/ + # - If a tag vX.Y.Z -> upload to vX.Y.Z/ + # - Also update stable/ to point to the same version + #. - Older versions of QGC are hardocded to look for stable/ + # - If a pull request -> do not upload + set -euo pipefail - - name: Uploading Artifacts to S3 [${{ needs.group_targets.outputs.branchname == 'main' && 'master' || needs.group_targets.outputs.branchname }}] + ref="${GITHUB_REF}" + branch=${{ needs.group_targets.outputs.branchname }} + location="$branch" + + if [[ "$branch" == "main" ]]; then + location="master" + fi + + if [[ "$ref" == refs/tags/v[0-9]* ]]; then + tag="${ref#refs/tags/}" + location="$tag" + fi + + echo "uploadlocation=$location" >> $GITHUB_OUTPUT + + - name: Uploading Artifacts to S3 [${{ steps.upload-location.outputs.uploadlocation }}] uses: jakejarvis/s3-sync-action@master with: args: --acl public-read @@ -149,25 +213,30 @@ jobs: AWS_SECRET_ACCESS_KEY: ${{ secrets.AWS_SECRET_ACCESS_KEY }} AWS_REGION: 'us-west-1' SOURCE_DIR: artifacts/ - DEST_DIR: Firmware/${{ needs.group_targets.outputs.branchname == 'main' && 'master' || needs.group_targets.outputs.branchname }}/ + DEST_DIR: Firmware/${{ steps.upload-location.outputs.uploadlocation }}/ - release: - name: Create Release and Upload Artifacts - permissions: - contents: write - # runs-on: ubuntu-latest - runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] - needs: [setup, group_targets] - if: startsWith(github.ref, 'refs/tags/') - steps: - - name: Download Artifacts - uses: actions/download-artifact@v4 + # if we are uploading artifacts to a versioned folder + # we should also update the stable folder in the s3 bucket + - name: Uploading Artifacts to S3 [stable] + uses: jakejarvis/s3-sync-action@master + if: startsWith(github.ref, 'refs/tags/v') with: - path: artifacts/ - merge-multiple: true + args: --acl public-read + env: + AWS_S3_BUCKET: 'px4-travis' + AWS_ACCESS_KEY_ID: ${{ secrets.AWS_ACCESS_KEY_ID }} + AWS_SECRET_ACCESS_KEY: ${{ secrets.AWS_SECRET_ACCESS_KEY }} + AWS_REGION: 'us-west-1' + SOURCE_DIR: artifacts/ + DEST_DIR: Firmware/stable/ - - name: Upload Binaries to Release + # if build is a release triggered by a versioned tag then create a github release + # and upload the build artifacts. A draft release is created so that the release + # can be reviewed before publishing + - name: Upload Artifacts to GitHub Release uses: softprops/action-gh-release@v2 + if: startsWith(github.ref, 'refs/tags/v') with: draft: true files: artifacts/*.px4 + name: ${{ steps.upload-location.outputs.uploadlocation }} diff --git a/.github/workflows/compile_ubuntu.yml b/.github/workflows/compile_ubuntu.yml index b213a5beaa..019081b9f6 100644 --- a/.github/workflows/compile_ubuntu.yml +++ b/.github/workflows/compile_ubuntu.yml @@ -29,7 +29,7 @@ jobs: fail-fast: false matrix: version: ['ubuntu:22.04', 'ubuntu:24.04'] - runs-on: [runs-on,runner=8cpu-linux-x64,"image=ubuntu24-full-x64","run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,"image=ubuntu24-full-x64","run-id=${{ github.run_id }}",spot=false] container: image: ${{ matrix.version }} volumes: diff --git a/.github/workflows/dev_container.yml b/.github/workflows/dev_container.yml index a8dd32388e..ee61d80c3c 100644 --- a/.github/workflows/dev_container.yml +++ b/.github/workflows/dev_container.yml @@ -39,7 +39,7 @@ jobs: name: Set Tags and Variables permissions: contents: read - runs-on: [runs-on,"runner=1cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,"runner=1cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",extras=s3-cache,spot=false] outputs: px4_version: ${{ steps.px4_version.outputs.px4_version }} meta_tags: ${{ steps.meta.outputs.tags }} @@ -87,7 +87,7 @@ jobs: - platform: linux/amd64 arch: amd64 runner: x64 - runs-on: [runs-on,"runner=8cpu-linux-${{ matrix.runner }}","image=ubuntu24-full-${{ matrix.runner }}","run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,"runner=4cpu-linux-${{ matrix.runner }}","image=ubuntu24-full-${{ matrix.runner }}","run-id=${{ github.run_id }}",extras=s3-cache,spot=false] steps: - uses: runs-on/action@v1 - uses: actions/checkout@v4 @@ -138,7 +138,7 @@ jobs: permissions: contents: read packages: write - runs-on: [runs-on,"runner=8cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,"runner=4cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",extras=s3-cache,spot=false] needs: [build, setup] if: ${{ startsWith(github.ref, 'refs/tags/') || (github.event_name == 'workflow_dispatch' && github.event.inputs.deploy_to_registry) }} steps: diff --git a/.github/workflows/docs_deploy.yml b/.github/workflows/docs_deploy.yml index 13a0df6f6d..bdf729b2b3 100644 --- a/.github/workflows/docs_deploy.yml +++ b/.github/workflows/docs_deploy.yml @@ -1,23 +1,6 @@ -name: Docs - Deploy PX4 User Guide +name: Docs - Deploy PX4 User Guide to Github pages (Manual) on: - push: - branches: - - 'main' - - 'release/**' - paths: - - 'docs/en/**' - - 'docs/uk/**' - - 'docs/zh/**' - pull_request: - branches: - - '**' - paths: - - 'docs/en/**' - - 'docs/uk/**' - - 'docs/zh/**' - - # Allows you to run this workflow manually from the Actions tab workflow_dispatch: # Sets permissions of the GITHUB_TOKEN to allow deployment to GitHub Pages @@ -37,7 +20,7 @@ env: jobs: build: - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",extras=s3-cache,spot=false] steps: - uses: runs-on/action@v1 - name: Checkout @@ -72,7 +55,7 @@ jobs: deploy: if: ${{ github.event_name == 'push' || (github.event_name == 'pull_request' && github.event.pull_request.merged) || github.event_name == 'workflow_dispatch' }} needs: build - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] steps: - name: Download Artifact diff --git a/.github/workflows/docs_deploy_aws.yml b/.github/workflows/docs_deploy_aws.yml index 304100fd81..788a303d5e 100644 --- a/.github/workflows/docs_deploy_aws.yml +++ b/.github/workflows/docs_deploy_aws.yml @@ -30,7 +30,7 @@ concurrency: jobs: build: - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] outputs: branchname: ${{ steps.set-branch.outputs.branchname }} releaseversion: ${{ steps.set-version.outputs.releaseversion }} diff --git a/.github/workflows/failsafe_sim.yml b/.github/workflows/failsafe_sim.yml index edf3d1cd67..24cdb49550 100644 --- a/.github/workflows/failsafe_sim.yml +++ b/.github/workflows/failsafe_sim.yml @@ -48,6 +48,7 @@ jobs: run: | git clone https://github.com/emscripten-core/emsdk.git _emscripten_sdk cd _emscripten_sdk + git checkout 4.0.15 ./emsdk install latest ./emsdk activate latest diff --git a/.github/workflows/flash_analysis.yml b/.github/workflows/flash_analysis.yml index e909e24822..143d54790c 100644 --- a/.github/workflows/flash_analysis.yml +++ b/.github/workflows/flash_analysis.yml @@ -24,7 +24,7 @@ env: jobs: analyze_flash: name: Analyzing ${{ matrix.target }} - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] container: image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 strategy: @@ -97,7 +97,7 @@ jobs: # Track this issue https://github.com/PX4/PX4-Autopilot/issues/24408 post_pr_comment: name: Publish Results - runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}"] needs: [analyze_flash] env: V5X-SUMMARY-MAP-ABS: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v5x-bloaty-summary-map).vm-absolute) }} diff --git a/.github/workflows/itcm_check.yml b/.github/workflows/itcm_check.yml index f6d5c4fd8c..5a1b0ecddc 100644 --- a/.github/workflows/itcm_check.yml +++ b/.github/workflows/itcm_check.yml @@ -22,7 +22,7 @@ concurrency: jobs: check_itcm: name: Checking ${{ matrix.target }} - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] container: image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 strategy: diff --git a/.github/workflows/ros_integration_tests.yml b/.github/workflows/ros_integration_tests.yml index e15aa081e7..022b46fb10 100644 --- a/.github/workflows/ros_integration_tests.yml +++ b/.github/workflows/ros_integration_tests.yml @@ -23,7 +23,7 @@ concurrency: jobs: build: - runs-on: [runs-on,runner=16cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] container: image: px4io/px4-dev-ros2-galactic:2021-09-08 options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined diff --git a/.github/workflows/ros_translation_node.yml b/.github/workflows/ros_translation_node.yml index 9b161dae90..64bae13f83 100644 --- a/.github/workflows/ros_translation_node.yml +++ b/.github/workflows/ros_translation_node.yml @@ -21,7 +21,7 @@ concurrency: jobs: build_and_test: name: Build and test - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] strategy: fail-fast: false matrix: diff --git a/.github/workflows/sitl_tests.yml b/.github/workflows/sitl_tests.yml index 6dc6eccd2d..68e16bed71 100644 --- a/.github/workflows/sitl_tests.yml +++ b/.github/workflows/sitl_tests.yml @@ -24,7 +24,7 @@ concurrency: jobs: build: name: Testing PX4 ${{ matrix.config.model }} - runs-on: [runs-on,runner=16cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] container: image: px4io/px4-dev-simulation-focal:2021-09-08 options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index ec8822e01c..b40113f5da 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -141,6 +141,11 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: ark_can-flow_canbootloader + ark_can-flow-mr_default: + short: ark_can-flow-mr_default + buildType: MinSizeRel + settings: + CONFIG: ark_can-flow-mr_default ark_can-flow-mr_canbootloader: short: ark_can-flow-mr_canbootloader buildType: MinSizeRel @@ -486,3 +491,13 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: x-mav_ap-h743v2_default + svehicle_e2_bootloader: + short: svehicle_e2_bootloader + buildType: MinSizeRel + settings: + CONFIG: svehicle_e2_bootloader + svehicle_e2_default: + short: svehicle_e2 + buildType: MinSizeRel + settings: + CONFIG: svehicle_e2_default diff --git a/LICENSE b/LICENSE index b6f204509f..57c2b07f68 100644 --- a/LICENSE +++ b/LICENSE @@ -1,6 +1,6 @@ BSD 3-Clause License -Copyright (c) 2012 - 2023, PX4 Development Team +Copyright (c) 2012 - 2025, PX4 Development Team All rights reserved. Redistribution and use in source and binary forms, with or without diff --git a/Makefile b/Makefile index 996ffd47e5..80e0ee1f64 100644 --- a/Makefile +++ b/Makefile @@ -325,6 +325,8 @@ bootloaders_update: \ ark_fmu-v6x_bootloader \ ark_fpv_bootloader \ ark_pi6x_bootloader \ + auterion_fmu-v6s_bootloader \ + auterion_fmu-v6x_bootloader \ cuav_nora_bootloader \ cuav_x7pro_bootloader \ cuav_7-nano_bootloader \ diff --git a/ROMFS/CMakeLists.txt b/ROMFS/CMakeLists.txt index e1b08d078b..9b282339fd 100644 --- a/ROMFS/CMakeLists.txt +++ b/ROMFS/CMakeLists.txt @@ -85,10 +85,32 @@ endif() if(PX4_ETHERNET) set(added_arguments ${added_arguments} --ethernet) endif() +# Check if board has an rc.board_airframes file to filter airframes +set(board_airframes_file "${PX4_BOARD_DIR}/init/rc.board_airframes") +set(airframes_whitelist "") +if(EXISTS "${board_airframes_file}") + message(STATUS "ROMFS: Using board-specific airframes list: ${board_airframes_file}") + file(STRINGS "${board_airframes_file}" airframes_whitelist) + # Remove comments and empty lines + list(FILTER airframes_whitelist EXCLUDE REGEX "^[ \t]*#") + list(FILTER airframes_whitelist EXCLUDE REGEX "^[ \t]*$") +endif() + # create list of relative romfs file names set(romfs_copy_files_relative) foreach(romfs_file IN LISTS romfs_copy_files) string(REPLACE "${romfs_src_dir}/" "" romfs_file_rel ${romfs_file}) + + # If we have an airframes whitelist, filter airframe files + if(airframes_whitelist AND romfs_file_rel MATCHES "^init.d/airframes/") + # Extract just the filename + get_filename_component(airframe_name "${romfs_file_rel}" NAME) + # Check if it's in the whitelist + if(NOT "${airframe_name}" IN_LIST airframes_whitelist) + continue() + endif() + endif() + list(APPEND romfs_copy_files_relative ${romfs_file_rel}) endforeach() # copy the ROMFS files by creating a tar and extracting it to the build diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 b/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 index f75374b15c..1904832613 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 @@ -26,7 +26,6 @@ param set-default TRIG_INTERFACE 3 param set-default TRIG_MODE 4 param set-default MNT_MODE_IN 4 param set-default MNT_MODE_OUT 2 -param set-default MAV_PROTO_VER 2 param set-default CA_AIRFRAME 0 param set-default CA_ROTOR_COUNT 6 diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index bbbc55930c..a2d331ba1e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -173,7 +173,6 @@ param set-default COM_RC_IN_MODE 1 param set-default EKF2_REQ_GPS_H 0.5 param set-default IMU_GYRO_FFT_EN 1 -param set-default MAV_PROTO_VER 2 # Ensures QGC does not drop the first few packets after a SITL restart due to MAVLINK 1 packets param set-default -s MC_AT_EN 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames index 150c7410d1..7830e5487e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames +++ b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames @@ -9,6 +9,7 @@ # @board px4_fmu-v5x exclude # @board auterion_fmu-v6s exclude # @board ark_fmu-v6x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 b/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 index c1b3c9a9ba..bc9ff44679 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 @@ -7,6 +7,7 @@ # # @board px4_fmu-v2 exclude # @board bitcraze_crazyflie exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x index 0e9b9df654..5dbd5ea3ee 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x +++ b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x @@ -15,6 +15,7 @@ # @board px4_fmu-v5x exclude # @board auterion_fmu-v6s exclude # @board ark_fmu-v6x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board px4_fmu-v6xrt exclude # @board bitcraze_crazyflie exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index fe40b95aa0..0d8ddaf2d8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -10,6 +10,7 @@ # @board cuav_x7pro exclude # @board px4_fmu-v4pro exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index 141ca861c4..25353b2a4c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -12,6 +12,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board cuav_x7pro exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s index 276e1b45db..ecc7ed5078 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s +++ b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s @@ -10,6 +10,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board cuav_x7pro exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 index 38ffa06896..1d5b47608d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 @@ -14,6 +14,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board diatone_mamba-f405-mk2 exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 index 85b045e84a..3a69a846af 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 +++ b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 @@ -13,6 +13,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board diatone_mamba-f405-mk2 exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/51002_nxp_b3rb b/ROMFS/px4fmu_common/init.d/airframes/51002_nxp_b3rb new file mode 100644 index 0000000000..09cf32a72e --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/51002_nxp_b3rb @@ -0,0 +1,31 @@ +#!/bin/sh +# +# @name NXP B3RB Rover Ackermann +# +# @type Rover +# @class Rover +# +# @board px4_fmu-v2 exclude +# @board bitcraze_crazyflie exclude +# + +. ${R}etc/init.d/rc.rover_ackermann_defaults + +param set-default BAT1_N_CELLS 3 + +# Set geometry & output configration +param set-default PWM_MAIN_FUNC1 201 +param set-default PWM_MAIN_FUNC2 101 +param set-default PWM_MAIN_FUNC3 101 +param set-default PWM_MAIN_DIS1 1500 +param set-default PWM_MAIN_DIS2 0 +param set-default PWM_MAIN_DIS3 1500 +param set-default PWM_MAIN_MIN1 1000 +param set-default PWM_MAIN_MIN2 2500 +param set-default PWM_MAIN_MIN3 0 +param set-default PWM_MAIN_MAX1 2000 +param set-default PWM_MAIN_MAX2 2500 +param set-default PWM_MAIN_MAX3 50 +param set-default PWM_MAIN_TIM0 400 +param set-default PWM_MAIN_TIM1 400 +param set-default PWM_MAIN_TIM2 20000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index 6728f842ce..8f13aa55b1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -153,6 +153,7 @@ if(CONFIG_MODULES_ROVER_ACKERMANN) # [51000, 51999] Ackermann rovers 51000_generic_rover_ackermann 51001_axial_scx10_2_trail_honcho + 51002_nxp_b3rb ) endif() diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 9d0db56e7c..a1e7ff450b 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -26,6 +26,7 @@ param set-default EKF2_MAG_ACCLIM 0 param set-default EKF2_REQ_EPH 10 param set-default EKF2_REQ_EPV 10 param set-default EKF2_REQ_HDRIFT 0.5 +param set-default EKF2_REQ_PDOP 4 param set-default EKF2_REQ_SACC 1 param set-default EKF2_REQ_VDRIFT 1 param set-default EKF2_RNG_QLTY_T 3 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index f747966e03..1337a777c8 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -228,30 +228,26 @@ else fi unset BOARD_RC_ADDITIONAL_INIT - # Load airframe configuration based on SYS_AUTOSTART parameter - if ! param compare SYS_AUTOSTART 0 + # Load airframe configuration based on SYS_AUTOSTART parameter if successful VEHICLE_TYPE gets set + # Run autogenerated ROMFS airframe script + . ${R}etc/init.d/rc.autostart + + if [ ${VEHICLE_TYPE} = none ] then - # rc.autostart directly run the right airframe script which sets the VEHICLE_TYPE - # Look for airframe in ROMFS - . ${R}etc/init.d/rc.autostart - - if [ ${VEHICLE_TYPE} = none ] + # Run external airframe script on SD card + if [ $STORAGE_AVAILABLE = yes ] then - # Use external startup file - if [ $STORAGE_AVAILABLE = yes ] - then - . ${R}etc/init.d/rc.autostart_ext - else - echo "ERROR [init] SD card not mounted - can't load external airframe" - fi + . ${R}etc/init.d/rc.autostart_ext + else + echo "ERROR [init] SD not mounted, skipping external airframe" fi + fi - if [ ${VEHICLE_TYPE} = none ] - then - echo "ERROR [init] No airframe file found for SYS_AUTOSTART value" - param set SYS_AUTOSTART 0 - tune_control play error - fi + if [ ${VEHICLE_TYPE} = none ] + then + echo "ERROR [init] No airframe file found for SYS_AUTOSTART value" + param set SYS_AUTOSTART 0 + tune_control play error fi # Check parameter version and reset upon airframe configuration version mismatch. diff --git a/Tools/astyle/astylerc b/Tools/astyle/astylerc index efdc279ca9..3d1b437ef3 100644 --- a/Tools/astyle/astylerc +++ b/Tools/astyle/astylerc @@ -15,4 +15,4 @@ ignore-exclude-errors-x lineend=linux exclude=EASTL add-brackets -max-code-length=120 +max-code-length=140 diff --git a/Tools/auterion/remote_update_fmu.sh b/Tools/auterion/remote_update_fmu.sh index 2eeb66b999..d3777aebaf 100755 --- a/Tools/auterion/remote_update_fmu.sh +++ b/Tools/auterion/remote_update_fmu.sh @@ -7,6 +7,7 @@ fi ssh_port=22 ssh_user=root +ssh_opts="-o UserKnownHostsFile=/dev/null -o StrictHostKeyChecking=no" while getopts ":f:c:d:p:u:r" opt; do case ${opt} in @@ -67,7 +68,7 @@ target_file_name="update-dev.tar" if [ "$revert" == true ]; then # revert to the release version which was originally deployed cmd="cp $target_dir/update.tar $target_dir/$target_file_name" - ssh -t -p $ssh_port $ssh_user@$device "$cmd" + ssh $ssh_opts -t -p $ssh_port $ssh_user@$device "$cmd" else # create custom update-dev.tar tmp_dir="$(mktemp -d)" @@ -105,11 +106,11 @@ else $tar_name -C "$tmp_dir" --sort=name --owner=root:0 --group=root:0 --mtime='2019-01-01 00:00:00' -cvf $target_file_name $firmware_path $config_path # send it to the target to start flashing - scp -P $ssh_port "$target_file_name" $ssh_user@"$device":$target_dir + scp $ssh_opts -P $ssh_port "$target_file_name" $ssh_user@"$device":$target_dir popd &>/dev/null rm -rf "$tmp_dir" fi # grab status output for flashing progress cmd="tail --follow=name $target_dir/update_status 2>/dev/null || true" -ssh -t -p $ssh_port $ssh_user@$device "$cmd" +ssh $ssh_opts -t -p $ssh_port $ssh_user@$device "$cmd" diff --git a/Tools/setup/requirements.txt b/Tools/setup/requirements.txt index a15da9b9e9..b9d83da852 100644 --- a/Tools/setup/requirements.txt +++ b/Tools/setup/requirements.txt @@ -6,6 +6,7 @@ future jinja2>=2.8 jsonschema kconfiglib +lark lxml matplotlib>=3.0 numpy>=1.13 @@ -14,8 +15,8 @@ packaging pandas>=0.21 pkgconfig psutil +pycryptodome pygments -wheel>=0.31.1 pymavlink pyros-genmsg pyserial @@ -24,7 +25,6 @@ pyyaml requests setuptools>=39.2.0 six>=1.12.0 -toml>=0.9 sympy>=1.10.1 -pycryptodome -lark +toml>=0.9 +wheel>=0.31.1 diff --git a/Tools/simulation/gz b/Tools/simulation/gz index b6127f4ec2..ee3835184c 160000 --- a/Tools/simulation/gz +++ b/Tools/simulation/gz @@ -1 +1 @@ -Subproject commit b6127f4ec20de867e215fb5f78ae88b80f371909 +Subproject commit ee3835184c816116887402d186962e13f4b1ff94 diff --git a/boards/ark/can-flow-mr/default.px4board b/boards/ark/can-flow-mr/default.px4board new file mode 100644 index 0000000000..6474b8cdb7 --- /dev/null +++ b/boards/ark/can-flow-mr/default.px4board @@ -0,0 +1,30 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_ROMFSROOT="cannode" +CONFIG_BOARD_CONSTRAINED_FLASH=y +CONFIG_BOARD_NO_HELP=y +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_DRIVERS_BOOTLOADERS=y +CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y +CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y +CONFIG_DRIVERS_OPTICAL_FLOW_PAA3905=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_DRIVERS_UAVCANNODE=y +CONFIG_UAVCANNODE_FLOW_MEASUREMENT=y +CONFIG_UAVCANNODE_RANGE_SENSOR_MEASUREMENT=y +CONFIG_UAVCANNODE_RAW_IMU=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_SENSORS=y +# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set +# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set +# CONFIG_SENSORS_VEHICLE_ACCELERATION is not set +# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set +# CONFIG_SENSORS_VEHICLE_MAGNETOMETER is not set +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/ark/can-flow-mr/init/rc.board_sensors b/boards/ark/can-flow-mr/init/rc.board_sensors index 2d476fcefb..131d5d58a8 100644 --- a/boards/ark/can-flow-mr/init/rc.board_sensors +++ b/boards/ark/can-flow-mr/init/rc.board_sensors @@ -8,9 +8,8 @@ param set-default SENS_FLOW_RATE 150 param set-default SENS_IMU_CLPNOTI 0 param set-default SENS_AFBR_S_RATE 25 -param set-default SENS_AFBR_L_RATE 10 -param set-default SENS_AFBR_THRESH 8 -param set-default SENS_AFBR_HYSTER 2 +param set-default SENS_AFBR_L_RATE 5 +param set-default SENS_AFBR_MODE 1 # Internal SPI paa3905 -s start -Y 180 diff --git a/boards/ark/dist/init/rc.board_sensors b/boards/ark/dist/init/rc.board_sensors index 0b7d52a6f1..16a809054c 100644 --- a/boards/ark/dist/init/rc.board_sensors +++ b/boards/ark/dist/init/rc.board_sensors @@ -11,7 +11,6 @@ param set-default SENS_AFBR_HYSTER 1 param set-default MAV_SYS_ID 158 param set-default MAV_COMP_ID 158 -param set-default MAV_PROTO_VER 2 param set-default MAV_0_MODE 14 param set-default MAV_0_FORWARD 0 diff --git a/boards/ark/pi6x/init/rc.board_airframes b/boards/ark/pi6x/init/rc.board_airframes new file mode 100644 index 0000000000..4468c66ee4 --- /dev/null +++ b/boards/ark/pi6x/init/rc.board_airframes @@ -0,0 +1,2 @@ +4001_quad_x +4601_droneblocks_dexi_5 diff --git a/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin b/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin index ab4a99d348..233552b397 100755 Binary files a/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin and b/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin differ diff --git a/boards/auterion/fmu-v6s/src/board_config.h b/boards/auterion/fmu-v6s/src/board_config.h index afad06894e..0b2f3c9225 100644 --- a/boards/auterion/fmu-v6s/src/board_config.h +++ b/boards/auterion/fmu-v6s/src/board_config.h @@ -171,6 +171,10 @@ /* Enable the buffer for the dmesg command */ #define BOARD_ENABLE_CONSOLE_BUFFER +/* No CDCACM driver for this board, so this is manually defined for version.c + * so that the px4_board_version reports the correct board id to the companion */ +#define CONFIG_CDCACM_PRODUCTID 60 + __BEGIN_DECLS /**************************************************************************************************** diff --git a/boards/auterion/fmu-v6x/bootloader.px4board b/boards/auterion/fmu-v6x/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/auterion/fmu-v6x/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/auterion/fmu-v6x/cmake/upload.cmake b/boards/auterion/fmu-v6x/cmake/upload.cmake new file mode 100644 index 0000000000..7319b46df3 --- /dev/null +++ b/boards/auterion/fmu-v6x/cmake/upload.cmake @@ -0,0 +1,49 @@ +############################################################################ +# +# Copyright (c) 2023 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. 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. +# 3. Neither the name PX4 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 OWNER 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. +# +############################################################################ + + +set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.px4) + +add_custom_target(upload_skynode_usb + COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} + DEPENDS ${PX4_FW_NAME} + COMMENT "Uploading PX4" + USES_TERMINAL +) + +add_custom_target(upload_skynode_wifi + COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} --wifi + DEPENDS ${PX4_FW_NAME} + COMMENT "Uploading PX4" + USES_TERMINAL +) diff --git a/boards/auterion/fmu-v6x/default.px4board b/boards/auterion/fmu-v6x/default.px4board new file mode 100644 index 0000000000..dece24a26f --- /dev/null +++ b/boards/auterion/fmu-v6x/default.px4board @@ -0,0 +1,102 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPIO_MCP23009=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y +CONFIG_DRIVERS_PWM_INPUT=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_RPM_CAPTURE=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_FIGURE_OF_EIGHT=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_HARDFAULT_STREAM=y +CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y +CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_MECANUM=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin b/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin new file mode 100755 index 0000000000..c619569917 Binary files /dev/null and b/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin differ diff --git a/boards/auterion/fmu-v6x/extras/px4_io-v2_default.bin b/boards/auterion/fmu-v6x/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000..145089ae0d Binary files /dev/null and b/boards/auterion/fmu-v6x/extras/px4_io-v2_default.bin differ diff --git a/boards/auterion/fmu-v6x/firmware.prototype b/boards/auterion/fmu-v6x/firmware.prototype new file mode 100644 index 0000000000..644953a9e1 --- /dev/null +++ b/boards/auterion/fmu-v6x/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 53, + "magic": "AutFWv1", + "description": "Firmware for the AutFMUv6X board", + "image": "", + "build_time": 0, + "summary": "AutFMUv6X", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/auterion/fmu-v6x/flash-analysis.px4board b/boards/auterion/fmu-v6x/flash-analysis.px4board new file mode 100644 index 0000000000..30717ad93c --- /dev/null +++ b/boards/auterion/fmu-v6x/flash-analysis.px4board @@ -0,0 +1 @@ +CONFIG_BOARD_LINKER_PREFIX="flash-analysis" diff --git a/boards/auterion/fmu-v6x/init/rc.board_defaults b/boards/auterion/fmu-v6x/init/rc.board_defaults new file mode 100644 index 0000000000..1a6fc9673c --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_defaults @@ -0,0 +1,34 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# By disabling all 3 INA modules, we use the +# i2c_launcher instead. +param set-default SENS_EN_INA238 0 +param set-default SENS_EN_INA228 0 +param set-default SENS_EN_INA226 0 + +# Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client +param set-default UXRCE_DDS_PTCFG 2 +param set-default UXRCE_DDS_AG_IP 170461697 +param set-default UXRCE_DDS_CFG 1000 + +# The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). +param set-default CBRK_BUZZER 782097 + +# Update default IP config if needed +netman update_default -i eth0 + +safety_button start + +# GPIO Expander driver on external I2C3 +if ver hwbasecmp 009 010 011 +then + # No USB + mcp23009 start -b 3 -X -D 0xf0 -O 0xf0 -P 0x0f -U 10 +fi +if ver hwbasecmp 00a 008 +then + mcp23009 start -b 3 -X -D 0xf1 -O 0xf0 -P 0x0f -U 10 +fi diff --git a/boards/auterion/fmu-v6x/init/rc.board_mavlink b/boards/auterion/fmu-v6x/init/rc.board_mavlink new file mode 100644 index 0000000000..88cdd87c66 --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_mavlink @@ -0,0 +1,18 @@ +#!/bin/sh +# +# Auterion FMUv6X specific board MAVLink startup script. +#------------------------------------------------------------------------------ + +if param compare MAV_S_FORWARD 1 +then + set S_FORWARD "-f" +else + set S_FORWARD "" +fi + +mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m p:MAV_S_MODE -x -z $S_FORWARD + +unset S_FORWARD + +# Ensure nothing else starts on TEL2 (ttyS4) +set PRT_TEL2_ 1 diff --git a/boards/auterion/fmu-v6x/init/rc.board_sensors b/boards/auterion/fmu-v6x/init/rc.board_sensors new file mode 100644 index 0000000000..162a0615ae --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_sensors @@ -0,0 +1,93 @@ +#!/bin/sh +# +# Auterion FMUv6X specific board sensors init +#------------------------------------------------------------------------------ +set HAVE_PM2 yes +set INA_CONFIGURED no + +if mft query -q -k MFT -s MFT_PM2 -v 0 +then + set HAVE_PM2 no +fi +if param compare -s ADC_ADS1115_EN 1 +then + ads1115 start -X + board_adc start -n +else + board_adc start +fi + + +if param compare SENS_EN_INA226 1 +then + # Start Digital power monitors + ina226 -X -b 1 -t 1 -k start + + if [ $HAVE_PM2 = yes ] + then + ina226 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +if param compare SENS_EN_INA228 1 +then + # Start Digital power monitors + ina228 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina228 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +if param compare SENS_EN_INA238 1 +then + # Start Digital power monitors + ina238 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina238 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +#Start Auterion Power Module selector for Skynode boards +pm_selector_auterion start + +# Auterion's INA238 uses a shunt value of 0.0003 instead of 0.0005. +param set-default INA238_SHUNT 0.0003 + +# Internal SPI BMI088 +bmi088 -A -R 6 -s start +bmi088 -G -R 6 -s start + +# Internal SPI bus ICM42688p +icm42688p -R 12 -s start + +# Internal SPI bus ICM20602 +icm20602 -R 6 -s start + +# Internal magnetometer on I2C +bmm150 -I -R 0 start + +# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer) +ist8310 -X -b 1 -R 10 start + +# Possible internal Baro +if param compare SENS_INT_BARO_EN 1 +then + bmp388 -I -a 0x77 start +fi + +#external baro +bmp388 -X start + +# Don't try to start external baro on I2C3 as it can conflict with the MS5525DSO airspeed sensor. +#ms5611 -X start + +unset INA_CONFIGURED +unset HAVE_PM2 diff --git a/boards/auterion/fmu-v6x/multicopter.px4board b/boards/auterion/fmu-v6x/multicopter.px4board new file mode 100644 index 0000000000..4f1b9ef033 --- /dev/null +++ b/boards/auterion/fmu-v6x/multicopter.px4board @@ -0,0 +1,12 @@ +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=n +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_COMMON_RC=y +# CONFIG_EKF2_SIDESLIP is not set +# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set diff --git a/boards/auterion/fmu-v6x/nuttx-config/Kconfig b/boards/auterion/fmu-v6x/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig b/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..fcbf56afd9 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig @@ -0,0 +1,83 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/auterion/fmu-v6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="auterion" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_UART5=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART5_RXBUFSIZE=512 +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=512 +CONFIG_UART5_TXDMA=y +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/auterion/fmu-v6x/nuttx-config/include/board.h b/boards/auterion/fmu-v6x/nuttx-config/include/board.h new file mode 100644 index 0000000000..964976318a --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/include/board.h @@ -0,0 +1,570 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6x/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 OWNER 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. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The px4_fmu-v6X board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 + +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The PX4 FMUV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ + +#ifdef PX4_RESTRICTED_BUILD +# define GPIO_USART3_RX 0 /* PD9 */ +#else +# define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#endif /* PX4_RESTRICTED_BUILD */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +// GPIO_UART5_RTS no remap /* PC8 */ +#undef GPIO_UART5_CTS +#define GPIO_UART5_CTS ((GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9) | GPIO_PULLDOWN) /* PC9 */ + + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is FRAM + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */ +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* The STM32 H7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 H7 BOARD DP83848TSQ/NOPB + * GPIO SIGNAL PIN NAME + * -------- ------------ ------------- + * PA7 ETH_CRS_DV CRS_DV + * PC1 ETH_MDC MDC + * PA2 ETH_MDIO MDIO + * PA1 ETH_REF_CL X1 + * PC4 ETH_RXD0 RX_D0 + * PC5 ETH_RXD1 RX_D1 + * PB11 ETH_TX_EN TX_EN + * PG13 ETH_TXD0 TX_D0 + * PG12 ETH_TXD1 TX_D1 + * + * The PHY address is 1, since COL/PHYAD0 features a pull up. + */ + +#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */ +#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */ +#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h b/boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..1f45efc569 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ + +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */ +//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ + +//#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA1:81 GPS2 */ +//#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA1:82 GPS2 */ + +// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned +// V + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ diff --git a/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..6070e6696e --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig @@ -0,0 +1,313 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/auterion/fmu-v6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="auterion" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_GPIO=y +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DEV_URANDOM=y +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE +CONFIG_NETINIT_IPADDR=0xA290A02 +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_NACTIVESOCKETS=16 +CONFIG_NET_SOLINGER=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_ETHMAC=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PHYSR=31 +CONFIG_STM32H7_PHYSR_100MBPS=0x8 +CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10 +CONFIG_STM32H7_PHYSR_MODE=0x10 +CONFIG_STM32H7_PHYSR_SPEED=0x8 +CONFIG_STM32H7_PHY_POLLING=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_DHCPC_RENEW=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=10000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART7_TXDMA=y +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..037356efd3 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 OWNER 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. + * + ****************************************************************************/ + +/* The Auterion FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Auterion FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld new file mode 100644 index 0000000000..5df2f5180a --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld @@ -0,0 +1,6 @@ +INCLUDE "script.ld" + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 10080K +} diff --git a/boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..860eb2ddd9 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 OWNER 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. + * + ****************************************************************************/ + +/* The Auterion FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Auterion FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +EXTERN(board_get_manifest) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/auterion/fmu-v6x/performance-test.px4board b/boards/auterion/fmu-v6x/performance-test.px4board new file mode 100644 index 0000000000..5e69dd7ae3 --- /dev/null +++ b/boards/auterion/fmu-v6x/performance-test.px4board @@ -0,0 +1,31 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_BOARD_ROMFSROOT="performance-test" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_MFT_CFG=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/auterion/fmu-v6x/rover.px4board b/boards/auterion/fmu-v6x/rover.px4board new file mode 100644 index 0000000000..cd49a241b5 --- /dev/null +++ b/boards/auterion/fmu-v6x/rover.px4board @@ -0,0 +1,17 @@ +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y +CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/auterion/fmu-v6x/spacecraft.px4board b/boards/auterion/fmu-v6x/spacecraft.px4board new file mode 100644 index 0000000000..997a9054a2 --- /dev/null +++ b/boards/auterion/fmu-v6x/spacecraft.px4board @@ -0,0 +1,21 @@ +CONFIG_BOARD_PWM_FREQ=100000 +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_LAND_DETECTOR=n +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_MODULES_ROVER_ACKERMANN=n +CONFIG_MODULES_ROVER_DIFFERENTIAL=n +CONFIG_MODULES_ROVER_MECANUM=n +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_SPACECRAFT=y diff --git a/boards/auterion/fmu-v6x/src/CMakeLists.txt b/boards/auterion/fmu-v6x/src/CMakeLists.txt new file mode 100644 index 0000000000..d0f1b0b1a7 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/CMakeLists.txt @@ -0,0 +1,74 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. 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. +# 3. Neither the name PX4 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 OWNER 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.cpp + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.cpp + led.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + platform_gpio_mcp23009 + ) +endif() diff --git a/boards/auterion/fmu-v6x/src/board_config.h b/boards/auterion/fmu-v6x/src/board_config.h new file mode 100644 index 0000000000..c304153abf --- /dev/null +++ b/boards/auterion/fmu-v6x/src/board_config.h @@ -0,0 +1,524 @@ +/**************************************************************************** + * + * Copyright (c) 2016-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 board_config.h + * + * AuterionFMU-v6x internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* PX4IO connection configuration */ + +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS5" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks +#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid +#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage +#define BOARD_HAS_NBAT_I 2d // 2 Digital Current + +/* PX4FMU GPIOs ***********************************************************************************/ + +/* Trace Clock and D0-D3 are available on the trace connector + * + * TRACECLK PE2 - Dedicated - Trace Connector Pin 1 + * TRACED0 PE3 - nLED_RED - Trace Connector Pin 3 + * TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5 + * TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7 + * TRACED3 PE6 - nARMED - Trace Connector Pin 8 + + */ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +#if !defined(TRACE_PINS) +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +#else + +# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) +# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) +//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + +# undef BOARD_HAS_CONTROL_STATUS_LEDS +# undef BOARD_OVERLOAD_LED +# undef BOARD_ARMED_STATE_LED + +# define GPIO_nLED_RED GPIO_TRACED0 +# define GPIO_nLED_GREEN GPIO_TRACED1 +# define GPIO_nLED_BLUE GPIO_TRACED2 +# define GPIO_nARMED GPIO_TRACED3 +# define GPIO_nARMED_INIT GPIO_TRACED3 +#endif + + +/* SPI */ + +#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) +#define GPIO_SYNC /* PE9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_100MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/ + +#define PX4_I2C_OBDEV_SE050 0x48 + +#define GPIO_I2C2_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. + * ADC3_6V6 and ADC3_3V3 are mapped back to ADC1 + * To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3 + * respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO + * PA0SO of 0. + * + * 0 Analog switch closed (pads are connected through the analog switch) + * + * So ADC3_INP0 is GPIO_ADC123_INP12 + * ADC3_INP1 is GPIO_ADC12_INP13 + */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16) +#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* PB0 */ ADC1_CH(9) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_ADC3_6V6_CHANNEL /* PC2 */ ADC3_CH(12) +#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13) +#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* PF12 */ ADC1_CH(6) +#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15) + +#define ADC_CHANNELS \ + ((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_ADC3_6V6_CHANNEL) | \ + (1 << ADC_ADC3_3V3_CHANNEL)) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* HW Version and Revision drive signals Default to 1 to detect */ +#define BOARD_HAS_HW_SPLIT_VERSIONING + +#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15 +#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 +#define HW_INFO_INIT_PREFIX "V6X" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 1 +// Base/FMUM +#define V6X_16 HW_FMUM_ID(0x10) // FMUV6X, Auterion Sensor Set Rev 16 from EEPROM + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PE6 is nARMED + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#if !defined(TRACE_PINS) +#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6) +#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) +#endif + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 9 + + +/* Power supply control and monitoring GPIOs */ + +#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) +#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */ +#define BOARD_NUMBER_BRICKS 2 +#define BOARD_NUMBER_DIGITAL_BRICKS 2 +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */ + +#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SENSORS4_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8) +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +/* MCP23009 GPIO expander */ +#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpio4" +#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpio5" + + +/* Spare GPIO */ + +#define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) +#define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) +#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true)) + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 14 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2 + +/* Some RC protocols are bi-directional, therefore we need a half-duplex UART */ +#define RC_SERIAL_SINGLEWIRE +/* The STM32 UART by default wires half-duplex mode to the TX pin, but our + * signal in routed to the RX pin, so we need to swap the pins */ +#define RC_SERIAL_SWAP_RXTX + +/* Input Capture Channels. */ +#define INPUT_CAP1_TIMER 1 +#define INPUT_CAP1_CHANNEL /* T1C2 */ 2 +#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT + +#define GPIO_SAFETY_SWITCH_IN /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * FMUv6X has a separate RC_IN + * + * GPIO PPM_IN on PI5 T8CH1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7 + * Inversion is possible in the UART and can drive GPIO PPM_IN as an output + */ + +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) + +/* FMUv6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#if !defined(BOARD_HAS_LTC44XX_VALIDS) || BOARD_HAS_LTC44XX_VALIDS == 0 +# define BOARD_ADC_BRICK1_VALID (1) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 1 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 2 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 3 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 4 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +# define BOARD_ADC_BRICK4_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK4_VALID)) +#else +# error Unsupported BOARD_HAS_LTC44XX_VALIDS value +#endif + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_nPOWER_IN_C, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS4_EN, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_PD15, \ + GPIO_SYNC, \ + SPI6_nRESET_EXTERNAL1, \ + GPIO_ETH_POWER_EN, \ + GPIO_NFC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_PG6, \ + GPIO_nARMED_INIT \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_I2C_BUS_MTD 4,5 + + +#define BOARD_NUM_IO_TIMERS 5 + +/* No CDCACM driver for this board, so this is manually defined for version.c + * so that the px4_board_version reports the correct board id to the companion */ +#define CONFIG_CDCACM_PRODUCTID 53 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/auterion/fmu-v6x/src/bootloader_main.c b/boards/auterion/fmu-v6x/src/bootloader_main.c new file mode 100644 index 0000000000..ccb9a8326b --- /dev/null +++ b/boards/auterion/fmu-v6x/src/bootloader_main.c @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (c) 2019-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +void board_late_initialize(void) +{ +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/auterion/fmu-v6x/src/can.c b/boards/auterion/fmu-v6x/src/can.c new file mode 100644 index 0000000000..cdebe7a3ad --- /dev/null +++ b/boards/auterion/fmu-v6x/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/auterion/fmu-v6x/src/hw_config.h b/boards/auterion/fmu-v6x/src/hw_config.h new file mode 100644 index 0000000000..949a9284a5 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/hw_config.h @@ -0,0 +1,127 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 0 +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 53 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +// Connected to VBUS on the Auterion FMU v6x +#define BOARD_FORCE_BL_PIN (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN9) +#define BOARD_FORCE_BL_STATE 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/auterion/fmu-v6x/src/i2c.cpp b/boards/auterion/fmu-v6x/src/i2c.cpp new file mode 100644 index 0000000000..8a557078e0 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusExternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/auterion/fmu-v6x/src/init.cpp b/boards/auterion/fmu-v6x/src/init.cpp new file mode 100644 index 0000000000..7e35a407c4 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/init.cpp @@ -0,0 +1,295 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 init.cpp + * + * AuterionFMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + VDD_3V3_SENSORS4_EN(false); + + bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); + /* Keep Spektum on to discharge rail*/ + VDD_3V3_SPEKTRUM_POWER_EN(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + VDD_3V3_SPEKTRUM_POWER_EN(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_3V3_SENSORS4_EN(true); + VDD_5V_PERIPH_EN(true); + +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +extern "C" __EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + VDD_3V3_ETH_POWER_EN(true); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ +#if !defined(BOOTLOADER) + + /* Power on Interfaces */ + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS4_EN(true); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + // Use the default HW_VER_REV(0x0,0x0) for Ramtron + + stm32_spiinitialize(); + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + if (OK == board_determine_hw_info()) { + syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), + board_get_hw_type_name()); + + } else { + syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); + } + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +# if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +# endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +# ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +# endif /* CONFIG_MMCSD */ + + ret = mcp23009_register_gpios(3, 0x25); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +#endif /* !defined(BOOTLOADER) */ + + return OK; +} diff --git a/boards/auterion/fmu-v6x/src/led.c b/boards/auterion/fmu-v6x/src/led.c new file mode 100644 index 0000000000..1e33dd1299 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/led.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/auterion/fmu-v6x/src/mtd.cpp b/boards/auterion/fmu-v6x/src/mtd.cpp new file mode 100644 index 0000000000..8e57555eac --- /dev/null +++ b/boards/auterion/fmu-v6x/src/mtd.cpp @@ -0,0 +1,136 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include +#include + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(3, 0x51) +}; +static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(4, 0x50) +}; + + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi5, + .npart = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = (32768 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) + } + }, +}; + +static const px4_mtd_entry_t base_eeprom = { + .device = &i2c3, + .npart = 2, + .partd = { + { + .type = MTD_MFT_VER, + .path = "/fs/mtd_mft_ver", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + + } + }, +}; + +static const px4_mtd_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 3, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 240 + }, + { + .type = MTD_MFT_REV, + .path = "/fs/mtd_mft_rev", + .nblocks = 8 + }, + { + .type = MTD_ID, + .path = "/fs/mtd_id", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 3, + .entries = { + &fmum_fram, + &base_eeprom, + &imu_eeprom + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_entry_s mft_mft = { + .type = MFT, + .pmft = (void *) system_query_manifest, +}; + +static const px4_mft_s mft = { + .nmft = 2, + .mfts = { + &mtd_mft, + &mft_mft, + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/auterion/fmu-v6x/src/sdio.c b/boards/auterion/fmu-v6x/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 OWNER 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/auterion/fmu-v6x/src/spi.cpp b/boards/auterion/fmu-v6x/src/spi.cpp new file mode 100644 index 0000000000..b1100edacf --- /dev/null +++ b/boards/auterion/fmu-v6x/src/spi.cpp @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (C) 2020, 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/auterion/fmu-v6x/src/timer_config.cpp b/boards/auterion/fmu-v6x/src/timer_config.cpp new file mode 100644 index 0000000000..928f4916f0 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/timer_config.cpp @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH2 T FMU_CAP1 < Capture + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + * TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer1), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/auterion/fmu-v6x/uuv.px4board b/boards/auterion/fmu-v6x/uuv.px4board new file mode 100644 index 0000000000..3a7b00f13d --- /dev/null +++ b/boards/auterion/fmu-v6x/uuv.px4board @@ -0,0 +1,23 @@ +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_LAND_DETECTOR=n +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_MODULES_ROVER_ACKERMANN=n +CONFIG_MODULES_ROVER_DIFFERENTIAL=n +CONFIG_MODULES_ROVER_MECANUM=n +CONFIG_MODULES_SPACECRAFT=n +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_UUV_ATT_CONTROL=y +CONFIG_MODULES_UUV_POS_CONTROL=y diff --git a/boards/auterion/fmu-v6x/zenoh.px4board b/boards/auterion/fmu-v6x/zenoh.px4board new file mode 100644 index 0000000000..cb14fde935 --- /dev/null +++ b/boards/auterion/fmu-v6x/zenoh.px4board @@ -0,0 +1,4 @@ +# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set +CONFIG_DRIVERS_UAVCAN=n +CONFIG_MODULES_UXRCE_DDS_CLIENT=n +CONFIG_MODULES_ZENOH=y diff --git a/boards/nxp/mr-canhubk3/fmu.px4board b/boards/nxp/mr-canhubk3/fmu.px4board index 366fac4e09..7f7e146fd2 100644 --- a/boards/nxp/mr-canhubk3/fmu.px4board +++ b/boards/nxp/mr-canhubk3/fmu.px4board @@ -1,6 +1,8 @@ # CONFIG_BOARD_ROMFSROOT is not set CONFIG_DRIVERS_BAROMETER_BMP388=n CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=n +CONFIG_ARCH_CHIP_S32K3XX=y +CONFIG_BOARD_PWM_FREQ=1000000 CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4" CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" @@ -20,6 +22,7 @@ CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IRLOCK=y CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_ROBOCLAW=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_UAVCAN=y CONFIG_EXAMPLES_FAKE_GPS=y @@ -33,9 +36,10 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y @@ -50,8 +54,10 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y -CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y +CONFIG_MODULES_ROVER_MECANUM=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y diff --git a/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig b/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig index 45821d6c6f..c397305d7e 100644 --- a/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig +++ b/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig @@ -94,6 +94,7 @@ CONFIG_FAT_LFN_ALIAS_HASH=y CONFIG_FDCLONE_STDIO=y CONFIG_FS26_SPI_FREQUENCY=5000000 CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y @@ -126,16 +127,24 @@ CONFIG_LPUART0_IFLOWCONTROL=y CONFIG_LPUART0_OFLOWCONTROL=y CONFIG_LPUART0_RXBUFSIZE=640 CONFIG_LPUART0_RXDMA=y +CONFIG_LPUART0_TXBUFSIZE=1100 CONFIG_LPUART0_TXDMA=y CONFIG_LPUART13_RXDMA=y CONFIG_LPUART13_TXDMA=y CONFIG_LPUART14_RXDMA=y CONFIG_LPUART14_TXDMA=y +CONFIG_LPUART1_RXBUFSIZE=600 CONFIG_LPUART1_RXDMA=y +CONFIG_LPUART1_TXBUFSIZE=1100 CONFIG_LPUART1_TXDMA=y CONFIG_LPUART2_RXDMA=y CONFIG_LPUART2_SERIAL_CONSOLE=y CONFIG_LPUART2_TXDMA=y +CONFIG_LPUART4_RXBUFSIZE=600 +CONFIG_LPUART4_TXBUFSIZE=600 +CONFIG_LPUART7_RXDMA=y +CONFIG_LPUART7_TXBUFSIZE=1500 +CONFIG_LPUART7_TXDMA=y CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y @@ -197,6 +206,7 @@ CONFIG_NSH_LINELEN=128 CONFIG_NSH_MAXARGUMENTS=15 CONFIG_NSH_MMCSDSPIPORTNO=1 CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_READLINE=y CONFIG_NSH_QUOTE=y CONFIG_NSH_ROMFSETC=y CONFIG_NSH_ROMFSSECTSIZE=128 @@ -213,6 +223,8 @@ CONFIG_PTHREAD_STACK_MIN=512 CONFIG_RAM_SIZE=272000 CONFIG_RAM_START=0x20400000 CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y CONFIG_S32K3XX_DTCM_HEAP=y CONFIG_S32K3XX_EDMA=y CONFIG_S32K3XX_EDMA_EDBG=y @@ -280,7 +292,10 @@ CONFIG_STACK_COLORATION=y CONFIG_START_DAY=30 CONFIG_START_MONTH=11 CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_SYSTEM_CLE=y CONFIG_SYSTEM_DHCPC_RENEW=y CONFIG_SYSTEM_NSH=y CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y CONFIG_TASK_NAME_SIZE=24 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/nxp/mr-canhubk3/src/board_config.h b/boards/nxp/mr-canhubk3/src/board_config.h index 7ea2a91e8b..47f1ca3c36 100644 --- a/boards/nxp/mr-canhubk3/src/board_config.h +++ b/boards/nxp/mr-canhubk3/src/board_config.h @@ -112,7 +112,7 @@ __BEGIN_DECLS /* To detect MR-CANHUBK3-ADAP board */ #define BOARD_HAS_HW_VERSIONING 1 -#define CANHUBK3_ADAP_DETECT (PIN_PTA12 | GPIO_INPUT | GPIO_PULLUP) +#define CANHUBK3_ADAP_DETECT (PIN_PTA11 | GPIO_INPUT | GPIO_PULLUP) /* diff --git a/boards/nxp/mr-canhubk3/src/init.c b/boards/nxp/mr-canhubk3/src/init.c index 97a41f8430..15148c7845 100644 --- a/boards/nxp/mr-canhubk3/src/init.c +++ b/boards/nxp/mr-canhubk3/src/init.c @@ -105,18 +105,18 @@ __EXPORT int board_app_initialize(uintptr_t arg) /* Configure LPSPI1 peripheral chip select */ - s32k3xx_pinconfig(PIN_LPSPI2_PCS); + s32k3xx_pinconfig(PIN_LPSPI1_PCS); /* Initialize the SPI driver for LPSPI1 */ - struct spi_dev_s *g_lpspi2 = s32k3xx_lpspibus_initialize(2); + struct spi_dev_s *g_lpspi1 = s32k3xx_lpspibus_initialize(1); - if (g_lpspi2 == NULL) { - spierr("ERROR: FAILED to initialize LPSPI2\n"); + if (g_lpspi1 == NULL) { + spierr("ERROR: FAILED to initialize LPSPI1\n"); return -ENODEV; } - rv = mmcsd_spislotinitialize(0, 0, g_lpspi2); + rv = mmcsd_spislotinitialize(0, 0, g_lpspi1); if (rv < 0) { mcerr("ERROR: Failed to bind SPI port %d to SD slot %d\n", diff --git a/boards/nxp/mr-canhubk3/src/timer_config.cpp b/boards/nxp/mr-canhubk3/src/timer_config.cpp index 607917f614..24b29ca071 100644 --- a/boards/nxp/mr-canhubk3/src/timer_config.cpp +++ b/boards/nxp/mr-canhubk3/src/timer_config.cpp @@ -51,18 +51,25 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { - initIOTimer(Timer::EMIOS0) + initIOTimer(Timer::EMIOS0_Channel0, Timer::Channel0), + initIOTimer(Timer::EMIOS0_Channel1, Timer::Channel1), + initIOTimer(Timer::EMIOS0_Channel2, Timer::Channel2), + initIOTimer(Timer::EMIOS0_Channel3, Timer::Channel3), + initIOTimer(Timer::EMIOS0_Channel4, Timer::Channel4), + initIOTimer(Timer::EMIOS0_Channel5, Timer::Channel5), + initIOTimer(Timer::EMIOS0_Channel6, Timer::Channel6), + initIOTimer(Timer::EMIOS0_Channel7, Timer::Channel7), }; constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel0}, PIN_EMIOS0_CH0_1), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel1}, PIN_EMIOS0_CH1_1), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel2}, PIN_EMIOS0_CH2_1), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel3}, PIN_EMIOS0_CH3_2), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel4}, PIN_EMIOS0_CH4_2), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel5}, PIN_EMIOS0_CH5_2), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel6}, PIN_EMIOS0_CH6_1), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel7}, PIN_EMIOS0_CH7_2), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel0, Timer::Channel0}, PIN_EMIOS0_CH0_1), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel1, Timer::Channel1}, PIN_EMIOS0_CH1_1), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel2, Timer::Channel2}, PIN_EMIOS0_CH2_1), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel3, Timer::Channel3}, PIN_EMIOS0_CH3_2), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel4, Timer::Channel4}, PIN_EMIOS0_CH4_2), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel5, Timer::Channel5}, PIN_EMIOS0_CH5_2), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel6, Timer::Channel6}, PIN_EMIOS0_CH6_1), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel7, Timer::Channel7}, PIN_EMIOS0_CH7_2), }; constexpr io_timers_channel_mapping_t io_timers_channel_mapping = diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 98117afdc7..f10ad2d99a 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -22,7 +22,6 @@ CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GNSS_SEPTENTRIO=y -CONFIG_DRIVERS_GPIO_MCP23009=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y @@ -40,7 +39,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y -CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y CONFIG_DRIVERS_PWM_INPUT=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y diff --git a/boards/px4/fmu-v6x/init/rc.board_defaults b/boards/px4/fmu-v6x/init/rc.board_defaults index 2d9a6ea49a..7dfe7b546a 100644 --- a/boards/px4/fmu-v6x/init/rc.board_defaults +++ b/boards/px4/fmu-v6x/init/rc.board_defaults @@ -9,35 +9,13 @@ param set-default SENS_EN_INA238 0 param set-default SENS_EN_INA228 0 param set-default SENS_EN_INA226 0 -if ver hwbasecmp 009 010 011 -then - # Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client - param set-default UXRCE_DDS_PTCFG 2 - param set-default UXRCE_DDS_AG_IP 170461697 - param set-default UXRCE_DDS_CFG 1000 - - # The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). - param set-default CBRK_BUZZER 782097 -else - # Mavlink ethernet (CFG 1000) - param set-default MAV_2_CONFIG 1000 - param set-default MAV_2_BROADCAST 1 - param set-default MAV_2_MODE 0 - param set-default MAV_2_RADIO_CTL 0 - param set-default MAV_2_RATE 100000 - param set-default MAV_2_REMOTE_PRT 14550 - param set-default MAV_2_UDP_PRT 14550 -fi +# Mavlink ethernet (CFG 1000) +param set-default MAV_2_CONFIG 1000 +param set-default MAV_2_BROADCAST 1 +param set-default MAV_2_MODE 0 +param set-default MAV_2_RADIO_CTL 0 +param set-default MAV_2_RATE 100000 +param set-default MAV_2_REMOTE_PRT 14550 +param set-default MAV_2_UDP_PRT 14550 safety_button start - -# GPIO Expander driver on external I2C3 -if ver hwbasecmp 009 -then - # No USB - mcp23009 start -b 3 -X -D 0xf0 -O 0xf0 -P 0x0f -U 10 -fi -if ver hwbasecmp 00a 008 -then - mcp23009 start -b 3 -X -D 0xf1 -O 0xf0 -P 0x0f -U 10 -fi diff --git a/boards/px4/fmu-v6x/init/rc.board_mavlink b/boards/px4/fmu-v6x/init/rc.board_mavlink deleted file mode 100644 index 713d7a41b7..0000000000 --- a/boards/px4/fmu-v6x/init/rc.board_mavlink +++ /dev/null @@ -1,13 +0,0 @@ -#!/bin/sh -# -# PX4 FMUv6X specific board MAVLink startup script. -#------------------------------------------------------------------------------ - -# if skynode base board is detected start Mavlink on Telem2 -if ver hwbasecmp 009 010 011 -then - mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z - - # Ensure nothing else starts on TEL2 (ttyS4) - set PRT_TEL2_ 1 -fi diff --git a/boards/px4/fmu-v6x/init/rc.board_sensors b/boards/px4/fmu-v6x/init/rc.board_sensors index 100c674108..75eaba3d1c 100644 --- a/boards/px4/fmu-v6x/init/rc.board_sensors +++ b/boards/px4/fmu-v6x/init/rc.board_sensors @@ -55,22 +55,13 @@ then set INA_CONFIGURED yes fi -#Start Auterion Power Module selector for Skynode boards -if ver hwbasecmp 009 010 011 +if [ $INA_CONFIGURED = no ] then - pm_selector_auterion start - - # Auterion's INA238 uses a shunt value of 0.0003 instead of 0.0005. - param set-default INA238_SHUNT 0.0003 -else - if [ $INA_CONFIGURED = no ] + # INA226, INA228, INA238 auto-start + i2c_launcher start -b 1 + if [ $HAVE_PM2 = yes ] then - # INA226, INA228, INA238 auto-start - i2c_launcher start -b 1 - if [ $HAVE_PM2 = yes ] - then - i2c_launcher start -b 2 - fi + i2c_launcher start -b 2 fi fi @@ -96,33 +87,22 @@ else icm20649 -s -R 6 start else # Internal SPI BMI088 - if ver hwbasecmp 009 010 011 + if ver hwtypecmp V6X010 then - bmi088 -A -R 6 -s start - bmi088 -G -R 6 -s start + bmi088 -A -R 0 -s start + bmi088 -G -R 0 -s start else - if ver hwtypecmp V6X010 - then - bmi088 -A -R 0 -s start - bmi088 -G -R 0 -s start - else - bmi088 -A -R 4 -s start - bmi088 -G -R 4 -s start - fi + bmi088 -A -R 4 -s start + bmi088 -G -R 4 -s start fi fi # Internal SPI bus ICM42688p - if ver hwbasecmp 009 010 011 + if ver hwtypecmp V6X010 then - icm42688p -R 12 -s start + icm42688p -R 14 -s start else - if ver hwtypecmp V6X010 - then - icm42688p -R 14 -s start - else - icm42688p -R 6 -s start - fi + icm42688p -R 6 -s start fi if ver hwtypecmp V6X003 V6X004 @@ -130,13 +110,8 @@ else # Internal SPI bus ICM-42670-P (hard-mounted) icm42670p -R 10 -s start else - if ver hwbasecmp 009 010 011 - then - icm20602 -R 6 -s start - else - # Internal SPI bus ICM-20649 (hard-mounted) - icm20649 -R 14 -s start - fi + # Internal SPI bus ICM-20649 (hard-mounted) + icm20649 -R 14 -s start fi fi diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index f0a8d6ae86..ec6b1c7e2b 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -91,7 +91,6 @@ CONFIG_DEBUG_SYMBOLS=y CONFIG_DEBUG_TCBINFO=y CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 -CONFIG_DEV_GPIO=y CONFIG_DEV_PIPE_MAXSIZE=1024 CONFIG_DEV_PIPE_SIZE=70 CONFIG_DEV_URANDOM=y diff --git a/boards/px4/fmu-v6x/src/CMakeLists.txt b/boards/px4/fmu-v6x/src/CMakeLists.txt index 39ec808e1e..605cf16ac9 100644 --- a/boards/px4/fmu-v6x/src/CMakeLists.txt +++ b/boards/px4/fmu-v6x/src/CMakeLists.txt @@ -71,6 +71,5 @@ else() nuttx_arch # sdio nuttx_drivers # sdio px4_layer - platform_gpio_mcp23009 ) endif() diff --git a/boards/px4/fmu-v6x/src/board_config.h b/boards/px4/fmu-v6x/src/board_config.h index a57610545c..3259c421d5 100644 --- a/boards/px4/fmu-v6x/src/board_config.h +++ b/boards/px4/fmu-v6x/src/board_config.h @@ -270,11 +270,6 @@ #define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) #define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) -/* MCP23009 GPIO expander */ -#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpio4" -#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpio5" - - /* Spare GPIO */ #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) diff --git a/boards/px4/fmu-v6x/src/init.cpp b/boards/px4/fmu-v6x/src/init.cpp index d914b75497..5d2a614206 100644 --- a/boards/px4/fmu-v6x/src/init.cpp +++ b/boards/px4/fmu-v6x/src/init.cpp @@ -74,7 +74,6 @@ #include #include #include -#include /**************************************************************************** * Pre-Processor Definitions @@ -286,13 +285,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) # endif /* CONFIG_MMCSD */ - ret = mcp23009_register_gpios(3, 0x25); - - if (ret != OK) { - led_on(LED_RED); - return ret; - } - #endif /* !defined(BOOTLOADER) */ return OK; diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 84e76cd888..f64b7801e4 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -40,7 +40,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y -CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y CONFIG_COMMON_RC=y diff --git a/boards/px4/fmu-v6xrt/init/rc.board_sensors b/boards/px4/fmu-v6xrt/init/rc.board_sensors index ae60e13536..99248dde72 100644 --- a/boards/px4/fmu-v6xrt/init/rc.board_sensors +++ b/boards/px4/fmu-v6xrt/init/rc.board_sensors @@ -69,19 +69,13 @@ then set INA_CONFIGURED yes fi -#Start Auterion Power Module selector for Skynode boards -if ver hwbasecmp 009 010 +if [ $INA_CONFIGURED = no ] then - pm_selector_auterion start -else - if [ $INA_CONFIGURED = no ] + # INA226, INA228, INA238 auto-start + i2c_launcher start -b 1 + if [ $HAVE_PM2 = yes ] then - # INA226, INA228, INA238 auto-start - i2c_launcher start -b 1 - if [ $HAVE_PM2 = yes ] - then - i2c_launcher start -b 2 - fi + i2c_launcher start -b 2 fi fi diff --git a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig index 0ab458bed6..855c435833 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig @@ -78,7 +78,8 @@ CONFIG_HAVE_CXXINITIALIZE=y CONFIG_I2C=y CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=2048 -CONFIG_IMXRT_DTCM=0 +CONFIG_IMXRT_DTCM=256 +CONFIG_IMXRT_DTCM_HEAP=y CONFIG_IMXRT_EDMA=y CONFIG_IMXRT_EDMA_EDBG=y CONFIG_IMXRT_EDMA_ELINK=y @@ -104,7 +105,7 @@ CONFIG_IMXRT_GPIO6_0_15_IRQ=y CONFIG_IMXRT_GPIO6_16_31_IRQ=y CONFIG_IMXRT_GPIO_IRQ=y CONFIG_IMXRT_INIT_FLEXRAM=y -CONFIG_IMXRT_ITCM=0 +CONFIG_IMXRT_ITCM=256 CONFIG_IMXRT_LPI2C1=y CONFIG_IMXRT_LPI2C2=y CONFIG_IMXRT_LPI2C3=y @@ -190,6 +191,7 @@ CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y CONFIG_MMCSD_SDIO=y +CONFIG_MM_REGIONS=2 CONFIG_MTD=y CONFIG_MTD_BYTE_WRITE=y CONFIG_MTD_PARTITION=y diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld index 70d861f30a..f9eb6915d0 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld @@ -35,7 +35,7 @@ MEMORY { flash (rx) : ORIGIN = 0x30020000, LENGTH = 4M-128K /* We have 64M but we do not want to wait to program it all */ - sram (rwx) : ORIGIN = 0x20240000, LENGTH = 2M-256k-512k + sram (rwx) : ORIGIN = 0x20240000, LENGTH = 2M-256k itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 256K /* TODO FlexRAM partition */ dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 256K } @@ -83,6 +83,7 @@ SECTIONS _sitcmfuncs = ABSOLUTE(.); FILL(0xFF) . = 0x40 ; + *(.ram_vectors) INCLUDE "itcm_static_functions.ld" INCLUDE "itcm_functions_includes.ld" . = ALIGN(8); @@ -91,12 +92,6 @@ SECTIONS _fitcmfuncs = LOADADDR(.itcmfunc); - /* The RAM vector table (if present) should lie at the beginning of SRAM */ - - .ram_vectors (COPY) : { - *(.ram_vectors) - } > dtcm - .text : ALIGN(4) { _stext = ABSOLUTE(.); diff --git a/boards/svehicle/e2/CMakeLists.txt b/boards/svehicle/e2/CMakeLists.txt new file mode 100644 index 0000000000..8756f63e64 --- /dev/null +++ b/boards/svehicle/e2/CMakeLists.txt @@ -0,0 +1,34 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. 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. +# 3. Neither the name PX4 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 OWNER 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. +# +############################################################################ + +add_subdirectory(pwm_voltage) diff --git a/boards/svehicle/e2/bootloader.px4board b/boards/svehicle/e2/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/svehicle/e2/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/svehicle/e2/default.px4board b/boards/svehicle/e2/default.px4board new file mode 100644 index 0000000000..eecdbb4293 --- /dev/null +++ b/boards/svehicle/e2/default.px4board @@ -0,0 +1,99 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y +CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y +CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +#CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/svehicle/e2/extras/px4_io-v2_default.bin b/boards/svehicle/e2/extras/px4_io-v2_default.bin new file mode 100644 index 0000000000..145089ae0d Binary files /dev/null and b/boards/svehicle/e2/extras/px4_io-v2_default.bin differ diff --git a/boards/svehicle/e2/extras/svehicle_e2_bootloader.bin b/boards/svehicle/e2/extras/svehicle_e2_bootloader.bin new file mode 100644 index 0000000000..44df59e2be Binary files /dev/null and b/boards/svehicle/e2/extras/svehicle_e2_bootloader.bin differ diff --git a/boards/svehicle/e2/firmware.prototype b/boards/svehicle/e2/firmware.prototype new file mode 100644 index 0000000000..b515e66fdb --- /dev/null +++ b/boards/svehicle/e2/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 6110, + "magic": "PX4FWv1", + "description": "Firmware for the SVehicleE2 board", + "image": "", + "build_time": 0, + "summary": "SVehicleE2", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/svehicle/e2/init/rc.board_defaults b/boards/svehicle/e2/init/rc.board_defaults new file mode 100644 index 0000000000..12dbca66c7 --- /dev/null +++ b/boards/svehicle/e2/init/rc.board_defaults @@ -0,0 +1,29 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# By disabling all 3 INA modules, we use the +# i2c_launcher instead. +param set-default SENS_EN_INA238 0 +param set-default SENS_EN_INA228 0 +param set-default SENS_EN_INA226 0 + +# Mavlink ethernet (CFG 1000) +param set-default MAV_2_CONFIG 1000 +param set-default MAV_2_BROADCAST 1 +param set-default MAV_2_MODE 0 +param set-default MAV_2_RADIO_CTL 0 +param set-default MAV_2_RATE 100000 +param set-default MAV_2_REMOTE_PRT 14550 +param set-default MAV_2_UDP_PRT 14550 + +param set-default BAT1_V_DIV 21.5 +param set-default BAT1_A_PER_V 33.33 + +param set-default SENS_EXT_I2C_PRB 0 + +safety_button start + +# pwm voltage 3.3V/5V switch +pwm_voltage_apply start diff --git a/boards/svehicle/e2/init/rc.board_sensors b/boards/svehicle/e2/init/rc.board_sensors new file mode 100644 index 0000000000..2a7e1c08b3 --- /dev/null +++ b/boards/svehicle/e2/init/rc.board_sensors @@ -0,0 +1,34 @@ +#!/bin/sh +# +# SVehicle E2 specific board sensors init +#------------------------------------------------------------------------------ + +if param compare -s ADC_ADS1115_EN 1 +then + ads1115 start -X + board_adc start -n +else + board_adc start +fi + +if param compare SENS_EN_INA228 1 +then + # Start Digital power monitors + ina228 -X start +fi + +bmi088 -A -R 4 -s -b 3 start +bmi088 -G -R 4 -s -b 3 start + +icm42688p -R 6 -s start + +# Internal SPI bus ICM-20649 (hard-mounted) +icm20649 -R 14 -s start + +# Internal magnetometer on I2c +rm3100 -I -R 12 start + +bmm150 -I -R 4 start + +icp201xx -X start +icp201xx -I -a 0x64 start diff --git a/boards/svehicle/e2/nuttx-config/Kconfig b/boards/svehicle/e2/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/svehicle/e2/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/svehicle/e2/nuttx-config/bootloader/defconfig b/boards/svehicle/e2/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..d6db9a0c8b --- /dev/null +++ b/boards/svehicle/e2/nuttx-config/bootloader/defconfig @@ -0,0 +1,95 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/svehicle/e2/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="svehicle" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x41F8 +CONFIG_CDCACM_PRODUCTSTR="SVehicle BL E2.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x20A3 +CONFIG_CDCACM_VENDORSTR="SVehicle" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_UART5=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART5_RXBUFSIZE=512 +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=512 +CONFIG_UART5_TXDMA=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/svehicle/e2/nuttx-config/include/board.h b/boards/svehicle/e2/nuttx-config/include/board.h new file mode 100644 index 0000000000..5133175ff7 --- /dev/null +++ b/boards/svehicle/e2/nuttx-config/include/board.h @@ -0,0 +1,562 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6x/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 OWNER 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. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The px4_fmu-v6X board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 + +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The PX4 FMUV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +#undef GPIO_UART5_CTS +#define GPIO_UART5_CTS ((GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9) | GPIO_PULLDOWN) /* PC9 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS (GPIO_UART7_RTS_2 | GPIO_PULLDOWN) /* PF8 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is FRAM + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */ +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* The STM32 H7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 H7 BOARD DP83848TSQ/NOPB + * GPIO SIGNAL PIN NAME + * -------- ------------ ------------- + * PA7 ETH_CRS_DV CRS_DV + * PC1 ETH_MDC MDC + * PA2 ETH_MDIO MDIO + * PA1 ETH_REF_CL X1 + * PC4 ETH_RXD0 RX_D0 + * PC5 ETH_RXD1 RX_D1 + * PB11 ETH_TX_EN TX_EN + * PG13 ETH_TXD0 TX_D0 + * PG12 ETH_TXD1 TX_D1 + * + * The PHY address is 1, since COL/PHYAD0 features a pull up. + */ + +#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */ +#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */ +#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/svehicle/e2/nuttx-config/include/board_dma_map.h b/boards/svehicle/e2/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..1f45efc569 --- /dev/null +++ b/boards/svehicle/e2/nuttx-config/include/board_dma_map.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ + +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */ +//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ + +//#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA1:81 GPS2 */ +//#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA1:82 GPS2 */ + +// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned +// V + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ diff --git a/boards/svehicle/e2/nuttx-config/nsh/defconfig b/boards/svehicle/e2/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..6c6d9c6edb --- /dev/null +++ b/boards/svehicle/e2/nuttx-config/nsh/defconfig @@ -0,0 +1,330 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/svehicle/e2/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="svehicle" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x41F8 +CONFIG_CDCACM_PRODUCTSTR="SVehicle E2.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x20A3 +CONFIG_CDCACM_VENDORSTR="SVehicle" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_NACTIVESOCKETS=16 +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_TELNET=y +CONFIG_NSH_TELNET_LOGIN=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_ETHMAC=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PHYSR=31 +CONFIG_STM32H7_PHYSR_100MBPS=0x8 +CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10 +CONFIG_STM32H7_PHYSR_MODE=0x10 +CONFIG_STM32H7_PHYSR_SPEED=0x8 +CONFIG_STM32H7_PHY_POLLING=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_DHCPC_RENEW=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=10000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART7_TXDMA=y +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/svehicle/e2/nuttx-config/scripts/bootloader_script.ld b/boards/svehicle/e2/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..2e6eba3607 --- /dev/null +++ b/boards/svehicle/e2/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 OWNER 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. + * + ****************************************************************************/ + +/* The PX4 FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/svehicle/e2/nuttx-config/scripts/script.ld b/boards/svehicle/e2/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..b6b341d4e8 --- /dev/null +++ b/boards/svehicle/e2/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 OWNER 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. + * + ****************************************************************************/ + +/* The PX4 FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +EXTERN(board_get_manifest) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/svehicle/e2/pwm_voltage/CMakeLists.txt b/boards/svehicle/e2/pwm_voltage/CMakeLists.txt new file mode 100644 index 0000000000..6db1696208 --- /dev/null +++ b/boards/svehicle/e2/pwm_voltage/CMakeLists.txt @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. 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. +# 3. Neither the name PX4 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 OWNER 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. +# +############################################################################ + +px4_add_module( + MODULE modules__pwm_voltage_apply + MAIN pwm_voltage_apply + + SRCS + pwm_voltage.cpp + DEPENDS + px4_work_queue + ) diff --git a/boards/svehicle/e2/pwm_voltage/parameters.c b/boards/svehicle/e2/pwm_voltage/parameters.c new file mode 100644 index 0000000000..728bcc7a55 --- /dev/null +++ b/boards/svehicle/e2/pwm_voltage/parameters.c @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +/** + * Control PWM output voltage + * + * @value 0 3.3V + * @value 1 5.0V + * + * @reboot_required true + * @group PWM Outputs + */ +PARAM_DEFINE_INT32(PWM_VOLT_SEL, 0); diff --git a/boards/svehicle/e2/pwm_voltage/pwm_voltage.cpp b/boards/svehicle/e2/pwm_voltage/pwm_voltage.cpp new file mode 100644 index 0000000000..2bef9ae0f6 --- /dev/null +++ b/boards/svehicle/e2/pwm_voltage/pwm_voltage.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include +#include + +#include +#include + +#include "board_config.h" + +extern "C" int pwm_voltage_apply_main(int argc, char *argv[]) +{ + int32_t pwm_volt_sel = 0; + + param_get(param_find("PWM_VOLT_SEL"), &pwm_volt_sel); + + if (pwm_volt_sel != 0) { + PWM_5V_VOLT_SEL(true); + + } else { + PWM_5V_VOLT_SEL(false); + } + + return 0; +} diff --git a/boards/svehicle/e2/src/CMakeLists.txt b/boards/svehicle/e2/src/CMakeLists.txt new file mode 100644 index 0000000000..a120ebe336 --- /dev/null +++ b/boards/svehicle/e2/src/CMakeLists.txt @@ -0,0 +1,75 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. 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. +# 3. Neither the name PX4 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 OWNER 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.c + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) +endif() diff --git a/boards/svehicle/e2/src/board_config.h b/boards/svehicle/e2/src/board_config.h new file mode 100644 index 0000000000..98677855c9 --- /dev/null +++ b/boards/svehicle/e2/src/board_config.h @@ -0,0 +1,484 @@ +/**************************************************************************** + * + * Copyright (c) 2016-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 board_config.h + * + * PX4FMU-v6x internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* PX4IO connection configuration */ + +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS5" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks +#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid +#define BOARD_HAS_NBAT_V 2 // one is adc,another is Digital Voltage(iic or can) +#define BOARD_HAS_NBAT_I 2 // one is adc,another is Digital Current(iic or can) + +/* PX4FMU GPIOs ***********************************************************************************/ + +/* Trace Clock and D0-D3 are available on the trace connector + * + * TRACECLK PE2 - Dedicated - Trace Connector Pin 1 + * TRACED0 PE3 - nLED_RED - Trace Connector Pin 3 + * TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5 + * TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7 + * TRACED3 PE6 - nARMED - Trace Connector Pin 8 + + */ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +#if !defined(TRACE_PINS) +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +#else + +# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) +# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) +//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + +# undef BOARD_HAS_CONTROL_STATUS_LEDS +# undef BOARD_OVERLOAD_LED +# undef BOARD_ARMED_STATE_LED + +# define GPIO_nLED_RED GPIO_TRACED0 +# define GPIO_nLED_GREEN GPIO_TRACED1 +# define GPIO_nLED_BLUE GPIO_TRACED2 +# define GPIO_nARMED GPIO_TRACED3 +# define GPIO_nARMED_INIT GPIO_TRACED3 +#endif + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/ + +#define PX4_I2C_OBDEV_SE050 0x48 + +#define GPIO_I2C2_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. + * ADC3_6V6 and ADC3_3V3 are mapped back to ADC1 + * To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3 + * respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO + * PA0SO of 0. + * + * 0 Analog switch closed (pads are connected through the analog switch) + * + * So ADC3_INP0 is GPIO_ADC123_INP12 + * ADC3_INP1 is GPIO_ADC12_INP13 + */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ + +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PF12 */ ADC1_CH(6) +#define ADC_BATTERY_CURRENT_CHANNEL /* PB0 */ ADC1_CH(9) +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16) +#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_ADC3_6V6_CHANNEL /* PC2 */ ADC3_CH(12) +#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13) +#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15) + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_ADC3_6V6_CHANNEL) | \ + (1 << ADC_ADC3_3V3_CHANNEL)) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) + + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +// // /* HW Version and Revision drive signals Default to 1 to detect */ +// #define BOARD_HAS_HW_SPLIT_VERSIONING + +#define BOARD_HAS_STATIC_MANIFEST 1 + +#define PX4_MFT_HW_SUPPORTED_PX4_MFT_CAN2 1 + +#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15 +#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PE6 is nARMED + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#if !defined(TRACE_PINS) +#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6) +#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) +#endif + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 9 + +/* PWM Power */ +#define GPIO_PWM_VOLT_SEL /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN6) +#define PWM_5V_VOLT_SEL(on_true) px4_arch_gpiowrite(GPIO_PWM_VOLT_SEL, (on_true)) + +/* Power supply control and monitoring GPIOs */ + +#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) +#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */ +#define BOARD_NUMBER_BRICKS 1 +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */ + +#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SENSORS4_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8) +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) +#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true)) + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 14 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2 + +/* RC Serial port */ + +#define RC_SERIAL_PORT "/dev/ttyS5" +#define RC_SERIAL_SINGLEWIRE + +/* Input Capture Channels. */ +#define INPUT_CAP1_TIMER 1 +#define INPUT_CAP1_CHANNEL /* T1C2 */ 2 +#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT + +#define GPIO_SAFETY_SWITCH_IN /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * FMUv6X has a separate RC_IN + * + * GPIO PPM_IN on PI5 T8CH1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7 + * Inversion is possible in the UART and can drive GPIO PPM_IN as an output + */ + +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) + +/* FMUv6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + + +#define BOARD_ADC_BRICK_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_nPOWER_IN_C, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS4_EN, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_ETH_POWER_EN, \ + GPIO_NFC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_nARMED_INIT, \ + GPIO_PWM_VOLT_SEL \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_I2C_BUS_MTD 4,5 + + +#define BOARD_NUM_IO_TIMERS 5 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/svehicle/e2/src/bootloader_main.c b/boards/svehicle/e2/src/bootloader_main.c new file mode 100644 index 0000000000..77df9e78bc --- /dev/null +++ b/boards/svehicle/e2/src/bootloader_main.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2019-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/svehicle/e2/src/can.c b/boards/svehicle/e2/src/can.c new file mode 100644 index 0000000000..1f4e1f28a3 --- /dev/null +++ b/boards/svehicle/e2/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 px4fmu_can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/svehicle/e2/src/hw_config.h b/boards/svehicle/e2/src/hw_config.h new file mode 100644 index 0000000000..73d4ec88df --- /dev/null +++ b/boards/svehicle/e2/src/hw_config.h @@ -0,0 +1,128 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 6110 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)//1024 + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/svehicle/e2/src/i2c.cpp b/boards/svehicle/e2/src/i2c.cpp new file mode 100644 index 0000000000..8a557078e0 --- /dev/null +++ b/boards/svehicle/e2/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusExternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/svehicle/e2/src/init.c b/boards/svehicle/e2/src/init.c new file mode 100644 index 0000000000..585bb41d5e --- /dev/null +++ b/boards/svehicle/e2/src/init.c @@ -0,0 +1,276 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 init.c + * + * PX4FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + board_control_spi_sensors_power(true, 0xffff); + VDD_5V_PERIPH_EN(true); + +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); + + VDD_3V3_ETH_POWER_EN(true); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ +#if !defined(BOOTLOADER) + + /* Power on Interfaces */ + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS4_EN(true); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + // Use the default HW_VER_REV(0x0,0x0) for Ramtron + + stm32_spiinitialize(); + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +# if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +# endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +# ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +# endif /* CONFIG_MMCSD */ + +#endif /* !defined(BOOTLOADER) */ + + return OK; +} diff --git a/boards/svehicle/e2/src/led.c b/boards/svehicle/e2/src/led.c new file mode 100644 index 0000000000..bff4b09864 --- /dev/null +++ b/boards/svehicle/e2/src/led.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 px4fmu2_led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/svehicle/e2/src/mtd.cpp b/boards/svehicle/e2/src/mtd.cpp new file mode 100644 index 0000000000..d6c8278a24 --- /dev/null +++ b/boards/svehicle/e2/src/mtd.cpp @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include +#include + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(3, 0x51) +}; +static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(4, 0x50) +}; + + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi5, + .npart = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = (32768 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) + } + }, +}; + +static const px4_mtd_entry_t base_eeprom = { + .device = &i2c3, + .npart = 2, + .partd = { + { + .type = MTD_MFT_VER, + .path = "/fs/mtd_mft_ver", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + + } + }, +}; + +static const px4_mtd_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 3, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 240 + }, + { + .type = MTD_MFT_REV, + .path = "/fs/mtd_mft_rev", + .nblocks = 8 + }, + { + .type = MTD_ID, + .path = "/fs/mtd_id", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 3, + .entries = { + &fmum_fram, + &base_eeprom, + &imu_eeprom + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mtd_mft, + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/svehicle/e2/src/sdio.c b/boards/svehicle/e2/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/svehicle/e2/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 OWNER 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/svehicle/e2/src/spi.cpp b/boards/svehicle/e2/src/spi.cpp new file mode 100644 index 0000000000..d8609d65f8 --- /dev/null +++ b/boards/svehicle/e2/src/spi.cpp @@ -0,0 +1,58 @@ +/**************************************************************************** + * + * Copyright (C) 2020, 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/svehicle/e2/src/timer_config.cpp b/boards/svehicle/e2/src/timer_config.cpp new file mode 100644 index 0000000000..928f4916f0 --- /dev/null +++ b/boards/svehicle/e2/src/timer_config.cpp @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH2 T FMU_CAP1 < Capture + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + * TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer1), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/svehicle/e2/src/usb.c b/boards/svehicle/e2/src/usb.c new file mode 100644 index 0000000000..6d42476b71 --- /dev/null +++ b/boards/svehicle/e2/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name PX4 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 OWNER 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 px4fmu_usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/docs/.vitepress/config.mjs b/docs/.vitepress/config.mjs index 95831b347a..e9190be018 100644 --- a/docs/.vitepress/config.mjs +++ b/docs/.vitepress/config.mjs @@ -31,6 +31,7 @@ export default defineConfig({ tabsPlugin(md); //https://github.com/Red-Asuka/vitepress-plugin-tabs }, }, + cleanUrls: true, vite: { plugins: [ diff --git a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params index 2b611958b9..53b68cdeb4 100644 --- a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params +++ b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params @@ -571,7 +571,6 @@ 1 1 MAV_FWDEXTSP 1 6 1 1 MAV_HASH_CHK_EN 1 6 1 1 MAV_HB_FORW_EN 1 6 -1 1 MAV_PROTO_VER 0 6 1 1 MAV_RADIO_TOUT 5 6 1 1 MAV_SIK_RADIO_ID 0 6 1 1 MAV_SYS_ID 1 6 @@ -804,92 +803,74 @@ 1 1 PWM_MAIN_TIM1 400 6 1 1 PWM_MAIN_TIM2 -1 6 1 1 PWM_SBUS_MODE 0 6 -1 1 RC10_DZ 0.000000000000000000 9 1 1 RC10_MAX 2000.000000000000000000 9 1 1 RC10_MIN 1000.000000000000000000 9 1 1 RC10_REV 1.000000000000000000 9 1 1 RC10_TRIM 1500.000000000000000000 9 -1 1 RC11_DZ 0.000000000000000000 9 1 1 RC11_MAX 2000.000000000000000000 9 1 1 RC11_MIN 1000.000000000000000000 9 1 1 RC11_REV 1.000000000000000000 9 1 1 RC11_TRIM 1500.000000000000000000 9 -1 1 RC12_DZ 0.000000000000000000 9 1 1 RC12_MAX 2000.000000000000000000 9 1 1 RC12_MIN 1000.000000000000000000 9 1 1 RC12_REV 1.000000000000000000 9 1 1 RC12_TRIM 1500.000000000000000000 9 -1 1 RC13_DZ 0.000000000000000000 9 1 1 RC13_MAX 2000.000000000000000000 9 1 1 RC13_MIN 1000.000000000000000000 9 1 1 RC13_REV 1.000000000000000000 9 1 1 RC13_TRIM 1500.000000000000000000 9 -1 1 RC14_DZ 0.000000000000000000 9 1 1 RC14_MAX 2000.000000000000000000 9 1 1 RC14_MIN 1000.000000000000000000 9 1 1 RC14_REV 1.000000000000000000 9 1 1 RC14_TRIM 1500.000000000000000000 9 -1 1 RC15_DZ 0.000000000000000000 9 1 1 RC15_MAX 2000.000000000000000000 9 1 1 RC15_MIN 1000.000000000000000000 9 1 1 RC15_REV 1.000000000000000000 9 1 1 RC15_TRIM 1500.000000000000000000 9 -1 1 RC16_DZ 0.000000000000000000 9 1 1 RC16_MAX 2000.000000000000000000 9 1 1 RC16_MIN 1000.000000000000000000 9 1 1 RC16_REV 1.000000000000000000 9 1 1 RC16_TRIM 1500.000000000000000000 9 -1 1 RC17_DZ 0.000000000000000000 9 1 1 RC17_MAX 2000.000000000000000000 9 1 1 RC17_MIN 1000.000000000000000000 9 1 1 RC17_REV 1.000000000000000000 9 1 1 RC17_TRIM 1500.000000000000000000 9 -1 1 RC18_DZ 0.000000000000000000 9 1 1 RC18_MAX 2000.000000000000000000 9 1 1 RC18_MIN 1000.000000000000000000 9 1 1 RC18_REV 1.000000000000000000 9 1 1 RC18_TRIM 1500.000000000000000000 9 -1 1 RC1_DZ 10.000000000000000000 9 1 1 RC1_MAX 1996.000000000000000000 9 1 1 RC1_MIN 999.000000000000000000 9 1 1 RC1_REV 1.000000000000000000 9 1 1 RC1_TRIM 1498.000000000000000000 9 -1 1 RC2_DZ 10.000000000000000000 9 1 1 RC2_MAX 1998.000000000000000000 9 1 1 RC2_MIN 1000.000000000000000000 9 1 1 RC2_REV 1.000000000000000000 9 1 1 RC2_TRIM 1499.000000000000000000 9 -1 1 RC3_DZ 10.000000000000000000 9 1 1 RC3_MAX 1997.000000000000000000 9 1 1 RC3_MIN 1000.000000000000000000 9 1 1 RC3_REV 1.000000000000000000 9 1 1 RC3_TRIM 1000.000000000000000000 9 -1 1 RC4_DZ 10.000000000000000000 9 1 1 RC4_MAX 1997.000000000000000000 9 1 1 RC4_MIN 1000.000000000000000000 9 1 1 RC4_REV 1.000000000000000000 9 1 1 RC4_TRIM 1498.000000000000000000 9 -1 1 RC5_DZ 10.000000000000000000 9 1 1 RC5_MAX 2000.000000000000000000 9 1 1 RC5_MIN 1000.000000000000000000 9 1 1 RC5_REV 1.000000000000000000 9 1 1 RC5_TRIM 1500.000000000000000000 9 -1 1 RC6_DZ 10.000000000000000000 9 1 1 RC6_MAX 2000.000000000000000000 9 1 1 RC6_MIN 1000.000000000000000000 9 1 1 RC6_REV 1.000000000000000000 9 1 1 RC6_TRIM 1500.000000000000000000 9 -1 1 RC7_DZ 10.000000000000000000 9 1 1 RC7_MAX 2000.000000000000000000 9 1 1 RC7_MIN 1000.000000000000000000 9 1 1 RC7_REV 1.000000000000000000 9 1 1 RC7_TRIM 1500.000000000000000000 9 -1 1 RC8_DZ 10.000000000000000000 9 1 1 RC8_MAX 2000.000000000000000000 9 1 1 RC8_MIN 1000.000000000000000000 9 1 1 RC8_REV 1.000000000000000000 9 1 1 RC8_TRIM 1500.000000000000000000 9 -1 1 RC9_DZ 0.000000000000000000 9 1 1 RC9_MAX 2000.000000000000000000 9 1 1 RC9_MIN 1000.000000000000000000 9 1 1 RC9_REV 1.000000000000000000 9 diff --git a/docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png b/docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png deleted file mode 100644 index 1296d02ed8..0000000000 Binary files a/docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png and /dev/null differ diff --git a/docs/assets/flight_controller/svehicle_e2/back.jpeg b/docs/assets/flight_controller/svehicle_e2/back.jpeg new file mode 100644 index 0000000000..6e38b365bd Binary files /dev/null and b/docs/assets/flight_controller/svehicle_e2/back.jpeg differ diff --git a/docs/assets/flight_controller/svehicle_e2/left.png b/docs/assets/flight_controller/svehicle_e2/left.png new file mode 100644 index 0000000000..4b68dd0665 Binary files /dev/null and b/docs/assets/flight_controller/svehicle_e2/left.png differ diff --git a/docs/assets/flight_controller/svehicle_e2/main.png b/docs/assets/flight_controller/svehicle_e2/main.png new file mode 100644 index 0000000000..ea500e137e Binary files /dev/null and b/docs/assets/flight_controller/svehicle_e2/main.png differ diff --git a/docs/assets/flight_controller/svehicle_e2/right.png b/docs/assets/flight_controller/svehicle_e2/right.png new file mode 100644 index 0000000000..b6d8f66748 Binary files /dev/null and b/docs/assets/flight_controller/svehicle_e2/right.png differ diff --git a/docs/assets/flight_controller/svehicle_e2/top.png b/docs/assets/flight_controller/svehicle_e2/top.png new file mode 100644 index 0000000000..ff000e2b47 Binary files /dev/null and b/docs/assets/flight_controller/svehicle_e2/top.png differ diff --git a/docs/assets/hardware/sensors/inertial/microstrain_3dm_cv7_hbk.png b/docs/assets/hardware/sensors/inertial/microstrain_3dm_cv7_hbk.png new file mode 100644 index 0000000000..5670c47c82 Binary files /dev/null and b/docs/assets/hardware/sensors/inertial/microstrain_3dm_cv7_hbk.png differ diff --git a/docs/assets/middleware/zenoh/architecture-px4-zenoh.svg b/docs/assets/middleware/zenoh/architecture-px4-zenoh.svg new file mode 100644 index 0000000000..e3d0fcc2fe --- /dev/null +++ b/docs/assets/middleware/zenoh/architecture-px4-zenoh.svg @@ -0,0 +1,221 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Page-1 + + + + Rectangle + Zenoh RMW implementation rmw_zenoh + + + + + + + Zenoh RMW implementationrmw_zenoh + + Rectangle.2 + ROS Middleware (RMW) API + + + + + + + ROS Middleware (RMW) API + + Rectangle.4 + ROS 2 Node + + + + + + + ROS 2Node + + Rectangle.5 + ROS 2 Node + + + + + + + ROS 2Node + + Rectangle.6 + PX4 Zenoh-Pico Node + + + + + + + PX4 Zenoh-Pico Node + + Rectangle.7 + uORB Topic α + + + + + + + uORB Topic α + + Rectangle.8 + uORB Topic β + + + + + + + uORB Topic β + + Rectangle.9 + uORB Topic γ + + + + + + + uORB Topic γ + + Rectangle.10 + ROS2 Topic α + + + + + + + ROS2 Topic α + + Rectangle.11 + ROS2 Topic β + + + + + + + ROS2 Topic β + + Rectangle.12 + ROS2 Topic γ + + + + + + + ROS2 Topic γ + + Rectangle.18 + PX4 + + + + + + + PX4 + + Rectangle.19 + Zenoh Router zenohd + + + + + + + Zenoh Routerzenohd + + Rectangle.20 + Linux + + + + + + + Linux + + Dynamic connector + + + + Dynamic connector.22 + + + + Dynamic connector.23 + + + + Sheet.24 + UART TCP UDP + + + + UARTTCPUDP + + diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index c1913bf6f2..f6a2784c29 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -187,6 +187,7 @@ - [Radiolink PIX6](flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md) + - [SVehicle E2](flight_controller/svehicle_e2.md) - [ThePeach FCC-K1](flight_controller/thepeach_k1.md) - [ThePeach FCC-R1](flight_controller/thepeach_r1.md) - [Experimental Autopilots](flight_controller/autopilot_experimental.md) @@ -284,6 +285,7 @@ - [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](sensor/inertial_navigation_systems.md) - [InertialLabs](sensor/inertiallabs.md) + - [MicroStrain](sensor/microstrain.md) - [sbgECom](sensor/sbgecom.md) - [VectorNav](sensor/vectornav.md) - [Optical Flow](sensor/optical_flow.md) @@ -681,6 +683,7 @@ - [SensorCombined](msg_docs/SensorCombined.md) - [SensorCorrection](msg_docs/SensorCorrection.md) - [SensorGnssRelative](msg_docs/SensorGnssRelative.md) + - [SensorGnssStatus](msg_docs/SensorGnssStatus.md) - [SensorGps](msg_docs/SensorGps.md) - [SensorGyro](msg_docs/SensorGyro.md) - [SensorGyroFft](msg_docs/SensorGyroFft.md) @@ -742,6 +745,7 @@ - [Standard Modes Protocol](mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md) - [UORB Bridged to ROS 2](middleware/dds_topics.md) + - [Zenoh (PX4 ROS 2)](middleware/zenoh.md) - [Modules & Commands](modules/modules_main.md) - [Autotune](modules/modules_autotune.md) - [Commands](modules/modules_command.md) @@ -831,8 +835,10 @@ - [Test MC_04 - Failsafe Testing](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](test_cards/mc_10_optical_flow_gps_mixed.md) - [Unit Tests](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [Continuous Integration](test_and_ci/continous_integration.md) diff --git a/docs/en/_sidebar.md b/docs/en/_sidebar.md index 2d1ed64e69..390114db6a 100644 --- a/docs/en/_sidebar.md +++ b/docs/en/_sidebar.md @@ -1,5 +1,4 @@ - - [Introduction](/index.md) - [Basic Concepts](/getting_started/px4_basic_concepts.md) @@ -9,6 +8,7 @@ - [Position Mode (MC)](/flight_modes_mc/position.md) - [Position Slow Mode (MC)](/flight_modes_mc/position_slow.md) - [Altitude Mode (MC)](/flight_modes_mc/altitude.md) + - [Altitude Cruise Mode (MC)](/flight_modes_mc/altitude_cruise.md) - [Stabilized Mode (MC)](/flight_modes_mc/manual_stabilized.md) - [Acro Mode (MC)](/flight_modes_mc/acro.md) - [Orbit Mode (MC)](/flight_modes_mc/orbit.md) @@ -185,6 +185,7 @@ - [Wiring Quickstart](/assembly/quick_start_holybro_pix32_v5.md) - [ModalAI VOXL 2](/flight_controller/modalai_voxl_2.md) - [mRo Control Zero F7](/flight_controller/mro_control_zero_f7.md) + - [Radiolink PIX6](/flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](/flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](/flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](/flight_controller/thepeach_k1.md) @@ -284,6 +285,7 @@ - [CubePilot Here+ (Discontined)](/gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](/sensor/inertial_navigation_systems.md) - [InertialLabs](/sensor/inertiallabs.md) + - [sbgECom](/sensor/sbgecom.md) - [VectorNav](/sensor/vectornav.md) - [Optical Flow](/sensor/optical_flow.md) - [ARK Flow](/dronecan/ark_flow.md) @@ -415,6 +417,7 @@ - [Attitude Tuning](/config_rover/attitude_tuning.md) - [Velocity Tuning](/config_rover/velocity_tuning.md) - [Position Tuning](/config_rover/position_tuning.md) + - [Apps & API](/flight_modes_rover/api.md) - [Complete Vehicles](/complete_vehicles_rover/index.md) - [Aion Robotics R1](/complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](/frames_sub/index.md) @@ -829,8 +832,10 @@ - [Test MC_04 - Failsafe Testing](/test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](/test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](/test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](/test_cards/mc_10_optical_flow_gps_mixed.md) - [Unit Tests](/test_and_ci/unit_tests.md) - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [Continuous Integration](/test_and_ci/continous_integration.md) @@ -850,6 +855,7 @@ - [PX4 ROS 2 Interface Library](/ros2/px4_ros2_interface_lib.md) - [Control Interface](/ros2/px4_ros2_control_interface.md) - [Navigation Interface](/ros2/px4_ros2_navigation_interface.md) + - [Waypoint Missions](/ros2/px4_ros2_waypoint_missions.md) - [ROS 2 Message Translation Node](/ros2/px4_ros2_msg_translation_node.md) - [ROS 1 (Deprecated)](/ros/ros1.md) - [ROS/MAVROS Installation Guide](/ros/mavros_installation.md) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index 10c8b67f67..41db8563d2 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -14216,24 +14216,11 @@ Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. -Increase the amplitude of the injected signal using -FW_AT_SYSID_AMP for more signal/noise ratio | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | |   | | | | Disabled (0) | -### FW_AT_SYSID_AMP (`FLOAT`) {#FW_AT_SYSID_AMP} - -Amplitude of the injected signal. - -This parameter scales the signal sent to the -rate controller during system identification. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 6.0 | | 1.0 | - ### FW_AT_SYSID_F0 (`FLOAT`) {#FW_AT_SYSID_F0} Start frequency of the injected signal. @@ -14252,7 +14239,7 @@ Can be set lower or higher than the start frequency | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 30.0 | | 20. | Hz | +|   | 0.1 | 30.0 | | 10. | Hz | ### FW_AT_SYSID_TIME (`FLOAT`) {#FW_AT_SYSID_TIME} @@ -14278,7 +14265,7 @@ Type of signal used during system identification to excite the system. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | | | | 1 | ### MC_AT_APPLY (`INT32`) {#MC_AT_APPLY} @@ -16135,29 +16122,36 @@ The default value of 1000 requires the stick to be held in the arm or disarm pos ### COM_RC_IN_MODE (`INT32`) {#COM_RC_IN_MODE} -RC control input mode. +Manual control input source configuration. -A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. -A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. -A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. -A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. -A value of 4 ignores any stick input. -A value of 5 allows either RC Transmitter or Joystick input. But RC has priority and whenever avaiable is immedietely used. -A value of 6 allows either RC Transmitter or Joystick input. But Joystick has priority and whenever avaiable is immedietely used. +Selects stick input selection behavior: +either a traditional remote control receiver (RC) or a MAVLink joystick (MANUAL_CONTROL message) +Priority sources are immediately switched to whenever they get valid. +0 RC only. Requires valid RC calibration. +1 MAVLink only. RC and related checks are disabled. +2 Switches only if current source becomes invalid. +3 Locks to the first valid source until reboot. +4 Ignores all sources. +5 RC priority, then MAVLink (lower instance before higher) +6 MAVLink priority (lower instance before higher), then RC +7 RC priority, then MAVLink (higher instance before lower) +8 MAVLink priority (higher instance before lower), then RC **Values:** -- `0`: RC Transmitter only -- `1`: Joystick only -- `2`: RC and Joystick with fallback -- `3`: RC or Joystick keep first -- `4`: Stick input disabled -- `5`: RC priority, Joystick fallback -- `6`: Joystick priority, RC fallback +- `0`: RC only +- `1`: MAVLink only +- `2`: RC or MAVLink with fallback +- `3`: RC or MAVLink keep first +- `4`: Disable manual control +- `5`: Prio: RC > MAVL 1 > MAVL 2 +- `6`: Prio: MAVL 1 > MAVL 2 > RC +- `7`: Prio: RC > MAVL 2 > MAVL 1 +- `8`: Prio: MAVL 2 > MAVL 1 > RC | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 4 | | 3 | +|   | 0 | 8 | | 3 | ### COM_RC_LOSS_T (`FLOAT`) {#COM_RC_LOSS_T} @@ -17528,7 +17522,7 @@ If the vehicle is on ground, is not moving as determined by the motion test and | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | | | 0.1 | m | +|   | 0.01 | | | 0.01 | m | ### EKF2_MULTI_IMU (`INT32`) {#EKF2_MULTI_IMU} @@ -24402,13 +24396,12 @@ MAVLink protocol version. **Values:** -- `0`: Default to 1, switch to 2 if GCS sends version 2 -- `1`: Always use version 1 -- `2`: Always use version 2 +- `1`: Version 1 with auto-upgrade to v2 if detected +- `2`: Version 2 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | | | | 2 | ### MAV_RADIO_TOUT (`INT32`) {#MAV_RADIO_TOUT} @@ -24443,6 +24436,36 @@ MAVLink system ID. | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 1 | 250 | | 1 | +### MAV_S_FORWARD (`INT32`) {#MAV_S_FORWARD} + +Enable MAVLink forwarding on TELEM2. + +TELEM2 on Skynode only. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | + +### MAV_S_MODE (`INT32`) {#MAV_S_MODE} + +MAVLink Mode for SOM to FMU communication channel. + +The MAVLink Mode defines the set of streamed messages (for example the +vehicle's attitude) and their sending rates. + +**Values:** + +- `0`: Normal +- `2`: Onboard +- `5`: Config +- `7`: Minimal +- `11`: Onboard Low Bandwidth +- `13`: Low Bandwidth + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 11 | + ### MAV_TYPE (`INT32`) {#MAV_TYPE} MAVLink airframe type. @@ -26250,7 +26273,7 @@ Pitch rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = MC*PITCHRATE_K * (MC*PITCHRATE_P * error +output = MC_PITCHRATE_K _ (MC_PITCHRATE_P _ error - MC_PITCHRATE_I \* error_integral - MC_PITCHRATE_D \* error_derivative) @@ -26317,7 +26340,7 @@ Roll rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = MC*ROLLRATE_K * (MC*ROLLRATE_P * error +output = MC_ROLLRATE_K _ (MC_ROLLRATE_P _ error - MC_ROLLRATE_I \* error_integral - MC_ROLLRATE_D \* error_derivative) @@ -26384,7 +26407,7 @@ Yaw rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = MC*YAWRATE_K * (MC*YAWRATE_P * error +output = MC_YAWRATE_K _ (MC_YAWRATE_P _ error - MC_YAWRATE_I \* error_integral - MC_YAWRATE_D \* error_derivative) @@ -26618,7 +26641,7 @@ Thrust to motor control signal model parameter. Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. -The model is: rel*thrust = factor * rel*signal^2 + (1-factor) * rel_signal, +The model is: rel_thrust = factor _ rel_signal^2 + (1-factor) _ rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1. @@ -26792,16 +26815,6 @@ Select your RC input protocol or auto to scan. ## Radio Calibration -### RC10_DZ (`FLOAT`) {#RC10_DZ} - -RC channel 10 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC10_MAX (`FLOAT`) {#RC10_MAX} RC channel 10 maximum. @@ -26847,16 +26860,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC11_DZ (`FLOAT`) {#RC11_DZ} - -RC channel 11 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC11_MAX (`FLOAT`) {#RC11_MAX} RC channel 11 maximum. @@ -26902,16 +26905,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC12_DZ (`FLOAT`) {#RC12_DZ} - -RC channel 12 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC12_MAX (`FLOAT`) {#RC12_MAX} RC channel 12 maximum. @@ -26957,16 +26950,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC13_DZ (`FLOAT`) {#RC13_DZ} - -RC channel 13 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC13_MAX (`FLOAT`) {#RC13_MAX} RC channel 13 maximum. @@ -27012,16 +26995,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC14_DZ (`FLOAT`) {#RC14_DZ} - -RC channel 14 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC14_MAX (`FLOAT`) {#RC14_MAX} RC channel 14 maximum. @@ -27067,16 +27040,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC15_DZ (`FLOAT`) {#RC15_DZ} - -RC channel 15 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC15_MAX (`FLOAT`) {#RC15_MAX} RC channel 15 maximum. @@ -27122,16 +27085,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC16_DZ (`FLOAT`) {#RC16_DZ} - -RC channel 16 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC16_MAX (`FLOAT`) {#RC16_MAX} RC channel 16 maximum. @@ -27177,16 +27130,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC17_DZ (`FLOAT`) {#RC17_DZ} - -RC channel 17 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC17_MAX (`FLOAT`) {#RC17_MAX} RC channel 17 maximum. @@ -27232,16 +27175,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC18_DZ (`FLOAT`) {#RC18_DZ} - -RC channel 18 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC18_MAX (`FLOAT`) {#RC18_MAX} RC channel 18 maximum. @@ -27287,16 +27220,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC1_DZ (`FLOAT`) {#RC1_DZ} - -RC channel 1 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 10.0 | us | - ### RC1_MAX (`FLOAT`) {#RC1_MAX} RC channel 1 maximum. @@ -27342,16 +27265,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500.0 | us | -### RC2_DZ (`FLOAT`) {#RC2_DZ} - -RC channel 2 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 10.0 | us | - ### RC2_MAX (`FLOAT`) {#RC2_MAX} RC channel 2 maximum. @@ -27397,16 +27310,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500.0 | us | -### RC3_DZ (`FLOAT`) {#RC3_DZ} - -RC channel 3 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 10.0 | us | - ### RC3_MAX (`FLOAT`) {#RC3_MAX} RC channel 3 maximum. @@ -27452,16 +27355,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC4_DZ (`FLOAT`) {#RC4_DZ} - -RC channel 4 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 10.0 | us | - ### RC4_MAX (`FLOAT`) {#RC4_MAX} RC channel 4 maximum. @@ -27507,16 +27400,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC5_DZ (`FLOAT`) {#RC5_DZ} - -RC channel 5 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 10.0 | - ### RC5_MAX (`FLOAT`) {#RC5_MAX} RC channel 5 maximum. @@ -27562,16 +27445,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC6_DZ (`FLOAT`) {#RC6_DZ} - -RC channel 6 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 10.0 | - ### RC6_MAX (`FLOAT`) {#RC6_MAX} RC channel 6 maximum. @@ -27617,16 +27490,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC7_DZ (`FLOAT`) {#RC7_DZ} - -RC channel 7 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 10.0 | - ### RC7_MAX (`FLOAT`) {#RC7_MAX} RC channel 7 maximum. @@ -27672,16 +27535,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC8_DZ (`FLOAT`) {#RC8_DZ} - -RC channel 8 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 10.0 | - ### RC8_MAX (`FLOAT`) {#RC8_MAX} RC channel 8 maximum. @@ -27727,16 +27580,6 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC9_DZ (`FLOAT`) {#RC9_DZ} - -RC channel 9 dead zone. - -The +- range of this value around the trim value will be considered as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 0.0 | - ### RC9_MAX (`FLOAT`) {#RC9_MAX} RC channel 9 maximum. @@ -29482,7 +29325,7 @@ Proportional gain for ground speed controller. Tuning parameter for the speed reduction based on the course error. -Reduced*speed = RO_MAX_THR_SPEED * (1 - normalized*course_error * RO_SPEED_RED) +Reduced_speed = RO_MAX_THR_SPEED _ (1 - normalized_course_error _ RO_SPEED_RED) The normalized course error is the angle between the current course and the bearing setpoint interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction. @@ -29596,10 +29439,7 @@ Selects the algorithm used for logfile encryption Logging Backend (integer bitmask). -If no logging is set the logger will not be started. -Set bits true to enable: -0: SD card logging -1: Mavlink logging +If no logging is set the logger will not be started. Set bits true to enable: 0: SD card logging 1: Mavlink logging **Bitmask:** @@ -29614,11 +29454,7 @@ Set bits true to enable: Battery-only Logging. -When enabled, logging will not start from boot if battery power is not detected -(e.g. powered via USB on a test bench). This prevents extraneous flight logs from -being created during bench testing. -Note that this only applies to log-from-boot modes. This has no effect on arm-based -modes. +When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -29628,13 +29464,7 @@ modes. Maximum number of log directories to keep. -If there are more log directories than this value, -the system will delete the oldest directories during startup. -In addition, the system will delete old logs if there is not enough free space left. -The minimum amount is 300 MB. -If this is set to 0, old directories will only be removed if the free space falls below -the minimum. -Note: this does not apply to mission log files. +If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -29644,9 +29474,7 @@ Note: this does not apply to mission log files. Logfile Encryption key exchange key. -If the logfile is encrypted using a symmetric key algorithm, -the used encryption key is generated at logging start and stored -on the sdcard RSA2048 encrypted using this key. +If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -29656,12 +29484,7 @@ on the sdcard RSA2048 encrypted using this key. Logfile Encryption key index. -Selects the key in keystore, used for encrypting the log. When using -a symmetric encryption algorithm, the key is generated at logging start -and kept stored in this index. For symmetric algorithms, the key is -volatile and valid only for the duration of logging. The key is stored -in encrypted format on the sdcard alongside the logfile, using an RSA2048 -key defined by the SDLOG_EXCHANGE_KEY +Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -29671,14 +29494,7 @@ key defined by the SDLOG_EXCHANGE_KEY Mission Log. -If enabled, a small additional "mission" log file will be written to the SD card. -The log contains just those messages that are useful for tasks like -generating flight statistics and geotagging. -The different modes can be used to further reduce the logged data -(and thus the log file size). For example, choose geotagging mode to -only log data required for geotagging. -Note that the normal/full log is still created, and contains all -the data in the mission log (and more). +If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). **Values:** @@ -29694,11 +29510,7 @@ the data in the mission log (and more). Logging Mode. -Determines when to start and stop logging. By default, logging is started -when arming the system, and stopped when disarming. -Note: The logging start/end points that can be configured here only apply to -SD logging. The mavlink backend is started/stopped independently -of these points. +Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. Note: The logging start/end points that can be configured here only apply to SD logging. The mavlink backend is started/stopped independently of these points. **Values:** @@ -29716,23 +29528,7 @@ of these points. Logging topic profile (integer bitmask). -This integer bitmask controls the set and rates of logged topics. -The default allows for general log analysis while keeping the -log file size reasonably small. -Enabling multiple sets leads to higher bandwidth requirements and larger log -files. -Set bits true to enable: -0 : Default set (used for general log analysis) -1 : Full rate estimator (EKF2) replay topics -2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) -3 : Topics for system identification (high rate actuator control and IMU data) -4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) -5 : Debugging topics (debug\_\*.msg topics, for custom code) -6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) -7 : Topics for computer vision and collision prevention -8 : Raw FIFO high-rate IMU (Gyro) -9 : Raw FIFO high-rate IMU (Accel) -10: Logging of mavlink tunnel message (useful for payload communication debugging) +This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug\_\*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging) **Bitmask:** @@ -29757,11 +29553,7 @@ Set bits true to enable: UTC offset (unit: min). -the difference in hours and minutes from Coordinated -Universal Time (UTC) for a your place and date. -for example, In case of South Korea(UTC+09:00), -UTC offset is 540 min (9\*60) -refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets +the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9\*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -32374,331 +32166,423 @@ INA238 Power Monitor Shunt. ### MS_ACCEL_RANGE (`INT32`) {#MS_ACCEL_RANGE} -Sets the range of the accelerometer. +MicroStrain accelerometer range. --1 = Will not be configured, and will use the device default range, -Each adjustable range has a corresponding integer setting. Refer to the device's User Manual to check the available adjustment ranges. -https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com -Restart required -This parameter is specific to the MicroStrain driver. +-1 = Will not be configured, and will use the device default range. +Ranges vary by device and map to integer codes. Check the device's [User Manual](https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com) for supported ranges and set the corresponding integer. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | -1 | ### MS_ALIGNMENT (`INT32`) {#MS_ALIGNMENT} -Alignment type. +MicroStrain heading alignment type. -Select the source of heading alignment -This is a bitfield, you can use more than 1 source -Bit 0 - Dual-antenna GNSS -Bit 1 - GNSS kinematic (requires motion, e.g. a GNSS velocity) -Bit 2 - Magnetometer -Bit 3 - External Heading (first valid external heading will be used to initialize the filter) -Restart required -This parameter is specific to the MicroStrain driver. +Select the source of heading alignment. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 2 | +**Bitmask:** + +- `0`: Dual-antenna GNSS +- `1`: GNSS kinematic (requires motion, e.g. a GNSS velocity) +- `2`: Magnetometer +- `3`: External Heading (first valid external heading will be used to initialize the filter) + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 1 | 15 | | 2 | ### MS_BARO_RATE_HZ (`INT32`) {#MS_BARO_RATE_HZ} -Barometer data rate. +MicroStrain barometer data rate. -Barometer data rate -Max Limit: 1000 -0 - Disable barometer datastream -The max limit should be divisible by the rate -eg: 1000 % MS_BARO_RATE_HZ = 0 -Restart required -This parameter is specific to the MicroStrain driver. +Barometer data rate (Hz). +Valid rates: 0 or any factor of 1000. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 50 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1000 | | 50 | + +### MS_EHEAD_YAW (`FLOAT`) {#MS_EHEAD_YAW} + +MicroStrain External Heading Orientation (Yaw). + +The orientation of the device (Radians) with respect to the vehicle frame around the z axis. +Requires MS_EXT_HEAD_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | + +### MS_EMAG_PTCH (`FLOAT`) {#MS_EMAG_PTCH} + +MicroStrain External Magnetometer Orientation (Pitch). + +The orientation of the device (Radians) with respect to the vehicle frame around the y axis. +Requires MS_EXT_MAG_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | + +### MS_EMAG_ROLL (`FLOAT`) {#MS_EMAG_ROLL} + +MicroStrain External Magnetometer Orientation (Roll). + +The orientation of the device (Radians) with respect to the vehicle frame around the x axis. +Requires MS_EXT_MAG_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | + +### MS_EMAG_UNCERT (`FLOAT`) {#MS_EMAG_UNCERT} + +MicroStrain external magnetometer uncertainty. + +The 1-sigma uncertainty (in Gauss) for all axes, which will remain constant across all aiding measurements. +Requires MS_EXT_MAG_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.1 | + +### MS_EMAG_YAW (`FLOAT`) {#MS_EMAG_YAW} + +MicroStrain External Magnetometer Orientation (Yaw). + +The orientation of the device (Radians) with respect to the vehicle frame around the z axis. +Requires MS_EXT_MAG_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_EXT_HEAD_EN (`INT32`) {#MS_EXT_HEAD_EN} +Enable MicroStrain external heading aiding. + Toggles external heading as an aiding measurement. - -0 = Disabled, -1 = Enabled If enabled, the filter will be configured to accept external heading as an aiding meaurement. -Restart required -This parameter is specific to the MicroStrain driver. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + +### MS_EXT_MAG_EN (`INT32`) {#MS_EXT_MAG_EN} + +Enable MicroStrain external magnetometer aiding. + +Toggles external magnetometer aiding in the device filter. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | ### MS_FILT_RATE_HZ (`INT32`) {#MS_FILT_RATE_HZ} -EKF data Rate. +MicroStrain EKF data rate. -EKF data rate -Max Limit: 1000 -0 - Disable EKF datastream -The max limit should be divisible by the rate -eg: 1000 % MS_FILT_RATE_HZ = 0 -Restart required -This parameter is specific to the MicroStrain driver. +The rate at which the INS data is published (Hz). +Valid rates: 0 or any factor of 1000. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 250 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1000 | | 250 | ### MS_GNSS_AID_SRC (`INT32`) {#MS_GNSS_AID_SRC} -GNSS aiding source control. +MicroStrain GNSS aiding source control. -Select the source of gnss aiding (GNSS/INS) -1 = All internal receivers, -2 = External GNSS messages, -3 = GNSS receiver 1 only -4 = GNSS receiver 2 only -Restart required -This parameter is specific to the MicroStrain driver. +Select the source of gnss aiding (GNSS/INS). -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 1 | +**Values:** + +- `1`: All internal receivers +- `2`: External GNSS messages +- `3`: GNSS receiver 1 only +- `4`: GNSS receiver 2 only + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 1 | ### MS_GNSS_OFF1_X (`FLOAT`) {#MS_GNSS_OFF1_X} -GNSS lever arm offset 1 (X). +MicroStrain GNSS lever arm offset 1 (X). -Lever arm offset (m) in the X direction for the external GNSS receiver -In the case of a dual antenna setup, this is antenna 1 -Restart required -This parameter is specific to the MicroStrain driver. +Lever arm offset (m) in the X direction for the external GNSS receiver. +In the case of a dual antenna setup, this is antenna 1. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_GNSS_OFF1_Y (`FLOAT`) {#MS_GNSS_OFF1_Y} -GNSS lever arm offset 1 (Y). +MicroStrain GNSS lever arm offset 1 (Y). -Lever arm offset (m) in the Y direction for the external GNSS receiver -In the case of a dual antenna setup, this is antenna 1 -Restart required -This parameter is specific to the MicroStrain driver. +Lever arm offset (m) in the Y direction for the external GNSS receiver. +In the case of a dual antenna setup, this is antenna 1. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_GNSS_OFF1_Z (`FLOAT`) {#MS_GNSS_OFF1_Z} -GNSS lever arm offset 1 (Z). +MicroStrain GNSS lever arm offset 1 (Z). -Lever arm offset (m) in the Z direction for the external GNSS receiver -In the case of a dual antenna setup, this is antenna 1 -Restart required -This parameter is specific to the MicroStrain driver. +Lever arm offset (m) in the Z direction for the external GNSS receiver. +In the case of a dual antenna setup, this is antenna 1. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_GNSS_OFF2_X (`FLOAT`) {#MS_GNSS_OFF2_X} -GNSS lever arm offset 2 (X). +MicroStrain GNSS lever arm offset 2 (X). Lever arm offset (m) in the X direction for antenna 2 -This will only be used if the device supports a dual antenna setup -Restart required -This parameter is specific to the MicroStrain driver. +This will only be used if the device supports a dual antenna setup. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_GNSS_OFF2_Y (`FLOAT`) {#MS_GNSS_OFF2_Y} -GNSS lever arm offset 2 (Y). +MicroStrain GNSS lever arm offset 2 (Y). -Lever arm offset (m) in the Y direction for antenna 2 -This will only be used if the device supports a dual antenna setup -Restart required -This parameter is specific to the MicroStrain driver. +Lever arm offset (m) in the Y direction for antenna 2. +This will only be used if the device supports a dual antenna setup. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_GNSS_OFF2_Z (`FLOAT`) {#MS_GNSS_OFF2_Z} -GNSS lever arm offset 2 (Z). +MicroStrain GNSS lever arm offset 2 (Z). -Lever arm offset (m) in the X direction for antenna 2 -This will only be used if the device supports a dual antenna setup -Restart required -This parameter is specific to the MicroStrain driver. +Lever arm offset (m) in the X direction for antenna 2. +This will only be used if the device supports a dual antenna setup. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_GNSS_RATE_HZ (`INT32`) {#MS_GNSS_RATE_HZ} -GNSS data Rate. +MicroStrain GNSS data rate. -GNSS receiver 1 and 2 data rate -Max Limit: 5 -The max limit should be divisible by the rate -0 - Disable GNSS datastream -eg: 5 % MS_GNSS_RATE_HZ = 0 -Restart required -This parameter is specific to the MicroStrain driver. +GNSS receiver 1 and 2 data rate (Hz). +Valid rates: 0, 1 or 5. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 5 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 5 | | 5 | ### MS_GYRO_RANGE (`INT32`) {#MS_GYRO_RANGE} -Sets the range of the gyro. +MicroStrain gyroscope range. --1 = Will not be configured, and will use the device default range, -Each adjustable range has a corresponding integer setting. Refer to the device's User Manual to check the available adjustment ranges. -https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com -Restart required -This parameter is specific to the MicroStrain driver. +-1 = Will not be configured, and will use the device default range. +Ranges vary by device and map to integer codes. Check the device's [User Manual](https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com) for supported ranges and set the corresponding integer. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | -1 | ### MS_IMU_RATE_HZ (`INT32`) {#MS_IMU_RATE_HZ} -IMU Data Rate. +MicroStrain IMU data rate. -IMU (Accelerometer and Gyroscope) data rate -The INS driver will be scheduled at a rate 2\*MS_IMU_RATE_HZ -Max Limit: 1000 -0 - Disable IMU datastream -The max limit should be divisible by the rate -eg: 1000 % MS_IMU_RATE_HZ = 0 -Restart required -This parameter is specific to the MicroStrain driver. +Accelerometer and Gyroscope data rate (Hz). +Valid rates: 0 or any factor of 1000. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 500 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1000 | | 500 | ### MS_INT_HEAD_EN (`INT32`) {#MS_INT_HEAD_EN} +Enable MicroStrain internal heading aiding. + Toggles internal heading as an aiding measurement. - -0 = Disabled, -1 = Enabled If dual antennas are supported (CV7-GNSS/INS). The filter will be configured to use dual antenna heading as an aiding measurement. -Restart required -This parameter is specific to the MicroStrain driver. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | ### MS_INT_MAG_EN (`INT32`) {#MS_INT_MAG_EN} +Enable MicroStrain internal magnetometer. + Toggles internal magnetometer aiding in the device filter. -0 = Disabled, -1 = Enabled -Restart required -This parameter is specific to the MicroStrain driver. +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | ### MS_MAG_RATE_HZ (`INT32`) {#MS_MAG_RATE_HZ} -Magnetometer Data Rate. +MicroStrain magnetometer data rate. -Magnetometer data rate -Max Limit: 1000 -0 - Disable magnetometer datastream -The max limit should be divisible by the rate -eg: 1000 % MS_MAG_RATE_HZ = 0 -Restart required -This parameter is specific to the MicroStrain driver. +Magnetometer data rate (Hz). +Valid rates: 0 or any factor of 1000. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 50 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1000 | | 50 | ### MS_MODE (`INT32`) {#MS_MODE} -Toggles using the device as the primary EKF. +MicroStrain device mode. -Setting to 1 will publish data from the device to the vehicle topics (global_position, attitude, local_position, odometry), estimator_status and sensor_selection -Setting to 0 will publish data from the device to the external_ins topics (global position, attitude, local position) -Restart Required -This parameter is specific to the MicroStrain driver. +Sensor mode publishes raw IMU data to be used by EKF2. INS data from the device is published to the external INS topics. +INS mode publishes the INS data to the vehicle topics to be used for navigation. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 1 | +**Values:** + +- `0`: Sensor Mode +- `1`: INS Mode + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + +### MS_OFLW_OFF_X (`FLOAT`) {#MS_OFLW_OFF_X} + +MicroStrain optical flow offset (X). + +Offset (m) in the X direction if an Optical Flow sensor is connected. +Requires MS_OPT_FLOW_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | + +### MS_OFLW_OFF_Y (`FLOAT`) {#MS_OFLW_OFF_Y} + +MicroStrain optical flow offset (Y). + +Offset (m) in the Y direction if an Optical Flow sensor is connected. +Requires MS_OPT_FLOW_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | + +### MS_OFLW_OFF_Z (`FLOAT`) {#MS_OFLW_OFF_Z} + +MicroStrain optical flow offset (Z). + +Offset (m) in the Z direction if an Optical Flow sensor is connected. +Requires MS_OPT_FLOW_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | + +### MS_OFLW_UNCERT (`FLOAT`) {#MS_OFLW_UNCERT} + +MicroStrain optical flow uncertainty. + +The 1-sigma uncertainty (in m/s) for the X and Y axes, which will remain constant across all aiding measurements. +The Z axis is not used for aiding. +Requires MS_OPT_FLOW_EN to be enabled to be used. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.1 | + +### MS_OPT_FLOW_EN (`INT32`) {#MS_OPT_FLOW_EN} + +Enable MicroStrain optical flow aiding. + +Toggles body frame velocity as an aiding measurement. +The driver uses the body frame velocity from the optical flow sensor as the aiding measurements. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | ### MS_SENSOR_PTCH (`FLOAT`) {#MS_SENSOR_PTCH} -Sensor to Vehicle Transform (Pitch). +MicroStrain Sensor to Vehicle Transform (Pitch). -The orientation of the device (Radians) with respect to the vehicle frame around the y axis -Requires MS_SVT_EN to be enabled to be used -Restart required -This parameter is specific to the MicroStrain driver. +The orientation of the device (Radians) with respect to the vehicle frame around the y axis. +Requires MS_SVT_EN to be enabled to be used. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_SENSOR_ROLL (`FLOAT`) {#MS_SENSOR_ROLL} -Sensor to Vehicle Transform (Roll). +MicroStrain Sensor to vehicle transform (Roll). -The orientation of the device (Radians) with respect to the vehicle frame around the x axis -Requires MS_SVT_EN to be enabled to be used -Restart required -This parameter is specific to the MicroStrain driver. +The orientation of the device (Radians) with respect to the vehicle frame around the x axis. +Requires MS_SVT_EN to be enabled to be used. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_SENSOR_YAW (`FLOAT`) {#MS_SENSOR_YAW} -Sensor to Vehicle Transform (Yaw). +MicroStrain Sensor to Vehicle Transform (Yaw). -The orientation of the device (Radians) with respect to the vehicle frame around the z axis -Requires MS_SVT_EN to be enabled to be used -Restart required -This parameter is specific to the MicroStrain driver. +The orientation of the device (Radians) with respect to the vehicle frame around the z axis. +Requires MS_SVT_EN to be enabled to be used. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0.0 | ### MS_SVT_EN (`INT32`) {#MS_SVT_EN} -Enables sensor to vehicle transform. +Enables Microstrain sensor to vehicle transform. -0 = Disabled, -1 = Enabled If the sensor has a different orientation with respect to the vehicle. This will enable a transform to correct itself. -The transform is described by MS_SENSOR_ROLL, MS_SENSOR_PITCH, MS_SENSOR_YAW -Restart required -This parameter is specific to the MicroStrain driver. +The transform is described by MS_SENSOR_ROLL, MS_SENSOR_PITCH, MS_SENSOR_YAW. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | ### PCF8583_MAGNET (`INT32`) {#PCF8583_MAGNET} @@ -33366,7 +33250,7 @@ Lightware SF1xx/SF20/LW20 laser rangefinder (i2c). | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 6 | | 0 | +| ✓ | 0 | 7 | | 0 | ### SENS_EN_SF45_CFG (`INT32`) {#SENS_EN_SF45_CFG} @@ -34299,6 +34183,31 @@ This parameter defines the rotation of the Mappydot sensor relative to the platf | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 0 | 7 | | 0 | +### SENS_MS_CFG (`INT32`) {#SENS_MS_CFG} + +Serial Configuration for MICROSTRAIN. + +Configure on which serial port to run MICROSTRAIN. + +**Values:** + +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + ### SENS_OR_ADIS164X (`INT32`) {#SENS_OR_ADIS164X} Analog Devices ADIS16448 IMU Orientation(external SPI). @@ -36261,7 +36170,7 @@ Pitch rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = SC*PITCHRATE_K * (SC*PITCHRATE_P * error +output = SC_PITCHRATE_K _ (SC_PITCHRATE_P _ error - SC_PITCHRATE_I \* error_integral - SC_PITCHRATE_D \* error_derivative) @@ -36328,7 +36237,7 @@ Roll rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = SC*ROLLRATE_K * (SC*ROLLRATE_P * error +output = SC_ROLLRATE_K _ (SC_ROLLRATE_P _ error - SC_ROLLRATE_I \* error_integral - SC_ROLLRATE_D \* error_derivative) @@ -36395,7 +36304,7 @@ Yaw rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = SC*YAWRATE_K * (SC*YAWRATE_P * error +output = SC_YAWRATE_K _ (SC_YAWRATE_P _ error - SC_YAWRATE_I \* error_integral - SC_YAWRATE_D \* error_derivative) diff --git a/docs/en/airframes/airframe_reference.md b/docs/en/airframes/airframe_reference.md index fdcefc78d9..2067c8f6a5 100644 --- a/docs/en/airframes/airframe_reference.md +++ b/docs/en/airframes/airframe_reference.md @@ -615,6 +615,10 @@ div.frame_variant td, div.frame_variant th { Axial SCX10 2 Trail Honcho Maintainer: John Doe <john@example.com>

SYS_AUTOSTART = 51001

+ + NXP B3RB Rover Ackermann + Maintainer: John Doe <john@example.com>

SYS_AUTOSTART = 51002

+ Generic Rover Mecanum Maintainer: John Doe <john@example.com>

SYS_AUTOSTART = 52000

diff --git a/docs/en/concept/system_startup.md b/docs/en/concept/system_startup.md index 4ef80d0de1..d425d35173 100644 --- a/docs/en/concept/system_startup.md +++ b/docs/en/concept/system_startup.md @@ -1,7 +1,7 @@ # System Startup The PX4 startup is controlled by shell scripts. -On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/MacOS). +On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/macOS). The scripts that are only used on Posix are located in [ROMFS/px4fmu_common/init.d-posix](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d-posix). All files starting with a number and underscore (e.g. `10000_airplane`) are predefined airframe configurations. @@ -13,7 +13,7 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot The following sections are split according to the operating system that PX4 runs on. -## POSIX (Linux/MacOS) +## POSIX (Linux/macOS) On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). For that to work, a few things are required: diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index a01a6c6bb7..5640f1dcd7 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -207,7 +207,7 @@ The relevant parameters shown below. ### Position Loss Failsafe Action Multicopters will switch to [Altitude mode](../flight_modes_mc/altitude.md) if a height estimate is available, otherwise [Stabilized mode](../flight_modes_mc/manual_stabilized.md). - + Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend. @@ -276,12 +276,12 @@ The relevant parameters are listed in the table below. ## Failure Detector -The failure detector allows a vehicle to take protective action(s) if it unexpectedly flips, or if it is notified by an external failure detection system. +The failure detector allows a vehicle to take protective actions if it unexpectedly flips, detects a motor failure, or if it is notified by an external failure detection system. During **flight**, the failure detector can be used to trigger [flight termination](../advanced_config/flight_termination.md) if failure conditions are met, which may then launch a [parachute](../peripherals/parachute.md) or perform some other action. ::: info -Failure detection during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). +Acting on a detected failure during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). ::: During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions). @@ -303,6 +303,26 @@ The relevant parameters are shown below: | [FD_FAIL_P_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_P_TTRI) | Time to exceed [FD_FAIL_P](#FD_FAIL_P) for failure detection (default 0.3s). | | [FD_FAIL_R_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_R_TTRI) | Time to exceed [FD_FAIL_R](#FD_FAIL_R) for failure detection (default 0.3s). | +### Motor Failure Trigger + +The failure detector can be configured to detect a motor failure while armed (and trigger an associated action) in the following conditions: + +- A 300 ms timeout occurs in telemetry from an ESC that was previously available. +- The input current in the telemetry of an ESC which was previously positive gets too low for more than [`FD_ACT_MOT_TOUT`](FD_ACT_MOT_TOUT) ms. + The "too low" condition is defined by: + + ```text + {esc current} < {parameter FD_ACT_MOT_C2T} * {motor command between 0 and 1} + ``` + +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [FD_ACT_EN](../advanced_config/parameter_reference.md#FD_ACT_EN) | Enable/disable the motor failure trigger completely. | +| [FD_ACT_MOT_THR](../advanced_config/parameter_reference.md#FD_ACT_MOT_THR) | Minimum normalized [0,1] motor command below which motor under current is ignored. | +| [FD_ACT_MOT_C2T](../advanced_config/parameter_reference.md#FD_ACT_MOT_C2T) | Scale between normalized [0,1] motor command and expected minimally reported currrent when the rotor is healthy. | +| [FD_ACT_MOT_TOUT](../advanced_config/parameter_reference.md#FD_ACT_MOT_TOUT) | Time in miliseconds for which the under current detection condition needs to stay true. | +| [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) | Configure to not only warn about a motor failure but remove the first motor that detects a failure from the allocation effectiveness which turns off the motor and tries to operate the vehicle without it until disarming the next time. | + ### External Automatic Trigger System (ATS) The [failure detector](#failure-detector), if [enabled](#CBRK_FLIGHTTERM), can also be triggered by an external ATS system. diff --git a/docs/en/debug/failure_injection.md b/docs/en/debug/failure_injection.md index 217a2b7ffb..298e1aad50 100644 --- a/docs/en/debug/failure_injection.md +++ b/docs/en/debug/failure_injection.md @@ -19,7 +19,7 @@ At time of writing (PX4 v1.14): ## Failure System Command -Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 console/shell, specifying both the target and type of the failure. +Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 [console/shell](../debug/consoles.md) (such as the [QGC MAVLink Console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) or SITL _pxh shell_), specifying both the target and type of the failure. ### Syntax @@ -61,12 +61,19 @@ where: - _instance number_ (optional): Instance number of affected sensor. 0 (default) indicates all sensors of specified type. -### Example +## MAVSDK Failure Plugin + +The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. +It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). + +The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection. + +## Example: RC signal To simulate losing RC signal without having to turn off your RC controller: -1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). And specifically to turn off motors also [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE). -1. Enter the following commands on the MAVLink console or SITL _pxh shell_: +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. +2. Enter the following commands on the MAVLink console or SITL _pxh shell_: ```sh # Fail RC (turn publishing off) @@ -76,9 +83,18 @@ To simulate losing RC signal without having to turn off your RC controller: failure rc_signal ok ``` -## MAVSDK Failure Plugin +## Example: Motor -The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. -It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). +To stop a motor mid-flight without the system anticipating it or excluding it from allocation effectiveness: -The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection. +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. +2. Enable [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) parameter to allow turning off motors. +3. Enter the following commands on the MAVLink console or SITL _pxh shell_: + + ```sh + # Turn off first motor + failure motor off -i 1 + + # Turn it back on + failure motor ok -i 1 + ``` diff --git a/docs/en/dev_log/logging.md b/docs/en/dev_log/logging.md index e2c91e56d5..47d4d6f385 100644 --- a/docs/en/dev_log/logging.md +++ b/docs/en/dev_log/logging.md @@ -161,7 +161,7 @@ There are different clients that support ulog streaming: - If log streaming does not start, make sure the `logger` is running (see above), and inspect the console output while starting. - If it still does not work, make sure that MAVLink 2 is used. - Enforce it by setting `MAV_PROTO_VER` to 2. + `MAV_PROTO_VER` needs to be set to 2. - Log streaming uses a maximum of 70% of the configured MAVLink rate (`-r` parameter). If more is needed, messages are dropped. The currently used percentage can be inspected with `mavlink status` (1.8% is used in this example): diff --git a/docs/en/dev_setup/dev_env.md b/docs/en/dev_setup/dev_env.md index fddacba0cc..33069072c6 100644 --- a/docs/en/dev_setup/dev_env.md +++ b/docs/en/dev_setup/dev_env.md @@ -2,15 +2,15 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (22.04/20.04/18.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 -- [Mac OS](../dev_setup/dev_env_mac.md) +- [macOS](../dev_setup/dev_env_mac.md) ## Supported Targets The table below shows what PX4 targets you can build on each OS. -| Target | Linux (Ubuntu) | Mac | Windows | +| Target | Linux (Ubuntu) | macOS | Windows | | -------------------------------------------------------------------------------------------------------------------------------------- | :------------: | :-: | :-----: | | **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | | **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | diff --git a/docs/en/dev_setup/dev_env_mac.md b/docs/en/dev_setup/dev_env_mac.md index a77be14982..fee66f554e 100644 --- a/docs/en/dev_setup/dev_env_mac.md +++ b/docs/en/dev_setup/dev_env_mac.md @@ -1,4 +1,4 @@ -# MacOS Development Environment +# macOS Development Environment The following instructions set up a PX4 development environment for macOS. This environment can be used to build PX4 for: @@ -21,8 +21,8 @@ The "base" macOS setup installs the tools needed for building firmware, and incl ### Environment Setup -:::details Apple Silicon Macbook users! -If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 by setting up an x86 terminal: +:::details Apple Silicon MacBook users! +If you have an Apple M1, M2 etc. MacBook, make sure to run the terminal as x86 by setting up an x86 terminal: 1. Locate the Terminal application within the Utilities folder (**Finder > Go menu > Utilities**) 2. Select _Terminal.app_ and right-click on it, then choose **Duplicate**. @@ -47,7 +47,7 @@ First set up the environment 1. Enforce Python 3 by appending the following lines to `~/.zshenv` ```sh - # Point pip3 to MacOS system python 3 pip + # Point pip3 to macOS system python 3 pip alias pip3=/usr/bin/pip3 ``` diff --git a/docs/en/dronecan/ark_cannode.md b/docs/en/dronecan/ark_cannode.md index 9b3d78a085..e1fca0c6d7 100644 --- a/docs/en/dronecan/ark_cannode.md +++ b/docs/en/dronecan/ark_cannode.md @@ -83,9 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter On the ARK CANnode, you may need to configure the following parameters: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------- | ----------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings diff --git a/docs/en/dronecan/ark_flow.md b/docs/en/dronecan/ark_flow.md index 1a107a4916..e97266dda7 100644 --- a/docs/en/dronecan/ark_flow.md +++ b/docs/en/dronecan/ark_flow.md @@ -110,9 +110,10 @@ When optical flow is the only source of horizontal position/velocity, then lower On the ARK Flow, you may need to configure the following parameters: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------- | ----------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings diff --git a/docs/en/dronecan/ark_flow_mr.md b/docs/en/dronecan/ark_flow_mr.md index 1262164b18..b36d0035fe 100644 --- a/docs/en/dronecan/ark_flow_mr.md +++ b/docs/en/dronecan/ark_flow_mr.md @@ -105,9 +105,10 @@ Set the following parameters in _QGroundControl_: You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------- | ----------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings diff --git a/docs/en/dronecan/ark_gps.md b/docs/en/dronecan/ark_gps.md index 1d83419d20..51f07f92c1 100644 --- a/docs/en/dronecan/ark_gps.md +++ b/docs/en/dronecan/ark_gps.md @@ -91,9 +91,17 @@ If the sensor is not centred within the vehicle you will also need to define sen - Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true. - Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO). -- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus. - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity. +### ARK GPS Configuration + +You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself: + +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | + ## LED Meanings You will see green, blue and red LEDs on the ARK GPS when it is being flashed, and a blinking green LED if it is running properly. diff --git a/docs/en/dronecan/ark_rtk_gps.md b/docs/en/dronecan/ark_rtk_gps.md index ec7840c132..472331d7e0 100644 --- a/docs/en/dronecan/ark_rtk_gps.md +++ b/docs/en/dronecan/ark_rtk_gps.md @@ -85,7 +85,15 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked). - Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO). - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity. -- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus. + +### ARK RTK GPS Configuration + +You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself: + +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | ### Setting Up Rover and Fixed Base diff --git a/docs/en/dronecan/index.md b/docs/en/dronecan/index.md index c76f18ce8f..d2262b6944 100644 --- a/docs/en/dronecan/index.md +++ b/docs/en/dronecan/index.md @@ -96,6 +96,10 @@ If the DNA is still running and certain devices need to be manually configured, ::: info The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter. The parameter is set to 1 by default. + +Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the +[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID. +Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID. ::: :::warning @@ -282,6 +286,11 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i ![QGC Parameter showing selected DroneCAN node](../../assets/can/dronecan/qgc_can_parameters.png) +Common CANNODE parameters that you can configure include: + +- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information. +- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus. + ## Device Specific Setup Most DroneCAN nodes require no further setup, unless specifically noted in their device-specific documentation. diff --git a/docs/en/dronecan/px4_cannode_fw.md b/docs/en/dronecan/px4_cannode_fw.md index c165b74662..ad31e5e1be 100644 --- a/docs/en/dronecan/px4_cannode_fw.md +++ b/docs/en/dronecan/px4_cannode_fw.md @@ -20,6 +20,26 @@ make ark_can-flow_default This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware. +## Configuration + +### Static Node ID + +By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller. +However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter. + +To configure a static node ID: + +1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration) +2. Reboot the device + +To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0. +Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior). + +:::warning +When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID. +Configuring two devices with the same ID will cause communication conflicts. +::: + ## Developer Information This section has information that is relevant to developers who want to add support for new DroneCAN hardware to the PX4 Autopilot. diff --git a/docs/en/flight_controller/autopilot_manufacturer_supported.md b/docs/en/flight_controller/autopilot_manufacturer_supported.md index 038e18fef4..f5482326a0 100644 --- a/docs/en/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/en/flight_controller/autopilot_manufacturer_supported.md @@ -35,5 +35,6 @@ The boards in this category are: - [Radiolink PIX6](../flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](../flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md) +- [Svehicle E2](../flight_controller/svehicle_e2.md) - [ThePeach FCC-K1](../flight_controller/thepeach_k1.md) - [ThePeach FCC-R1](../flight_controller/thepeach_r1.md) diff --git a/docs/en/flight_controller/svehicle_e2.md b/docs/en/flight_controller/svehicle_e2.md new file mode 100644 index 0000000000..bbddcba59e --- /dev/null +++ b/docs/en/flight_controller/svehicle_e2.md @@ -0,0 +1,175 @@ +# S-Vehicle E2 + +:::warning +PX4 does not manufacture this (or any) autopilot. +::: + +The _E2_ is an advanced autopilot manufactured by S-Vehicle®. + +The autopilot is recommended for commercial system integration, but is also suitable for academic research and any other applications. +It brings you ultimate performance, stability, and reliability in every aspect. + +![SVehicle-E2](../../assets/flight_controller/svehicle_e2/main.png) + +::: info +These flight controllers are [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +### Processors & Sensors + +- FMU Processor: STM32H753IIK6 + - 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM +- IO Processor: STM32F103 + - 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM +- On-board sensors + - Accel/Gyro: BMI088 + - Accel/Gyro: ICM-42688-P + - Accel/Gyro: ICM-20649 + - Mag: RM3100 + - Barometer: 2x ICP-20100 + +### Interfaces + +- 14x PWM Servo Outputs +- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus +- 1x Analog/PWM RSSI Input +- 2x TELEM Ports (with full flow control) +- 1x UART4 Port +- 2x GPS Ports + - 1x Full GPS plus Safety Switch Port (GPS1) + - 1x Basic GPS Port (with I2C, GPS2) +- 1x USB Port (TYPE-C) +- 1x Ethernet Port + - Transformerless application + - 100Mbps +- 3x I2C Bus Ports +- 1x SPI Bus + - 1x Chip Select Line + - 1x Data Ready Line + - 1x SPI Reset Line +- 2x CAN Ports +- 3x Power Input Ports + - ADC Power Input + - I2C Power Input + - DroneCAN/UAVCAN Power Input +- 2x AD Ports + - Analog Input (3.3V) + - Analog Input (6.6V - not supported by PX4) +- 1x Dedicated Debug Port + - FMU Debug + +## Purchase Channels + +Order from [S-Vehicle](https://svehicle.cn/). + +## Radio Control +A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes). + +You will need to select a compatible transmitter/receiver and then bind them so that they communicate (read the instructions that come with your specific transmitter/receiver). + +Spektrum/DSM receivers connect to the DSM/SBUS RC input. +PPM or SBUS receivers connect to the RC IN input port. +CRSF receiver must be wired to a spare port (UART) on the Flight Controller. Then you can bind the transmitter and receiver together. + +## Serial Port Mapping + +| UART | Device | Port | +| ------ | ---------- | ------------- | +| USART1 | /dev/ttyS0 | GPS | +| USART2 | /dev/ttyS1 | TELEM3 | +| USART3 | /dev/ttyS2 | Debug Console | +| UART4 | /dev/ttyS3 | UART4 | +| UART5 | /dev/ttyS4 | TELEM2 | +| USART6 | /dev/ttyS5 | PX4IO/RC | +| UART7 | /dev/ttyS6 | TELEM1 | +| UART8 | /dev/ttyS7 | GPS2 | + +## PWM Output + +The E2-Plus flight controller supports up to 14 PWM outputs. +The first 8 outputs (labelled M1 to M8) are controlled by a dedicated STM32F103 IOMCU controller. +The remaining 6 outputs (labelled 9 to 14) are the "auxiliary" outputs. +These are directly attached to the STM32H753 FMU controller . + +The 14 PWM outputs are: + +M1 - M8 are connected to the IOMCU +A1 - A6 are connected to the FMU + +M1 - M8 support DShot and are in 3 groups: + +- M1, M2 in group 1 +- M3, M4 in group 2 +- M5, M6, M7, M8 in group 3 + +The 6 FMU PWM outputs are in 2 groups: + +A1 - A4 are in one group. +A5, A6 are in a 2nd group. + +Channels within the same group need to use the same output rate. +If any channel in a group uses DShot then all channels in the group need to use DShot. + +### Electrical data + +- Voltage Ratings: + - Max input voltage: 5.7V + - USB Power Input: 4.75\~5.25V + - Servo Rail Input: 0\~9.9V +- Current Ratings: + - TELEM1 and GPS2 combined output current limiter: 1.5A + - All other port combined output current limiter: 1.5A + +## Battery Monitoring + +The board has connectors for 3 power monitors. + +- POWER1 -- ADC +- POWER2 -- DroneCAN +- POWER3 -- I2C + +The board is configure by default for a analog power monitor, and also has DroneCAN power monitor and I2C defaults configured which is enabled. + +The default PDB included with the E2+ is analog and must be connected to `POWER1`. + +## Building Firmware + +To [build PX4](../dev_setup/building_px4.md) for this target, execute: + +```sh +make svehicle_e2_default +``` + +## Debug Port + +The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port. + +| Pin | Signal | Volt | +| ------- | -------------- | ----- | +| 1 (red) | 5V+ | +5V | +| 2 (blk) | DEBUG TX (OUT) | +3.3V | +| 3 (blk) | DEBUG RX (IN) | +3.3V | +| 4 (blk) | FMU_SWDIO | +3.3V | +| 5 (blk) | FMU_SWCLK | +3.3V | +| 6 (blk) | GND | GND | + +For information about using this port see: + +- [SWD Debug Port](../debug/swd_debug.md) +- [PX4 System Console](../debug/system_console.md) (Note, the FMU console maps to USART3). +- All ports use GH1.25 ,power ports use ports on E2 uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/en-us/products/part-detail/5024430670). + +## Pinouts + +![SVehicle-E2 Top Down Photo](../../assets/flight_controller/svehicle_e2/top.png) + +![SVehicle-E2 Bottom Photo](../../assets/flight_controller/svehicle_e2/back.jpeg) + +![SVehicle-E2 left Photo](../../assets/flight_controller/svehicle_e2/left.png) + +![SVehicle-E2 right Photo](../../assets/flight_controller/svehicle_e2/right.png) + +## Supported Platforms / Airframes + +Any multirotor/airplane/rover or boat that can be controlled using normal RC servos or Futaba S-Bus servos. +The complete set of supported configurations can be found in the [Airframe Reference](../airframes/airframe_reference.md). diff --git a/docs/en/flight_modes_mc/altitude.md b/docs/en/flight_modes_mc/altitude.md index fda7dde9bb..7d35590443 100644 --- a/docs/en/flight_modes_mc/altitude.md +++ b/docs/en/flight_modes_mc/altitude.md @@ -47,5 +47,4 @@ The mode is affected by the following parameters: | ----------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | | `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | diff --git a/docs/en/flight_modes_mc/position.md b/docs/en/flight_modes_mc/position.md index 69367bc4b1..75fae4ab21 100644 --- a/docs/en/flight_modes_mc/position.md +++ b/docs/en/flight_modes_mc/position.md @@ -67,7 +67,6 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | | [MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | Altitude for second phase of slow landing. Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Value needs to be lower than "MPC_LAND_ALT1". Default 5m. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | | `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | | [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Stick input to movement translation strategy. From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). Other options allow stick deflection to directly control speed over ground, with and without smoothing and acceleration limits. | | [MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | Maximum horizontal acceleration. | diff --git a/docs/en/gps_compass/rtk_gps.md b/docs/en/gps_compass/rtk_gps.md index fcaea1c01b..b24cf96c77 100644 --- a/docs/en/gps_compass/rtk_gps.md +++ b/docs/en/gps_compass/rtk_gps.md @@ -203,7 +203,7 @@ This should be enabled by default on recent builds. To ensure MAVLink2 is used: - Update the telemetry module firmware to the latest version (see [QGroundControl > Setup > Firmware](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/firmware.html)). -- Set [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) +- Ensure [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) is set to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) #### Tuning diff --git a/docs/en/index.md b/docs/en/index.md index 047ff55c45..53bcd97f66 100644 --- a/docs/en/index.md +++ b/docs/en/index.md @@ -1,3 +1,8 @@ + +
# PX4 Autopilot User Guide @@ -8,17 +13,22 @@ PX4 is the _Professional Autopilot_. Developed by world-class developers from industry and academia, and supported by an active world wide community, it powers all kinds of vehicles from racing and cargo drones through to ground vehicles and submersibles. :::tip -This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. Interested in contributing? Check out the [Development](development/development.md) section. - +This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. +Interested in contributing? Check out the [Development](development/development.md) section. ::: +
+ :::warning + This guide is for the _development_ version of PX4 (`main` branch). Use the **Version** selector to find the current _stable_ version. Documented changes since the stable release are captured in the evolving [release note](releases/main.md). ::: +
+ ## How Do I Get Started? [Basic Concepts](getting_started/px4_basic_concepts.md) should be read by all users! diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index b174fe7638..82ec12edcd 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -5,7 +5,7 @@ This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main ::: -The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). +The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) and/or [zenoh](../modules/modules_driver.md#zenoh) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on. @@ -13,7 +13,7 @@ This document shows a markdown-rendered version of [dds_topics.yaml](https://git Topic | Type| Rate Limit --- | --- | --- -`/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) | +`/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) | `/fmu/out/arming_check_request` | [px4_msgs::msg::ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) | 5.0 `/fmu/out/mode_completed` | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) | 50.0 `/fmu/out/battery_status` | [px4_msgs::msg::BatteryStatus](../msg_docs/BatteryStatus.md) | 1.0 @@ -21,21 +21,21 @@ Topic | Type| Rate Limit `/fmu/out/estimator_status_flags` | [px4_msgs::msg::EstimatorStatusFlags](../msg_docs/EstimatorStatusFlags.md) | 5.0 `/fmu/out/failsafe_flags` | [px4_msgs::msg::FailsafeFlags](../msg_docs/FailsafeFlags.md) | 5.0 `/fmu/out/manual_control_setpoint` | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) | 25.0 -`/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) | +`/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) | `/fmu/out/position_setpoint_triplet` | [px4_msgs::msg::PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) | 5.0 -`/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) | +`/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) | `/fmu/out/timesync_status` | [px4_msgs::msg::TimesyncStatus](../msg_docs/TimesyncStatus.md) | 10.0 `/fmu/out/vehicle_land_detected` | [px4_msgs::msg::VehicleLandDetected](../msg_docs/VehicleLandDetected.md) | 5.0 -`/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) | +`/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) | `/fmu/out/vehicle_control_mode` | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) | 50.0 -`/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) | +`/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) | `/fmu/out/vehicle_global_position` | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) | 50.0 `/fmu/out/vehicle_gps_position` | [px4_msgs::msg::SensorGps](../msg_docs/SensorGps.md) | 50.0 `/fmu/out/vehicle_local_position` | [px4_msgs::msg::VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) | 50.0 -`/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) | +`/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) | `/fmu/out/vehicle_status` | [px4_msgs::msg::VehicleStatus](../msg_docs/VehicleStatus.md) | 5.0 `/fmu/out/airspeed_validated` | [px4_msgs::msg::AirspeedValidated](../msg_docs/AirspeedValidated.md) | 50.0 -`/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) | +`/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) | `/fmu/out/home_position` | [px4_msgs::msg::HomePosition](../msg_docs/HomePosition.md) | 5.0 ## Subscriptions diff --git a/docs/en/middleware/zenoh.md b/docs/en/middleware/zenoh.md new file mode 100644 index 0000000000..bfee1e79f1 --- /dev/null +++ b/docs/en/middleware/zenoh.md @@ -0,0 +1,200 @@ +# Zenoh (PX4 ROS 2 rmw_zenoh) + + + +:::warning Experimental +At the time of writing, PX4 Zenoh-pico is experimental, and hence subject to change. +::: + +PX4 supports Zenoh as an alternative mechanism (to DDS) for bridging uORB topics to [ROS 2](../ros2/user_guide.md) (via the ROS 2 [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh) middleware). +This allows uORB messages to be published and subscribed on a companion computer as though they were ROS 2 topics. +It provides a fast and lightweight way to connect PX4 to ROS 2, making it easier for applications to access vehicle telemetry and send control commands. + +The following guide describes the architecture and various options for setting up the Zenoh client and router. +In particular, it covers the options that are most important to PX4 users exploring Zenoh as an alternative communication layer for ROS 2. + +## Architecture + +The Zenoh-based middleware consists of a client running on PX4 and a Zenoh router running on the companion computer, with bi-directional data exchange between them over a UART, TCP, UDP, or multicast-UDP link. +The router acts as a broker and discovery service, enabling PX4 to publish and subscribe to topics in the global Zenoh data space. +This allows seamless integration with ROS 2 nodes using [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh), and supports flexible deployment across distributed systems. + +![Architecture PX4 Zenoh-Pico with ROS 2](../../assets/middleware/zenoh/architecture-px4-zenoh.svg) + +The client is the _PX4 Zenoh-Pico Node_ referred to above, which is implemented in the [PX4 `zenoh` module](../modules/modules_driver.md#zenoh). +This is based on Zenoh-Pico, a minimalistic version of [Eclipse Zenoh](https://zenoh.io/) (a data-centric protocol designed for real-time, distributed, and resource-constrained environments). + +The router suggested above is [zenohd](https://github.com/eclipse-zenoh/zenoh/tree/main/zenohd). + +:::info +UART is supported by Zenoh but has not yet implemented in the PX4 Zenoh-Pico node. +::: + +## ROS 2 Zenoh Bring-up on Linux Companion + +In order for PX4 uORB topics to be shared with ROS 2 applications, you will need the PX4 Zenoh-Pico Node client running on your FMU, connected to a Zenoh router running on the companion computer (or elsewhere in the network). + +First select Zenoh as the ROS 2 transport by setting the `RMW_IMPLEMENTATION` environment variable as shown: + +```sh +export RMW_IMPLEMENTATION=rmw_zenoh_cpp +``` + +Then start the Zenoh router using the command: + +```sh +ros2 run rmw_zenoh_cpp rmw_zenohd +``` + +For more information about the Zenoh Router see the [rmw_zenoh](https://github.com/ros2/rmw_zenoh?tab=readme-ov-file#start-the-zenoh-router) documentation. + +## PX4 Zenoh-Pico Node Setup + +### PX4 Firmware + +Before setting up the Zenoh communication, first make sure that your firmware contains the driver that implements the [`zenoh` driver](../modules/modules_driver.md#zenoh), which provides the implementation of the _PX4 Zenoh-Pico Node_. + +You can check if the module is present on your board by searching for the key `CONFIG_MODULES_ZENOH=y` in your board's `default.px4board` KConfig file. +For example, you can see that the module is present in `px4_fmu-v6xrt` build targets from [/boards/px4/fmu-v6xrt/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6xrt/default.px4board#L91). + +If `CONFIG_MODULES_ZENOH=y` is not preset you can add this key to your board configuration and rebuild. +Note that due to flash constraints you may need to remove other components in order to include the module (such as the [`uxrce_dds_client` module](../modules/modules_system.md#uxrce-dds-client), which you will not need if you are using Zenoh). + +The table below shows some of the PX4 targets that include Zenoh by default. + +| PX4 Target | Notes | +| ---------------------- | ------------------------------------------------------------------------------------------- | +| `px4_fmu-v6xrt` | For [FMUv6X-RT](../flight_controller/nxp_mr_vmu_rt1176.md) (reference platform for testing) | +| `nxp_tropic-community` | | +| `nxp_mr-tropic` | | +| `nxp_mr-canhubk344` | | +| `px4_sitl_zenoh` | Zenoh-enabled simulation build | +| `px4_fmu-v6x_zenoh` | Zenoh-enabled firmware for FMUv6X | + +Zenoh is not included in the default `px4_fmu-` targets for any firmware other than `px4_fmu-v6xrt` (`px4_sitl_zenoh` and `px4_fmu-v6x_zenoh` [are build variants](../dev_setup/building_px4.md#px4-make-build-targets)). + +::: tip +You can check if Zenoh is present at runtime by using QGroundControl to [find the parameter](../advanced_config/parameters.md#finding-a-parameter) [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE). +If present, the module is installed. +::: + +### Enable Zenoh on PX4 Startup + +Set the [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE) parameter to `1` to enable Zenoh on PX4 startup. + +### Configure Zenoh Network + +Set up PX4 to connect to the companion computer running `zenohd`. + +PX4's default IP address of the Zenoh daemon host is `10.41.10.1`. +If you're using a different IP for the Zenoh daemon, run the following command (replacing the address) in a PX4 shell and then reboot: + +```sh +zenoh config net client tcp/10.41.10.1:7447#iface=eth0 +``` + +Note that for the simulation target with Zeroh (`px4_sitl_zenoh`) you won't need to make any changes because the default IP address of the Zenoh daemon is set to `localhost`. + +:::warning +Any changes to the network configuration require a PX4 system reboot to take effect. +::: + +:::tip +See [PX4 Ethernet Setup](../advanced_config/ethernet_setup.md) for more information about Ethernet configuration. +::: + +### PX4 Zenoh-pico Node configuration + +The **default configuration** is auto-generated from the [dds_topics.yaml](../middleware/dds_topics.md) file in the PX4 repository. +This file specifies which uORB message definitions are to be published/subscribed by ROS 2 applications, and hence (indirectly) which topics are compiled into the zenoh module. + +To inspect the current Zenoh configuration: + +```sh +zenoh config +``` + +The PX4 Zenoh-pico node stores its configuration on the **SD card** under the `zenoh` folder. +This folder contains three key files: + +- **`net.txt`** – Defines the **Zenoh network configuration**. +- **`pub.csv`** – Maps **uORB topics to ROS2 topics** (used for publishing). +- **`sub.csv`** – Maps **ROS2 topics to uORB topics** (used for subscribing). + +### 4. Modifying Topic Mappings + +Zenoh topic mappings define how data flows between PX4's internal uORB topics and external ROS2 topics via Zenoh. +These mappings are stored in `pub.csv` and `sub.csv` on the SD card, and can be modified at runtime using the `zenoh config` CLI tool. + +:::warning +Any changes to the topic mappings require a PX4 system reboot to take effect. +::: + +There are two types of mappings you can modify: + +- **Publisher mappings**: Forward data from a uORB topic to a Zenoh topic. +- **Subscriber mappings**: Receive data from a Zenoh topic and publish it to a uORB topic. + +The main operations and their commands are: + +- Publish a uORB topic to a Zenoh topic: + + ```sh + zenoh config add publisher [uorb_instance] + ``` + +- Subscribe to a Zenoh topic and forward it to a uORB topic: + + ```sh + zenoh config add subscriber [uorb_instance] + ``` + +- Remove existing mappings: + + ```sh + zenoh config delete publisher + zenoh config delete subscriber + ``` + +After modifying the mappings, reboot PX4 to apply the changes. +The updated configuration will be loaded from the SD card during startup. + +## Communicating with PX4 from ROS 2 via Zenoh + +Once your PX4 FMU is publishing data into ROS 2, you can inspect the available topics and their contents using standard ROS 2 CLI tools: + +```sh +ros2 topic list +``` + +Check topic type and publishers/subscribers: + +```sh +ros2 topic info -v /fmu/out/vehicle_status +Type: px4_msgs/msg/VehicleStatus + +Publisher count: 1 + +Node name: px4_aabbcc00000000000000000000000000 +Node namespace: / +Topic type: px4_msgs/msg/VehicleStatus +Topic type hash: RIHS01_828bddbb7d4c2aa6ad93757955f6893be1ec5d8f11885ec7715bcdd76b5226c9 +Endpoint type: PUBLISHER +GID: 82.99.74.2c.b6.7d.93.44.91.4d.fe.14.93.58.40.16 +QoS profile: + Reliability: RELIABLE + History (Depth): KEEP_LAST (7) + Durability: VOLATILE + Lifespan: Infinite + Deadline: Infinite + Liveliness: AUTOMATIC + Liveliness lease duration: Infinite + +Subscription count: 0 +``` + +### PX4 ROS 2 Interface with Zenoh + +The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) works out of the box with Zenoh as a transport backend. +This means you can publish and subscribe to PX4 topics over Zenoh without changing your ROS 2 nodes or dealing with DDS configuration. +For setup details and supported message types, refer to the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md). diff --git a/docs/en/modules/modules_driver_distance_sensor.md b/docs/en/modules/modules_driver_distance_sensor.md index af48d491a5..4e78a7e7ff 100644 --- a/docs/en/modules/modules_driver_distance_sensor.md +++ b/docs/en/modules/modules_driver_distance_sensor.md @@ -104,7 +104,7 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### Description -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html diff --git a/docs/en/msg_docs/AirspeedValidated.md b/docs/en/msg_docs/AirspeedValidated.md index b5fe9191a5..61f607e7fa 100644 --- a/docs/en/msg_docs/AirspeedValidated.md +++ b/docs/en/msg_docs/AirspeedValidated.md @@ -1,31 +1,39 @@ # AirspeedValidated (UORB message) +Validated airspeed +Provides information about airspeed (indicated, true, calibrated) and the source of the data. +Used by controllers, estimators and for airspeed reporting to operator. [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) ```c +# Validated airspeed +# +# Provides information about airspeed (indicated, true, calibrated) and the source of the data. +# Used by controllers, estimators and for airspeed reporting to operator. + + uint32 MESSAGE_VERSION = 1 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start -float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid -float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid -float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid +float32 indicated_airspeed_m_s # [m/s] [@invalid NaN] Indicated airspeed (IAS) +float32 calibrated_airspeed_m_s # [m/s] [@invalid NaN] Calibrated airspeed (CAS) +float32 true_airspeed_m_s # [m/s] [@invalid NaN] True airspeed (TAS) -int8 airspeed_source # Source of currently published airspeed values -int8 DISABLED = -1 -int8 GROUND_MINUS_WIND = 0 -int8 SENSOR_1 = 1 -int8 SENSOR_2 = 2 -int8 SENSOR_3 = 3 -int8 SYNTHETIC = 4 +int8 airspeed_source # [@enum SOURCE] Source of currently published airspeed values +int8 SOURCE_DISABLED = -1 # Disabled +int8 SOURCE_GROUND_MINUS_WIND = 0 # Ground speed minus wind +int8 SOURCE_SENSOR_1 = 1 # Sensor 1 +int8 SOURCE_SENSOR_2 = 2 # Sensor 2 +int8 SOURCE_SENSOR_3 = 3 # Sensor 3 +int8 SOURCE_SYNTHETIC = 4 # Synthetic airspeed -# debug states -float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid -float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid -float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] -float32 throttle_filtered # filtered fixed-wing throttle [-] -float32 pitch_filtered # filtered pitch [rad] +float32 calibrated_ground_minus_wind_m_s # [m/s] [@invalid NaN] CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption +float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airspeed +float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative +float32 throttle_filtered # [-] Filtered fixed-wing throttle +float32 pitch_filtered # [rad] Filtered pitch ``` diff --git a/docs/en/msg_docs/AutotuneAttitudeControlStatus.md b/docs/en/msg_docs/AutotuneAttitudeControlStatus.md index b8d7517950..31a47ef204 100644 --- a/docs/en/msg_docs/AutotuneAttitudeControlStatus.md +++ b/docs/en/msg_docs/AutotuneAttitudeControlStatus.md @@ -1,44 +1,59 @@ # AutotuneAttitudeControlStatus (UORB message) +Autotune attitude control status +This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +and is subscribed to by the respective attitude controllers to command rate setpoints. + +The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AutotuneAttitudeControlStatus.msg) ```c -uint64 timestamp # time since system start (microseconds) +# Autotune attitude control status +# +# This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +# and is subscribed to by the respective attitude controllers to command rate setpoints. +# +# The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. -float32[5] coeff # coefficients of the identified discrete-time model -float32[5] coeff_var # coefficients' variance of the identified discrete-time model -float32 fitness # fitness of the parameter estimate -float32 innov -float32 dt_model +uint64 timestamp # [us] Time since system start -float32 kc -float32 ki -float32 kd -float32 kff -float32 att_p +float32[5] coeff # [-] Coefficients of the identified discrete-time model +float32[5] coeff_var # [-] Coefficients' variance of the identified discrete-time model +float32 fitness # [-] Fitness of the parameter estimate +float32 innov # [rad/s] Innovation (residual error between model and measured output) +float32 dt_model # [s] Model sample time used for identification -float32[3] rate_sp -float32 u_filt -float32 y_filt +float32 kc # [-] Proportional rate-loop gain (ideal form) +float32 ki # [-] Integral rate-loop gain (ideal form) +float32 kd # [-] Derivative rate-loop gain (ideal form) +float32 kff # [-] Feedforward rate-loop gain +float32 att_p # [-] Proportional attitude gain -uint8 STATE_IDLE = 0 -uint8 STATE_INIT = 1 -uint8 STATE_ROLL = 2 -uint8 STATE_ROLL_PAUSE = 3 -uint8 STATE_PITCH = 4 -uint8 STATE_PITCH_PAUSE = 5 -uint8 STATE_YAW = 6 -uint8 STATE_YAW_PAUSE = 7 -uint8 STATE_VERIFICATION = 8 -uint8 STATE_APPLY = 9 -uint8 STATE_TEST = 10 -uint8 STATE_COMPLETE = 11 -uint8 STATE_FAIL = 12 -uint8 STATE_WAIT_FOR_DISARM = 13 +float32[3] rate_sp # [rad/s] Rate setpoint commanded to the attitude controller. -uint8 state +float32 u_filt # [-] Filtered input signal (normalized torque setpoint) used in system identification. +float32 y_filt # [rad/s] Filtered output signal (angular velocity) used in system identification. + +uint8 state # [@enum STATE] Current state of the autotune procedure. +uint8 STATE_IDLE = 0 # Idle (not running) +uint8 STATE_INIT = 1 # Initialize filters and setup +uint8 STATE_ROLL_AMPLITUDE_DETECTION = 2 # FW only: determine required excitation amplitude (roll) +uint8 STATE_ROLL = 3 # Roll-axis excitation and model identification +uint8 STATE_ROLL_PAUSE = 4 # Pause to return to level flight +uint8 STATE_PITCH_AMPLITUDE_DETECTION = 5 # FW only: determine required excitation amplitude (pitch) +uint8 STATE_PITCH = 6 # Pitch-axis excitation and model identification +uint8 STATE_PITCH_PAUSE = 7 # Pause to return to level flight +uint8 STATE_YAW_AMPLITUDE_DETECTION = 8 # FW only: determine required excitation amplitude (yaw) +uint8 STATE_YAW = 9 # Yaw-axis excitation and model identification +uint8 STATE_YAW_PAUSE = 10 # Pause to return to level flight +uint8 STATE_VERIFICATION = 11 # Verify model and candidate gains +uint8 STATE_APPLY = 12 # Apply gains +uint8 STATE_TEST = 13 # Test gains in closed-loop +uint8 STATE_COMPLETE = 14 # Tuning completed successfully +uint8 STATE_FAIL = 15 # Tuning failed (model invalid or controller unstable) +uint8 STATE_WAIT_FOR_DISARM = 16 # Waiting for disarm before finalizing ``` diff --git a/docs/en/msg_docs/ControlAllocatorStatus.md b/docs/en/msg_docs/ControlAllocatorStatus.md index 0ac1b24b55..4068e7b4f4 100644 --- a/docs/en/msg_docs/ControlAllocatorStatus.md +++ b/docs/en/msg_docs/ControlAllocatorStatus.md @@ -1,7 +1,5 @@ # ControlAllocatorStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ControlAllocatorStatus.msg) ```c @@ -26,5 +24,6 @@ int8[16] actuator_saturation # Indicates actuator saturation status. # Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value. uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector +uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection ``` diff --git a/docs/en/msg_docs/EstimatorStatusFlags.md b/docs/en/msg_docs/EstimatorStatusFlags.md index 0ac832817d..aa7250fe1e 100644 --- a/docs/en/msg_docs/EstimatorStatusFlags.md +++ b/docs/en/msg_docs/EstimatorStatusFlags.md @@ -54,8 +54,9 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended -bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_gnss_fault # 45 - true if GNSS true if GNSS measurements (lat, lon, vel) have been declared faulty bool cs_yaw_manual # 46 - true if yaw has been set manually +bool cs_gnss_hgt_fault # 47 - true if GNSS true if GNSS measurements (alt) have been declared faulty # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/docs/en/msg_docs/FailureDetectorStatus.md b/docs/en/msg_docs/FailureDetectorStatus.md index 369a176b24..a112a1e642 100644 --- a/docs/en/msg_docs/FailureDetectorStatus.md +++ b/docs/en/msg_docs/FailureDetectorStatus.md @@ -1,7 +1,5 @@ # FailureDetectorStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FailureDetectorStatus.msg) ```c @@ -19,5 +17,6 @@ bool fd_motor float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed) uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures +uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection ``` diff --git a/docs/en/msg_docs/GimbalDeviceAttitudeStatus.md b/docs/en/msg_docs/GimbalDeviceAttitudeStatus.md index cb14c570d5..0935029087 100644 --- a/docs/en/msg_docs/GimbalDeviceAttitudeStatus.md +++ b/docs/en/msg_docs/GimbalDeviceAttitudeStatus.md @@ -1,7 +1,5 @@ # GimbalDeviceAttitudeStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceAttitudeStatus.msg) ```c @@ -16,6 +14,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2 uint16 DEVICE_FLAGS_ROLL_LOCK = 4 uint16 DEVICE_FLAGS_PITCH_LOCK = 8 uint16 DEVICE_FLAGS_YAW_LOCK = 16 +uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 +uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 + float32[4] q float32 angular_velocity_x diff --git a/docs/en/msg_docs/SensorGnssStatus.md b/docs/en/msg_docs/SensorGnssStatus.md new file mode 100644 index 0000000000..70602b85fc --- /dev/null +++ b/docs/en/msg_docs/SensorGnssStatus.md @@ -0,0 +1,19 @@ +# SensorGnssStatus (UORB message) + +Gnss quality indicators + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssStatus.msg) + +```c +# Gnss quality indicators + +uint64 timestamp # time since system start (microseconds) +uint32 device_id # unique device ID for the sensor that does not change between power cycles + +bool quality_available # Set to true if quality indicators are available +uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if not available +uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available +uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available +uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available + +``` diff --git a/docs/en/msg_docs/SensorGps.md b/docs/en/msg_docs/SensorGps.md index c8d09e9472..1b5fb3cf41 100644 --- a/docs/en/msg_docs/SensorGps.md +++ b/docs/en/msg_docs/SensorGps.md @@ -38,18 +38,26 @@ float32 vdop # Vertical dilution of precision int32 noise_per_ms # GPS noise per millisecond uint16 automatic_gain_control # Automatic gain control monitor -uint8 JAMMING_STATE_UNKNOWN = 0 -uint8 JAMMING_STATE_OK = 1 -uint8 JAMMING_STATE_WARNING = 2 -uint8 JAMMING_STATE_CRITICAL = 3 -uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical -int32 jamming_indicator # indicates jamming is occurring +uint8 JAMMING_STATE_UNKNOWN = 0 #default +uint8 JAMMING_STATE_OK = 1 +uint8 JAMMING_STATE_MITIGATED = 2 +uint8 JAMMING_STATE_DETECTED = 3 +uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected +int32 jamming_indicator # indicates jamming is occurring -uint8 SPOOFING_STATE_UNKNOWN = 0 -uint8 SPOOFING_STATE_NONE = 1 -uint8 SPOOFING_STATE_INDICATED = 2 -uint8 SPOOFING_STATE_MULTIPLE = 3 -uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical +uint8 SPOOFING_STATE_UNKNOWN = 0 #default +uint8 SPOOFING_STATE_OK = 1 +uint8 SPOOFING_STATE_MITIGATED = 2 +uint8 SPOOFING_STATE_DETECTED = 3 +uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected + +# Combined authentication state (e.g. Galileo OSNMA) +uint8 AUTHENTICATION_STATE_UNKNOWN = 0 #default +uint8 AUTHENTICATION_STATE_INITIALIZING = 1 +uint8 AUTHENTICATION_STATE_ERROR = 2 +uint8 AUTHENTICATION_STATE_OK = 3 +uint8 AUTHENTICATION_STATE_DISABLED = 4 +uint8 authentication_state # GPS signal authentication state float32 vel_m_s # GPS ground speed, (metres/sec) float32 vel_n_m_s # GPS North velocity, (metres/sec) @@ -63,6 +71,16 @@ uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp whi uint8 satellites_used # Number of satellites used +uint32 SYSTEM_ERROR_OK = 0 #default +uint32 SYSTEM_ERROR_INCOMING_CORRECTIONS = 1 +uint32 SYSTEM_ERROR_CONFIGURATION = 2 +uint32 SYSTEM_ERROR_SOFTWARE = 4 +uint32 SYSTEM_ERROR_ANTENNA = 8 +uint32 SYSTEM_ERROR_EVENT_CONGESTION = 16 +uint32 SYSTEM_ERROR_CPU_OVERLOAD = 32 +uint32 SYSTEM_ERROR_OUTPUT_CONGESTION = 64 +uint32 system_error # General errors with the connected GPS receiver + float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI]) float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI]) float32 heading_accuracy # heading accuracy (rad, [0, 2PI]) diff --git a/docs/en/msg_docs/VehicleOdometry.md b/docs/en/msg_docs/VehicleOdometry.md index d559ded6c7..4213c23337 100644 --- a/docs/en/msg_docs/VehicleOdometry.md +++ b/docs/en/msg_docs/VehicleOdometry.md @@ -1,41 +1,44 @@ # VehicleOdometry (UORB message) -Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +Vehicle odometry data + +Fits ROS REP 147 for aerial vehicles [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleOdometry.msg) ```c -# Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +# Vehicle odometry data +# +# Fits ROS REP 147 for aerial vehicles uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp sample -uint8 POSE_FRAME_UNKNOWN = 0 -uint8 POSE_FRAME_NED = 1 # NED earth-fixed frame -uint8 POSE_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference -uint8 pose_frame # Position and orientation frame of reference +uint8 pose_frame # [@enum POSE_FRAME] Position and orientation frame of reference +uint8 POSE_FRAME_UNKNOWN = 0 # Unknown frame +uint8 POSE_FRAME_NED = 1 # North-East-Down (NED) navigation frame. Aligned with True North. +uint8 POSE_FRAME_FRD = 2 # Forward-Right-Down (FRD) frame. Constant arbitrary heading offset from True North. Z is down. -float32[3] position # Position in meters. Frame of reference defined by local_frame. NaN if invalid/unknown -float32[4] q # Quaternion rotation from FRD body frame to reference frame. First value NaN if invalid/unknown +float32[3] position # [m] [@frame local frame] [@invalid NaN If invalid/unknown] Position. Origin is position of GC at startup. +float32[4] q # [-] [@invalid NaN First value if invalid/unknown] Attitude (expressed as a quaternion) relative to pose reference frame at current location. Follows the Hamiltonian convention (w, x, y, z, right-handed, passive rotations from body to world) -uint8 VELOCITY_FRAME_UNKNOWN = 0 -uint8 VELOCITY_FRAME_NED = 1 # NED earth-fixed frame -uint8 VELOCITY_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference -uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame -uint8 velocity_frame # Reference frame of the velocity data +uint8 velocity_frame # [@enum VELOCITY_FRAME] Reference frame of the velocity data +uint8 VELOCITY_FRAME_UNKNOWN = 0 # Unknown frame +uint8 VELOCITY_FRAME_NED = 1 # NED navigation frame at current position. +uint8 VELOCITY_FRAME_FRD = 2 # FRD navigation frame at current position. Constant arbitrary heading offset from True North. Z is down. +uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame -float32[3] velocity # Velocity in meters/sec. Frame of reference defined by velocity_frame variable. NaN if invalid/unknown +float32[3] velocity # [m/s] [@frame @velocity_frame] [@invalid NaN If invalid/unknown] Velocity. +float32[3] angular_velocity # [rad/s] [@frame @VELOCITY_FRAME_BODY_FRD] [@invalid NaN If invalid/unknown] Angular velocity in body-fixed frame -float32[3] angular_velocity # Angular velocity in body-fixed frame (rad/s). NaN if invalid/unknown +float32[3] position_variance # [m^2] Variance of position error +float32[3] orientation_variance # [rad^2] Variance of orientation/attitude error (expressed in body frame) +float32[3] velocity_variance # [m^2/s^2] Variance of velocity error -float32[3] position_variance -float32[3] orientation_variance -float32[3] velocity_variance - -uint8 reset_counter -int8 quality +uint8 reset_counter # [-] Reset counter. Counts reset events on attitude, velocity and position. +int8 quality # [-] [@invalid 0] Quality. Unused. # TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry # TOPICS estimator_odometry diff --git a/docs/en/msg_docs/index.md b/docs/en/msg_docs/index.md index 23f6c9441f..44ab566a6b 100644 --- a/docs/en/msg_docs/index.md +++ b/docs/en/msg_docs/index.md @@ -15,7 +15,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message -- [AirspeedValidated](AirspeedValidated.md) +- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed - [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply - [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request - [BatteryStatus](BatteryStatus.md) — Battery status @@ -70,7 +70,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [VehicleLandDetected](VehicleLandDetected.md) - [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data - [VehicleRatesSetpoint](VehicleRatesSetpoint.md) - [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander - [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE @@ -87,7 +87,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [AdcReport](AdcReport.md) - [Airspeed](Airspeed.md) — Airspeed data from sensors - [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector) -- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) +- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status - [BatteryInfo](BatteryInfo.md) — Battery information - [ButtonEvent](ButtonEvent.md) - [CameraCapture](CameraCapture.md) @@ -246,6 +246,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m change with board revisions and sensor updates. - [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor - [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. +- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators - [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds) - [SensorGyro](SensorGyro.md) diff --git a/docs/en/ros2/px4_ros2_waypoint_missions.md b/docs/en/ros2/px4_ros2_waypoint_missions.md index 0e54b9e6cb..4484e1c136 100644 --- a/docs/en/ros2/px4_ros2_waypoint_missions.md +++ b/docs/en/ros2/px4_ros2_waypoint_missions.md @@ -36,7 +36,7 @@ There are some benefits and drawbacks to using ROS-based missions, which are pro - QGroundControl currently does not display the mission or progress during execution, and cannot upload or download a mission. Therefore you will need another mechanism to provide a mission, such as from a web server, a custom GCS, or by generating it directly inside the application. -- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-gotosetpointtype), which only works for multicopters, and VTOL in MC mode). +- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-multicoptergotosetpointtype), which only works for multicopters, and VTOL in MC mode). It is designed to be extendable to any other vehicle type. ## Overview diff --git a/docs/en/sensor/inertial_navigation_systems.md b/docs/en/sensor/inertial_navigation_systems.md index 090fd5bca6..bdf7f39b6d 100644 --- a/docs/en/sensor/inertial_navigation_systems.md +++ b/docs/en/sensor/inertial_navigation_systems.md @@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) +- [MicroStrain](../sensor/microstrain.md): Includes VRU, AHRS, INS, and GNSS/INS devices. - [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. - [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. diff --git a/docs/en/sensor/microstrain.md b/docs/en/sensor/microstrain.md new file mode 100644 index 0000000000..c4aad808eb --- /dev/null +++ b/docs/en/sensor/microstrain.md @@ -0,0 +1,212 @@ +# MicroStrain (INS, IMU, VRU, AHRS) + +MicroStrain by HBK provides high-performance inertial sensors engineered for reliability and precision in challenging environments. +Widely used across industries like aerospace, robotics, industrial automation, and research, MicroStrain sensors are optimized for real-time, accurate motion tracking and orientation data. + +![CV7](../../assets/hardware/sensors/inertial/microstrain_3dm_cv7_hbk.png) + +The driver currently supports the following hardware: + +- [`MicroStrain CV7-AR`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/vertical-reference-units--vru-/3dm-cv7-ar): Inertial Measurement Unit (IMU) and Vertical Reference Unit (VRU) +- [`MicroStrain CV7-AHRS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/attitude-and-heading-reference-systems--ahrs-/3dm-cv7-ahrs): Inertial Measurement Unit (IMU) and Attitude Heading Reference System (AHRS) +- [`MicroStrain CV7-INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS). +- [`MicroStrain CV7-GNSS/INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-gnss-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS) combined with dual multiband (GNSS) receivers. + +PX4 can use these sensors to provide raw IMU data for EKF2 or to replace EKF2 as an external INS. +For more information, including user manuals and datasheets, please refer to the sensors product page. + +## Where to Buy + +MicroStrain sensors can be purchased through HBK's official [MicroStrain product page](https://www.hbkworld.com/en/products/transducers/inertial-sensors) or through authorized distributors globally. +For large orders, custom requirements, or technical inquiries, reach out directly to [sales](https://www.hbkworld.com/en/contact-us/contact-sales-microstrain) + +## Hardware Setup + +### Wiring + +Connect the main UART port of the MicroStrain sensor to any unused serial port on the flight controller. +This port needs to be specified while starting the device. + +### Mounting + +The MicroStrain sensor can be mounted in any orientation. +The default coordinate system uses X for the front, Y for the right, and Z for down, with directions marked on the device. + +## Firmware Configuration + +### PX4 Configuration + +To use the MicroStrain driver: + +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`. +2. Configure the driver mode by setting [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) + + - To use the MicroStrain sensor to provide raw IMU data to EKF2 + + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 0 + 2. Update the [EKF2_MULTI_IMU](../advanced_config/parameter_reference.md#EKF2_MULTI_IMU) parameter to account for the added MicroStrain sensor. + 3. Enable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 1 + 4. To prioritize MicroStrain sensor output, adjust the priority level of individual sensors from 0-100 using the following parameters: + + - [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO) + - [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO) + - [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO) + - [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO) + + where `n` corresponds to the index of the corresponding sensor. + + ::: tip + Sensors can be identified by their device id, which can be found by checking the parameters: + + - [CAL_ACCn_ID](../advanced_config/parameter_reference.md#CAL_ACC0_ID) + - [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) + - [CAL_MAGn_ID](../advanced_config/parameter_reference.md#CAL_MAG0_ID) + - [CAL_BAROn_ID](../advanced_config/parameter_reference.md#CAL_BARO0_ID) + + ::: + + - To use the MicroStrain sensor as an external INS + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 1 + 2. Disable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 0 + +3. Reboot and start the driver + - `microstrain start -d ` + - To start the driver automatically when the flight controller powers on, set [SENS_MS_CFG](../advanced_config/parameter_reference.md#SENS_MS_CFG) to the sensor’s connected port. + +## MicroStrain Configuration + +1. Rates: + + - By default, accel and gyro data are published at 500 Hz, magnetometer at 50 Hz, and barometric pressure at 50 Hz. + This can be changed by adjusting the following parameters: + + - [MS_IMU_RATE_HZ](../advanced_config/parameter_reference.md#MS_IMU_RATE_HZ) + - [MS_MAG_RATE_HZ](../advanced_config/parameter_reference.md#MS_MAG_RATE_HZ) + - [MS_BARO_RATE_HZ](../advanced_config/parameter_reference.md#MS_BARO_RATE_HZ) + + - Global position, local position, attitude and odometry will be published at 250 Hz by default. + This can be configured via: + + - [MS_FILT_RATE_HZ](../advanced_config/parameter_reference.md#MS_FILT_RATE_HZ) + + - For the CV7-GNSS/INS, the GNSS receiver 1 and 2 will publish data at 5Hz by default. + This can be changed using: + + - [MS_GNSS_RATE_HZ](../advanced_config/parameter_reference.md#MS_GNSS_RATE_HZ) + + - The driver will automatically configure data outputs based on the specific sensor model and available data streams. + - The driver is scheduled to run at twice the fastest configured data rate. + +2. Aiding measurements: + + - If supported, GNSS position and velocity aiding are always enabled. + - Internal/external magnetometer and heading aiding, as well as optical flow aiding, are disabled by default. They can be enabled using the following parameters: + + - [MS_INT_MAG_EN](../advanced_config/parameter_reference.md#MS_INT_MAG_EN) + - [MS_INT_HEAD_EN](../advanced_config/parameter_reference.md#MS_INT_HEAD_EN) + - [MS_EXT_HEAD_EN](../advanced_config/parameter_reference.md#MS_EXT_HEAD_EN) + - [MS_EXT_MAG_EN](../advanced_config/parameter_reference.md#MS_EXT_MAG_EN) + - [MS_OPT_FLOW_EN](../advanced_config/parameter_reference.md#MS_OPT_FLOW_EN) + + - The aiding frames for external sources can be configured using the following parameters: + + - [MS_EHEAD_YAW](../advanced_config/parameter_reference.md#MS_EHEAD_YAW) + - [MS_EMAG_ROLL](../advanced_config/parameter_reference.md#MS_EMAG_ROLL) + - [MS_EMAG_PTCH](../advanced_config/parameter_reference.md#MS_EMAG_PTCH) + - [MS_EMAG_YAW](../advanced_config/parameter_reference.md#MS_EMAG_YAW) + - [MS_OFLW_OFF_X](../advanced_config/parameter_reference.md#MS_OFLW_OFF_X) + - [MS_OFLW_OFF_Y](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Y) + - [MS_OFLW_OFF_Z](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Z) + - [SENS_FLOW_ROT](../advanced_config/parameter_reference.md#SENS_FLOW_ROT) + + - The uncertainty for optical flow and external magnetometer aiding must be specified using the following parameters: + + - [MS_EMAG_UNCERT](../advanced_config/parameter_reference.md#MS_EMAG_UNCERT) + - [MS_OFLW_UNCERT](../advanced_config/parameter_reference.md#MS_OFLW_UNCERT) + + ::: tip + 1. When optical flow aiding is enabled, the sensor uses the `vehicle_optical_flow_vel` output from the flight controller as a body-frame velocity aiding measurement. + 2. If the MicroStrain sensor does not support these aiding sources but they are enabled, sensor initialization will fail. + + ::: + +3. Initial heading alignment: + + - Initial heading alignment is set to kinematic by default. This can be changed by adjusting + + - [MS_ALIGNMENT](../advanced_config/parameter_reference.md#MS_ALIGNMENT) + +4. GNSS Aiding Source Control (GNSS/INS only) + + - The Source of the GNSS aiding data can be configured using: + + - [MS_GNSS_AID_SRC](../advanced_config/parameter_reference.md#MS_GNSS_AID_SRC) + +5. Sensor to vehicle transform: + + - If the sensor is mounted in an orientation different from the vehicle frame. A sensor to vehicle transform can be enabled using + + - [MS_SVT_EN](../advanced_config/parameter_reference.md#MS_SVT_EN) + + - The transform is defined using the following parameters + + - [MS_SENSOR_ROLL](../advanced_config/parameter_reference.md#MS_SENSOR_ROLL) + - [MS_SENSOR_PTCH](../advanced_config/parameter_reference.md#MS_SENSOR_PTCH) + - [MS_SENSOR_YAW](../advanced_config/parameter_reference.md#MS_SENSOR_YAW) + +6. IMU ranges: + + - The accelerometer and gyroscope ranges on the device are configurable using: + + - [MS_ACCEL_RANGE](../advanced_config/parameter_reference.md#MS_ACCEL_RANGE) + - [MS_GYRO_RANGE](../advanced_config/parameter_reference.md#MS_GYRO_RANGE) + + ::: tip + Available range settings depend on the specific [sensor](https://www.hbkworld.com/en/products/transducers/inertial-sensors) and can be found in the corresponding user manual. + By default, the ranges are not changed. + + ::: + +7. GNSS Lever arm offsets: + + - The lever arm offset for the external GNSS receiver can be configured using: + + - [MS_GNSS_OFF1_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_X) + - [MS_GNSS_OFF1_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Y) + - [MS_GNSS_OFF1_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Z) + + - For dual-antenna configurations, the second GNSS receiver’s offset is configured using: + + - [MS_GNSS_OFF2_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_X) + - [MS_GNSS_OFF2_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Y) + - [MS_GNSS_OFF2_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Z) + +## Published Data + +The MicroStrain driver continuously publishes sensor data to the following uORB topics: + +- [sensor_accel](../msg_docs/SensorAccel.md) +- [sensor_gyro](../msg_docs/SensorGyro.md) +- [sensor_mag](../msg_docs/SensorMag.md) +- [sensor_baro](../msg_docs/SensorBaro.md) + +For GNSS/INS devices, GPS data is also published to: + +- [sensor_gps](../msg_docs/SensorGps.md) + +If used as an external INS replacing EKF2, it publishes: + +- [vehicle_global_position](../msg_docs/VehicleGlobalPosition.md) +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) +- [vehicle_odometry](../msg_docs/VehicleOdometry.md) + +otherwise the same data is published to the following topics + +- `external_ins_global_position` +- `external_ins_attitude` +- `external_ins_local_position` + +::: tip +Published topics can be viewed using the `listener` command. +::: diff --git a/docs/en/test_and_ci/test_flights.md b/docs/en/test_and_ci/test_flights.md index f9579c1ccb..91a7681f97 100644 --- a/docs/en/test_and_ci/test_flights.md +++ b/docs/en/test_and_ci/test_flights.md @@ -28,5 +28,7 @@ These are run by the test team as part of release testing, and for more signific - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) -- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_07 - Optical Flow Low Mount](../test_cards/mc_07_optical_flow_low_mount.md) - [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) +- [MC_09 - VIO (Visual-Inertial Odometry)](../test_cards/mc_09_vio.md) +- [MC_10 - Optical Flow / GPS Mixed](../test_cards/mc_10_optical_flow_gps_mixed.md) diff --git a/docs/en/test_cards/mc_06_optical_flow.md b/docs/en/test_cards/mc_06_optical_flow.md index 8a7eb71211..22877115e6 100644 --- a/docs/en/test_cards/mc_06_optical_flow.md +++ b/docs/en/test_cards/mc_06_optical_flow.md @@ -2,25 +2,23 @@ ## Objective -To test that optical flow works as expected +Test that optical flow works as expected ## Preflight -Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation -([Setup Information here](../sensor/optical_flow.md)) +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation ([setup information here](../sensor/optical_flow.md)) -Ensure there are no other sources of positioning besides optical flow +Ensure there are no other sources of positioning besides optical flow: - [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` - [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` - [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` -- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into Altitude / Position mode while still on the ground ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -28,7 +26,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -38,6 +36,16 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates +❏ Varying height terrain + +    ❏ Put boxes on the ground to create varying heights in terrain + +    ❏ Take off in position mode and fly over the boxes such that the downward facing rangefinder varies in value + +    ❏ Do a few passes with varying amounts of time over the boxes (1-30 seconds if possible) + +    ❏ Drone should not raise in height when flying over boxes + ## Landing ❏ Land in either Position or Altitude mode with the throttle below 40% @@ -47,7 +55,8 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## Expected Results - Take-off should be smooth as throttle is raised -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering (over surface with many features) +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - No oscillations should present in any of the above flight modes +- Drone should not raise in height when flying over boxes - Upon landing, copter should not bounce on the ground diff --git a/docs/en/test_cards/mc_07_optical_flow_low_mount.md b/docs/en/test_cards/mc_07_optical_flow_low_mount.md new file mode 100644 index 0000000000..73c06f4e4a --- /dev/null +++ b/docs/en/test_cards/mc_07_optical_flow_low_mount.md @@ -0,0 +1,45 @@ +# Test MC_07 - Optical Flow Low Sensor + +## Objective + +Test that optical flow works as expected with a low mounted optical flow sensor + +## Preflight + +Ensure that the drone's optical flow sensor is mounted more than an inch off of the ground + +Ensure that [MPC_THR_MIN](../advanced_config/parameter_reference.md#MPC_THR_MIN) is tuned correctly for landing + +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` + +Ensure that the drone can go into [Position mode](../flight_modes_mc/position.md) while still on the ground + +## Flight Tests + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## Landing + +❏ Land in Position mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## Expected Results + +- Take-off should be smooth as throttle is raised +- Drone should stay in Position mode, NOT fall into [altitude](../flight_modes_mc/altitude.md) mode diff --git a/docs/en/test_cards/mc_08_dshot.md b/docs/en/test_cards/mc_08_dshot.md index 1ce413b34f..d2012aabd5 100644 --- a/docs/en/test_cards/mc_08_dshot.md +++ b/docs/en/test_cards/mc_08_dshot.md @@ -6,22 +6,22 @@ Regression test for DSHOT working with PX4 ## Preflight -- Ensure vehicle is using a DSHOT ESC. +- Ensure vehicle is using a DSHOT ESC - Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled - Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) - Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked ## Flight Tests -❏ Stabilized Flight mode +❏ [Stabilized mode](../flight_modes_mc/manual_stabilized.md) -    ❏ Takeoff in stabilized flight mode to ensure correct motor spin +    ❏ Takeoff in stabilized mode to ensure correct motor spin     ❏ Pitch/Roll/Yaw response 1:1     ❏ Throttle response 1:1 -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -41,6 +41,6 @@ Regression test for DSHOT working with PX4 - Download flight logs - Load into Data Plot Juggler -- Ensure data is logged for esc_status/esc.0x/esc_rpm +- Ensure data is logged for `esc_status`/`esc.0x`/`esc_rpm` ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/en/test_cards/mc_07_vio.md b/docs/en/test_cards/mc_09_vio.md similarity index 75% rename from docs/en/test_cards/mc_07_vio.md rename to docs/en/test_cards/mc_09_vio.md index 24743eaf7e..994fa9e4cf 100644 --- a/docs/en/test_cards/mc_07_vio.md +++ b/docs/en/test_cards/mc_09_vio.md @@ -1,14 +1,14 @@ -# Test MC_07 - VIO (Visual-Inertial Odometry) +# Test MC_09 - VIO (Visual-Inertial Odometry) ## Objective -To test that external vision (VIO) works as expected +Test that external vision (VIO) works as expected ## Preflight Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground Ensure there are no other sources of positioning besides VIO: @@ -19,7 +19,7 @@ Ensure there are no other sources of positioning besides VIO: ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -27,7 +27,7 @@ Ensure there are no other sources of positioning besides VIO:     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -46,7 +46,7 @@ Ensure there are no other sources of positioning besides VIO: ## Expected Results - Take-off should be smooth as throttle is raised -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - No oscillations should present in any of the above flight modes - Upon landing, copter should not bounce on the ground diff --git a/docs/en/test_cards/mc_10_optical_flow_gps_mixed.md b/docs/en/test_cards/mc_10_optical_flow_gps_mixed.md new file mode 100644 index 0000000000..740900f911 --- /dev/null +++ b/docs/en/test_cards/mc_10_optical_flow_gps_mixed.md @@ -0,0 +1,74 @@ +# Test MC_10 - Optical Flow / GPS Mixed + +## Objective + +Test that optical flow mixed with GPS works as expected + +## Preflight + +[Setup optical flow and GPS](../sensor/optical_flow.md) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `7` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `1` +- [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF): `1` (GPS) + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +❏ GPS Cutout + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Open QGC and navigate to MAVLink Console + +    ❏ Type `gps off` to disable GPS + +    ❏ Drone should maintain position hold via optical flow + +❏ GPS Degredation + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Fly under a metal surface (or other GPS blocking structure) + +    ❏ Ensure drone does not lose position hold or start drifting + +    ❏ Fly out of metal structure to regain GPS + +❏ GPS Acquisition + +    ❏ Takeoff in position mode in non-GPS environment + +    ❏ Fly into a GPS rich environment (outdoors) + +    ❏ Ensure drone acquires GPS position + +## Expected Results + +- Take-off should be smooth as throttle is raised +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Drone should hold position in GPS rich environment as well as non-GPS environment +- No oscillations should present in any of the above flight modes diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index d0a8f566c2..3f6edca6b1 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -286,6 +286,7 @@ - [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](sensor/inertial_navigation_systems.md) - [InertialLabs](sensor/inertiallabs.md) + - [MicroStrain](sensor/microstrain.md) - [sbgECom](sensor/sbgecom.md) - [VectorNav](sensor/vectornav.md) - [광류 센서](sensor/optical_flow.md) @@ -701,6 +702,7 @@ - [SensorCombined](msg_docs/SensorCombined.md) - [SensorCorrection](msg_docs/SensorCorrection.md) - [SensorGnssRelative](msg_docs/SensorGnssRelative.md) + - [SensorGnssStatus](msg_docs/SensorGnssStatus.md) - [SensorGps](msg_docs/SensorGps.md) - [SensorGyro](msg_docs/SensorGyro.md) - [SensorGyroFft](msg_docs/SensorGyroFft.md) @@ -762,6 +764,7 @@ - [Standard Modes Protocol](mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md) - [UORB Bridged to ROS 2](middleware/dds_topics.md) + - [Zenoh (PX4 ROS 2)](middleware/zenoh.md) - [모듈과 명령어](modules/modules_main.md) - [자동 튜닝](modules/modules_autotune.md) - [명령어](modules/modules_command.md) @@ -851,8 +854,10 @@ - [시험 MC_04 - 안전 장치 시험](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](test_cards/mc_10_optical_flow_gps_mixed.md) - [단위 테스트](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [지속 통합](test_and_ci/continous_integration.md) diff --git a/docs/ko/_sidebar.md b/docs/ko/_sidebar.md index 6fda5a26c0..3455e4ecec 100644 --- a/docs/ko/_sidebar.md +++ b/docs/ko/_sidebar.md @@ -8,6 +8,7 @@ - [위치 모드 (멀티콥터)](/flight_modes_mc/position.md) - [Position Slow Mode (MC)](/flight_modes_mc/position_slow.md) - [고도 모드 (멀티콥터)](/flight_modes_mc/altitude.md) + - [Altitude Cruise Mode (MC)](/flight_modes_mc/altitude_cruise.md) - [Stabilized Mode (MC)](/flight_modes_mc/manual_stabilized.md) - [아크로 모드 (멀티콥터)](/flight_modes_mc/acro.md) - [궤도 모드 (멀티콥터)](/flight_modes_mc/orbit.md) @@ -158,6 +159,7 @@ - [mRo (3DR) Pixhawk 배선 퀵 스타트](/assembly/quick_start_pixhawk.md) - [Holybro Pixhawk Mini (FMUv3) - Discontinued](/flight_controller/pixhawk_mini.md) - [Manufacturer-Supported Autopilots](/flight_controller/autopilot_manufacturer_supported.md) + - [Accton Godwit GA1](/flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](/flight_controller/mindpx.md) - [AirMind MindRacer](/flight_controller/mindracer.md) - [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md) @@ -183,6 +185,7 @@ - [Wiring Quickstart](/assembly/quick_start_holybro_pix32_v5.md) - [ModalAI VOXL 2](/flight_controller/modalai_voxl_2.md) - [mRo Control Zero F7](/flight_controller/mro_control_zero_f7.md) + - [Radiolink PIX6](/flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](/flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](/flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](/flight_controller/thepeach_k1.md) @@ -284,6 +287,7 @@ - [CubePilot Here+ (Discontined)](/gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](/sensor/inertial_navigation_systems.md) - [InertialLabs](/sensor/inertiallabs.md) + - [sbgECom](/sensor/sbgecom.md) - [VectorNav](/sensor/vectornav.md) - [광류 센서](/sensor/optical_flow.md) - [ARK Flow](/dronecan/ark_flow.md) @@ -433,6 +437,7 @@ - [Attitude Tuning](/config_rover/attitude_tuning.md) - [Velocity Tuning](/config_rover/velocity_tuning.md) - [Position Tuning](/config_rover/position_tuning.md) + - [Apps & API](/flight_modes_rover/api.md) - [Complete Vehicles](/complete_vehicles_rover/index.md) - [Aion Robotics R1](/complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](/frames_sub/index.md) @@ -680,6 +685,8 @@ - [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](/msg_docs/RoverRateStatus.md) + - [RoverSpeedSetpoint](/msg_docs/RoverSpeedSetpoint.md) + - [RoverSpeedStatus](/msg_docs/RoverSpeedStatus.md) - [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md) - [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md) @@ -740,6 +747,7 @@ - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md) - [ArmingCheckReplyV0](/msg_docs/ArmingCheckReplyV0.md) + - [ArmingCheckRequestV0](/msg_docs/ArmingCheckRequestV0.md) - [BatteryStatusV0](/msg_docs/BatteryStatusV0.md) - [EventV0](/msg_docs/EventV0.md) - [HomePositionV0](/msg_docs/HomePositionV0.md) @@ -844,8 +852,10 @@ - [시험 MC_04 - 안전 장치 시험](/test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](/test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](/test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](/test_cards/mc_10_optical_flow_gps_mixed.md) - [단위 테스트](/test_and_ci/unit_tests.md) - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [지속 통합](/test_and_ci/continous_integration.md) @@ -866,6 +876,7 @@ - [PX4 ROS 2 Interface Library](/ros2/px4_ros2_interface_lib.md) - [Control Interface](/ros2/px4_ros2_control_interface.md) - [Navigation Interface](/ros2/px4_ros2_navigation_interface.md) + - [Waypoint Missions](/ros2/px4_ros2_waypoint_missions.md) - [ROS 2 Message Translation Node](/ros2/px4_ros2_msg_translation_node.md) - [ROS 1 (Deprecated)](/ros/ros1.md) - [ROS/MAVROS 설치 가이드](/ros/mavros_installation.md) diff --git a/docs/ko/airframes/airframe_reference.md b/docs/ko/airframes/airframe_reference.md index 06c9517842..0ae87398fc 100644 --- a/docs/ko/airframes/airframe_reference.md +++ b/docs/ko/airframes/airframe_reference.md @@ -618,6 +618,10 @@ div.frame_variant td, div.frame_variant th { Axial SCX10 2 Trail Honcho 유지보수: John Doe <john@example.com>

SYS_AUTOSTART = 51001

+ + NXP B3RB Rover Ackermann + 유지보수: John Doe <john@example.com>

SYS_AUTOSTART = 51002

+ Generic Rover Mecanum 유지보수: John Doe <john@example.com>

SYS_AUTOSTART = 52000

diff --git a/docs/ko/concept/system_startup.md b/docs/ko/concept/system_startup.md index 79fd6cb79b..058b7577c7 100644 --- a/docs/ko/concept/system_startup.md +++ b/docs/ko/concept/system_startup.md @@ -1,7 +1,7 @@ # 시스템 시작 PX4 시작은 쉘 스크립트에 의해 제어됩니다. -On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/MacOS). +On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/macOS). The scripts that are only used on Posix are located in [ROMFS/px4fmu_common/init.d-posix](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d-posix). All files starting with a number and underscore (e.g. `10000_airplane`) are predefined airframe configurations. @@ -13,7 +13,7 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot 다음 섹션은 PX4가 실행되는 운영 체제에 따라 달라집니다. -## POSIX (Linux/MacOS) +## POSIX (Linux/macOS) On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). 동작하기 위한 몇가지 조건이 있습니다. diff --git a/docs/ko/config/safety.md b/docs/ko/config/safety.md index d819eb304b..0debe65eb2 100644 --- a/docs/ko/config/safety.md +++ b/docs/ko/config/safety.md @@ -276,12 +276,12 @@ The relevant parameters are listed in the table below. ## 고장 감지기 -고장 감지기를 사용하여 차량의 예기치 않게 전복되거나 외부의 고장 감지 시스템에 따른 보호 조치를 할 수 있습니다. +The failure detector allows a vehicle to take protective actions if it unexpectedly flips, detects a motor failure, or if it is notified by an external failure detection system. During **flight**, the failure detector can be used to trigger [flight termination](../advanced_config/flight_termination.md) if failure conditions are met, which may then launch a [parachute](../peripherals/parachute.md) or perform some other action. :::info -Failure detection during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). +Acting on a detected failure during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). ::: During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions). @@ -303,6 +303,26 @@ The failure detector is active in all vehicle types and modes, except for those | [FD_FAIL_P_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_P_TTRI) | Time to exceed [FD_FAIL_P](#FD_FAIL_P) for failure detection (default 0.3s). | | [FD_FAIL_R_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_R_TTRI) | Time to exceed [FD_FAIL_R](#FD_FAIL_R) for failure detection (default 0.3s). | +### Motor Failure Trigger + +The failure detector can be configured to detect a motor failure while armed (and trigger an associated action) in the following conditions: + +- A 300 ms timeout occurs in telemetry from an ESC that was previously available. +- The input current in the telemetry of an ESC which was previously positive gets too low for more than [`FD_ACT_MOT_TOUT`](FD_ACT_MOT_TOUT) ms. + The "too low" condition is defined by: + + ```text + {esc current} < {parameter FD_ACT_MOT_C2T} * {motor command between 0 and 1} + ``` + +| 매개변수 | 설명 | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [FD_ACT_EN](../advanced_config/parameter_reference.md#FD_ACT_EN) | Enable/disable the motor failure trigger completely. | +| [FD_ACT_MOT_THR](../advanced_config/parameter_reference.md#FD_ACT_MOT_THR) | Minimum normalized [0,1] motor command below which motor under current is ignored. | +| [FD_ACT_MOT_C2T](../advanced_config/parameter_reference.md#FD_ACT_MOT_C2T) | Scale between normalized [0,1] motor command and expected minimally reported currrent when the rotor is healthy. | +| [FD_ACT_MOT_TOUT](../advanced_config/parameter_reference.md#FD_ACT_MOT_TOUT) | Time in miliseconds for which the under current detection condition needs to stay true. | +| [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) | Configure to not only warn about a motor failure but remove the first motor that detects a failure from the allocation effectiveness which turns off the motor and tries to operate the vehicle without it until disarming the next time. | + ### 외부 자동 작동 시스템 (ATS) The [failure detector](#failure-detector), if [enabled](#CBRK_FLIGHTTERM), can also be triggered by an external ATS system. diff --git a/docs/ko/debug/failure_injection.md b/docs/ko/debug/failure_injection.md index ba39466e7b..fdc4a49589 100644 --- a/docs/ko/debug/failure_injection.md +++ b/docs/ko/debug/failure_injection.md @@ -19,7 +19,7 @@ At time of writing (PX4 v1.14): ## 장애 시스템 명령 -Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 console/shell, specifying both the target and type of the failure. +Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 [console/shell](../debug/consoles.md) (such as the [QGC MAVLink Console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) or SITL _pxh shell_), specifying both the target and type of the failure. ### 구문 @@ -61,11 +61,18 @@ failure [-i ] - _instance number_ (optional): Instance number of affected sensor. 0 (기본값) 지정된 유형의 모든 센서를 나타냅니다. -### Example +## MAVSDK 실패 플러그인 + +The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. +It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). + +The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection. + +## Example: RC signal To simulate losing RC signal without having to turn off your RC controller: -1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). And specifically to turn off motors also [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE). +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. 2. Enter the following commands on the MAVLink console or SITL _pxh shell_: ```sh @@ -76,9 +83,18 @@ To simulate losing RC signal without having to turn off your RC controller: failure rc_signal ok ``` -## MAVSDK 실패 플러그인 +## Example: Motor -The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. -It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). +To stop a motor mid-flight without the system anticipating it or excluding it from allocation effectiveness: -The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection. +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. +2. Enable [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) parameter to allow turning off motors. +3. Enter the following commands on the MAVLink console or SITL _pxh shell_: + + ```sh + # Turn off first motor + failure motor off -i 1 + + # Turn it back on + failure motor ok -i 1 + ``` diff --git a/docs/ko/dev_log/logging.md b/docs/ko/dev_log/logging.md index 4373a1e946..527e053184 100644 --- a/docs/ko/dev_log/logging.md +++ b/docs/ko/dev_log/logging.md @@ -160,7 +160,7 @@ ulog 스트리밍을 지원하는 다양한 클라이언트가 있습니다. - If log streaming does not start, make sure the `logger` is running (see above), and inspect the console output while starting. - 그래도 작동하지 않으면, MAVLink 2를 사용하고 있는지 확인하십시오. - Enforce it by setting `MAV_PROTO_VER` to 2. + `MAV_PROTO_VER` needs to be set to 2. - Log streaming uses a maximum of 70% of the configured MAVLink rate (`-r` parameter). 더 큰 전송율이 요구되는 상황에서는, 메세지가 사라집니다. The currently used percentage can be inspected with `mavlink status` (1.8% is used in this example): diff --git a/docs/ko/dev_log/ulog_file_format.md b/docs/ko/dev_log/ulog_file_format.md index 70e1ac0510..9e8a29b7e7 100644 --- a/docs/ko/dev_log/ulog_file_format.md +++ b/docs/ko/dev_log/ulog_file_format.md @@ -502,6 +502,7 @@ Since the Definitions and Data Sections use the same message header format, they - [ulogreader](https://github.com/maxsun/ulogreader): Javascript, ULog reader and parser outputs log in JSON object format. - [Foxglove](https://foxglove.dev): an integrated visualization and diagnosis tool for robotics data that supports ULog files. - [TypeScript ULog parser](https://github.com/foxglove/ulog): TypeScript, ULog reader that outputs JS objects. +- [yule_log](https://crates.io/crates/yule_log): A streaming ULog parser written in Rust. ## 파일 형식 버전 이력 diff --git a/docs/ko/dev_setup/dev_env.md b/docs/ko/dev_setup/dev_env.md index 427f28d302..9ed3e0cfd8 100644 --- a/docs/ko/dev_setup/dev_env.md +++ b/docs/ko/dev_setup/dev_env.md @@ -2,22 +2,22 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (22.04/20.04/18.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 -- [Mac OS](../dev_setup/dev_env_mac.md) +- [macOS](../dev_setup/dev_env_mac.md) ## 지원 대상 아래 표는 각 OS에서 구축 가능한 PX 대상을 보여줍니다. -| 대상 | Linux (Ubuntu) | Mac | 윈도우 | -| ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :-: | :-: | -| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | -| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | -| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | -| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | +| 대상 | Linux (Ubuntu) | macOS | 윈도우 | +| ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :---: | :-: | +| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | +| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | +| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | +| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | Experienced Docker users can also build with the containers used by our continuous integration system: [Docker Containers](../test_and_ci/docker.md) diff --git a/docs/ko/dev_setup/dev_env_mac.md b/docs/ko/dev_setup/dev_env_mac.md index 5b31516462..63e8e3ca38 100644 --- a/docs/ko/dev_setup/dev_env_mac.md +++ b/docs/ko/dev_setup/dev_env_mac.md @@ -1,4 +1,4 @@ -# MacOS 개발 환경 +# macOS Development Environment 아래에서 macOS용 PX4 개발 환경 설정 방법을 설명합니다. PX4 빌드에 사용되어 집니다. @@ -22,8 +22,8 @@ The "base" macOS setup installs the tools needed for building firmware, and incl ### Environment Setup :::details -Apple Silicon Macbook users! -If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 by setting up an x86 terminal: +Apple Silicon MacBook users! +If you have an Apple M1, M2 etc. MacBook, make sure to run the terminal as x86 by setting up an x86 terminal: 1. Locate the Terminal application within the Utilities folder (**Finder > Go menu > Utilities**) 2. Select _Terminal.app_ and right-click on it, then choose **Duplicate**. @@ -38,21 +38,21 @@ First set up the environment 1. Enable more open files by appending the following line to the `~/.zshenv` file (creating it if necessary): - ```sh - echo ulimit -S -n 2048 >> ~/.zshenv - ``` + ```sh + echo ulimit -S -n 2048 >> ~/.zshenv + ``` - ::: info - If you don't do this, the build toolchain may report the error: `"LD: too many open files"` + ::: info + If you don't do this, the build toolchain may report the error: `"LD: too many open files"` ::: 2. Enforce Python 3 by appending the following lines to `~/.zshenv` - ```sh - # Point pip3 to MacOS system python 3 pip - alias pip3=/usr/bin/pip3 - ``` + ```sh + # Point pip3 to macOS system python 3 pip + alias pip3=/usr/bin/pip3 + ``` ### 공통 도구 @@ -62,19 +62,19 @@ To setup the environment to be able to build for Pixhawk/NuttX hardware (and ins 2. Run these commands in your shell to install the common tools: - ```sh - brew tap PX4/px4 - brew install px4-dev - ``` + ```sh + brew tap PX4/px4 + brew install px4-dev + ``` 3. Install the required Python packages: - ```sh - # install required packages using pip3 - python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema - # if this fails with a permissions error, your Python install is in a system path - use this command instead: - sudo -H python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema - ``` + ```sh + # install required packages using pip3 + python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema + # if this fails with a permissions error, your Python install is in a system path - use this command instead: + sudo -H python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema + ``` ## Gazebo Classic Simulation @@ -82,35 +82,35 @@ To setup the environment for [Gazebo Classic](../sim_gazebo_classic/index.md) si 1. Run the following commands in your shell: - ```sh - brew unlink tbb - sed -i.bak '/disable! date:/s/^/ /; /disable! date:/s/./#/3' $(brew --prefix)/Library/Taps/homebrew/homebrew-core/Formula/tbb@2020.rb - brew install tbb@2020 - brew link tbb@2020 - ``` + ```sh + brew unlink tbb + sed -i.bak '/disable! date:/s/^/ /; /disable! date:/s/./#/3' $(brew --prefix)/Library/Taps/homebrew/homebrew-core/Formula/tbb@2020.rb + brew install tbb@2020 + brew link tbb@2020 + ``` - ::: info - September 2021: The commands above are a workaround to this bug: [PX4-Autopilot#17644](https://github.com/PX4/PX4-Autopilot/issues/17644). - They can be removed once it is fixed (along with this note). + ::: info + September 2021: The commands above are a workaround to this bug: [PX4-Autopilot#17644](https://github.com/PX4/PX4-Autopilot/issues/17644). + They can be removed once it is fixed (along with this note). ::: 2. To install SITL simulation with Gazebo Classic: - ```sh - brew install --cask temurin - brew install --cask xquartz - brew install px4-sim-gazebo - ``` + ```sh + brew install --cask temurin + brew install --cask xquartz + brew install px4-sim-gazebo + ``` 3. Run the macOS setup script: `PX4-Autopilot/Tools/setup/macos.sh` - The easiest way to do this is to clone the PX4 source, and then run the script from the directory, as shown: + The easiest way to do this is to clone the PX4 source, and then run the script from the directory, as shown: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - cd PX4-Autopilot/Tools/setup - sh macos.sh - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + cd PX4-Autopilot/Tools/setup + sh macos.sh + ``` ## 다음 단계 diff --git a/docs/ko/dronecan/ark_cannode.md b/docs/ko/dronecan/ark_cannode.md index d87becac70..918d210e8f 100644 --- a/docs/ko/dronecan/ark_cannode.md +++ b/docs/ko/dronecan/ark_cannode.md @@ -83,9 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter On the ARK CANnode, you may need to configure the following parameters: -| 매개변수 | 설명 | -| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED 신호의 의미 diff --git a/docs/ko/dronecan/ark_flow.md b/docs/ko/dronecan/ark_flow.md index 780cd8a9bd..17766bbdb6 100644 --- a/docs/ko/dronecan/ark_flow.md +++ b/docs/ko/dronecan/ark_flow.md @@ -109,9 +109,10 @@ When optical flow is the only source of horizontal position/velocity, then lower On the ARK Flow, you may need to configure the following parameters: -| 매개변수 | 설명 | -| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED 신호의 의미 diff --git a/docs/ko/dronecan/ark_flow_mr.md b/docs/ko/dronecan/ark_flow_mr.md index 6ca91d771d..c9e0bbced3 100644 --- a/docs/ko/dronecan/ark_flow_mr.md +++ b/docs/ko/dronecan/ark_flow_mr.md @@ -104,9 +104,10 @@ Set the following parameters in _QGroundControl_: You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself: -| 매개변수 | 설명 | -| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED 신호의 의미 diff --git a/docs/ko/dronecan/ark_gps.md b/docs/ko/dronecan/ark_gps.md index 9d604f745d..4bcd150a6d 100644 --- a/docs/ko/dronecan/ark_gps.md +++ b/docs/ko/dronecan/ark_gps.md @@ -91,9 +91,17 @@ If the sensor is not centred within the vehicle you will also need to define sen - Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true. - Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO). -- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus. - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity. +### ARK GPS Configuration + +You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself: + +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | + ## LED 신호의 의미 You will see green, blue and red LEDs on the ARK GPS when it is being flashed, and a blinking green LED if it is running properly. diff --git a/docs/ko/dronecan/ark_rtk_gps.md b/docs/ko/dronecan/ark_rtk_gps.md index 917dd95e30..c8e8a5ce5e 100644 --- a/docs/ko/dronecan/ark_rtk_gps.md +++ b/docs/ko/dronecan/ark_rtk_gps.md @@ -85,7 +85,15 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked). - Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO). - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity. -- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus. + +### ARK RTK GPS Configuration + +You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself: + +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | ### Setting Up Rover and Fixed Base diff --git a/docs/ko/dronecan/index.md b/docs/ko/dronecan/index.md index f5b9efe0ce..975a7762fa 100644 --- a/docs/ko/dronecan/index.md +++ b/docs/ko/dronecan/index.md @@ -102,6 +102,10 @@ If the DNA is still running and certain devices need to be manually configured, :::info The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter. The parameter is set to 1 by default. + +Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the +[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID. +Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID. ::: :::warning @@ -288,6 +292,11 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i ![QGC Parameter showing selected DroneCAN node](../../assets/can/dronecan/qgc_can_parameters.png) +Common CANNODE parameters that you can configure include: + +- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information. +- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus. + ## Device Specific Setup Most DroneCAN nodes require no further setup, unless specifically noted in their device-specific documentation. diff --git a/docs/ko/dronecan/px4_cannode_fw.md b/docs/ko/dronecan/px4_cannode_fw.md index 65262d4152..3e29a57f5a 100644 --- a/docs/ko/dronecan/px4_cannode_fw.md +++ b/docs/ko/dronecan/px4_cannode_fw.md @@ -20,6 +20,26 @@ make ark_can-flow_default This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware. +## 설정 + +### Static Node ID + +By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller. +However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter. + +To configure a static node ID: + +1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration) +2. Reboot the device + +To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0. +Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior). + +:::warning +When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID. +Configuring two devices with the same ID will cause communication conflicts. +::: + ## 개발자 정보 This section has information that is relevant to developers who want to add support for new DroneCAN hardware to the PX4 Autopilot. diff --git a/docs/ko/flight_modes_mc/altitude.md b/docs/ko/flight_modes_mc/altitude.md index 36aff1468f..b1d4bcadae 100644 --- a/docs/ko/flight_modes_mc/altitude.md +++ b/docs/ko/flight_modes_mc/altitude.md @@ -43,9 +43,8 @@ The horizontal position of the vehicle can move due to wind (or pre-existing mom The mode is affected by the following parameters: -| 매개변수 | 설명 | -| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | 최대 수직 상승 속도. 기본값: 3 m/s. | -| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 최대 수직 하강 속도. 기본값: 1 m/s. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | -| `MPC_XXXX` | 대부분의 MPC_xxx 매개 변수는이 모드에서 비행 동작에 어느정도 영향을 미칩니다 . For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | +| 매개변수 | 설명 | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | 최대 수직 상승 속도. 기본값: 3 m/s. | +| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 최대 수직 하강 속도. 기본값: 1 m/s. | +| `MPC_XXXX` | 대부분의 MPC_xxx 매개 변수는이 모드에서 비행 동작에 어느정도 영향을 미칩니다 . For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | diff --git a/docs/ko/flight_modes_mc/position.md b/docs/ko/flight_modes_mc/position.md index a86b9dbea4..a70a503627 100644 --- a/docs/ko/flight_modes_mc/position.md +++ b/docs/ko/flight_modes_mc/position.md @@ -67,7 +67,6 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 최대 수직 하강 속도. 기본값: 1 m/s. | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | | [MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | Altitude for second phase of slow landing. Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Value needs to be lower than "MPC_LAND_ALT1". Default 5m. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | | `MPC_XXXX` | 대부분의 MPC_xxx 매개 변수는이 모드에서 비행 동작에 어느정도 영향을 미칩니다 . For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | | [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Stick input to movement translation strategy. From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). Other options allow stick deflection to directly control speed over ground, with and without smoothing and acceleration limits. | | [MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | Maximum horizontal acceleration. | diff --git a/docs/ko/gps_compass/rtk_gps.md b/docs/ko/gps_compass/rtk_gps.md index 1d40ffce20..279173c618 100644 --- a/docs/ko/gps_compass/rtk_gps.md +++ b/docs/ko/gps_compass/rtk_gps.md @@ -123,35 +123,35 @@ This should be set by default, but if not, follow the [MAVLink2 configuration in RTK GPS 연결은 기본적으로 플러그앤플레이입니다. 1. Start _QGroundControl_ and attach the base RTK GPS via USB to the ground station. - 장치가 자동으로 인식됩니다. + 장치가 자동으로 인식됩니다. 2. Start the vehicle and make sure it is connected to _QGroundControl_. - :::tip - _QGroundControl_ displays an RTK GPS status icon in the top icon bar while an RTK GPS device is connected (in addition to the normal GPS status icon). - RTK가 설정되는 동안 아이콘은 빨간색으로 표시되고, RTK GPS가 활성화되면 흰색으로 바뀝니다. - 아이콘을 클릭하여 현재 상태와 RTK 정확도를 확인할 수 있습니다. + :::tip + _QGroundControl_ displays an RTK GPS status icon in the top icon bar while an RTK GPS device is connected (in addition to the normal GPS status icon). + RTK가 설정되는 동안 아이콘은 빨간색으로 표시되고, RTK GPS가 활성화되면 흰색으로 바뀝니다. + 아이콘을 클릭하여 현재 상태와 RTK 정확도를 확인할 수 있습니다. ::: 3. _QGroundControl_ then starts the RTK setup process (known as "Survey-In"). - Survey-In은 기지국의 정확한 위치 추정치를 획득을 위한 시작 절차입니다. - The process typically takes several minutes (it ends after reaching the minimum time and accuracy specified in the [RTK settings](#rtk-gps-settings)). + Survey-In은 기지국의 정확한 위치 추정치를 획득을 위한 시작 절차입니다. + The process typically takes several minutes (it ends after reaching the minimum time and accuracy specified in the [RTK settings](#rtk-gps-settings)). - RTK GPS 상태 아이콘을 클릭하여 진행 상황을 추적할 수 있습니다. + RTK GPS 상태 아이콘을 클릭하여 진행 상황을 추적할 수 있습니다. - ![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png) + ![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png) 4. Survey-in이 완료되면 : - - The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle: + - The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle: - ![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png) + ![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png) - - 기체의 GPS가 RTK 모드로 전환됩니다. - The new mode is displayed in the _normal_ GPS status icon (`3D RTK GPS Lock`): + - 기체의 GPS가 RTK 모드로 전환됩니다. + The new mode is displayed in the _normal_ GPS status icon (`3D RTK GPS Lock`): - ![RTK GPS Status](../../assets/qgc/setup/rtk/qgc_rtk_gps_status.png) + ![RTK GPS Status](../../assets/qgc/setup/rtk/qgc_rtk_gps_status.png) ### GPS를 Yaw/Heading 소스로 설정 @@ -206,7 +206,7 @@ MAVLink2 프로토콜은 낮은 대역폭 채널을 보다 효율적으로 사 MAVLink2가 사용되는 지 확인하려면 : - Update the telemetry module firmware to the latest version (see [QGroundControl > Setup > Firmware](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/firmware.html)). -- Set [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) +- Ensure [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) is set to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) #### 튜닝 diff --git a/docs/ko/index.md b/docs/ko/index.md index 0e579b2428..4ae116f0c7 100644 --- a/docs/ko/index.md +++ b/docs/ko/index.md @@ -1,3 +1,8 @@ + +
# PX4 Autopilot 사용자 안내서 @@ -9,17 +14,22 @@ PX4 is the _Professional Autopilot_. 세계 각국에서 활동중인 여러 단체들의 지원을 받을 수 있습니다. PX4는 레이싱 드론, 운송용 드론, 자동차와 선박 등의 다양한 운송체에 적용하여 사용할 수 있습니다. :::tip -This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. 이 프로젝트에 기여하시려면, Check out the [Development](development/development.md) section. - +This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. +이 프로젝트에 기여하시려면, Check out the [Development](development/development.md) section. ::: +
+ :::warning + This guide is for the _development_ version of PX4 (`main` branch). Use the **Version** selector to find the current _stable_ version. Documented changes since the stable release are captured in the evolving [release note](releases/main.md). ::: +
+ ## 시작하기 [Basic Concepts](getting_started/px4_basic_concepts.md) should be read by all users! diff --git a/docs/ko/middleware/dds_topics.md b/docs/ko/middleware/dds_topics.md index 5bcfb87d5d..ce7533dcfc 100644 --- a/docs/ko/middleware/dds_topics.md +++ b/docs/ko/middleware/dds_topics.md @@ -4,7 +4,7 @@ This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code. ::: -The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). +The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) and/or [zenoh](../modules/modules_driver.md#zenoh) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on. diff --git a/docs/ko/middleware/zenoh.md b/docs/ko/middleware/zenoh.md new file mode 100644 index 0000000000..71ca88d941 --- /dev/null +++ b/docs/ko/middleware/zenoh.md @@ -0,0 +1,201 @@ +# Zenoh (PX4 ROS 2 rmw_zenoh) + + + +:::warning +실험 +At the time of writing, PX4 Zenoh-pico is experimental, and hence subject to change. +::: + +PX4 supports Zenoh as an alternative mechanism (to DDS) for bridging uORB topics to [ROS 2](../ros2/user_guide.md) (via the ROS 2 [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh) middleware). +This allows uORB messages to be published and subscribed on a companion computer as though they were ROS 2 topics. +It provides a fast and lightweight way to connect PX4 to ROS 2, making it easier for applications to access vehicle telemetry and send control commands. + +The following guide describes the architecture and various options for setting up the Zenoh client and router. +In particular, it covers the options that are most important to PX4 users exploring Zenoh as an alternative communication layer for ROS 2. + +## 아키텍쳐 + +The Zenoh-based middleware consists of a client running on PX4 and a Zenoh router running on the companion computer, with bi-directional data exchange between them over a UART, TCP, UDP, or multicast-UDP link. +The router acts as a broker and discovery service, enabling PX4 to publish and subscribe to topics in the global Zenoh data space. +This allows seamless integration with ROS 2 nodes using [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh), and supports flexible deployment across distributed systems. + +![Architecture PX4 Zenoh-Pico with ROS 2](../../assets/middleware/zenoh/architecture-px4-zenoh.svg) + +The client is the _PX4 Zenoh-Pico Node_ referred to above, which is implemented in the [PX4 `zenoh` module](../modules/modules_driver.md#zenoh). +This is based on Zenoh-Pico, a minimalistic version of [Eclipse Zenoh](https://zenoh.io/) (a data-centric protocol designed for real-time, distributed, and resource-constrained environments). + +The router suggested above is [zenohd](https://github.com/eclipse-zenoh/zenoh/tree/main/zenohd). + +:::info +UART is supported by Zenoh but has not yet implemented in the PX4 Zenoh-Pico node. +::: + +## ROS 2 Zenoh Bring-up on Linux Companion + +In order for PX4 uORB topics to be shared with ROS 2 applications, you will need the PX4 Zenoh-Pico Node client running on your FMU, connected to a Zenoh router running on the companion computer (or elsewhere in the network). + +First select Zenoh as the ROS 2 transport by setting the `RMW_IMPLEMENTATION` environment variable as shown: + +```sh +export RMW_IMPLEMENTATION=rmw_zenoh_cpp +``` + +Then start the Zenoh router using the command: + +```sh +ros2 run rmw_zenoh_cpp rmw_zenohd +``` + +For more information about the Zenoh Router see the [rmw_zenoh](https://github.com/ros2/rmw_zenoh?tab=readme-ov-file#start-the-zenoh-router) documentation. + +## PX4 Zenoh-Pico Node Setup + +### PX4 Firmware + +Before setting up the Zenoh communication, first make sure that your firmware contains the driver that implements the [`zenoh` driver](../modules/modules_driver.md#zenoh), which provides the implementation of the _PX4 Zenoh-Pico Node_. + +You can check if the module is present on your board by searching for the key `CONFIG_MODULES_ZENOH=y` in your board's `default.px4board` KConfig file. +For example, you can see that the module is present in `px4_fmu-v6xrt` build targets from [/boards/px4/fmu-v6xrt/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6xrt/default.px4board#L91). + +If `CONFIG_MODULES_ZENOH=y` is not preset you can add this key to your board configuration and rebuild. +Note that due to flash constraints you may need to remove other components in order to include the module (such as the [`uxrce_dds_client` module](../modules/modules_system.md#uxrce-dds-client), which you will not need if you are using Zenoh). + +The table below shows some of the PX4 targets that include Zenoh by default. + +| PX4 Target | 참고 | +| ---------------------- | -------------------------------------------------------------------------------------------------------------- | +| `px4_fmu-v6xrt` | For [FMUv6X-RT](../flight_controller/nxp_mr_vmu_rt1176.md) (reference platform for testing) | +| `nxp_tropic-community` | | +| `nxp_mr-tropic` | | +| `nxp_mr-canhubk344` | | +| `px4_sitl_zenoh` | Zenoh-enabled simulation build | +| `px4_fmu-v6x_zenoh` | Zenoh-enabled firmware for FMUv6X | + +Zenoh is not included in the default `px4_fmu-` targets for any firmware other than `px4_fmu-v6xrt` (`px4_sitl_zenoh` and `px4_fmu-v6x_zenoh` [are build variants](../dev_setup/building_px4.md#px4-make-build-targets)). + +:::tip +You can check if Zenoh is present at runtime by using QGroundControl to [find the parameter](../advanced_config/parameters.md#finding-a-parameter) [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE). +If present, the module is installed. +::: + +### Enable Zenoh on PX4 Startup + +Set the [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE) parameter to `1` to enable Zenoh on PX4 startup. + +### Configure Zenoh Network + +Set up PX4 to connect to the companion computer running `zenohd`. + +PX4's default IP address of the Zenoh daemon host is `10.41.10.1`. +If you're using a different IP for the Zenoh daemon, run the following command (replacing the address) in a PX4 shell and then reboot: + +```sh +zenoh config net client tcp/10.41.10.1:7447#iface=eth0 +``` + +Note that for the simulation target with Zeroh (`px4_sitl_zenoh`) you won't need to make any changes because the default IP address of the Zenoh daemon is set to `localhost`. + +:::warning +Any changes to the network configuration require a PX4 system reboot to take effect. +::: + +:::tip +See [PX4 Ethernet Setup](../advanced_config/ethernet_setup.md) for more information about Ethernet configuration. +::: + +### PX4 Zenoh-pico Node configuration + +The **default configuration** is auto-generated from the [dds_topics.yaml](../middleware/dds_topics.md) file in the PX4 repository. +This file specifies which uORB message definitions are to be published/subscribed by ROS 2 applications, and hence (indirectly) which topics are compiled into the zenoh module. + +To inspect the current Zenoh configuration: + +```sh +zenoh config +``` + +The PX4 Zenoh-pico node stores its configuration on the **SD card** under the `zenoh` folder. +This folder contains three key files: + +- **`net.txt`** – Defines the **Zenoh network configuration**. +- **`pub.csv`** – Maps **uORB topics to ROS2 topics** (used for publishing). +- **`sub.csv`** – Maps **ROS2 topics to uORB topics** (used for subscribing). + +### 4. Modifying Topic Mappings + +Zenoh topic mappings define how data flows between PX4's internal uORB topics and external ROS2 topics via Zenoh. +These mappings are stored in `pub.csv` and `sub.csv` on the SD card, and can be modified at runtime using the `zenoh config` CLI tool. + +:::warning +Any changes to the topic mappings require a PX4 system reboot to take effect. +::: + +There are two types of mappings you can modify: + +- **Publisher mappings**: Forward data from a uORB topic to a Zenoh topic. +- **Subscriber mappings**: Receive data from a Zenoh topic and publish it to a uORB topic. + +The main operations and their commands are: + +- Publish a uORB topic to a Zenoh topic: + + ```sh + zenoh config add publisher [uorb_instance] + ``` + +- Subscribe to a Zenoh topic and forward it to a uORB topic: + + ```sh + zenoh config add subscriber [uorb_instance] + ``` + +- Remove existing mappings: + + ```sh + zenoh config delete publisher + zenoh config delete subscriber + ``` + +After modifying the mappings, reboot PX4 to apply the changes. +The updated configuration will be loaded from the SD card during startup. + +## Communicating with PX4 from ROS 2 via Zenoh + +Once your PX4 FMU is publishing data into ROS 2, you can inspect the available topics and their contents using standard ROS 2 CLI tools: + +```sh +ros2 topic list +``` + +Check topic type and publishers/subscribers: + +```sh +ros2 topic info -v /fmu/out/vehicle_status +Type: px4_msgs/msg/VehicleStatus + +Publisher count: 1 + +Node name: px4_aabbcc00000000000000000000000000 +Node namespace: / +Topic type: px4_msgs/msg/VehicleStatus +Topic type hash: RIHS01_828bddbb7d4c2aa6ad93757955f6893be1ec5d8f11885ec7715bcdd76b5226c9 +Endpoint type: PUBLISHER +GID: 82.99.74.2c.b6.7d.93.44.91.4d.fe.14.93.58.40.16 +QoS profile: + Reliability: RELIABLE + History (Depth): KEEP_LAST (7) + Durability: VOLATILE + Lifespan: Infinite + Deadline: Infinite + Liveliness: AUTOMATIC + Liveliness lease duration: Infinite + +Subscription count: 0 +``` + +### PX4 ROS 2 Interface with Zenoh + +The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) works out of the box with Zenoh as a transport backend. +This means you can publish and subscribe to PX4 topics over Zenoh without changing your ROS 2 nodes or dealing with DDS configuration. +For setup details and supported message types, refer to the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md). diff --git a/docs/ko/modules/modules_driver_distance_sensor.md b/docs/ko/modules/modules_driver_distance_sensor.md index 6e61c2ef42..3d34e69be4 100644 --- a/docs/ko/modules/modules_driver_distance_sensor.md +++ b/docs/ko/modules/modules_driver_distance_sensor.md @@ -104,7 +104,7 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### 설명 -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html diff --git a/docs/ko/msg_docs/AirspeedValidated.md b/docs/ko/msg_docs/AirspeedValidated.md index 9034960626..61f607e7fa 100644 --- a/docs/ko/msg_docs/AirspeedValidated.md +++ b/docs/ko/msg_docs/AirspeedValidated.md @@ -1,29 +1,39 @@ # AirspeedValidated (UORB message) +Validated airspeed + +Provides information about airspeed (indicated, true, calibrated) and the source of the data. +Used by controllers, estimators and for airspeed reporting to operator. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) ```c +# Validated airspeed +# +# Provides information about airspeed (indicated, true, calibrated) and the source of the data. +# Used by controllers, estimators and for airspeed reporting to operator. + + uint32 MESSAGE_VERSION = 1 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start -float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid -float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid -float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid +float32 indicated_airspeed_m_s # [m/s] [@invalid NaN] Indicated airspeed (IAS) +float32 calibrated_airspeed_m_s # [m/s] [@invalid NaN] Calibrated airspeed (CAS) +float32 true_airspeed_m_s # [m/s] [@invalid NaN] True airspeed (TAS) -int8 airspeed_source # Source of currently published airspeed values -int8 DISABLED = -1 -int8 GROUND_MINUS_WIND = 0 -int8 SENSOR_1 = 1 -int8 SENSOR_2 = 2 -int8 SENSOR_3 = 3 -int8 SYNTHETIC = 4 +int8 airspeed_source # [@enum SOURCE] Source of currently published airspeed values +int8 SOURCE_DISABLED = -1 # Disabled +int8 SOURCE_GROUND_MINUS_WIND = 0 # Ground speed minus wind +int8 SOURCE_SENSOR_1 = 1 # Sensor 1 +int8 SOURCE_SENSOR_2 = 2 # Sensor 2 +int8 SOURCE_SENSOR_3 = 3 # Sensor 3 +int8 SOURCE_SYNTHETIC = 4 # Synthetic airspeed -# debug states -float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid -float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid -float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] -float32 throttle_filtered # filtered fixed-wing throttle [-] -float32 pitch_filtered # filtered pitch [rad] +float32 calibrated_ground_minus_wind_m_s # [m/s] [@invalid NaN] CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption +float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airspeed +float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative +float32 throttle_filtered # [-] Filtered fixed-wing throttle +float32 pitch_filtered # [rad] Filtered pitch ``` diff --git a/docs/ko/msg_docs/AutotuneAttitudeControlStatus.md b/docs/ko/msg_docs/AutotuneAttitudeControlStatus.md index 734a671ffd..31a47ef204 100644 --- a/docs/ko/msg_docs/AutotuneAttitudeControlStatus.md +++ b/docs/ko/msg_docs/AutotuneAttitudeControlStatus.md @@ -1,42 +1,59 @@ # AutotuneAttitudeControlStatus (UORB message) +Autotune attitude control status + +This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +and is subscribed to by the respective attitude controllers to command rate setpoints. + +The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AutotuneAttitudeControlStatus.msg) ```c -uint64 timestamp # time since system start (microseconds) +# Autotune attitude control status +# +# This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +# and is subscribed to by the respective attitude controllers to command rate setpoints. +# +# The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. -float32[5] coeff # coefficients of the identified discrete-time model -float32[5] coeff_var # coefficients' variance of the identified discrete-time model -float32 fitness # fitness of the parameter estimate -float32 innov -float32 dt_model +uint64 timestamp # [us] Time since system start -float32 kc -float32 ki -float32 kd -float32 kff -float32 att_p +float32[5] coeff # [-] Coefficients of the identified discrete-time model +float32[5] coeff_var # [-] Coefficients' variance of the identified discrete-time model +float32 fitness # [-] Fitness of the parameter estimate +float32 innov # [rad/s] Innovation (residual error between model and measured output) +float32 dt_model # [s] Model sample time used for identification -float32[3] rate_sp -float32 u_filt -float32 y_filt +float32 kc # [-] Proportional rate-loop gain (ideal form) +float32 ki # [-] Integral rate-loop gain (ideal form) +float32 kd # [-] Derivative rate-loop gain (ideal form) +float32 kff # [-] Feedforward rate-loop gain +float32 att_p # [-] Proportional attitude gain -uint8 STATE_IDLE = 0 -uint8 STATE_INIT = 1 -uint8 STATE_ROLL = 2 -uint8 STATE_ROLL_PAUSE = 3 -uint8 STATE_PITCH = 4 -uint8 STATE_PITCH_PAUSE = 5 -uint8 STATE_YAW = 6 -uint8 STATE_YAW_PAUSE = 7 -uint8 STATE_VERIFICATION = 8 -uint8 STATE_APPLY = 9 -uint8 STATE_TEST = 10 -uint8 STATE_COMPLETE = 11 -uint8 STATE_FAIL = 12 -uint8 STATE_WAIT_FOR_DISARM = 13 +float32[3] rate_sp # [rad/s] Rate setpoint commanded to the attitude controller. -uint8 state +float32 u_filt # [-] Filtered input signal (normalized torque setpoint) used in system identification. +float32 y_filt # [rad/s] Filtered output signal (angular velocity) used in system identification. + +uint8 state # [@enum STATE] Current state of the autotune procedure. +uint8 STATE_IDLE = 0 # Idle (not running) +uint8 STATE_INIT = 1 # Initialize filters and setup +uint8 STATE_ROLL_AMPLITUDE_DETECTION = 2 # FW only: determine required excitation amplitude (roll) +uint8 STATE_ROLL = 3 # Roll-axis excitation and model identification +uint8 STATE_ROLL_PAUSE = 4 # Pause to return to level flight +uint8 STATE_PITCH_AMPLITUDE_DETECTION = 5 # FW only: determine required excitation amplitude (pitch) +uint8 STATE_PITCH = 6 # Pitch-axis excitation and model identification +uint8 STATE_PITCH_PAUSE = 7 # Pause to return to level flight +uint8 STATE_YAW_AMPLITUDE_DETECTION = 8 # FW only: determine required excitation amplitude (yaw) +uint8 STATE_YAW = 9 # Yaw-axis excitation and model identification +uint8 STATE_YAW_PAUSE = 10 # Pause to return to level flight +uint8 STATE_VERIFICATION = 11 # Verify model and candidate gains +uint8 STATE_APPLY = 12 # Apply gains +uint8 STATE_TEST = 13 # Test gains in closed-loop +uint8 STATE_COMPLETE = 14 # Tuning completed successfully +uint8 STATE_FAIL = 15 # Tuning failed (model invalid or controller unstable) +uint8 STATE_WAIT_FOR_DISARM = 16 # Waiting for disarm before finalizing ``` diff --git a/docs/ko/msg_docs/ControlAllocatorStatus.md b/docs/ko/msg_docs/ControlAllocatorStatus.md index b355b772b6..4068e7b4f4 100644 --- a/docs/ko/msg_docs/ControlAllocatorStatus.md +++ b/docs/ko/msg_docs/ControlAllocatorStatus.md @@ -24,5 +24,6 @@ int8[16] actuator_saturation # Indicates actuator saturation status. # Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value. uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector +uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection ``` diff --git a/docs/ko/msg_docs/EstimatorStatusFlags.md b/docs/ko/msg_docs/EstimatorStatusFlags.md index 0ac832817d..aa7250fe1e 100644 --- a/docs/ko/msg_docs/EstimatorStatusFlags.md +++ b/docs/ko/msg_docs/EstimatorStatusFlags.md @@ -54,8 +54,9 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended -bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_gnss_fault # 45 - true if GNSS true if GNSS measurements (lat, lon, vel) have been declared faulty bool cs_yaw_manual # 46 - true if yaw has been set manually +bool cs_gnss_hgt_fault # 47 - true if GNSS true if GNSS measurements (alt) have been declared faulty # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/docs/ko/msg_docs/FailureDetectorStatus.md b/docs/ko/msg_docs/FailureDetectorStatus.md index 88e3ca4c24..a112a1e642 100644 --- a/docs/ko/msg_docs/FailureDetectorStatus.md +++ b/docs/ko/msg_docs/FailureDetectorStatus.md @@ -17,5 +17,6 @@ bool fd_motor float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed) uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures +uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection ``` diff --git a/docs/ko/msg_docs/GimbalDeviceAttitudeStatus.md b/docs/ko/msg_docs/GimbalDeviceAttitudeStatus.md index 2c8c6eca9b..0935029087 100644 --- a/docs/ko/msg_docs/GimbalDeviceAttitudeStatus.md +++ b/docs/ko/msg_docs/GimbalDeviceAttitudeStatus.md @@ -14,6 +14,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2 uint16 DEVICE_FLAGS_ROLL_LOCK = 4 uint16 DEVICE_FLAGS_PITCH_LOCK = 8 uint16 DEVICE_FLAGS_YAW_LOCK = 16 +uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 +uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 + float32[4] q float32 angular_velocity_x diff --git a/docs/ko/msg_docs/SensorGnssStatus.md b/docs/ko/msg_docs/SensorGnssStatus.md new file mode 100644 index 0000000000..70602b85fc --- /dev/null +++ b/docs/ko/msg_docs/SensorGnssStatus.md @@ -0,0 +1,19 @@ +# SensorGnssStatus (UORB message) + +Gnss quality indicators + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssStatus.msg) + +```c +# Gnss quality indicators + +uint64 timestamp # time since system start (microseconds) +uint32 device_id # unique device ID for the sensor that does not change between power cycles + +bool quality_available # Set to true if quality indicators are available +uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if not available +uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available +uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available +uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available + +``` diff --git a/docs/ko/msg_docs/SensorGps.md b/docs/ko/msg_docs/SensorGps.md index c8d09e9472..1b5fb3cf41 100644 --- a/docs/ko/msg_docs/SensorGps.md +++ b/docs/ko/msg_docs/SensorGps.md @@ -38,18 +38,26 @@ float32 vdop # Vertical dilution of precision int32 noise_per_ms # GPS noise per millisecond uint16 automatic_gain_control # Automatic gain control monitor -uint8 JAMMING_STATE_UNKNOWN = 0 -uint8 JAMMING_STATE_OK = 1 -uint8 JAMMING_STATE_WARNING = 2 -uint8 JAMMING_STATE_CRITICAL = 3 -uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical -int32 jamming_indicator # indicates jamming is occurring +uint8 JAMMING_STATE_UNKNOWN = 0 #default +uint8 JAMMING_STATE_OK = 1 +uint8 JAMMING_STATE_MITIGATED = 2 +uint8 JAMMING_STATE_DETECTED = 3 +uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected +int32 jamming_indicator # indicates jamming is occurring -uint8 SPOOFING_STATE_UNKNOWN = 0 -uint8 SPOOFING_STATE_NONE = 1 -uint8 SPOOFING_STATE_INDICATED = 2 -uint8 SPOOFING_STATE_MULTIPLE = 3 -uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical +uint8 SPOOFING_STATE_UNKNOWN = 0 #default +uint8 SPOOFING_STATE_OK = 1 +uint8 SPOOFING_STATE_MITIGATED = 2 +uint8 SPOOFING_STATE_DETECTED = 3 +uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected + +# Combined authentication state (e.g. Galileo OSNMA) +uint8 AUTHENTICATION_STATE_UNKNOWN = 0 #default +uint8 AUTHENTICATION_STATE_INITIALIZING = 1 +uint8 AUTHENTICATION_STATE_ERROR = 2 +uint8 AUTHENTICATION_STATE_OK = 3 +uint8 AUTHENTICATION_STATE_DISABLED = 4 +uint8 authentication_state # GPS signal authentication state float32 vel_m_s # GPS ground speed, (metres/sec) float32 vel_n_m_s # GPS North velocity, (metres/sec) @@ -63,6 +71,16 @@ uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp whi uint8 satellites_used # Number of satellites used +uint32 SYSTEM_ERROR_OK = 0 #default +uint32 SYSTEM_ERROR_INCOMING_CORRECTIONS = 1 +uint32 SYSTEM_ERROR_CONFIGURATION = 2 +uint32 SYSTEM_ERROR_SOFTWARE = 4 +uint32 SYSTEM_ERROR_ANTENNA = 8 +uint32 SYSTEM_ERROR_EVENT_CONGESTION = 16 +uint32 SYSTEM_ERROR_CPU_OVERLOAD = 32 +uint32 SYSTEM_ERROR_OUTPUT_CONGESTION = 64 +uint32 system_error # General errors with the connected GPS receiver + float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI]) float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI]) float32 heading_accuracy # heading accuracy (rad, [0, 2PI]) diff --git a/docs/ko/msg_docs/VehicleOdometry.md b/docs/ko/msg_docs/VehicleOdometry.md index d559ded6c7..4213c23337 100644 --- a/docs/ko/msg_docs/VehicleOdometry.md +++ b/docs/ko/msg_docs/VehicleOdometry.md @@ -1,41 +1,44 @@ # VehicleOdometry (UORB message) -Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +Vehicle odometry data + +Fits ROS REP 147 for aerial vehicles [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleOdometry.msg) ```c -# Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +# Vehicle odometry data +# +# Fits ROS REP 147 for aerial vehicles uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp sample -uint8 POSE_FRAME_UNKNOWN = 0 -uint8 POSE_FRAME_NED = 1 # NED earth-fixed frame -uint8 POSE_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference -uint8 pose_frame # Position and orientation frame of reference +uint8 pose_frame # [@enum POSE_FRAME] Position and orientation frame of reference +uint8 POSE_FRAME_UNKNOWN = 0 # Unknown frame +uint8 POSE_FRAME_NED = 1 # North-East-Down (NED) navigation frame. Aligned with True North. +uint8 POSE_FRAME_FRD = 2 # Forward-Right-Down (FRD) frame. Constant arbitrary heading offset from True North. Z is down. -float32[3] position # Position in meters. Frame of reference defined by local_frame. NaN if invalid/unknown -float32[4] q # Quaternion rotation from FRD body frame to reference frame. First value NaN if invalid/unknown +float32[3] position # [m] [@frame local frame] [@invalid NaN If invalid/unknown] Position. Origin is position of GC at startup. +float32[4] q # [-] [@invalid NaN First value if invalid/unknown] Attitude (expressed as a quaternion) relative to pose reference frame at current location. Follows the Hamiltonian convention (w, x, y, z, right-handed, passive rotations from body to world) -uint8 VELOCITY_FRAME_UNKNOWN = 0 -uint8 VELOCITY_FRAME_NED = 1 # NED earth-fixed frame -uint8 VELOCITY_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference -uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame -uint8 velocity_frame # Reference frame of the velocity data +uint8 velocity_frame # [@enum VELOCITY_FRAME] Reference frame of the velocity data +uint8 VELOCITY_FRAME_UNKNOWN = 0 # Unknown frame +uint8 VELOCITY_FRAME_NED = 1 # NED navigation frame at current position. +uint8 VELOCITY_FRAME_FRD = 2 # FRD navigation frame at current position. Constant arbitrary heading offset from True North. Z is down. +uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame -float32[3] velocity # Velocity in meters/sec. Frame of reference defined by velocity_frame variable. NaN if invalid/unknown +float32[3] velocity # [m/s] [@frame @velocity_frame] [@invalid NaN If invalid/unknown] Velocity. +float32[3] angular_velocity # [rad/s] [@frame @VELOCITY_FRAME_BODY_FRD] [@invalid NaN If invalid/unknown] Angular velocity in body-fixed frame -float32[3] angular_velocity # Angular velocity in body-fixed frame (rad/s). NaN if invalid/unknown +float32[3] position_variance # [m^2] Variance of position error +float32[3] orientation_variance # [rad^2] Variance of orientation/attitude error (expressed in body frame) +float32[3] velocity_variance # [m^2/s^2] Variance of velocity error -float32[3] position_variance -float32[3] orientation_variance -float32[3] velocity_variance - -uint8 reset_counter -int8 quality +uint8 reset_counter # [-] Reset counter. Counts reset events on attitude, velocity and position. +int8 quality # [-] [@invalid 0] Quality. Unused. # TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry # TOPICS estimator_odometry diff --git a/docs/ko/msg_docs/index.md b/docs/ko/msg_docs/index.md index 7887060b3b..a94bc75e82 100644 --- a/docs/ko/msg_docs/index.md +++ b/docs/ko/msg_docs/index.md @@ -15,7 +15,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message -- [AirspeedValidated](AirspeedValidated.md) +- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed - [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply - [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request - [BatteryStatus](BatteryStatus.md) — Battery status @@ -70,7 +70,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [VehicleLandDetected](VehicleLandDetected.md) - [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data - [VehicleRatesSetpoint](VehicleRatesSetpoint.md) - [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander - [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE @@ -87,7 +87,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [AdcReport](AdcReport.md) - [Airspeed](Airspeed.md) — Airspeed data from sensors - [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector) -- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) +- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status - [BatteryInfo](BatteryInfo.md) — Battery information - [ButtonEvent](ButtonEvent.md) - [CameraCapture](CameraCapture.md) @@ -246,6 +246,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m change with board revisions and sensor updates. - [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor - [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. +- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators - [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds) - [SensorGyro](SensorGyro.md) diff --git a/docs/ko/ros2/px4_ros2_waypoint_missions.md b/docs/ko/ros2/px4_ros2_waypoint_missions.md index f99f3597e0..4a82072ff0 100644 --- a/docs/ko/ros2/px4_ros2_waypoint_missions.md +++ b/docs/ko/ros2/px4_ros2_waypoint_missions.md @@ -36,7 +36,7 @@ There are some benefits and drawbacks to using ROS-based missions, which are pro - QGroundControl currently does not display the mission or progress during execution, and cannot upload or download a mission. Therefore you will need another mechanism to provide a mission, such as from a web server, a custom GCS, or by generating it directly inside the application. -- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-gotosetpointtype), which only works for multicopters, and VTOL in MC mode). +- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-multicoptergotosetpointtype), which only works for multicopters, and VTOL in MC mode). It is designed to be extendable to any other vehicle type. ## 개요 diff --git a/docs/ko/sensor/inertial_navigation_systems.md b/docs/ko/sensor/inertial_navigation_systems.md index ca354d569e..8a2ec11989 100644 --- a/docs/ko/sensor/inertial_navigation_systems.md +++ b/docs/ko/sensor/inertial_navigation_systems.md @@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) +- [MicroStrain](../sensor/microstrain.md): Includes VRU, AHRS, INS, and GNSS/INS devices. - [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. - [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. diff --git a/docs/ko/sensor/microstrain.md b/docs/ko/sensor/microstrain.md new file mode 100644 index 0000000000..1cb0e1b8d5 --- /dev/null +++ b/docs/ko/sensor/microstrain.md @@ -0,0 +1,219 @@ +# MicroStrain (INS, IMU, VRU, AHRS) + +MicroStrain by HBK provides high-performance inertial sensors engineered for reliability and precision in challenging environments. +Widely used across industries like aerospace, robotics, industrial automation, and research, MicroStrain sensors are optimized for real-time, accurate motion tracking and orientation data. + +![CV7](../../assets/hardware/sensors/inertial/microstrain_3dm_cv7_hbk.png) + +The driver currently supports the following hardware: + +- [`MicroStrain CV7-AR`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/vertical-reference-units--vru-/3dm-cv7-ar): Inertial Measurement Unit (IMU) and Vertical Reference Unit (VRU) +- [`MicroStrain CV7-AHRS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/attitude-and-heading-reference-systems--ahrs-/3dm-cv7-ahrs): Inertial Measurement Unit (IMU) and Attitude Heading Reference System (AHRS) +- [`MicroStrain CV7-INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS). +- [`MicroStrain CV7-GNSS/INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-gnss-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS) combined with dual multiband (GNSS) receivers. + +PX4 can use these sensors to provide raw IMU data for EKF2 or to replace EKF2 as an external INS. +For more information, including user manuals and datasheets, please refer to the sensors product page. + +## 구매처 + +MicroStrain sensors can be purchased through HBK's official [MicroStrain product page](https://www.hbkworld.com/en/products/transducers/inertial-sensors) or through authorized distributors globally. +For large orders, custom requirements, or technical inquiries, reach out directly to [sales](https://www.hbkworld.com/en/contact-us/contact-sales-microstrain) + +## 하드웨어 설정 + +### 배선 + +Connect the main UART port of the MicroStrain sensor to any unused serial port on the flight controller. +This port needs to be specified while starting the device. + +### 장착 + +The MicroStrain sensor can be mounted in any orientation. +The default coordinate system uses X for the front, Y for the right, and Z for down, with directions marked on the device. + +## 펌웨어 설정 + +### PX4 설정 + +To use the MicroStrain driver: + +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`. + +2. Configure the driver mode by setting [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) + + - To use the MicroStrain sensor to provide raw IMU data to EKF2 + + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 0 + 2. Update the [EKF2_MULTI_IMU](../advanced_config/parameter_reference.md#EKF2_MULTI_IMU) parameter to account for the added MicroStrain sensor. + 3. Enable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 1 + 4. To prioritize MicroStrain sensor output, adjust the priority level of individual sensors from 0-100 using the following parameters: + + - [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO) + - [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO) + - [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO) + - [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO) + + where `n` corresponds to the index of the corresponding sensor. + + ::: tip + Sensors can be identified by their device id, which can be found by checking the parameters: + + - [CAL_ACCn_ID](../advanced_config/parameter_reference.md#CAL_ACC0_ID) + - [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) + - [CAL_MAGn_ID](../advanced_config/parameter_reference.md#CAL_MAG0_ID) + - [CAL_BAROn_ID](../advanced_config/parameter_reference.md#CAL_BARO0_ID) + + +::: + + - To use the MicroStrain sensor as an external INS + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 1 + 2. Disable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 0 + +3. Reboot and start the driver + - `microstrain start -d ` + - To start the driver automatically when the flight controller powers on, set [SENS_MS_CFG](../advanced_config/parameter_reference.md#SENS_MS_CFG) to the sensor’s connected port. + +## MicroStrain Configuration + +1. Rates: + + - By default, accel and gyro data are published at 500 Hz, magnetometer at 50 Hz, and barometric pressure at 50 Hz. + This can be changed by adjusting the following parameters: + + - [MS_IMU_RATE_HZ](../advanced_config/parameter_reference.md#MS_IMU_RATE_HZ) + - [MS_MAG_RATE_HZ](../advanced_config/parameter_reference.md#MS_MAG_RATE_HZ) + - [MS_BARO_RATE_HZ](../advanced_config/parameter_reference.md#MS_BARO_RATE_HZ) + + - Global position, local position, attitude and odometry will be published at 250 Hz by default. + This can be configured via: + + - [MS_FILT_RATE_HZ](../advanced_config/parameter_reference.md#MS_FILT_RATE_HZ) + + - For the CV7-GNSS/INS, the GNSS receiver 1 and 2 will publish data at 5Hz by default. + This can be changed using: + + - [MS_GNSS_RATE_HZ](../advanced_config/parameter_reference.md#MS_GNSS_RATE_HZ) + + - The driver will automatically configure data outputs based on the specific sensor model and available data streams. + + - The driver is scheduled to run at twice the fastest configured data rate. + +2. Aiding measurements: + + - If supported, GNSS position and velocity aiding are always enabled. + + - Internal/external magnetometer and heading aiding, as well as optical flow aiding, are disabled by default. They can be enabled using the following parameters: + + - [MS_INT_MAG_EN](../advanced_config/parameter_reference.md#MS_INT_MAG_EN) + - [MS_INT_HEAD_EN](../advanced_config/parameter_reference.md#MS_INT_HEAD_EN) + - [MS_EXT_HEAD_EN](../advanced_config/parameter_reference.md#MS_EXT_HEAD_EN) + - [MS_EXT_MAG_EN](../advanced_config/parameter_reference.md#MS_EXT_MAG_EN) + - [MS_OPT_FLOW_EN](../advanced_config/parameter_reference.md#MS_OPT_FLOW_EN) + + - The aiding frames for external sources can be configured using the following parameters: + + - [MS_EHEAD_YAW](../advanced_config/parameter_reference.md#MS_EHEAD_YAW) + - [MS_EMAG_ROLL](../advanced_config/parameter_reference.md#MS_EMAG_ROLL) + - [MS_EMAG_PTCH](../advanced_config/parameter_reference.md#MS_EMAG_PTCH) + - [MS_EMAG_YAW](../advanced_config/parameter_reference.md#MS_EMAG_YAW) + - [MS_OFLW_OFF_X](../advanced_config/parameter_reference.md#MS_OFLW_OFF_X) + - [MS_OFLW_OFF_Y](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Y) + - [MS_OFLW_OFF_Z](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Z) + - [SENS_FLOW_ROT](../advanced_config/parameter_reference.md#SENS_FLOW_ROT) + + - The uncertainty for optical flow and external magnetometer aiding must be specified using the following parameters: + + - [MS_EMAG_UNCERT](../advanced_config/parameter_reference.md#MS_EMAG_UNCERT) + - [MS_OFLW_UNCERT](../advanced_config/parameter_reference.md#MS_OFLW_UNCERT) + + ::: tip + + 1. When optical flow aiding is enabled, the sensor uses the `vehicle_optical_flow_vel` output from the flight controller as a body-frame velocity aiding measurement. + 2. If the MicroStrain sensor does not support these aiding sources but they are enabled, sensor initialization will fail. + + +::: + +3. Initial heading alignment: + + - Initial heading alignment is set to kinematic by default. This can be changed by adjusting + + - [MS_ALIGNMENT](../advanced_config/parameter_reference.md#MS_ALIGNMENT) + +4. GNSS Aiding Source Control (GNSS/INS only) + + - The Source of the GNSS aiding data can be configured using: + + - [MS_GNSS_AID_SRC](../advanced_config/parameter_reference.md#MS_GNSS_AID_SRC) + +5. Sensor to vehicle transform: + + - If the sensor is mounted in an orientation different from the vehicle frame. A sensor to vehicle transform can be enabled using + + - [MS_SVT_EN](../advanced_config/parameter_reference.md#MS_SVT_EN) + + - The transform is defined using the following parameters + + - [MS_SENSOR_ROLL](../advanced_config/parameter_reference.md#MS_SENSOR_ROLL) + - [MS_SENSOR_PTCH](../advanced_config/parameter_reference.md#MS_SENSOR_PTCH) + - [MS_SENSOR_YAW](../advanced_config/parameter_reference.md#MS_SENSOR_YAW) + +6. IMU ranges: + + - The accelerometer and gyroscope ranges on the device are configurable using: + + - [MS_ACCEL_RANGE](../advanced_config/parameter_reference.md#MS_ACCEL_RANGE) + - [MS_GYRO_RANGE](../advanced_config/parameter_reference.md#MS_GYRO_RANGE) + + ::: tip + Available range settings depend on the specific [sensor](https://www.hbkworld.com/en/products/transducers/inertial-sensors) and can be found in the corresponding user manual. + By default, the ranges are not changed. + + +::: + +7. GNSS Lever arm offsets: + + - The lever arm offset for the external GNSS receiver can be configured using: + + - [MS_GNSS_OFF1_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_X) + - [MS_GNSS_OFF1_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Y) + - [MS_GNSS_OFF1_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Z) + + - For dual-antenna configurations, the second GNSS receiver’s offset is configured using: + + - [MS_GNSS_OFF2_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_X) + - [MS_GNSS_OFF2_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Y) + - [MS_GNSS_OFF2_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Z) + +## Published Data + +The MicroStrain driver continuously publishes sensor data to the following uORB topics: + +- [sensor_accel](../msg_docs/SensorAccel.md) +- [sensor_gyro](../msg_docs/SensorGyro.md) +- [sensor_mag](../msg_docs/SensorMag.md) +- [sensor_baro](../msg_docs/SensorBaro.md) + +For GNSS/INS devices, GPS data is also published to: + +- [sensor_gps](../msg_docs/SensorGps.md) + +If used as an external INS replacing EKF2, it publishes: + +- [vehicle_global_position](../msg_docs/VehicleGlobalPosition.md) +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) +- [vehicle_odometry](../msg_docs/VehicleOdometry.md) + +otherwise the same data is published to the following topics + +- `external_ins_global_position` +- `external_ins_attitude` +- `external_ins_local_position` + +:::tip +Published topics can be viewed using the `listener` command. +::: diff --git a/docs/ko/test_and_ci/test_flights.md b/docs/ko/test_and_ci/test_flights.md index eabc3c3176..b0c65c3a6d 100644 --- a/docs/ko/test_and_ci/test_flights.md +++ b/docs/ko/test_and_ci/test_flights.md @@ -28,5 +28,7 @@ These are run by the test team as part of release testing, and for more signific - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) -- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_07 - Optical Flow Low Mount](../test_cards/mc_07_optical_flow_low_mount.md) - [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) +- [MC_09 - VIO (Visual-Inertial Odometry)](../test_cards/mc_09_vio.md) +- [MC_10 - Optical Flow / GPS Mixed](../test_cards/mc_10_optical_flow_gps_mixed.md) diff --git a/docs/ko/test_cards/mc_06_optical_flow.md b/docs/ko/test_cards/mc_06_optical_flow.md index 901e113218..9378bf2e4d 100644 --- a/docs/ko/test_cards/mc_06_optical_flow.md +++ b/docs/ko/test_cards/mc_06_optical_flow.md @@ -2,25 +2,23 @@ ## Objective -To test that optical flow works as expected +Test that optical flow works as expected ## Preflight -Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation -([Setup Information here](../sensor/optical_flow.md)) +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation ([setup information here](../sensor/optical_flow.md)) -Ensure there are no other sources of positioning besides optical flow +Ensure there are no other sources of positioning besides optical flow: - [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` - [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` - [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` -- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into Altitude / Position mode while still on the ground ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -28,7 +26,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -38,6 +36,16 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates +❏ Varying height terrain + +    ❏ Put boxes on the ground to create varying heights in terrain + +    ❏ Take off in position mode and fly over the boxes such that the downward facing rangefinder varies in value + +    ❏ Do a few passes with varying amounts of time over the boxes (1-30 seconds if possible) + +    ❏ Drone should not raise in height when flying over boxes + ## 착륙 ❏ Land in either Position or Altitude mode with the throttle below 40% @@ -47,7 +55,8 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## 예상 결과 - 추력을 올릴 때 서서히 이륙한다 -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering (over surface with many features) +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨 +- Drone should not raise in height when flying over boxes - 지면에 착륙시, 콥터가 지면에서 튀면 안됨 diff --git a/docs/ko/test_cards/mc_07_optical_flow_low_mount.md b/docs/ko/test_cards/mc_07_optical_flow_low_mount.md new file mode 100644 index 0000000000..5ac887e804 --- /dev/null +++ b/docs/ko/test_cards/mc_07_optical_flow_low_mount.md @@ -0,0 +1,45 @@ +# Test MC_07 - Optical Flow Low Sensor + +## Objective + +Test that optical flow works as expected with a low mounted optical flow sensor + +## Preflight + +Ensure that the drone's optical flow sensor is mounted more than an inch off of the ground + +Ensure that [MPC_THR_MIN](../advanced_config/parameter_reference.md#MPC_THR_MIN) is tuned correctly for landing + +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` + +Ensure that the drone can go into [Position mode](../flight_modes_mc/position.md) while still on the ground + +## Flight Tests + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 착륙 + +❏ Land in Position mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 예상 결과 + +- 추력을 올릴 때 서서히 이륙한다 +- Drone should stay in Position mode, NOT fall into [altitude](../flight_modes_mc/altitude.md) mode diff --git a/docs/ko/test_cards/mc_08_dshot.md b/docs/ko/test_cards/mc_08_dshot.md index e5b7f8f073..0df821802b 100644 --- a/docs/ko/test_cards/mc_08_dshot.md +++ b/docs/ko/test_cards/mc_08_dshot.md @@ -6,22 +6,22 @@ Regression test for DSHOT working with PX4 ## Preflight -- Ensure vehicle is using a DSHOT ESC. +- Ensure vehicle is using a DSHOT ESC - Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled - Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) - Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked ## Flight Tests -❏ Stabilized Flight mode +❏ [Stabilized mode](../flight_modes_mc/manual_stabilized.md) -    ❏ Takeoff in stabilized flight mode to ensure correct motor spin +    ❏ Takeoff in stabilized mode to ensure correct motor spin     ❏ Pitch/Roll/Yaw response 1:1     ❏ Throttle response 1:1 -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -41,6 +41,6 @@ Regression test for DSHOT working with PX4 - Download flight logs - Load into Data Plot Juggler -- Ensure data is logged for esc_status/esc.0x/esc_rpm +- Ensure data is logged for `esc_status`/`esc.0x`/`esc_rpm` ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/ko/test_cards/mc_09_vio.md b/docs/ko/test_cards/mc_09_vio.md new file mode 100644 index 0000000000..966073fafd --- /dev/null +++ b/docs/ko/test_cards/mc_09_vio.md @@ -0,0 +1,52 @@ +# Test MC_09 - VIO (Visual-Inertial Odometry) + +## Objective + +Test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 착륙 + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 예상 결과 + +- 추력을 올릴 때 서서히 이륙한다 +- Drone should hold altitude in Altitude mode without wandering +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨 +- 지면에 착륙시, 콥터가 지면에서 튀면 안됨 diff --git a/docs/ko/test_cards/mc_10_optical_flow_gps_mixed.md b/docs/ko/test_cards/mc_10_optical_flow_gps_mixed.md new file mode 100644 index 0000000000..0f53829de9 --- /dev/null +++ b/docs/ko/test_cards/mc_10_optical_flow_gps_mixed.md @@ -0,0 +1,74 @@ +# Test MC_10 - Optical Flow / GPS Mixed + +## Objective + +Test that optical flow mixed with GPS works as expected + +## Preflight + +[Setup optical flow and GPS](../sensor/optical_flow.md) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `7` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `1` +- [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF): `1` (GPS) + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +❏ GPS Cutout + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Open QGC and navigate to MAVLink Console + +    ❏ Type `gps off` to disable GPS + +    ❏ Drone should maintain position hold via optical flow + +❏ GPS Degredation + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Fly under a metal surface (or other GPS blocking structure) + +    ❏ Ensure drone does not lose position hold or start drifting + +    ❏ Fly out of metal structure to regain GPS + +❏ GPS Acquisition + +    ❏ Takeoff in position mode in non-GPS environment + +    ❏ Fly into a GPS rich environment (outdoors) + +    ❏ Ensure drone acquires GPS position + +## 예상 결과 + +- 추력을 올릴 때 서서히 이륙한다 +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Drone should hold position in GPS rich environment as well as non-GPS environment +- 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨 diff --git a/docs/package-lock.json b/docs/package-lock.json index 3313510d76..9b3b318cac 100644 --- a/docs/package-lock.json +++ b/docs/package-lock.json @@ -9,7 +9,7 @@ "version": "1.0.1", "license": "CC-BY-4.0", "dependencies": { - "@red-asuka/vitepress-plugin-tabs": "^0.0.3", + "@red-asuka/vitepress-plugin-tabs": "0.0.4", "lite-youtube-embed": "^0.3.3", "markdown-it-mathjax3": "^4.3.2", "medium-zoom": "^1.1.0", @@ -727,9 +727,9 @@ "license": "MIT" }, "node_modules/@red-asuka/vitepress-plugin-tabs": { - "version": "0.0.3", - "resolved": "https://registry.npmjs.org/@red-asuka/vitepress-plugin-tabs/-/vitepress-plugin-tabs-0.0.3.tgz", - "integrity": "sha512-YZX7lBzoL8rgNRahk85XmXtOYfX9P8RFtHpT33K2LClrbYF1N2J1ds5iKK1nQ9e5m9Wt4shC6Bk/rGwCxhHPHg==", + "version": "0.0.4", + "resolved": "https://registry.npmjs.org/@red-asuka/vitepress-plugin-tabs/-/vitepress-plugin-tabs-0.0.4.tgz", + "integrity": "sha512-fcZAR281xnPiTm2ha8Wogg3PyFG5ZdJoeCGFeg7lOif53wXxo1obJQS98A8n/ujL//fFok/sDr1659Hbx6MD0Q==", "license": "MIT", "dependencies": { "markdown-it": "^13.0.1", @@ -3043,9 +3043,9 @@ } }, "node_modules/vite": { - "version": "5.4.19", - "resolved": "https://registry.npmjs.org/vite/-/vite-5.4.19.tgz", - "integrity": "sha512-qO3aKv3HoQC8QKiNSTuUM1l9o/XX3+c+VTgLHbJWHZGeTPVAg2XwazI9UWzoxjIJCGCV2zU60uqMzjeLZuULqA==", + "version": "5.4.21", + "resolved": "https://registry.npmjs.org/vite/-/vite-5.4.21.tgz", + "integrity": "sha512-o5a9xKjbtuhY6Bi5S3+HvbRERmouabWbyUcpXXUA1u+GNUKoROi9byOJ8M0nHbHYHkYICiMlqxkg1KkYmm25Sw==", "license": "MIT", "dependencies": { "esbuild": "^0.21.3", diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index a438e6bfeb..779440e3bf 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -286,6 +286,7 @@ - [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md) - [INS (Інерціальна навігація/GNSS)](sensor/inertial_navigation_systems.md) - [InertialLabs](sensor/inertiallabs.md) + - [MicroStrain](sensor/microstrain.md) - [sbgECom](sensor/sbgecom.md) - [VectorNav](sensor/vectornav.md) - [Optical Flow](sensor/optical_flow.md) @@ -436,6 +437,7 @@ - [Attitude Tuning](config_rover/attitude_tuning.md) - [Velocity Tuning](config_rover/velocity_tuning.md) - [Position Tuning](config_rover/position_tuning.md) + - [Apps & API](flight_modes_rover/api.md) - [Complete Vehicles](complete_vehicles_rover/index.md) - [Aion Robotics R1](complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](frames_sub/index.md) @@ -700,6 +702,7 @@ - [SensorCombined](msg_docs/SensorCombined.md) - [SensorCorrection](msg_docs/SensorCorrection.md) - [SensorGnssRelative](msg_docs/SensorGnssRelative.md) + - [SensorGnssStatus](msg_docs/SensorGnssStatus.md) - [SensorGps](msg_docs/SensorGps.md) - [SensorGyro](msg_docs/SensorGyro.md) - [SensorGyroFft](msg_docs/SensorGyroFft.md) @@ -761,6 +764,7 @@ - [Standard Modes Protocol](mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md) - [UORB Bridged to ROS 2](middleware/dds_topics.md) + - [Zenoh (PX4 ROS 2)](middleware/zenoh.md) - [Модулі & Команди](modules/modules_main.md) - [Автоматичне підлаштування](modules/modules_autotune.md) - [Команди](modules/modules_command.md) @@ -850,8 +854,10 @@ - [Тест MC_04 - Тестування відмовостійкості](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](test_cards/mc_10_optical_flow_gps_mixed.md) - [Модульні Тести](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [Безперервна інтеграція](test_and_ci/continous_integration.md) @@ -872,6 +878,7 @@ - [Інтерфейсна бібліотека PX4 ROS 2](ros2/px4_ros2_interface_lib.md) - [Керування інтерфейсом](ros2/px4_ros2_control_interface.md) - [Навігаційний інтерфейс](ros2/px4_ros2_navigation_interface.md) + - [Waypoint Missions](ros2/px4_ros2_waypoint_missions.md) - [ROS 2 Message Translation Node](ros2/px4_ros2_msg_translation_node.md) - [ROS 1 (Deprecated)](ros/ros1.md) - [Посібник із встановлення ROS/MAVROS](ros/mavros_installation.md) diff --git a/docs/uk/_sidebar.md b/docs/uk/_sidebar.md index e441417899..07336221de 100644 --- a/docs/uk/_sidebar.md +++ b/docs/uk/_sidebar.md @@ -8,6 +8,7 @@ - [Position Mode (MC)](/flight_modes_mc/position.md) - [Position Slow Mode (MC)](/flight_modes_mc/position_slow.md) - [Altitude Mode (MC)](/flight_modes_mc/altitude.md) + - [Altitude Cruise Mode (MC)](/flight_modes_mc/altitude_cruise.md) - [Stabilized Mode (MC)](/flight_modes_mc/manual_stabilized.md) - [Acro Mode (MC)](/flight_modes_mc/acro.md) - [Orbit Mode (MC)](/flight_modes_mc/orbit.md) @@ -158,6 +159,7 @@ - [Швидке підключення mRo (3DR) Pixhawk](/assembly/quick_start_pixhawk.md) - [Holybro Pixhawk Mini (FMUv3) - Припинено](/flight_controller/pixhawk_mini.md) - [Автопілоти, що підтримуються виробником](/flight_controller/autopilot_manufacturer_supported.md) + - [Accton Godwit GA1](/flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](/flight_controller/mindpx.md) - [AirMind MindRacer](/flight_controller/mindracer.md) - [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md) @@ -183,6 +185,7 @@ - [Wiring Quickstart](/assembly/quick_start_holybro_pix32_v5.md) - [ModalAI VOXL 2](/flight_controller/modalai_voxl_2.md) - [mRo Control Zero F7](/flight_controller/mro_control_zero_f7.md) + - [Radiolink PIX6](/flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](/flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](/flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](/flight_controller/thepeach_k1.md) @@ -284,6 +287,7 @@ - [CubePilot Here+ (Discontined)](/gps_compass/rtk_gps_hex_hereplus.md) - [INS (Інерціальна навігація/GNSS)](/sensor/inertial_navigation_systems.md) - [InertialLabs](/sensor/inertiallabs.md) + - [sbgECom](/sensor/sbgecom.md) - [VectorNav](/sensor/vectornav.md) - [Optical Flow](/sensor/optical_flow.md) - [ARK Flow](/dronecan/ark_flow.md) @@ -433,6 +437,7 @@ - [Attitude Tuning](/config_rover/attitude_tuning.md) - [Velocity Tuning](/config_rover/velocity_tuning.md) - [Position Tuning](/config_rover/position_tuning.md) + - [Apps & API](/flight_modes_rover/api.md) - [Complete Vehicles](/complete_vehicles_rover/index.md) - [Aion Robotics R1](/complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](/frames_sub/index.md) @@ -680,6 +685,8 @@ - [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](/msg_docs/RoverRateStatus.md) + - [RoverSpeedSetpoint](/msg_docs/RoverSpeedSetpoint.md) + - [RoverSpeedStatus](/msg_docs/RoverSpeedStatus.md) - [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md) - [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md) @@ -740,6 +747,7 @@ - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md) - [ArmingCheckReplyV0](/msg_docs/ArmingCheckReplyV0.md) + - [ArmingCheckRequestV0](/msg_docs/ArmingCheckRequestV0.md) - [BatteryStatusV0](/msg_docs/BatteryStatusV0.md) - [EventV0](/msg_docs/EventV0.md) - [HomePositionV0](/msg_docs/HomePositionV0.md) @@ -844,8 +852,10 @@ - [Тест MC_04 - Тестування відмовостійкості](/test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](/test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](/test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](/test_cards/mc_10_optical_flow_gps_mixed.md) - [Модульні Тести](/test_and_ci/unit_tests.md) - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [Безперервна інтеграція](/test_and_ci/continous_integration.md) @@ -866,6 +876,7 @@ - [Інтерфейсна бібліотека PX4 ROS 2](/ros2/px4_ros2_interface_lib.md) - [Керування інтерфейсом](/ros2/px4_ros2_control_interface.md) - [Навігаційний інтерфейс](/ros2/px4_ros2_navigation_interface.md) + - [Waypoint Missions](/ros2/px4_ros2_waypoint_missions.md) - [ROS 2 Message Translation Node](/ros2/px4_ros2_msg_translation_node.md) - [ROS 1 (Deprecated)](/ros/ros1.md) - [Посібник із встановлення ROS/MAVROS](/ros/mavros_installation.md) diff --git a/docs/uk/airframes/airframe_reference.md b/docs/uk/airframes/airframe_reference.md index 53f18bc47c..c54f02eac1 100644 --- a/docs/uk/airframes/airframe_reference.md +++ b/docs/uk/airframes/airframe_reference.md @@ -615,6 +615,10 @@ div.frame_variant td, div.frame_variant th { Axial SCX10 2 Trail Honcho Підтримувач: John Doe <john@example.com>

SYS_AUTOSTART = 51001

+ + NXP B3RB Rover Ackermann + Підтримувач: John Doe <john@example.com>

SYS_AUTOSTART = 51002

+ Generic Rover Mecanum Підтримувач: John Doe <john@example.com>

SYS_AUTOSTART = 52000

diff --git a/docs/uk/concept/system_startup.md b/docs/uk/concept/system_startup.md index e1cc0abd18..f94b70aa7c 100644 --- a/docs/uk/concept/system_startup.md +++ b/docs/uk/concept/system_startup.md @@ -1,7 +1,7 @@ # Запуск системи Запуск PX4 контрольований скриптами оболонки. -На NuttX вони знаходяться у директорії [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d), деякі з них також використовуються на Posix системах (Linux/MacOS). +On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/macOS). Скрипти які використовуються тільки на Posix системах знаходяться у [ROMFS/px4fmu_common/init.d-posix](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d-posix). Усі файли, які починаються з числа і підкреслення (наприклад, `10000_airaipl`) є попередньо визначеними конфігураціями планерів. @@ -13,7 +13,7 @@ They are exported at build-time into an `airframes.xml` file which is parsed by Наступні секції розділені відповідно до операційної системи, на яких виконується PX4. -## POSIX (Linux/MacOS) +## POSIX (Linux/macOS) On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). Щоб це працювало потрібно кілька речей: diff --git a/docs/uk/config/_autotune.md b/docs/uk/config/_autotune.md index f03800852a..7c31b3604b 100644 --- a/docs/uk/config/_autotune.md +++ b/docs/uk/config/_autotune.md @@ -95,9 +95,17 @@ The RC sticks cannot be used during autotuning (moving the sticks will stop the 4. Read the warning popup and click on **OK** to start tuning. -4. Дрон спочатку почне виконувати швидкі рухи кочення, а потім рухи тангажу та рухи курсу. +
+ +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. The progress is shown in the progress bar, next to the _Autotune_ button. +
+ +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + The progress is shown in the progress bar, next to the _Autotune_ button. + +
5. Manually land and disarm to apply the new tuning parameters. @@ -108,6 +116,13 @@ The RC sticks cannot be used during autotuning (moving the sticks will stop the 5. The tuning will be immediately/automatically be applied and tested in flight (by default). PX4 will then run a 4 second test and revert the new tuning if a problem is detected. +The figure below shows how steps 4 and 5 might look in flight on the pitch axis. +The pitch rate gradually increases up until it reaches the target. +This amplitude is then held while the signal frequency is increased. +You can then see how the tuned system is able to follow the setpoint in the test signal. + + +
:::warning @@ -174,9 +189,20 @@ Fast oscillations (more than 1 oscillation per second): this is because the gain ### Послідовність автоматичної настройки не вдається +
+ Якщо безпілотник не рухався достатньо під час автоматичного налаштування, алгоритм ідентифікації системи може мати проблеми з визначенням правильних коефіцієнтів. -Increase the
[MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP)
[FW_AT_SYSID_AMP](../advanced_config/parameter_reference.md#FW_AT_SYSID_AMP)
parameter by steps of 1 and trigger the auto-tune again. +Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP) parameter by steps of 1 and trigger the auto-tune again. + +
+
+ +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + +If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. + +
### The drone oscillates after auto-tuning diff --git a/docs/uk/config/safety.md b/docs/uk/config/safety.md index 850b7ab348..2ae88fb8a6 100644 --- a/docs/uk/config/safety.md +++ b/docs/uk/config/safety.md @@ -274,12 +274,12 @@ The relevant parameters are listed in the table below. ## Виявлення відмов -Детектор відмов дозволяє автомобілю вжити захисних заходів, якщо він несподівано перевертається, або якщо йому повідомлено зовнішньою системою виявлення відмов. +The failure detector allows a vehicle to take protective actions if it unexpectedly flips, detects a motor failure, or if it is notified by an external failure detection system. During **flight**, the failure detector can be used to trigger [flight termination](../advanced_config/flight_termination.md) if failure conditions are met, which may then launch a [parachute](../peripherals/parachute.md) or perform some other action. :::info -Failure detection during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). +Acting on a detected failure during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). ::: During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions). @@ -301,6 +301,26 @@ The failure detector is active in all vehicle types and modes, except for those | [FD_FAIL_P_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_P_TTRI) | Time to exceed [FD_FAIL_P](#FD_FAIL_P) for failure detection (default 0.3s). | | [FD_FAIL_R_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_R_TTRI) | Time to exceed [FD_FAIL_R](#FD_FAIL_R) for failure detection (default 0.3s). | +### Motor Failure Trigger + +The failure detector can be configured to detect a motor failure while armed (and trigger an associated action) in the following conditions: + +- A 300 ms timeout occurs in telemetry from an ESC that was previously available. +- The input current in the telemetry of an ESC which was previously positive gets too low for more than [`FD_ACT_MOT_TOUT`](FD_ACT_MOT_TOUT) ms. + The "too low" condition is defined by: + + ```text + {esc current} < {parameter FD_ACT_MOT_C2T} * {motor command between 0 and 1} + ``` + +| Параметр | Опис | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [FD_ACT_EN](../advanced_config/parameter_reference.md#FD_ACT_EN) | Enable/disable the motor failure trigger completely. | +| [FD_ACT_MOT_THR](../advanced_config/parameter_reference.md#FD_ACT_MOT_THR) | Minimum normalized [0,1] motor command below which motor under current is ignored. | +| [FD_ACT_MOT_C2T](../advanced_config/parameter_reference.md#FD_ACT_MOT_C2T) | Scale between normalized [0,1] motor command and expected minimally reported currrent when the rotor is healthy. | +| [FD_ACT_MOT_TOUT](../advanced_config/parameter_reference.md#FD_ACT_MOT_TOUT) | Time in miliseconds for which the under current detection condition needs to stay true. | +| [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) | Configure to not only warn about a motor failure but remove the first motor that detects a failure from the allocation effectiveness which turns off the motor and tries to operate the vehicle without it until disarming the next time. | + ### Зовнішня автоматична система тригерування (ATS) The [failure detector](#failure-detector), if [enabled](#CBRK_FLIGHTTERM), can also be triggered by an external ATS system. diff --git a/docs/uk/debug/failure_injection.md b/docs/uk/debug/failure_injection.md index aaa939dc0c..1f17a35b64 100644 --- a/docs/uk/debug/failure_injection.md +++ b/docs/uk/debug/failure_injection.md @@ -9,7 +9,7 @@ Failure injection is disabled by default, and can be enabled using the [SYS_FAIL Failure injection still in development. На момент написання (PX4 v1.14): -- Це можна використовувати лише в симуляції (підтримка як для впровадження в реальному польоті запланована). +- Support may vary by failure type and between simulatiors and real vehicle. - Потребує підтримки в симуляторі. Це підтримується в Gazebo Classic - Багато типів відмов не широко реалізовані. @@ -19,7 +19,7 @@ Failure injection still in development. ## Команда системи збою -Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 console/shell, specifying both the target and type of the failure. +Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 [console/shell](../debug/consoles.md) (such as the [QGC MAVLink Console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) or SITL _pxh shell_), specifying both the target and type of the failure. ### Синтаксис @@ -33,39 +33,46 @@ failure [-i ] - _component_: - Датчики: - - `gyro`: Gyro. - - `accel`: Accelerometer. + - `gyro`: Gyroscope + - `accel`: Accelerometer - `mag`: Magnetometer - `baro`: Barometer - - `gps`: GPS + - `gps`: Global navigation satellite system - `optical_flow`: Optical flow. - - `vio`: Visual inertial odometry. + - `vio`: Visual inertial odometry - `distance_sensor`: Distance sensor (rangefinder). - - `airspeed`: Airspeed sensor. + - `airspeed`: Airspeed sensor - Системи: - - `battery`: Battery. - - `motor`: Motor. - - `servo`: Servo. - - `avoidance`: Avoidance. - - `rc_signal`: RC Signal. - - `mavlink_signal`: MAVLink signal (data telemetry). + - `battery`: Battery + - `motor`: Motor + - `servo`: Servo + - `avoidance`: Avoidance + - `rc_signal`: RC Signal + - `mavlink_signal`: MAVLink data telemetry connection - _failure_type_: - - `ok`: Publish as normal (Disable failure injection). - - `off`: Stop publishing. - - `stuck`: Report same value every time (_could_ indicate a malfunctioning sensor). - - `garbage`: Publish random noise. Це схоже на читання неініціалізованої пам'яті. - - `wrong`: Publish invalid values (that still look reasonable/aren't "garbage"). - - `slow`: Publish at a reduced rate. - - `delayed`: Publish valid data with a significant delay. - - `intermittent`: Publish intermittently. + - `ok`: Publish as normal (Disable failure injection) + - `off`: Stop publishing + - `stuck`: Constantly report the same value which _can_ happen on a malfunctioning sensor + - `garbage`: Publish random noise. This looks like reading uninitialized memory + - `wrong`: Publish invalid values that still look reasonable/aren't "garbage" + - `slow`: Publish at a reduced rate + - `delayed`: Publish valid data with a significant delay + - `intermittent`: Publish intermittently - _instance number_ (optional): Instance number of affected sensor. 0 (за замовчуванням) вказує на всі сенсори вказаного типу. -### Example +## MAVSDK відлагоджувальний плагін + +The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. +It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). + +API плагіна - це пряме відображення команди збою, показаної вище, з деякими додатковими сигналами про помилки, пов'язані з підключенням. + +## Example: RC signal Щоб симулювати втрату сигналу RC без вимкнення вашого пульта керування RC: -1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. 2. Enter the following commands on the MAVLink console or SITL _pxh shell_: ```sh @@ -76,9 +83,18 @@ failure [-i ] failure rc_signal ok ``` -## MAVSDK відлагоджувальний плагін +## Example: Motor -The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. -It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). +To stop a motor mid-flight without the system anticipating it or excluding it from allocation effectiveness: -API плагіна - це пряме відображення команди збою, показаної вище, з деякими додатковими сигналами про помилки, пов'язані з підключенням. +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. +2. Enable [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) parameter to allow turning off motors. +3. Enter the following commands on the MAVLink console or SITL _pxh shell_: + + ```sh + # Turn off first motor + failure motor off -i 1 + + # Turn it back on + failure motor ok -i 1 + ``` diff --git a/docs/uk/dev_log/logging.md b/docs/uk/dev_log/logging.md index 31a86cce4a..7b5da1b821 100644 --- a/docs/uk/dev_log/logging.md +++ b/docs/uk/dev_log/logging.md @@ -160,7 +160,7 @@ If you have concerns about a particular card you can run the above test and repo - If log streaming does not start, make sure the `logger` is running (see above), and inspect the console output while starting. - Якщо це все ще не працює, переконайтеся, що використовується MAVLink 2. - Enforce it by setting `MAV_PROTO_VER` to 2. + `MAV_PROTO_VER` needs to be set to 2. - Log streaming uses a maximum of 70% of the configured MAVLink rate (`-r` parameter). Якщо потрібно більше, повідомлення видаляються. The currently used percentage can be inspected with `mavlink status` (1.8% is used in this example): diff --git a/docs/uk/dev_log/ulog_file_format.md b/docs/uk/dev_log/ulog_file_format.md index 12df33315d..4e15845983 100644 --- a/docs/uk/dev_log/ulog_file_format.md +++ b/docs/uk/dev_log/ulog_file_format.md @@ -502,6 +502,7 @@ struct message_dropout_s { - [ulogreader](https://github.com/maxsun/ulogreader): Javascript, ULog reader and parser outputs log in JSON object format. - [Foxglove](https://foxglove.dev): an integrated visualization and diagnosis tool for robotics data that supports ULog files. - [TypeScript ULog parser](https://github.com/foxglove/ulog): TypeScript, ULog reader that outputs JS objects. +- [yule_log](https://crates.io/crates/yule_log): A streaming ULog parser written in Rust. ## Історія версій формату файлу diff --git a/docs/uk/dev_setup/dev_env.md b/docs/uk/dev_setup/dev_env.md index 46bcc54138..6a23af23fa 100644 --- a/docs/uk/dev_setup/dev_env.md +++ b/docs/uk/dev_setup/dev_env.md @@ -2,22 +2,22 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (22.04/20.04/18.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 -- [Mac OS](../dev_setup/dev_env_mac.md) +- [macOS](../dev_setup/dev_env_mac.md) ## Цільові платформи що підтримуються Таблиця нижче показує, які цільові платформи PX4 можна побудувати на кожній ОС. -| Цільова платформа | Linux (Ubuntu) | Mac | Windows | -| ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :-: | :-----: | -| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | -| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | -| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | -| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | +| Цільова платформа | Linux (Ubuntu) | macOS | Windows | +| ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :---: | :-----: | +| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | +| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | +| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | +| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | Experienced Docker users can also build with the containers used by our continuous integration system: [Docker Containers](../test_and_ci/docker.md) diff --git a/docs/uk/dev_setup/dev_env_mac.md b/docs/uk/dev_setup/dev_env_mac.md index 65f1453411..214f44b7f3 100644 --- a/docs/uk/dev_setup/dev_env_mac.md +++ b/docs/uk/dev_setup/dev_env_mac.md @@ -1,4 +1,4 @@ -# Середовище розробки MacOS +# macOS Development Environment Наступні інструкції для встановлення середовища розробки PX4 для macOS. Це середовище може бути використане для збірки PX4 для: @@ -22,8 +22,8 @@ To build other targets you will need to use a [different OS](../dev_setup/dev_en ### Налаштування середовища :::details -Apple Silicon Macbook users! -If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 by setting up an x86 terminal: +Apple Silicon MacBook users! +If you have an Apple M1, M2 etc. MacBook, make sure to run the terminal as x86 by setting up an x86 terminal: 1. Locate the Terminal application within the Utilities folder (**Finder > Go menu > Utilities**) 2. Select _Terminal.app_ and right-click on it, then choose **Duplicate**. @@ -50,7 +50,7 @@ If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 b 2. Enforce Python 3 by appending the following lines to `~/.zshenv` ```sh - # Point pip3 to MacOS system python 3 pip + # Point pip3 to macOS system python 3 pip alias pip3=/usr/bin/pip3 ``` diff --git a/docs/uk/dronecan/ark_cannode.md b/docs/uk/dronecan/ark_cannode.md index 07b6da9458..69cc232ce6 100644 --- a/docs/uk/dronecan/ark_cannode.md +++ b/docs/uk/dronecan/ark_cannode.md @@ -83,9 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter На ARK CANnode вам може знадобитися налаштувати наступні параметри: -| Параметр | Опис | -| -------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. | +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. | ## Значення LED індикаторів diff --git a/docs/uk/dronecan/ark_flow.md b/docs/uk/dronecan/ark_flow.md index 9f17cc3100..29d50e3f2b 100644 --- a/docs/uk/dronecan/ark_flow.md +++ b/docs/uk/dronecan/ark_flow.md @@ -109,9 +109,10 @@ When optical flow is the only source of horizontal position/velocity, then lower On the ARK Flow, you may need to configure the following parameters: -| Параметр | Опис | -| -------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. | +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. | ## Значення LED індикаторів diff --git a/docs/uk/dronecan/ark_flow_mr.md b/docs/uk/dronecan/ark_flow_mr.md index 2b374b5b9f..44a77ab7a0 100644 --- a/docs/uk/dronecan/ark_flow_mr.md +++ b/docs/uk/dronecan/ark_flow_mr.md @@ -104,9 +104,10 @@ Set the following parameters in _QGroundControl_: You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself: -| Параметр | Опис | -| -------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. | +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. | ## Значення LED індикаторів diff --git a/docs/uk/dronecan/ark_gps.md b/docs/uk/dronecan/ark_gps.md index 1320fb7057..3283dd252b 100644 --- a/docs/uk/dronecan/ark_gps.md +++ b/docs/uk/dronecan/ark_gps.md @@ -91,9 +91,17 @@ DroneCAN configuration in PX4 is explained in more detail in [DroneCAN > Enablin - Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true. - Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO). -- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus. - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity. +### ARK GPS Configuration + +You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself: + +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. Set to `1` if this is the last node on the CAN bus. | + ## Значення LED індикаторів Ви побачите зелені, сині та червоні світлодіоди на ARK GPS під час прошивки, а також мигаючий зелений світлодіод, якщо все працює належним чином. diff --git a/docs/uk/dronecan/ark_rtk_gps.md b/docs/uk/dronecan/ark_rtk_gps.md index 4034e1ed9d..9c2573fa53 100644 --- a/docs/uk/dronecan/ark_rtk_gps.md +++ b/docs/uk/dronecan/ark_rtk_gps.md @@ -85,7 +85,15 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked). - Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO). - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity. -- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus. + +### ARK RTK GPS Configuration + +You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself: + +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. Set to `1` if this is the last node on the CAN bus. | ### Setting Up Rover and Fixed Base diff --git a/docs/uk/dronecan/index.md b/docs/uk/dronecan/index.md index 76f7b7ad8d..7389a29531 100644 --- a/docs/uk/dronecan/index.md +++ b/docs/uk/dronecan/index.md @@ -102,6 +102,10 @@ If you wish to disable the DNA completely, set `UAVCAN_ENABLE` to `1` and manual :::info The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter. Параметр за замовчуванням встановлено на 1. + +Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the +[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID. +Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID. ::: :::warning @@ -288,6 +292,11 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i ![QGC Parameter showing selected DroneCAN node](../../assets/can/dronecan/qgc_can_parameters.png) +Common CANNODE parameters that you can configure include: + +- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information. +- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus. + ## Налаштування пристрою Більшість вузлів DroneCAN не потребують додаткової настройки, якщо це не вказано у їх документації, специфічній для пристрою. diff --git a/docs/uk/dronecan/px4_cannode_fw.md b/docs/uk/dronecan/px4_cannode_fw.md index 12e6a028cf..83ffba7e03 100644 --- a/docs/uk/dronecan/px4_cannode_fw.md +++ b/docs/uk/dronecan/px4_cannode_fw.md @@ -20,6 +20,26 @@ make ark_can-flow_default This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware. +## Налаштування + +### Static Node ID + +By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller. +However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter. + +To configure a static node ID: + +1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration) +2. Reboot the device + +To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0. +Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior). + +:::warning +When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID. +Configuring two devices with the same ID will cause communication conflicts. +::: + ## Інформація для розробників Цей розділ містить інформацію, яка є актуальною для розробників, які хочуть додати підтримку нового апаратного забезпечення DroneCAN до автопілота PX4. diff --git a/docs/uk/flight_modes/offboard.md b/docs/uk/flight_modes/offboard.md index c9d04c0255..e2c100783d 100644 --- a/docs/uk/flight_modes/offboard.md +++ b/docs/uk/flight_modes/offboard.md @@ -62,6 +62,11 @@ bool thrust_and_torque bool direct_actuator ``` +:::warning +The following list shows the `OffboardControlMode` options for copter, fixed-wing, and VTOL. +For rovers see the [rover section](#rover). +::: + The fields are ordered in terms of priority such that `position` takes precedence over `velocity` and later fields, `velocity` takes precedence over `acceleration`, and so on. Перше поле, яке має ненульове значення (зверху вниз), визначає, яка допустима оцінка необхідна для використання режиму безпілотного керування, а також повідомлення заданих значень, які можуть бути використані. For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `velocity estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message. @@ -90,20 +95,93 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values acceleration are used as feedforward terms for the inner loop controllers. - Acceleration setpoint (`acceleration` different from `NaN` and `position` and `velocity` set to `NaN`) - - Всі значення інтерпретуються в NED (Nord, East, Down) координатну систему і одиниці вимірювання, є \[m/s\] і \[m/s^2\] для позиції, швидкості і прискорення, відповідно. + - All values are interpreted in NED (Nord, East, Down) coordinate system and the units are `[m]`, `[m/s]` and `[m/s^2]` for position, velocity and acceleration, respectively. - [px4_msgs::msg::VehicleAttitudeSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) - Підтримується наступна комбінація введення: - quaternion `q_d` + thrust setpoint `thrust_body`. - Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in \[rad/s\]. + Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in `[rad/s]`. - - Кватерніон представляє обертання між корпусом дрона у системі координат FRD (перед, праворуч, вниз) та системою координат NED. Тяга у корпусі дрона виражена у системі координат FRD та у нормалізованих значеннях. + - Кватерніон представляє обертання між корпусом дрона у системі координат FRD (перед, праворуч, вниз) та системою координат NED. + Тяга у корпусі дрона виражена у системі координат FRD та у нормалізованих значеннях. - [px4_msgs::msg::VehicleRatesSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleRatesSetpoint.msg) - Підтримується наступна комбінація введення: - `roll`, `pitch`, `yaw` and `thrust_body`. - - Всі значення подані в для дрона в системі FRD. Значення в \[rad/s\] і thrust_body нормалізовано в \[-1, 1\]. + - Всі значення подані в для дрона в системі FRD. + The rates are in `[rad/s]` while thrust_body is normalized in `[-1, 1]`. + +### Ровер + +Rover modules must set the control mode using `OffboardControlMode` and use the appropriate messages to configure the corresponding setpoints. +The approach is similar to other vehicle types, but the allowed control mode combinations and setpoints are different: + +| Category | Використання | Setpoints | +| -------------------------------------------------------------------------------------- | ----------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| (Recommended) [Rover Setpoints](#rover-setpoints) | General rover control | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md), [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md), [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md), [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md), [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md), [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) | +| [Actuator Setpoints](#actuator-setpoints) | Direct actuator control | [ActuatorMotors](../msg_docs/ActuatorMotors.md), [ActuatorServos](../msg_docs/ActuatorServos.md) | +| (Deprecated) [Trajectory Setpoint](#deprecated-trajectory-setpoint) | General vehicle control | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | + +#### Rover Setpoints + +The rover modules use a hierarchical structure to propagate setpoints: + +![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg) + +The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (overriding them!). +With this hierarchy there are clear rules for providing a valid control input: + +- Provide a position setpoint **or** +- One of the setpoints on the "left" (speed **or** throttle) **and** one of the setpoints on the "right" (attitude, rate **or** steering). + All combinations of "left" and "right" setpoints are valid. + +The following are all valid setpoint combinations and their respective control flags that must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md) (set all others to _false_). +Additionally, for some combinations we require certain setpoints to be published with `NAN` values so that the setpoints of interest are not overridden by the rover module (due to the hierarchy above). +✓ are the relevant setpoints we publish, and ✗ are the setpoint that need to be published with `NAN` values. + +| Setpoint Combination | Control Flag | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md) | [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md) | [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) | [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md) | [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md) | [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) | +| -------------------- | ----------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------------- | ----------------------------------------------------- | ------------------------------------------------------------- | +| Положення | положення | ✓ | | | | | | +| Speed + Attitude | швидкість | | ✓ | | ✓ | | | +| Speed + Rate | швидкість | | ✓ | | ✗ | ✓ | | +| Speed + Steering | швидкість | | ✓ | | ✗ | ✗ | ✓ | +| Throttle + Attitude | attitude | | | ✓ | ✓ | | | +| Throttle + Rate | body_rate | | | ✓ | | ✓ | | +| Throttle + Steering | thrust_and_torque | | | ✓ | | | ✓ | + +:::info +If you intend to use the rover setpoints, we recommend using the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) instead since it simplifies the publishing of these setpoints. +::: + +#### Actuator Setpoints + +Instead of controlling the vehicle using position, speed, rate and other setpoints, you can directly control the motors and actuators using [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md). +In [OffboardControlMode](../msg_docs/OffboardControlMode.md) set `direct_actuator` to _true_ and all other flags to _false_. + +:::info +This bypasses the rover modules including any limits on steering rates or accelerations and the inverse kinematics step. +We recommend using [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) and [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) instead for low level control (see [Rover Setpoints](#rover-setpoints)). +::: + +#### (Deprecated) Trajectory Setpoint + +:::warning +The [Rover Setpoints](#rover-setpoints) are a replacement for the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) and we highly recommend using those instead as they have a well defined behaviour and offer more flexibility. +::: + +The rover modules support the _position_, _velocity_ and _yaw_ fields of the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md). +However, only one of the fields is active at a time and is defined by the flags of [OffboardControlMode](../msg_docs/OffboardControlMode.md): + +| Control Mode Flag | Active Trajectory Setpoint Field | +| ----------------- | -------------------------------- | +| положення | положення | +| швидкість | швидкість | +| attitude | yaw | + +:::info +Ackermann rovers do not support the yaw setpoint. +::: ### Універсальний апарат @@ -116,8 +194,10 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - [px4_msgs::msg::ActuatorMotors](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) + [px4_msgs::msg::ActuatorServos](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg) - Ви безпосередньо керуєте вихідними сигналами моторів та/або сервоприводів. - - Currently works at lower level than then `control_allocator` module. Do not publish these messages when not in offboard mode. - - Усі значення нормалізовані у діапазоні \[-1, 1\]. For outputs that do not support negative values, negative entries map to `NaN`. + - Currently works at lower level than then `control_allocator` module. + Do not publish these messages when not in offboard mode. + - All the values normalized in `[-1, 1]`. + For outputs that do not support negative values, negative entries map to `NaN`. - `NaN` maps to disarmed. ## Повідомлення MAVLink @@ -206,41 +286,7 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding ### Ровер -- [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `x`, `y`, `z`) - - Specify the _type_ of the setpoint in `type_mask`: - - ::: info - The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. - :: - - Значення: - - - 12288: задане значення Loiter (пристрій зупиняється, коли вже достатньо близько, щоб встановити точку). - - - Velocity setpoint (only `vx`, `vy`, `vz`) - - - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) and [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED). - -- [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `lat_int`, `lon_int`, `alt`) - - - Specify the _type_ of the setpoint in `type_mask` (not part of the MAVLink standard). - Значення: - - Якщо наступні біти не встановлені, то виконується звичайна поведінка. - - 12288: задане значення Loiter (пристрій зупиняється, коли вже достатньо близько, щоб встановити точку). - - - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_GLOBAL](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL). - -- [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) - - Підтримуються наступні вхідні комбінації: - - Attitude/orientation (`SET_ATTITUDE_TARGET.q`) with thrust setpoint (`SET_ATTITUDE_TARGET.thrust`). - ::: info - Only the yaw setting is actually used/extracted. - -::: +Rover does not support a MAVLink offboard API (ROS2 is supported). ## Параметри для відключення diff --git a/docs/uk/flight_modes_mc/altitude.md b/docs/uk/flight_modes_mc/altitude.md index 62231d3190..51dfb83d58 100644 --- a/docs/uk/flight_modes_mc/altitude.md +++ b/docs/uk/flight_modes_mc/altitude.md @@ -43,9 +43,8 @@ RC/manual mode like [Stabilized mode](../flight_modes_mc/manual_stabilized.md) b Режим впливає на наступні параметри: -| Параметр | Опис | -| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Максимальна швидкість вертикального підйому. За замовчуванням: 3 м/с. | -| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Максимальна швидкість вертикального спуску. За замовчуванням: 1 m/s. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | -| `MPC_XXXX` | Більшість параметрів MPC_xxx впливають на поведінку польоту в цьому режимі (принаймні до певної міри). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | +| Параметр | Опис | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Максимальна швидкість вертикального підйому. За замовчуванням: 3 м/с. | +| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Максимальна швидкість вертикального спуску. За замовчуванням: 1 m/s. | +| `MPC_XXXX` | Більшість параметрів MPC_xxx впливають на поведінку польоту в цьому режимі (принаймні до певної міри). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | diff --git a/docs/uk/flight_modes_mc/position.md b/docs/uk/flight_modes_mc/position.md index 8e43219a1a..51abfe20f2 100644 --- a/docs/uk/flight_modes_mc/position.md +++ b/docs/uk/flight_modes_mc/position.md @@ -67,7 +67,6 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Максимальна швидкість вертикального спуску. За замовчуванням: 1 m/s. | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Висота для спрацювання першої фази повільної посадки. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). За замовчуванням 10м. | | [MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | Висота для другої фази повільної посадки. Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Значення повинно бути нижче, ніж "MPC_LAND_ALT1". Значення за замовчуванням: 5m. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | | `MPC_XXXX` | Більшість параметрів MPC_xxx впливають на поведінку польоту в цьому режимі (принаймні до певної міри). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | | [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Стратегія перекладу введення на рух. From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). Інші параметри дозволяють відхилення палиці безпосередньо контролювати швидкість над землею, з і без згладжування та обмежень прискорення. | | [MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | Максимальне горизонтальне прискорення. | diff --git a/docs/uk/flight_modes_rover/api.md b/docs/uk/flight_modes_rover/api.md new file mode 100644 index 0000000000..e32de3e8ee --- /dev/null +++ b/docs/uk/flight_modes_rover/api.md @@ -0,0 +1,29 @@ +# Apps & API + +The rover modules have been tested and integrated with a subset of the available [Apps & API](../middleware/index.md) methods. +We specifically provide guides for using [ROS 2](../ros2/index.md) to interface a companion computer with PX4 via [uXRCE-DDS](../middleware/uxrce_dds.md). + +| Method | Опис | +| ---------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [PX4 ROS 2 Interface](#px4-ros-2-interface) (Recommended) | Register a custom mode and publish [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). | +| [ROS 2 Offboard Control](#ros-2-offboard-control) | Use the PX4 internal [Offboard Mode](../flight_modes/offboard.md) and publish messages defined in [dds_topics.yaml](../middleware/dds_topics.md). | + +## PX4 ROS 2 Interface + +We recommend the use of the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) which allows you to register a custom drive mode and exposes [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). + +By using these setpoints (instead of the PX4 internal rover setpoints), you are guaranteed to send valid control inputs to your vehicle and the control flags for the setpoints you are using are automatically set for you. +Registering a custom drive mode instead of using [ROS 2 Offboard Control](#ros-2-offboard-control) additionally provides the advantages listed [here](../concept/flight_modes.md#internal-vs-external-modes). + +To get familiar with this method, read through the guide for the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) where we also provide an example app for rover. + +## ROS 2 Offboard Control + +[ROS 2 Offboard Control](../ros2/offboard_control.md) uses the PX4 internal [Offboard Mode](../flight_modes/offboard.md). + +While you can subscribe/publish to all topics specified in [dds_topics.yaml](../middleware/dds_topics.md), not all rover modules support all of these topics (see [Supported Setpoints](../flight_modes/offboard.md#rover)). +Unlike the [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints) exposed through the [PX4 ROS 2 Interface](#px4-ros-2-interface), there is no guarantee that the published setpoints lead to a valid control input. + +In addition, the correct control mode flags must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md). +This requires a deeper understanding of PX4 and the structure of the rover modules. +For general information on setting up offboard mode read through [Offboard Mode](../flight_modes/offboard.md) and then consult [Supported Setpoints](../flight_modes/offboard.md#rover). diff --git a/docs/uk/frames_rover/index.md b/docs/uk/frames_rover/index.md index 39f404f32c..f2d7e9e4b7 100644 --- a/docs/uk/frames_rover/index.md +++ b/docs/uk/frames_rover/index.md @@ -57,15 +57,17 @@ Each wheel is driven by its own motor, and by controlling the speed and directio ## Дивіться також -- [Drive Modes](../flight_modes_rover/index.md). +- [Drive Modes](../flight_modes_rover/index.md) - [Configuration/Tuning](../config_rover/index.md) +- [Apps & API](../flight_modes_rover/api.md) - [Complete Vehicles](../complete_vehicles_rover/index.md) ## Симуляція -[Gazebo](../sim_gazebo_gz/index.md) provides simulations for ackermann and differential rovers: +PX4 provides synthetic simulation models for [Gazebo](../sim_gazebo_gz/index.md) of all three rover types to test the software and validate changes and new features: - [Ackermann rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) - [Differential rover](../sim_gazebo_gz/vehicles.md#differential-rover) +- [Mecanum rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) ![Rover gazebo simulation](../../assets/airframes/rover/rover_simulation.png) diff --git a/docs/uk/gps_compass/rtk_gps.md b/docs/uk/gps_compass/rtk_gps.md index 1e8f3c158e..86f1ac7ec6 100644 --- a/docs/uk/gps_compass/rtk_gps.md +++ b/docs/uk/gps_compass/rtk_gps.md @@ -205,7 +205,7 @@ You can save and reuse a base position in order to save time: perform Survey-In Для забезпечення використання MAVLink2: - Update the telemetry module firmware to the latest version (see [QGroundControl > Setup > Firmware](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/firmware.html)). -- Set [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) +- Ensure [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) is set to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) #### Вдосконалення diff --git a/docs/uk/index.md b/docs/uk/index.md index 6bba5ae0dc..b0ec59c754 100644 --- a/docs/uk/index.md +++ b/docs/uk/index.md @@ -1,3 +1,8 @@ + +
# Посібник користувача автопілота PX4 @@ -8,17 +13,22 @@ PX4 is the _Professional Autopilot_. Розроблений розробниками світового класу з дрон індустрії та наукових закладів і активно підтримується спільнотою у світі. Він дозволяє працювати з різними типами безпілотних транспортних засобів від гоночних, вантажних дронів до сухопутних автомобілів та надводних човнів. :::tip -This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. Хочете зробити внесок? Check out the [Development](development/development.md) section. - +This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. +Хочете зробити внесок? Check out the [Development](development/development.md) section. ::: +
+ :::warning + This guide is for the _development_ version of PX4 (`main` branch). Use the **Version** selector to find the current _stable_ version. Documented changes since the stable release are captured in the evolving [release note](releases/main.md). ::: +
+ ## Як почати? [Basic Concepts](getting_started/px4_basic_concepts.md) should be read by all users! diff --git a/docs/uk/middleware/dds_topics.md b/docs/uk/middleware/dds_topics.md index 1feef1a6b1..7420e8b9bd 100644 --- a/docs/uk/middleware/dds_topics.md +++ b/docs/uk/middleware/dds_topics.md @@ -4,7 +4,7 @@ This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code. ::: -The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). +The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) and/or [zenoh](../modules/modules_driver.md#zenoh) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on. diff --git a/docs/uk/middleware/zenoh.md b/docs/uk/middleware/zenoh.md new file mode 100644 index 0000000000..800d0b5fae --- /dev/null +++ b/docs/uk/middleware/zenoh.md @@ -0,0 +1,201 @@ +# Zenoh (PX4 ROS 2 rmw_zenoh) + + + +:::warning +Експериментальні налаштування +At the time of writing, PX4 Zenoh-pico is experimental, and hence subject to change. +::: + +PX4 supports Zenoh as an alternative mechanism (to DDS) for bridging uORB topics to [ROS 2](../ros2/user_guide.md) (via the ROS 2 [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh) middleware). +This allows uORB messages to be published and subscribed on a companion computer as though they were ROS 2 topics. +It provides a fast and lightweight way to connect PX4 to ROS 2, making it easier for applications to access vehicle telemetry and send control commands. + +The following guide describes the architecture and various options for setting up the Zenoh client and router. +In particular, it covers the options that are most important to PX4 users exploring Zenoh as an alternative communication layer for ROS 2. + +## Архітектура + +The Zenoh-based middleware consists of a client running on PX4 and a Zenoh router running on the companion computer, with bi-directional data exchange between them over a UART, TCP, UDP, or multicast-UDP link. +The router acts as a broker and discovery service, enabling PX4 to publish and subscribe to topics in the global Zenoh data space. +This allows seamless integration with ROS 2 nodes using [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh), and supports flexible deployment across distributed systems. + +![Architecture PX4 Zenoh-Pico with ROS 2](../../assets/middleware/zenoh/architecture-px4-zenoh.svg) + +The client is the _PX4 Zenoh-Pico Node_ referred to above, which is implemented in the [PX4 `zenoh` module](../modules/modules_driver.md#zenoh). +This is based on Zenoh-Pico, a minimalistic version of [Eclipse Zenoh](https://zenoh.io/) (a data-centric protocol designed for real-time, distributed, and resource-constrained environments). + +The router suggested above is [zenohd](https://github.com/eclipse-zenoh/zenoh/tree/main/zenohd). + +:::info +UART is supported by Zenoh but has not yet implemented in the PX4 Zenoh-Pico node. +::: + +## ROS 2 Zenoh Bring-up on Linux Companion + +In order for PX4 uORB topics to be shared with ROS 2 applications, you will need the PX4 Zenoh-Pico Node client running on your FMU, connected to a Zenoh router running on the companion computer (or elsewhere in the network). + +First select Zenoh as the ROS 2 transport by setting the `RMW_IMPLEMENTATION` environment variable as shown: + +```sh +export RMW_IMPLEMENTATION=rmw_zenoh_cpp +``` + +Then start the Zenoh router using the command: + +```sh +ros2 run rmw_zenoh_cpp rmw_zenohd +``` + +For more information about the Zenoh Router see the [rmw_zenoh](https://github.com/ros2/rmw_zenoh?tab=readme-ov-file#start-the-zenoh-router) documentation. + +## PX4 Zenoh-Pico Node Setup + +### PX4 Firmware + +Before setting up the Zenoh communication, first make sure that your firmware contains the driver that implements the [`zenoh` driver](../modules/modules_driver.md#zenoh), which provides the implementation of the _PX4 Zenoh-Pico Node_. + +You can check if the module is present on your board by searching for the key `CONFIG_MODULES_ZENOH=y` in your board's `default.px4board` KConfig file. +For example, you can see that the module is present in `px4_fmu-v6xrt` build targets from [/boards/px4/fmu-v6xrt/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6xrt/default.px4board#L91). + +If `CONFIG_MODULES_ZENOH=y` is not preset you can add this key to your board configuration and rebuild. +Note that due to flash constraints you may need to remove other components in order to include the module (such as the [`uxrce_dds_client` module](../modules/modules_system.md#uxrce-dds-client), which you will not need if you are using Zenoh). + +The table below shows some of the PX4 targets that include Zenoh by default. + +| PX4 Target | Примітки | +| ---------------------- | -------------------------------------------------------------------------------------------------------------- | +| `px4_fmu-v6xrt` | For [FMUv6X-RT](../flight_controller/nxp_mr_vmu_rt1176.md) (reference platform for testing) | +| `nxp_tropic-community` | | +| `nxp_mr-tropic` | | +| `nxp_mr-canhubk344` | | +| `px4_sitl_zenoh` | Zenoh-enabled simulation build | +| `px4_fmu-v6x_zenoh` | Zenoh-enabled firmware for FMUv6X | + +Zenoh is not included in the default `px4_fmu-` targets for any firmware other than `px4_fmu-v6xrt` (`px4_sitl_zenoh` and `px4_fmu-v6x_zenoh` [are build variants](../dev_setup/building_px4.md#px4-make-build-targets)). + +:::tip +You can check if Zenoh is present at runtime by using QGroundControl to [find the parameter](../advanced_config/parameters.md#finding-a-parameter) [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE). +If present, the module is installed. +::: + +### Enable Zenoh on PX4 Startup + +Set the [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE) parameter to `1` to enable Zenoh on PX4 startup. + +### Configure Zenoh Network + +Set up PX4 to connect to the companion computer running `zenohd`. + +PX4's default IP address of the Zenoh daemon host is `10.41.10.1`. +If you're using a different IP for the Zenoh daemon, run the following command (replacing the address) in a PX4 shell and then reboot: + +```sh +zenoh config net client tcp/10.41.10.1:7447#iface=eth0 +``` + +Note that for the simulation target with Zeroh (`px4_sitl_zenoh`) you won't need to make any changes because the default IP address of the Zenoh daemon is set to `localhost`. + +:::warning +Any changes to the network configuration require a PX4 system reboot to take effect. +::: + +:::tip +See [PX4 Ethernet Setup](../advanced_config/ethernet_setup.md) for more information about Ethernet configuration. +::: + +### PX4 Zenoh-pico Node configuration + +The **default configuration** is auto-generated from the [dds_topics.yaml](../middleware/dds_topics.md) file in the PX4 repository. +This file specifies which uORB message definitions are to be published/subscribed by ROS 2 applications, and hence (indirectly) which topics are compiled into the zenoh module. + +To inspect the current Zenoh configuration: + +```sh +zenoh config +``` + +The PX4 Zenoh-pico node stores its configuration on the **SD card** under the `zenoh` folder. +This folder contains three key files: + +- **`net.txt`** – Defines the **Zenoh network configuration**. +- **`pub.csv`** – Maps **uORB topics to ROS2 topics** (used for publishing). +- **`sub.csv`** – Maps **ROS2 topics to uORB topics** (used for subscribing). + +### 4. Modifying Topic Mappings + +Zenoh topic mappings define how data flows between PX4's internal uORB topics and external ROS2 topics via Zenoh. +These mappings are stored in `pub.csv` and `sub.csv` on the SD card, and can be modified at runtime using the `zenoh config` CLI tool. + +:::warning +Any changes to the topic mappings require a PX4 system reboot to take effect. +::: + +There are two types of mappings you can modify: + +- **Publisher mappings**: Forward data from a uORB topic to a Zenoh topic. +- **Subscriber mappings**: Receive data from a Zenoh topic and publish it to a uORB topic. + +The main operations and their commands are: + +- Publish a uORB topic to a Zenoh topic: + + ```sh + zenoh config add publisher [uorb_instance] + ``` + +- Subscribe to a Zenoh topic and forward it to a uORB topic: + + ```sh + zenoh config add subscriber [uorb_instance] + ``` + +- Remove existing mappings: + + ```sh + zenoh config delete publisher + zenoh config delete subscriber + ``` + +After modifying the mappings, reboot PX4 to apply the changes. +The updated configuration will be loaded from the SD card during startup. + +## Communicating with PX4 from ROS 2 via Zenoh + +Once your PX4 FMU is publishing data into ROS 2, you can inspect the available topics and their contents using standard ROS 2 CLI tools: + +```sh +ros2 topic list +``` + +Check topic type and publishers/subscribers: + +```sh +ros2 topic info -v /fmu/out/vehicle_status +Type: px4_msgs/msg/VehicleStatus + +Publisher count: 1 + +Node name: px4_aabbcc00000000000000000000000000 +Node namespace: / +Topic type: px4_msgs/msg/VehicleStatus +Topic type hash: RIHS01_828bddbb7d4c2aa6ad93757955f6893be1ec5d8f11885ec7715bcdd76b5226c9 +Endpoint type: PUBLISHER +GID: 82.99.74.2c.b6.7d.93.44.91.4d.fe.14.93.58.40.16 +QoS profile: + Reliability: RELIABLE + History (Depth): KEEP_LAST (7) + Durability: VOLATILE + Lifespan: Infinite + Deadline: Infinite + Liveliness: AUTOMATIC + Liveliness lease duration: Infinite + +Subscription count: 0 +``` + +### PX4 ROS 2 Interface with Zenoh + +The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) works out of the box with Zenoh as a transport backend. +This means you can publish and subscribe to PX4 topics over Zenoh without changing your ROS 2 nodes or dealing with DDS configuration. +For setup details and supported message types, refer to the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md). diff --git a/docs/uk/modules/modules_driver_distance_sensor.md b/docs/uk/modules/modules_driver_distance_sensor.md index 249776c2ca..4ed7caf5f7 100644 --- a/docs/uk/modules/modules_driver_distance_sensor.md +++ b/docs/uk/modules/modules_driver_distance_sensor.md @@ -104,7 +104,7 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### Опис -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html diff --git a/docs/uk/msg_docs/AirspeedValidated.md b/docs/uk/msg_docs/AirspeedValidated.md index 41bfe31f09..1aa9bdbd02 100644 --- a/docs/uk/msg_docs/AirspeedValidated.md +++ b/docs/uk/msg_docs/AirspeedValidated.md @@ -1,29 +1,39 @@ # AirspeedValidated (повідомлення UORB) +Validated airspeed + +Provides information about airspeed (indicated, true, calibrated) and the source of the data. +Used by controllers, estimators and for airspeed reporting to operator. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) ```c +# Validated airspeed +# +# Provides information about airspeed (indicated, true, calibrated) and the source of the data. +# Used by controllers, estimators and for airspeed reporting to operator. + + uint32 MESSAGE_VERSION = 1 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start -float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid -float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid -float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid +float32 indicated_airspeed_m_s # [m/s] [@invalid NaN] Indicated airspeed (IAS) +float32 calibrated_airspeed_m_s # [m/s] [@invalid NaN] Calibrated airspeed (CAS) +float32 true_airspeed_m_s # [m/s] [@invalid NaN] True airspeed (TAS) -int8 airspeed_source # Source of currently published airspeed values -int8 DISABLED = -1 -int8 GROUND_MINUS_WIND = 0 -int8 SENSOR_1 = 1 -int8 SENSOR_2 = 2 -int8 SENSOR_3 = 3 -int8 SYNTHETIC = 4 +int8 airspeed_source # [@enum SOURCE] Source of currently published airspeed values +int8 SOURCE_DISABLED = -1 # Disabled +int8 SOURCE_GROUND_MINUS_WIND = 0 # Ground speed minus wind +int8 SOURCE_SENSOR_1 = 1 # Sensor 1 +int8 SOURCE_SENSOR_2 = 2 # Sensor 2 +int8 SOURCE_SENSOR_3 = 3 # Sensor 3 +int8 SOURCE_SYNTHETIC = 4 # Synthetic airspeed -# debug states -float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid -float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid -float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] -float32 throttle_filtered # filtered fixed-wing throttle [-] -float32 pitch_filtered # filtered pitch [rad] +float32 calibrated_ground_minus_wind_m_s # [m/s] [@invalid NaN] CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption +float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airspeed +float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative +float32 throttle_filtered # [-] Filtered fixed-wing throttle +float32 pitch_filtered # [rad] Filtered pitch ``` diff --git a/docs/uk/msg_docs/AutotuneAttitudeControlStatus.md b/docs/uk/msg_docs/AutotuneAttitudeControlStatus.md index a8d88537a4..afda316aa2 100644 --- a/docs/uk/msg_docs/AutotuneAttitudeControlStatus.md +++ b/docs/uk/msg_docs/AutotuneAttitudeControlStatus.md @@ -1,42 +1,59 @@ # AutotuneAttitudeControlStatus (повідомлення UORB) +Autotune attitude control status + +This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +and is subscribed to by the respective attitude controllers to command rate setpoints. + +The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AutotuneAttitudeControlStatus.msg) ```c -uint64 timestamp # time since system start (microseconds) +# Autotune attitude control status +# +# This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +# and is subscribed to by the respective attitude controllers to command rate setpoints. +# +# The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. -float32[5] coeff # coefficients of the identified discrete-time model -float32[5] coeff_var # coefficients' variance of the identified discrete-time model -float32 fitness # fitness of the parameter estimate -float32 innov -float32 dt_model +uint64 timestamp # [us] Time since system start -float32 kc -float32 ki -float32 kd -float32 kff -float32 att_p +float32[5] coeff # [-] Coefficients of the identified discrete-time model +float32[5] coeff_var # [-] Coefficients' variance of the identified discrete-time model +float32 fitness # [-] Fitness of the parameter estimate +float32 innov # [rad/s] Innovation (residual error between model and measured output) +float32 dt_model # [s] Model sample time used for identification -float32[3] rate_sp -float32 u_filt -float32 y_filt +float32 kc # [-] Proportional rate-loop gain (ideal form) +float32 ki # [-] Integral rate-loop gain (ideal form) +float32 kd # [-] Derivative rate-loop gain (ideal form) +float32 kff # [-] Feedforward rate-loop gain +float32 att_p # [-] Proportional attitude gain -uint8 STATE_IDLE = 0 -uint8 STATE_INIT = 1 -uint8 STATE_ROLL = 2 -uint8 STATE_ROLL_PAUSE = 3 -uint8 STATE_PITCH = 4 -uint8 STATE_PITCH_PAUSE = 5 -uint8 STATE_YAW = 6 -uint8 STATE_YAW_PAUSE = 7 -uint8 STATE_VERIFICATION = 8 -uint8 STATE_APPLY = 9 -uint8 STATE_TEST = 10 -uint8 STATE_COMPLETE = 11 -uint8 STATE_FAIL = 12 -uint8 STATE_WAIT_FOR_DISARM = 13 +float32[3] rate_sp # [rad/s] Rate setpoint commanded to the attitude controller. -uint8 state +float32 u_filt # [-] Filtered input signal (normalized torque setpoint) used in system identification. +float32 y_filt # [rad/s] Filtered output signal (angular velocity) used in system identification. + +uint8 state # [@enum STATE] Current state of the autotune procedure. +uint8 STATE_IDLE = 0 # Idle (not running) +uint8 STATE_INIT = 1 # Initialize filters and setup +uint8 STATE_ROLL_AMPLITUDE_DETECTION = 2 # FW only: determine required excitation amplitude (roll) +uint8 STATE_ROLL = 3 # Roll-axis excitation and model identification +uint8 STATE_ROLL_PAUSE = 4 # Pause to return to level flight +uint8 STATE_PITCH_AMPLITUDE_DETECTION = 5 # FW only: determine required excitation amplitude (pitch) +uint8 STATE_PITCH = 6 # Pitch-axis excitation and model identification +uint8 STATE_PITCH_PAUSE = 7 # Pause to return to level flight +uint8 STATE_YAW_AMPLITUDE_DETECTION = 8 # FW only: determine required excitation amplitude (yaw) +uint8 STATE_YAW = 9 # Yaw-axis excitation and model identification +uint8 STATE_YAW_PAUSE = 10 # Pause to return to level flight +uint8 STATE_VERIFICATION = 11 # Verify model and candidate gains +uint8 STATE_APPLY = 12 # Apply gains +uint8 STATE_TEST = 13 # Test gains in closed-loop +uint8 STATE_COMPLETE = 14 # Tuning completed successfully +uint8 STATE_FAIL = 15 # Tuning failed (model invalid or controller unstable) +uint8 STATE_WAIT_FOR_DISARM = 16 # Waiting for disarm before finalizing ``` diff --git a/docs/uk/msg_docs/ControlAllocatorStatus.md b/docs/uk/msg_docs/ControlAllocatorStatus.md index f93715bdc6..eb6cb73385 100644 --- a/docs/uk/msg_docs/ControlAllocatorStatus.md +++ b/docs/uk/msg_docs/ControlAllocatorStatus.md @@ -24,5 +24,6 @@ int8[16] actuator_saturation # Indicates actuator saturation status. # Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value. uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector +uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection ``` diff --git a/docs/uk/msg_docs/EstimatorStatusFlags.md b/docs/uk/msg_docs/EstimatorStatusFlags.md index 7aaef39405..af4ee8c081 100644 --- a/docs/uk/msg_docs/EstimatorStatusFlags.md +++ b/docs/uk/msg_docs/EstimatorStatusFlags.md @@ -54,8 +54,9 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended -bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_gnss_fault # 45 - true if GNSS true if GNSS measurements (lat, lon, vel) have been declared faulty bool cs_yaw_manual # 46 - true if yaw has been set manually +bool cs_gnss_hgt_fault # 47 - true if GNSS true if GNSS measurements (alt) have been declared faulty # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/docs/uk/msg_docs/FailureDetectorStatus.md b/docs/uk/msg_docs/FailureDetectorStatus.md index b74da3ec41..111bd96b78 100644 --- a/docs/uk/msg_docs/FailureDetectorStatus.md +++ b/docs/uk/msg_docs/FailureDetectorStatus.md @@ -17,5 +17,6 @@ bool fd_motor float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed) uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures +uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection ``` diff --git a/docs/uk/msg_docs/GimbalDeviceAttitudeStatus.md b/docs/uk/msg_docs/GimbalDeviceAttitudeStatus.md index a47faa3574..032a3876ee 100644 --- a/docs/uk/msg_docs/GimbalDeviceAttitudeStatus.md +++ b/docs/uk/msg_docs/GimbalDeviceAttitudeStatus.md @@ -14,6 +14,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2 uint16 DEVICE_FLAGS_ROLL_LOCK = 4 uint16 DEVICE_FLAGS_PITCH_LOCK = 8 uint16 DEVICE_FLAGS_YAW_LOCK = 16 +uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 +uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 + float32[4] q float32 angular_velocity_x diff --git a/docs/uk/msg_docs/SensorGnssStatus.md b/docs/uk/msg_docs/SensorGnssStatus.md new file mode 100644 index 0000000000..70602b85fc --- /dev/null +++ b/docs/uk/msg_docs/SensorGnssStatus.md @@ -0,0 +1,19 @@ +# SensorGnssStatus (UORB message) + +Gnss quality indicators + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssStatus.msg) + +```c +# Gnss quality indicators + +uint64 timestamp # time since system start (microseconds) +uint32 device_id # unique device ID for the sensor that does not change between power cycles + +bool quality_available # Set to true if quality indicators are available +uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if not available +uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available +uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available +uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available + +``` diff --git a/docs/uk/msg_docs/SensorGps.md b/docs/uk/msg_docs/SensorGps.md index 8cb9d3d304..e451e98aaa 100644 --- a/docs/uk/msg_docs/SensorGps.md +++ b/docs/uk/msg_docs/SensorGps.md @@ -38,18 +38,26 @@ float32 vdop # Vertical dilution of precision int32 noise_per_ms # GPS noise per millisecond uint16 automatic_gain_control # Automatic gain control monitor -uint8 JAMMING_STATE_UNKNOWN = 0 -uint8 JAMMING_STATE_OK = 1 -uint8 JAMMING_STATE_WARNING = 2 -uint8 JAMMING_STATE_CRITICAL = 3 -uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical -int32 jamming_indicator # indicates jamming is occurring +uint8 JAMMING_STATE_UNKNOWN = 0 #default +uint8 JAMMING_STATE_OK = 1 +uint8 JAMMING_STATE_MITIGATED = 2 +uint8 JAMMING_STATE_DETECTED = 3 +uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected +int32 jamming_indicator # indicates jamming is occurring -uint8 SPOOFING_STATE_UNKNOWN = 0 -uint8 SPOOFING_STATE_NONE = 1 -uint8 SPOOFING_STATE_INDICATED = 2 -uint8 SPOOFING_STATE_MULTIPLE = 3 -uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical +uint8 SPOOFING_STATE_UNKNOWN = 0 #default +uint8 SPOOFING_STATE_OK = 1 +uint8 SPOOFING_STATE_MITIGATED = 2 +uint8 SPOOFING_STATE_DETECTED = 3 +uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected + +# Combined authentication state (e.g. Galileo OSNMA) +uint8 AUTHENTICATION_STATE_UNKNOWN = 0 #default +uint8 AUTHENTICATION_STATE_INITIALIZING = 1 +uint8 AUTHENTICATION_STATE_ERROR = 2 +uint8 AUTHENTICATION_STATE_OK = 3 +uint8 AUTHENTICATION_STATE_DISABLED = 4 +uint8 authentication_state # GPS signal authentication state float32 vel_m_s # GPS ground speed, (metres/sec) float32 vel_n_m_s # GPS North velocity, (metres/sec) @@ -63,6 +71,16 @@ uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp whi uint8 satellites_used # Number of satellites used +uint32 SYSTEM_ERROR_OK = 0 #default +uint32 SYSTEM_ERROR_INCOMING_CORRECTIONS = 1 +uint32 SYSTEM_ERROR_CONFIGURATION = 2 +uint32 SYSTEM_ERROR_SOFTWARE = 4 +uint32 SYSTEM_ERROR_ANTENNA = 8 +uint32 SYSTEM_ERROR_EVENT_CONGESTION = 16 +uint32 SYSTEM_ERROR_CPU_OVERLOAD = 32 +uint32 SYSTEM_ERROR_OUTPUT_CONGESTION = 64 +uint32 system_error # General errors with the connected GPS receiver + float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI]) float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI]) float32 heading_accuracy # heading accuracy (rad, [0, 2PI]) diff --git a/docs/uk/msg_docs/VehicleOdometry.md b/docs/uk/msg_docs/VehicleOdometry.md index 7dce09ab10..c7abbc98c4 100644 --- a/docs/uk/msg_docs/VehicleOdometry.md +++ b/docs/uk/msg_docs/VehicleOdometry.md @@ -1,41 +1,44 @@ # VehicleOdometry (повідомлення UORB) -Дані odometry Техніки. Fits ROS REP 147 for aerial vehicles +Vehicle odometry data + +Fits ROS REP 147 for aerial vehicles [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleOdometry.msg) ```c -# Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +# Vehicle odometry data +# +# Fits ROS REP 147 for aerial vehicles uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp sample -uint8 POSE_FRAME_UNKNOWN = 0 -uint8 POSE_FRAME_NED = 1 # NED earth-fixed frame -uint8 POSE_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference -uint8 pose_frame # Position and orientation frame of reference +uint8 pose_frame # [@enum POSE_FRAME] Position and orientation frame of reference +uint8 POSE_FRAME_UNKNOWN = 0 # Unknown frame +uint8 POSE_FRAME_NED = 1 # North-East-Down (NED) navigation frame. Aligned with True North. +uint8 POSE_FRAME_FRD = 2 # Forward-Right-Down (FRD) frame. Constant arbitrary heading offset from True North. Z is down. -float32[3] position # Position in meters. Frame of reference defined by local_frame. NaN if invalid/unknown -float32[4] q # Quaternion rotation from FRD body frame to reference frame. First value NaN if invalid/unknown +float32[3] position # [m] [@frame local frame] [@invalid NaN If invalid/unknown] Position. Origin is position of GC at startup. +float32[4] q # [-] [@invalid NaN First value if invalid/unknown] Attitude (expressed as a quaternion) relative to pose reference frame at current location. Follows the Hamiltonian convention (w, x, y, z, right-handed, passive rotations from body to world) -uint8 VELOCITY_FRAME_UNKNOWN = 0 -uint8 VELOCITY_FRAME_NED = 1 # NED earth-fixed frame -uint8 VELOCITY_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference -uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame -uint8 velocity_frame # Reference frame of the velocity data +uint8 velocity_frame # [@enum VELOCITY_FRAME] Reference frame of the velocity data +uint8 VELOCITY_FRAME_UNKNOWN = 0 # Unknown frame +uint8 VELOCITY_FRAME_NED = 1 # NED navigation frame at current position. +uint8 VELOCITY_FRAME_FRD = 2 # FRD navigation frame at current position. Constant arbitrary heading offset from True North. Z is down. +uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame -float32[3] velocity # Velocity in meters/sec. Frame of reference defined by velocity_frame variable. NaN if invalid/unknown +float32[3] velocity # [m/s] [@frame @velocity_frame] [@invalid NaN If invalid/unknown] Velocity. +float32[3] angular_velocity # [rad/s] [@frame @VELOCITY_FRAME_BODY_FRD] [@invalid NaN If invalid/unknown] Angular velocity in body-fixed frame -float32[3] angular_velocity # Angular velocity in body-fixed frame (rad/s). NaN if invalid/unknown +float32[3] position_variance # [m^2] Variance of position error +float32[3] orientation_variance # [rad^2] Variance of orientation/attitude error (expressed in body frame) +float32[3] velocity_variance # [m^2/s^2] Variance of velocity error -float32[3] position_variance -float32[3] orientation_variance -float32[3] velocity_variance - -uint8 reset_counter -int8 quality +uint8 reset_counter # [-] Reset counter. Counts reset events on attitude, velocity and position. +int8 quality # [-] [@invalid 0] Quality. Unused. # TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry # TOPICS estimator_odometry diff --git a/docs/uk/msg_docs/index.md b/docs/uk/msg_docs/index.md index 4e64d5af95..d383ce1452 100644 --- a/docs/uk/msg_docs/index.md +++ b/docs/uk/msg_docs/index.md @@ -15,7 +15,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message -- [AirspeedValidated](AirspeedValidated.md) +- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed - [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply - [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request - [BatteryStatus](BatteryStatus.md) — Battery status @@ -70,7 +70,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [VehicleLandDetected](VehicleLandDetected.md) - [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data - [VehicleRatesSetpoint](VehicleRatesSetpoint.md) - [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander - [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE @@ -87,7 +87,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [AdcReport](AdcReport.md) - [Airspeed](Airspeed.md) — Airspeed data from sensors - [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector) -- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) +- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status - [BatteryInfo](BatteryInfo.md) — Battery information - [ButtonEvent](ButtonEvent.md) - [CameraCapture](CameraCapture.md) @@ -246,6 +246,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m change with board revisions and sensor updates. - [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor - [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. NED кадр визначається як локальна топологічна система на задній станції. +- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators - [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds) - [SensorGyro](SensorGyro.md) @@ -255,9 +256,9 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [SensorMag](SensorMag.md) - [SensorOpticalFlow](SensorOpticalFlow.md) - [SensorPreflightMag](SensorPreflightMag.md) — Pre-flight sensor check metrics. - Тема не буде оновлена, коли транспортний засіб зброєний + The topic will not be updated when the vehicle is armed - [SensorSelection](SensorSelection.md) — Sensor ID's for the voted sensors output on the sensor_combined topic. - Буде оновлено при запуску модуля датчика та при зміні вибору датчика + Will be updated on startup of the sensor module and when sensor selection changes - [SensorUwb](SensorUwb.md) — UWB distance contains the distance information measured by an ultra-wideband positioning system, such as Pozyx or NXP Rddrone. - [SensorsStatus](SensorsStatus.md) — Sensor check metrics. Це значення буде нульовим для датчика, який є первинним або незаповненим. @@ -289,7 +290,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [VehicleImuStatus](VehicleImuStatus.md) - [VehicleLocalPositionSetpoint](VehicleLocalPositionSetpoint.md) — Local position setpoint in NED frame Telemetry of PID position controller to monitor tracking. - NaN означає, що стан не був контрольований + NaN means the state was not controlled - [VehicleMagnetometer](VehicleMagnetometer.md) - [VehicleOpticalFlow](VehicleOpticalFlow.md) — Optical flow in XYZ body frame in SI units. - [VehicleOpticalFlowVel](VehicleOpticalFlowVel.md) diff --git a/docs/uk/releases/main.md b/docs/uk/releases/main.md index dd3875875b..dbce991f2c 100644 --- a/docs/uk/releases/main.md +++ b/docs/uk/releases/main.md @@ -58,7 +58,10 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Симуляція -- Уточнюється +- Overhaul rover simulation: + - Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107) + - Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113) + - Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117) ### Ethernet @@ -67,6 +70,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 - [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). +- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md). ### MAVLink @@ -89,6 +93,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Ровер - Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)). +- Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)). +- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details). ### ROS 2 diff --git a/docs/uk/ros2/offboard_control.md b/docs/uk/ros2/offboard_control.md index 142c9931cb..2a6b62079d 100644 --- a/docs/uk/ros2/offboard_control.md +++ b/docs/uk/ros2/offboard_control.md @@ -1,6 +1,6 @@ # ROS 2 Offboard Control Приклад -The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node. +The following C++ example shows how to do multicopter position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node. Приклад починає відправляти установочні точки, входить у режим offboard, озброюється, піднімається на 5 метрів і чекає. Незважаючи на простоту, він демонструє основні принципи використання offboard control і способи надсилання команд транспортному засобу. @@ -22,7 +22,7 @@ To subscribe to data coming from nodes that publish in a different frame (for ex ## Випробування -Follow the instructions in [ROS 2 User Guide](../ros2/user_guide.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent. +Follow the instructions in [ROS 2 User Guide](../ros2/user_guide.md) to install PX and run the multicopter simulator, install ROS 2, and start the XRCE-DDS Agent. After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros2/user_guide.md#build-ros-2-workspace) to run the example. diff --git a/docs/uk/ros2/px4_ros2_control_interface.md b/docs/uk/ros2/px4_ros2_control_interface.md index 1bf129ee18..0905f468a6 100644 --- a/docs/uk/ros2/px4_ros2_control_interface.md +++ b/docs/uk/ros2/px4_ros2_control_interface.md @@ -348,6 +348,7 @@ private: - [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control - [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - DirectActuatorsSetpointType: Пряме керування моторами та установками сервоприводів польотних поверхонь +- [Rover Setpoints](#rover-setpoints): Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering). :::tip The other setpoint types are currently experimental, and can be found in: [px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental). @@ -359,6 +360,8 @@ The other setpoint types are currently experimental, and can be found in: [px4_r + + :::info This setpoint type is currently only supported for multicopters. ::: @@ -552,6 +555,40 @@ and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). Якщо ви хочете керувати клапаном, який не контролює рух транспортного засобу, але, наприклад, сервопривід навантаження, подивіться нижче. ::: +#### Rover Setpoints + + + +The rover modules use a hierarchical structure to propagate setpoints: + +![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg) + +:::info +The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (Overriding them!). +With this hierarchy there are clear rules for providing a valid control input: + +- Provide a position setpoint, **or** +- One of the setpoints on the "left" (speed **or** throttle) **and** one of the setpoints on the "right" (attitude, rate **or** steering). All combinations of "left" and "right" setpoints are valid. + +For ease of use we expose these valid combinations as new SetpointTypes. +::: + +The RoverSetpointTypes exposed through the control interface are combinations of these setpoints that lead to a valid control input: + +| SetpointType | Положення | Speed | Тяга | Attitude | Rate | Steering | Control Flags | +| ----------------------------------------------------------------------------------------------------------------------------------- | --------------------------- | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------------ | +| [RoverPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverPositionSetpointType.html#details) | ✓ | (✓) | (✓) | (✓) | (✓) | (✓) | Position, Velocity, Attitude, Rate, Control Allocation | +| [RoverSpeedAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedAttitudeSetpointType.html) | | ✓ | (✓) | ✓ | (✓) | (✓) | Velocity, Attitude, Rate, Control Allocation | +| [RoverSpeedRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedRateSetpointType.html) | | ✓ | (✓) | | ✓ | (✓) | Velocity, Rate, Control Allocation | +| [RoverSpeedSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedSteeringSetpointType.html) | | ✓ | (✓) | | | ✓ | Velocity, Control Allocation | +| [RoverThrottleAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleAttitudeSetpointType.html) | | | ✓ | ✓ | (✓) | (✓) | Attitude, Rate, Control Allocation | +| [RoverThrottleRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleRateSetpointType.html) | | | ✓ | | ✓ | (✓) | Rate, Control Allocation | +| [RoverThrottleSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleSteeringSetpointType.html) | | | ✓ | | | ✓ | Control Allocation | + +✓ are the setpoints we publish, and (✓) are generated internally by the PX4 rover modules according to the hierarchy above. + +An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpointType` is provided [here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/rover_velocity). + ### Controlling a VTOL diff --git a/docs/uk/ros2/px4_ros2_interface_lib.md b/docs/uk/ros2/px4_ros2_interface_lib.md index 1829bd5d64..c392c93f85 100644 --- a/docs/uk/ros2/px4_ros2_interface_lib.md +++ b/docs/uk/ros2/px4_ros2_interface_lib.md @@ -9,15 +9,12 @@ [PX4 ROS 2 Інтерфейс бібліотеки](https://github.com/Auterion/px4-ros2-interface-lib) є бібліотекою C+++, яка спрощує контроль і взаємодіє з PX4 з ROS 2. -Бібліотека надає два інтерфейси високого рівня для розробників: +The library provides three high-level interfaces for developers: 1. [Control Interface](./px4_ros2_interface.md) дозволяє розробникам створювати та динамічно реєструвати режими, написані з використанням ROS 2. Бібліотека також надає класи для надсилання різних типів налаштувань, починаючи від багаторівневих навігаційних завдань на високому рівні аж до прямого контролю приводу. 2. [Навігаційний інтерфейс](./px4_ros2_navigation_interface.md) дозволяє надсилати позицію автомобіля з позиції PX4 з ROS 2 додатків, таких як система VIO. - - +3. [Waypoint Missions](./px4_ros2_waypoint_missions.md) allows waypoint missions to run entirely in ROS 2. ## Встановлення в робочому просторі ROS 2 diff --git a/docs/uk/ros2/px4_ros2_waypoint_missions.md b/docs/uk/ros2/px4_ros2_waypoint_missions.md new file mode 100644 index 0000000000..c6d6f7caff --- /dev/null +++ b/docs/uk/ros2/px4_ros2_waypoint_missions.md @@ -0,0 +1,190 @@ +# PX4 ROS 2 Waypoint Missions + + + +The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) provides a high-level interface for executing ROS-based waypoint missions in ROS 2. +The main use-case is for creating missions where a custom behavior is required, such as a pickup action within a mission. + +:::warning +ROS 2 missions are not compatible with MAVLink mission definitions, plan files, or ground stations. +They completely bypass the existing PX4 mission mode and waypoint logic, and cannot be planned or displayed within a ground station. +::: + +ROS 2 waypoint missions are effectively special PX4 ROS 2 custom modes that are run based on the content of a [JSON mission definition](#mission-definition). +Mission definitions can contain actions that reference existing PX4 modes, such as Takeoff mode or RTL, and can also be extended with arbitrary custom actions written in ROS. +A [mode executor](px4_ros2_control_interface.md#mode-executor) is used to schedule the modes. + +Mission definitions can be hard coded in the custom mission mode (either in code or statically loaded from a JSON string), or directly generated within the application. +They can also be dynamically loaded based on modification of a particular JSON file — this allows for building a more generic mission framework with a fixed set of custom actions. +The file can then be written by any other application, for example a HTTP or MAVFTP server. + +The current implementation only supports multicopters but is designed to be extendable to any other vehicle type. + +## Comparison to PX4/MAVLink Missions + +There are some benefits and drawbacks to using ROS-based missions, which are provided in the following paragraphs. + +### Переваги + +- Allows to extend mission capabilities by registering custom actions. +- More control over how the mission is executed. + A custom trajectory executor can be implemented, which can use any of the existing PX4 setpoint types to track the trajectory. +- Reduced complexity on the flight controller side by running non-safety-critical and non-real-time code on a more high-level companion computer. +- It can be extended to support other trajectory types, like Bezier or Dubin curves. + +### Drawbacks + +- QGroundControl currently does not display the mission or progress during execution, and cannot upload or download a mission. + Therefore you will need another mechanism to provide a mission, such as from a web server, a custom GCS, or by generating it directly inside the application. +- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-multicoptergotosetpointtype), which only works for multicopters, and VTOL in MC mode). + It is designed to be extendable to any other vehicle type. + +## Загальний огляд + +This diagram provides a conceptual overview of the main classes and their interactions: + +![Waypoint missions overview diagram](../../assets/middleware/ros2/px4_ros2_interface_lib/waypoint_missions.svg) + + + +Missions can be defined in [JSON](#mission-definition), either as a file, or directly inside the application. +There is a file change monitor (`MissionFileMonitor`), that can be used to automatically load a mission from a specific file whenever it is created by another application (e.g. upload via MAVFTP or a cloud service). + +The **`MissionExecutor`** class contains the state machine to progress the mission index, and is at the core of the implementation: + +- Internally, it builds on top of the [Modes and Mode Executors](px4_ros2_control_interface.md#overview) and registers itself through a custom mode and executor with PX4. +- It handles switching in and out of missions: it gets activated when the user switches to the custom mode that represents the mission and the vehicle is armed. + The mode name can be customized (`My Mission` in the example below). + The mission can be paused, which makes the vehicle switch into _Hold mode_. + To resume the mission, the custom mode has to be selected again. +- When an action switches into another mode (for example Takeoff), QGroundControl will display this mode until it is completed. + The mission executor will then automatically continue. +- Custom actions can be registered. +- The mission can be set. + It then checks that all the actions which the mission defines are available and can be run. +- The state can be stored persistently by providing a file name, allowing for battery swapping. + +The **`ActionInterface`** is an interface class for custom actions. +They are identified by a name, and any number of these can be registered with the `MissionExecutor`. +A custom action is then run whenever a mission item with matching name is executed, and any extra arguments from the JSON definition are passed as arguments (for example an altitude for a takeoff action). +Actions can call other actions, run any mode (PX4 or external by its ID), run a trajectory, or run any other external action before deciding when to continue the mission. + +There is a set of default actions, for example for RTL, Land, etc. +These simply trigger the corresponding PX4 mode. +They can be disabled or replaced with custom implementations. +There are also some special actions (which can be replaced as well): + +- `OnFailure`: this is called in case of a failure, e.g. a mode switch failed, a non-existing action is called (by another action) or by an explicit call to `MissionExecutor::abort()`. + The default is to run RTL, with fallback to Land. +- `OnResume`: this is called when resuming a mission (either from the ground or in-air). + It handles a number of cases: + - when called with an argument `action="storeState"`: this can be used to store the current position when the mission is deactivated, so it can be resumed from the same position. + Currently it does not store anything. + - otherwise, when called without a valid mission index or 0, it directly continues. + - otherwise, when called while in-air, it also directly continues. + - otherwise, if landed and if the current mission item is an action that supports resuming from landed, it continues to let the action handle the resuming. + - otherwise, if landed, it finds the takeoff action from the mission, runs it, and then flies to the previous waypoint from the current index to continue the mission. +- `ChangeSettings`: this can be used to change the mission settings, such as the velocity. + The settings are applied to all following items in the mission. + +The **`TrajectoryExecutorInterface`** is an interface class to execute segments of a trajectory. +It can use any setpoint that PX4 and the current vehicle supports for tracking the trajectory. +This class is vehicle-type specific. +The current default implementation (`multicopter::WaypointTrajectoryExecutor`) uses a Goto setpoint (and thus is limited to multicopters). +The default can be replaced with a custom implementation. + +## Використання + +The following provides a small example. +It defines a custom action and a mission that uses it. + +```c++ +class CustomAction : public px4_ros2::ActionInterface { +public: + CustomAction(px4_ros2::ModeBase & mode) : _node(mode.node()) { } + + std::string name() const override {return "customAction";} + + void run( + const std::shared_ptr & handler, + const px4_ros2::ActionArguments & arguments, + const std::function & on_completed) override + { + RCLCPP_INFO(_node.get_logger(), "Running custom action"); + // Do something... + + on_completed(); + } +private: + rclcpp::Node & _node; +}; + +class MyMission { +public: + MyMission(const std::shared_ptr & node) : _node(node) + { + const auto mission = px4_ros2::Mission(nlohmann::json::parse(R"( + { + "version": 1, + "mission": { + "items": [ + { + "type": "takeoff" + }, + { + "type": "navigation", + "navigationType": "waypoint", + "x": 47.3977419, + "y": 8.5455939, + "z": 500, + "frame": "global" + }, + { + "type": "navigation", + "navigationType": "waypoint", + "x": 47.39791657, + "y": 8.54595214, + "z": 500, + "frame": "global" + }, + { + "type": "customAction" + }, + { + "type": "rtl" + } + ] + } + } +)")); + _mission_executor = std::make_unique("My Mission", + px4_ros2::MissionExecutor::Configuration().addCustomAction(), *node); + + if (!_mission_executor->doRegister()) { + throw std::runtime_error("Failed to register mission executor"); + } + _mission_executor->setMission(mission); + + _mission_executor->onProgressUpdate([&](int current_index) { + RCLCPP_INFO(_node->get_logger(), "Current mission index: %i", current_index); + }); + _mission_executor->onCompleted([&] { + RCLCPP_INFO(_node->get_logger(), "Mission completed callback"); + }); + } + +private: + std::shared_ptr _node; + std::unique_ptr _mission_executor; +}; +``` + +A full example with a few custom actions can be found under [github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/mission/include](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/mission/include). + +## Mission Definition + +The mission JSON file can contain mission defaults and a list of mission items, including user-defined types with custom arguments. +Waypoint coordinates currently need to be defined in global frame, and other frame types might be added in future. + +The schema can be found under [github.com/Auterion/px4-ros2-interface-lib/blob/main/mission/schema.yaml](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/mission/schema.yaml). +It provides more details and can be used to validate a JSON file. diff --git a/docs/uk/sensor/inertial_navigation_systems.md b/docs/uk/sensor/inertial_navigation_systems.md index 0f01d9b58e..6dd786584c 100644 --- a/docs/uk/sensor/inertial_navigation_systems.md +++ b/docs/uk/sensor/inertial_navigation_systems.md @@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) +- [MicroStrain](../sensor/microstrain.md): Includes VRU, AHRS, INS, and GNSS/INS devices. - [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. - [VectorNav](../sensor/vectornav.md): ІВП/AHRS, ССН/INS, Dual GNSS/INS системи, котрі можуть бути використані як зовнішній INS, або джерело вхідної інформації датчиків. diff --git a/docs/uk/sensor/microstrain.md b/docs/uk/sensor/microstrain.md new file mode 100644 index 0000000000..6a78dc6895 --- /dev/null +++ b/docs/uk/sensor/microstrain.md @@ -0,0 +1,219 @@ +# MicroStrain (INS, IMU, VRU, AHRS) + +MicroStrain by HBK provides high-performance inertial sensors engineered for reliability and precision in challenging environments. +Widely used across industries like aerospace, robotics, industrial automation, and research, MicroStrain sensors are optimized for real-time, accurate motion tracking and orientation data. + +![CV7](../../assets/hardware/sensors/inertial/microstrain_3dm_cv7_hbk.png) + +The driver currently supports the following hardware: + +- [`MicroStrain CV7-AR`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/vertical-reference-units--vru-/3dm-cv7-ar): Inertial Measurement Unit (IMU) and Vertical Reference Unit (VRU) +- [`MicroStrain CV7-AHRS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/attitude-and-heading-reference-systems--ahrs-/3dm-cv7-ahrs): Inertial Measurement Unit (IMU) and Attitude Heading Reference System (AHRS) +- [`MicroStrain CV7-INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS). +- [`MicroStrain CV7-GNSS/INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-gnss-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS) combined with dual multiband (GNSS) receivers. + +PX4 can use these sensors to provide raw IMU data for EKF2 or to replace EKF2 as an external INS. +For more information, including user manuals and datasheets, please refer to the sensors product page. + +## Де купити + +MicroStrain sensors can be purchased through HBK's official [MicroStrain product page](https://www.hbkworld.com/en/products/transducers/inertial-sensors) or through authorized distributors globally. +For large orders, custom requirements, or technical inquiries, reach out directly to [sales](https://www.hbkworld.com/en/contact-us/contact-sales-microstrain) + +## Налаштування програмного забезпечення + +### Підключення + +Connect the main UART port of the MicroStrain sensor to any unused serial port on the flight controller. +This port needs to be specified while starting the device. + +### Встановлення + +The MicroStrain sensor can be mounted in any orientation. +The default coordinate system uses X for the front, Y for the right, and Z for down, with directions marked on the device. + +## Конфігурація прошивки + +### Конфігурація PX4 + +To use the MicroStrain driver: + +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`. + +2. Configure the driver mode by setting [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) + + - To use the MicroStrain sensor to provide raw IMU data to EKF2 + + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 0 + 2. Update the [EKF2_MULTI_IMU](../advanced_config/parameter_reference.md#EKF2_MULTI_IMU) parameter to account for the added MicroStrain sensor. + 3. Enable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 1 + 4. To prioritize MicroStrain sensor output, adjust the priority level of individual sensors from 0-100 using the following parameters: + + - [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO) + - [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO) + - [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO) + - [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO) + + where `n` corresponds to the index of the corresponding sensor. + + ::: tip + Sensors can be identified by their device id, which can be found by checking the parameters: + + - [CAL_ACCn_ID](../advanced_config/parameter_reference.md#CAL_ACC0_ID) + - [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) + - [CAL_MAGn_ID](../advanced_config/parameter_reference.md#CAL_MAG0_ID) + - [CAL_BAROn_ID](../advanced_config/parameter_reference.md#CAL_BARO0_ID) + + +::: + + - To use the MicroStrain sensor as an external INS + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 1 + 2. Disable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 0 + +3. Reboot and start the driver + - `microstrain start -d ` + - To start the driver automatically when the flight controller powers on, set [SENS_MS_CFG](../advanced_config/parameter_reference.md#SENS_MS_CFG) to the sensor’s connected port. + +## MicroStrain Configuration + +1. Rates: + + - By default, accel and gyro data are published at 500 Hz, magnetometer at 50 Hz, and barometric pressure at 50 Hz. + This can be changed by adjusting the following parameters: + + - [MS_IMU_RATE_HZ](../advanced_config/parameter_reference.md#MS_IMU_RATE_HZ) + - [MS_MAG_RATE_HZ](../advanced_config/parameter_reference.md#MS_MAG_RATE_HZ) + - [MS_BARO_RATE_HZ](../advanced_config/parameter_reference.md#MS_BARO_RATE_HZ) + + - Global position, local position, attitude and odometry will be published at 250 Hz by default. + This can be configured via: + + - [MS_FILT_RATE_HZ](../advanced_config/parameter_reference.md#MS_FILT_RATE_HZ) + + - For the CV7-GNSS/INS, the GNSS receiver 1 and 2 will publish data at 5Hz by default. + This can be changed using: + + - [MS_GNSS_RATE_HZ](../advanced_config/parameter_reference.md#MS_GNSS_RATE_HZ) + + - The driver will automatically configure data outputs based on the specific sensor model and available data streams. + + - The driver is scheduled to run at twice the fastest configured data rate. + +2. Aiding measurements: + + - If supported, GNSS position and velocity aiding are always enabled. + + - Internal/external magnetometer and heading aiding, as well as optical flow aiding, are disabled by default. They can be enabled using the following parameters: + + - [MS_INT_MAG_EN](../advanced_config/parameter_reference.md#MS_INT_MAG_EN) + - [MS_INT_HEAD_EN](../advanced_config/parameter_reference.md#MS_INT_HEAD_EN) + - [MS_EXT_HEAD_EN](../advanced_config/parameter_reference.md#MS_EXT_HEAD_EN) + - [MS_EXT_MAG_EN](../advanced_config/parameter_reference.md#MS_EXT_MAG_EN) + - [MS_OPT_FLOW_EN](../advanced_config/parameter_reference.md#MS_OPT_FLOW_EN) + + - The aiding frames for external sources can be configured using the following parameters: + + - [MS_EHEAD_YAW](../advanced_config/parameter_reference.md#MS_EHEAD_YAW) + - [MS_EMAG_ROLL](../advanced_config/parameter_reference.md#MS_EMAG_ROLL) + - [MS_EMAG_PTCH](../advanced_config/parameter_reference.md#MS_EMAG_PTCH) + - [MS_EMAG_YAW](../advanced_config/parameter_reference.md#MS_EMAG_YAW) + - [MS_OFLW_OFF_X](../advanced_config/parameter_reference.md#MS_OFLW_OFF_X) + - [MS_OFLW_OFF_Y](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Y) + - [MS_OFLW_OFF_Z](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Z) + - [SENS_FLOW_ROT](../advanced_config/parameter_reference.md#SENS_FLOW_ROT) + + - The uncertainty for optical flow and external magnetometer aiding must be specified using the following parameters: + + - [MS_EMAG_UNCERT](../advanced_config/parameter_reference.md#MS_EMAG_UNCERT) + - [MS_OFLW_UNCERT](../advanced_config/parameter_reference.md#MS_OFLW_UNCERT) + + ::: tip + + 1. When optical flow aiding is enabled, the sensor uses the `vehicle_optical_flow_vel` output from the flight controller as a body-frame velocity aiding measurement. + 2. If the MicroStrain sensor does not support these aiding sources but they are enabled, sensor initialization will fail. + + +::: + +3. Initial heading alignment: + + - Initial heading alignment is set to kinematic by default. This can be changed by adjusting + + - [MS_ALIGNMENT](../advanced_config/parameter_reference.md#MS_ALIGNMENT) + +4. GNSS Aiding Source Control (GNSS/INS only) + + - The Source of the GNSS aiding data can be configured using: + + - [MS_GNSS_AID_SRC](../advanced_config/parameter_reference.md#MS_GNSS_AID_SRC) + +5. Sensor to vehicle transform: + + - If the sensor is mounted in an orientation different from the vehicle frame. A sensor to vehicle transform can be enabled using + + - [MS_SVT_EN](../advanced_config/parameter_reference.md#MS_SVT_EN) + + - The transform is defined using the following parameters + + - [MS_SENSOR_ROLL](../advanced_config/parameter_reference.md#MS_SENSOR_ROLL) + - [MS_SENSOR_PTCH](../advanced_config/parameter_reference.md#MS_SENSOR_PTCH) + - [MS_SENSOR_YAW](../advanced_config/parameter_reference.md#MS_SENSOR_YAW) + +6. IMU ranges: + + - The accelerometer and gyroscope ranges on the device are configurable using: + + - [MS_ACCEL_RANGE](../advanced_config/parameter_reference.md#MS_ACCEL_RANGE) + - [MS_GYRO_RANGE](../advanced_config/parameter_reference.md#MS_GYRO_RANGE) + + ::: tip + Available range settings depend on the specific [sensor](https://www.hbkworld.com/en/products/transducers/inertial-sensors) and can be found in the corresponding user manual. + By default, the ranges are not changed. + + +::: + +7. GNSS Lever arm offsets: + + - The lever arm offset for the external GNSS receiver can be configured using: + + - [MS_GNSS_OFF1_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_X) + - [MS_GNSS_OFF1_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Y) + - [MS_GNSS_OFF1_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Z) + + - For dual-antenna configurations, the second GNSS receiver’s offset is configured using: + + - [MS_GNSS_OFF2_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_X) + - [MS_GNSS_OFF2_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Y) + - [MS_GNSS_OFF2_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Z) + +## Опубліковані дані + +The MicroStrain driver continuously publishes sensor data to the following uORB topics: + +- [sensor_accel](../msg_docs/SensorAccel.md) +- [датчик_гіроскопа](../msg_docs/SensorGyro.md) +- [sensor_mag](../msg_docs/SensorMag.md) +- [sensor_baro](../msg_docs/SensorBaro.md) + +For GNSS/INS devices, GPS data is also published to: + +- [sensor_gps](../msg_docs/SensorGps.md) + +If used as an external INS replacing EKF2, it publishes: + +- [vehicle_global_position](../msg_docs/VehicleGlobalPosition.md) +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) +- [vehicle_odometry](../msg_docs/VehicleOdometry.md) + +otherwise the same data is published to the following topics + +- `external_ins_global_position` +- `external_ins_attitude` +- `external_ins_local_position` + +:::tip +Опубліковані теми можна переглянути за допомогою команди `listener`. +::: diff --git a/docs/uk/sim_gazebo_gz/index.md b/docs/uk/sim_gazebo_gz/index.md index 01fbe74cbe..a05e18c158 100644 --- a/docs/uk/sim_gazebo_gz/index.md +++ b/docs/uk/sim_gazebo_gz/index.md @@ -20,6 +20,8 @@ See [Simulation](../simulation/index.md) for general information about simulator Gazebo Harmonic is installed by default on Ubuntu 22.04 as part of the normal [development environment setup](../dev_setup/dev_env_linux_ubuntu.md#simulation-and-nuttx-pixhawk-targets). +Gazebo versions Harmonic, Ionic, and Jetty are supported on Ubuntu 24.04. The latest installed Gazebo release is used by default. + :::info The PX4 installation scripts are based on the instructions: [Binary Installation on Ubuntu](https://gazebosim.org/docs/harmonic/install_ubuntu/) (gazebosim.org). ::: @@ -48,22 +50,23 @@ make px4_sitl gz_x500 The supported vehicles and `make` commands are listed below. Note that all gazebo make targets have the prefix `gz_`. -| Транспортний засіб | Команда | `PX4_SYS_AUTOSTART` | -| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------- | ------------------- | -| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4001 | -| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | -| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | -| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | -| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | -| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | -| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | -| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | -| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | -| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | -| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_r1_rover` | 4009 | -| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 4012 | -| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | -| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| Транспортний засіб | Команда | `PX4_SYS_AUTOSTART` | +| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------- | ------------------- | +| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4001 | +| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | +| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | +| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | +| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | +| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | +| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | +| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | +| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | +| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | +| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | +| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_rover_differential` | 50000 | +| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 51000 | +| [Mecanum Rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) | `make px4_sitl gz_rover_mecanum` | 52000 | All [vehicle models](../sim_gazebo_gz/vehicles.md) (and [worlds](#specify-world)) are included as a submodule from the [Gazebo Models Repository](../sim_gazebo_gz/gazebo_models.md) repository. diff --git a/docs/uk/sim_gazebo_gz/vehicles.md b/docs/uk/sim_gazebo_gz/vehicles.md index 25a52f2447..1660045bed 100644 --- a/docs/uk/sim_gazebo_gz/vehicles.md +++ b/docs/uk/sim_gazebo_gz/vehicles.md @@ -185,7 +185,7 @@ make px4_sitl gz_tiltrotor [Differential Rover](../frames_rover/index.md#differential) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. ```sh -make px4_sitl gz_r1_rover +make px4_sitl gz_rover_differential ``` ![Differential Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_differential.png) @@ -199,3 +199,13 @@ make px4_sitl gz_rover_ackermann ``` ![Ackermann Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_ackermann.png) + +### Mecanum Rover + +[Mecanum Rover](../frames_rover/index.md#mecanum) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. + +```sh +make px4_sitl gz_rover_mecanum +``` + +![Mecanum Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_mecanum.png) diff --git a/docs/uk/test_and_ci/test_flights.md b/docs/uk/test_and_ci/test_flights.md index 6771beac6e..103549e361 100644 --- a/docs/uk/test_and_ci/test_flights.md +++ b/docs/uk/test_and_ci/test_flights.md @@ -28,5 +28,7 @@ When submitting [Pull Requests](../contribute/code.md#pull-requests) for new fun - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) -- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_07 - Optical Flow Low Mount](../test_cards/mc_07_optical_flow_low_mount.md) - [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) +- [MC_09 - VIO (Visual-Inertial Odometry)](../test_cards/mc_09_vio.md) +- [MC_10 - Optical Flow / GPS Mixed](../test_cards/mc_10_optical_flow_gps_mixed.md) diff --git a/docs/uk/test_cards/mc_06_optical_flow.md b/docs/uk/test_cards/mc_06_optical_flow.md index 6a10870404..3ade1bd015 100644 --- a/docs/uk/test_cards/mc_06_optical_flow.md +++ b/docs/uk/test_cards/mc_06_optical_flow.md @@ -2,25 +2,23 @@ ## Objective -To test that optical flow works as expected +Test that optical flow works as expected ## Preflight -Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation -([Setup Information here](../sensor/optical_flow.md)) +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation ([setup information here](../sensor/optical_flow.md)) -Ensure there are no other sources of positioning besides optical flow +Ensure there are no other sources of positioning besides optical flow: - [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` - [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` - [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` -- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into Altitude / Position mode while still on the ground ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -28,7 +26,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -38,6 +36,16 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates +❏ Varying height terrain + +    ❏ Put boxes on the ground to create varying heights in terrain + +    ❏ Take off in position mode and fly over the boxes such that the downward facing rangefinder varies in value + +    ❏ Do a few passes with varying amounts of time over the boxes (1-30 seconds if possible) + +    ❏ Drone should not raise in height when flying over boxes + ## Посадка ❏ Land in either Position or Altitude mode with the throttle below 40% @@ -47,7 +55,8 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## Очікувані результати - Зліт повинен бути плавним, коли газ піднято -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering (over surface with many features) +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - Немає коливання в жодному з перерахованих режимів польоту +- Drone should not raise in height when flying over boxes - Після посадки, коптер не повинен підскакувати на землі diff --git a/docs/uk/test_cards/mc_07_optical_flow_low_mount.md b/docs/uk/test_cards/mc_07_optical_flow_low_mount.md new file mode 100644 index 0000000000..1679a2c8d4 --- /dev/null +++ b/docs/uk/test_cards/mc_07_optical_flow_low_mount.md @@ -0,0 +1,45 @@ +# Test MC_07 - Optical Flow Low Sensor + +## Objective + +Test that optical flow works as expected with a low mounted optical flow sensor + +## Preflight + +Ensure that the drone's optical flow sensor is mounted more than an inch off of the ground + +Ensure that [MPC_THR_MIN](../advanced_config/parameter_reference.md#MPC_THR_MIN) is tuned correctly for landing + +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` + +Ensure that the drone can go into [Position mode](../flight_modes_mc/position.md) while still on the ground + +## Flight Tests + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## Посадка + +❏ Land in Position mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## Очікувані результати + +- Зліт повинен бути плавним, коли газ піднято +- Drone should stay in Position mode, NOT fall into [altitude](../flight_modes_mc/altitude.md) mode diff --git a/docs/uk/test_cards/mc_08_dshot.md b/docs/uk/test_cards/mc_08_dshot.md index 422482bbc9..148534cae8 100644 --- a/docs/uk/test_cards/mc_08_dshot.md +++ b/docs/uk/test_cards/mc_08_dshot.md @@ -6,22 +6,22 @@ Regression test for DSHOT working with PX4 ## Preflight -- Ensure vehicle is using a DSHOT ESC. +- Ensure vehicle is using a DSHOT ESC - Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled - Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) - Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked ## Flight Tests -❏ Stabilized Flight mode +❏ [Stabilized mode](../flight_modes_mc/manual_stabilized.md) -    ❏ Takeoff in stabilized flight mode to ensure correct motor spin +    ❏ Takeoff in stabilized mode to ensure correct motor spin     ❏ Pitch/Roll/Yaw response 1:1     ❏ Throttle response 1:1 -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -41,6 +41,6 @@ Regression test for DSHOT working with PX4 - Download flight logs - Load into Data Plot Juggler -- Ensure data is logged for esc_status/esc.0x/esc_rpm +- Ensure data is logged for `esc_status`/`esc.0x`/`esc_rpm` ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/uk/test_cards/mc_09_vio.md b/docs/uk/test_cards/mc_09_vio.md new file mode 100644 index 0000000000..29ab4a0253 --- /dev/null +++ b/docs/uk/test_cards/mc_09_vio.md @@ -0,0 +1,52 @@ +# Test MC_09 - VIO (Visual-Inertial Odometry) + +## Objective + +Test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## Посадка + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## Очікувані результати + +- Зліт повинен бути плавним, коли газ піднято +- Drone should hold altitude in Altitude mode without wandering +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Немає коливання в жодному з перерахованих режимів польоту +- Після посадки, коптер не повинен підскакувати на землі diff --git a/docs/uk/test_cards/mc_10_optical_flow_gps_mixed.md b/docs/uk/test_cards/mc_10_optical_flow_gps_mixed.md new file mode 100644 index 0000000000..a1a165e322 --- /dev/null +++ b/docs/uk/test_cards/mc_10_optical_flow_gps_mixed.md @@ -0,0 +1,74 @@ +# Test MC_10 - Optical Flow / GPS Mixed + +## Objective + +Test that optical flow mixed with GPS works as expected + +## Preflight + +[Setup optical flow and GPS](../sensor/optical_flow.md) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `7` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `1` +- [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF): `1` (GPS) + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +❏ GPS Cutout + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Open QGC and navigate to MAVLink Console + +    ❏ Type `gps off` to disable GPS + +    ❏ Drone should maintain position hold via optical flow + +❏ GPS Degredation + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Fly under a metal surface (or other GPS blocking structure) + +    ❏ Ensure drone does not lose position hold or start drifting + +    ❏ Fly out of metal structure to regain GPS + +❏ GPS Acquisition + +    ❏ Takeoff in position mode in non-GPS environment + +    ❏ Fly into a GPS rich environment (outdoors) + +    ❏ Ensure drone acquires GPS position + +## Очікувані результати + +- Зліт повинен бути плавним, коли газ піднято +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Drone should hold position in GPS rich environment as well as non-GPS environment +- Немає коливання в жодному з перерахованих режимів польоту diff --git a/docs/yarn.lock b/docs/yarn.lock index 28f60812e2..4f5e5541de 100644 --- a/docs/yarn.lock +++ b/docs/yarn.lock @@ -1643,9 +1643,9 @@ vfile@^6.0.0: vfile-message "^4.0.0" vite@^5.4.14: - version "5.4.19" - resolved "https://registry.yarnpkg.com/vite/-/vite-5.4.19.tgz#20efd060410044b3ed555049418a5e7d1998f959" - integrity sha512-qO3aKv3HoQC8QKiNSTuUM1l9o/XX3+c+VTgLHbJWHZGeTPVAg2XwazI9UWzoxjIJCGCV2zU60uqMzjeLZuULqA== + version "5.4.21" + resolved "https://registry.yarnpkg.com/vite/-/vite-5.4.21.tgz#84a4f7c5d860b071676d39ba513c0d598fdc7027" + integrity sha512-o5a9xKjbtuhY6Bi5S3+HvbRERmouabWbyUcpXXUA1u+GNUKoROi9byOJ8M0nHbHYHkYICiMlqxkg1KkYmm25Sw== dependencies: esbuild "^0.21.3" postcss "^8.4.43" diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index cbe5e1a28b..44eb72121e 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -286,6 +286,7 @@ - [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](sensor/inertial_navigation_systems.md) - [InertialLabs](sensor/inertiallabs.md) + - [MicroStrain](sensor/microstrain.md) - [sbgECom](sensor/sbgecom.md) - [VectorNav](sensor/vectornav.md) - [光流](sensor/optical_flow.md) @@ -436,6 +437,7 @@ - [Attitude Tuning](config_rover/attitude_tuning.md) - [Velocity Tuning](config_rover/velocity_tuning.md) - [Position Tuning](config_rover/position_tuning.md) + - [Apps & API](flight_modes_rover/api.md) - [Complete Vehicles](complete_vehicles_rover/index.md) - [Aion Robotics R1](complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](frames_sub/index.md) @@ -700,6 +702,7 @@ - [SensorCombined](msg_docs/SensorCombined.md) - [SensorCorrection](msg_docs/SensorCorrection.md) - [SensorGnssRelative](msg_docs/SensorGnssRelative.md) + - [SensorGnssStatus](msg_docs/SensorGnssStatus.md) - [SensorGps](msg_docs/SensorGps.md) - [SensorGyro](msg_docs/SensorGyro.md) - [SensorGyroFft](msg_docs/SensorGyroFft.md) @@ -761,6 +764,7 @@ - [Standard Modes Protocol](mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md) - [UORB Bridged to ROS 2](middleware/dds_topics.md) + - [Zenoh (PX4 ROS 2)](middleware/zenoh.md) - [模块 & 命令](modules/modules_main.md) - [自动调参](modules/modules_autotune.md) - [命令](modules/modules_command.md) @@ -850,8 +854,10 @@ - [测试 MC_04 -故障安全测试](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](test_cards/mc_10_optical_flow_gps_mixed.md) - [单元测试](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [持续集成](test_and_ci/continous_integration.md) @@ -872,6 +878,7 @@ - [PX4 ROS 2 Interface Library](ros2/px4_ros2_interface_lib.md) - [Control Interface](ros2/px4_ros2_control_interface.md) - [Navigation Interface](ros2/px4_ros2_navigation_interface.md) + - [Waypoint Missions](ros2/px4_ros2_waypoint_missions.md) - [ROS 2 Message Translation Node](ros2/px4_ros2_msg_translation_node.md) - [ROS 1 (Deprecated)](ros/ros1.md) - [ROS/MAVROS安装指南](ros/mavros_installation.md) diff --git a/docs/zh/_sidebar.md b/docs/zh/_sidebar.md index d95b8103d5..cb4c6eba8e 100644 --- a/docs/zh/_sidebar.md +++ b/docs/zh/_sidebar.md @@ -8,6 +8,7 @@ - [位置模式(多旋翼)](/flight_modes_mc/position.md) - [Position Slow Mode (MC)](/flight_modes_mc/position_slow.md) - [高度模式(多旋翼)](/flight_modes_mc/altitude.md) + - [Altitude Cruise Mode (MC)](/flight_modes_mc/altitude_cruise.md) - [Stabilized Mode (MC)](/flight_modes_mc/manual_stabilized.md) - [特技模式(多旋翼)](/flight_modes_mc/acro.md) - [环绕模式(多旋翼)](/flight_modes_mc/orbit.md) @@ -158,6 +159,7 @@ - [mRo (3DR) Pixhawk Wiring Quickstart](/assembly/quick_start_pixhawk.md) - [Holybro Pixhawk Mini (FMUv3) - Discontinued](/flight_controller/pixhawk_mini.md) - [Manufacturer-Supported Autopilots](/flight_controller/autopilot_manufacturer_supported.md) + - [Accton Godwit GA1](/flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](/flight_controller/mindpx.md) - [AirMind MindRacer](/flight_controller/mindracer.md) - [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md) @@ -183,6 +185,7 @@ - [Wiring Quickstart](/assembly/quick_start_holybro_pix32_v5.md) - [ModalAI VOXL 2](/flight_controller/modalai_voxl_2.md) - [mRo Control Zero F7](/flight_controller/mro_control_zero_f7.md) + - [Radiolink PIX6](/flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](/flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](/flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](/flight_controller/thepeach_k1.md) @@ -284,6 +287,7 @@ - [CubePilot Here+ (Discontined)](/gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](/sensor/inertial_navigation_systems.md) - [InertialLabs](/sensor/inertiallabs.md) + - [sbgECom](/sensor/sbgecom.md) - [VectorNav](/sensor/vectornav.md) - [光流](/sensor/optical_flow.md) - [ARK 光流](/dronecan/ark_flow.md) @@ -433,6 +437,7 @@ - [Attitude Tuning](/config_rover/attitude_tuning.md) - [Velocity Tuning](/config_rover/velocity_tuning.md) - [Position Tuning](/config_rover/position_tuning.md) + - [Apps & API](/flight_modes_rover/api.md) - [Complete Vehicles](/complete_vehicles_rover/index.md) - [Aion Robotics R1](/complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](/frames_sub/index.md) @@ -680,6 +685,8 @@ - [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](/msg_docs/RoverRateStatus.md) + - [RoverSpeedSetpoint](/msg_docs/RoverSpeedSetpoint.md) + - [RoverSpeedStatus](/msg_docs/RoverSpeedStatus.md) - [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md) - [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md) @@ -740,6 +747,7 @@ - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md) - [ArmingCheckReplyV0](/msg_docs/ArmingCheckReplyV0.md) + - [ArmingCheckRequestV0](/msg_docs/ArmingCheckRequestV0.md) - [BatteryStatusV0](/msg_docs/BatteryStatusV0.md) - [EventV0](/msg_docs/EventV0.md) - [HomePositionV0](/msg_docs/HomePositionV0.md) @@ -844,8 +852,10 @@ - [测试 MC_04 -故障安全测试](/test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](/test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](/test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](/test_cards/mc_10_optical_flow_gps_mixed.md) - [单元测试](/test_and_ci/unit_tests.md) - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [持续集成](/test_and_ci/continous_integration.md) @@ -866,6 +876,7 @@ - [PX4 ROS 2 Interface Library](/ros2/px4_ros2_interface_lib.md) - [Control Interface](/ros2/px4_ros2_control_interface.md) - [Navigation Interface](/ros2/px4_ros2_navigation_interface.md) + - [Waypoint Missions](/ros2/px4_ros2_waypoint_missions.md) - [ROS 2 Message Translation Node](/ros2/px4_ros2_msg_translation_node.md) - [ROS 1 (Deprecated)](/ros/ros1.md) - [ROS/MAVROS安装指南](/ros/mavros_installation.md) diff --git a/docs/zh/airframes/airframe_reference.md b/docs/zh/airframes/airframe_reference.md index 1d821bd5ad..940ae6a4be 100644 --- a/docs/zh/airframes/airframe_reference.md +++ b/docs/zh/airframes/airframe_reference.md @@ -615,6 +615,10 @@ div.frame_variant td, div.frame_variant th { Axial SCX10 2 Trail Honcho Maintainer: John Doe <john@example.com>

SYS_AUTOSTART = 51001

+ + NXP B3RB Rover Ackermann + Maintainer: John Doe <john@example.com>

SYS_AUTOSTART = 51002

+ Generic Rover Mecanum Maintainer: John Doe <john@example.com>

SYS_AUTOSTART = 52000

diff --git a/docs/zh/companion_computer/pixhawk_rpi.md b/docs/zh/companion_computer/pixhawk_rpi.md index beb8a1f7fe..73406d2a8d 100644 --- a/docs/zh/companion_computer/pixhawk_rpi.md +++ b/docs/zh/companion_computer/pixhawk_rpi.md @@ -266,7 +266,7 @@ The configuration steps are: ``` [MAV_1_CONFIG=0](../advanced_config/parameter_reference.md#MAV_1_CONFIG) and [UXRCE_DDS_CFG=102](../advanced_config/parameter_reference.md#UXRCE_DDS_CFG) disable MAVLink on TELEM2 and enable the uXRCE-DDS client on TELEM2, respectively. - The `SER_TEL2_BAUD` rate sets the comms link data rate.\ + The `SER_TEL2_BAUD` rate sets the comms link data rate. You could similarly configure a connection to `TELEM1` using either `MAV_1_CONFIG` or `MAV_0_CONFIG`. ::: info diff --git a/docs/zh/concept/system_startup.md b/docs/zh/concept/system_startup.md index 3986658e97..28456ce738 100644 --- a/docs/zh/concept/system_startup.md +++ b/docs/zh/concept/system_startup.md @@ -1,7 +1,7 @@ # 系统启动 PX4 系统的启动由 shell 脚本文件控制。 -On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/MacOS). +On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/macOS). The scripts that are only used on Posix are located in [ROMFS/px4fmu_common/init.d-posix](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d-posix). All files starting with a number and underscore (e.g. `10000_airplane`) are predefined airframe configurations. @@ -13,7 +13,7 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot 根据 PX4 运行的操作系统将本文后续内容分成了如下各小节。 -## POSIX (Linux/MacOS) +## POSIX (Linux/macOS) On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). 为了使 PX4 可以在 Posix 中正常运行,需要做到以下几点: diff --git a/docs/zh/config/_autotune.md b/docs/zh/config/_autotune.md index 8c5df070ae..6a75da6380 100644 --- a/docs/zh/config/_autotune.md +++ b/docs/zh/config/_autotune.md @@ -95,9 +95,17 @@ The test steps are: 4. Read the warning popup and click on **OK** to start tuning. +
+ 4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. The progress is shown in the progress bar, next to the _Autotune_ button. +
+ +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + The progress is shown in the progress bar, next to the _Autotune_ button. + +
5. Manually land and disarm to apply the new tuning parameters. @@ -108,6 +116,13 @@ The test steps are: 5. The tuning will be immediately/automatically be applied and tested in flight (by default). PX4 will then run a 4 second test and revert the new tuning if a problem is detected. +The figure below shows how steps 4 and 5 might look in flight on the pitch axis. +The pitch rate gradually increases up until it reaches the target. +This amplitude is then held while the signal frequency is increased. +You can then see how the tuned system is able to follow the setpoint in the test signal. + + +
:::warning @@ -174,9 +189,20 @@ Fast oscillations (more than 1 oscillation per second): this is because the gain ### The auto-tuning sequence fails +
+ If the drone was not moving enough during auto-tuning, the system identification algorithm might have issues to find the correct coefficients. -Increase the
[MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP)
[FW_AT_SYSID_AMP](../advanced_config/parameter_reference.md#FW_AT_SYSID_AMP)
parameter by steps of 1 and trigger the auto-tune again. +Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP) parameter by steps of 1 and trigger the auto-tune again. + +
+
+ +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + +If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. + +
### The drone oscillates after auto-tuning diff --git a/docs/zh/config/safety.md b/docs/zh/config/safety.md index 4fcba64ce9..6929365518 100644 --- a/docs/zh/config/safety.md +++ b/docs/zh/config/safety.md @@ -276,12 +276,12 @@ The relevant parameters are listed in the table below. ## 故障检测器 -The failure detector allows a vehicle to take protective action(s) if it unexpectedly flips, or if it is notified by an external failure detection system. +The failure detector allows a vehicle to take protective actions if it unexpectedly flips, detects a motor failure, or if it is notified by an external failure detection system. During **flight**, the failure detector can be used to trigger [flight termination](../advanced_config/flight_termination.md) if failure conditions are met, which may then launch a [parachute](../peripherals/parachute.md) or perform some other action. :::info -Failure detection during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). +Acting on a detected failure during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). ::: During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions). @@ -303,6 +303,26 @@ The relevant parameters are shown below: | [FD_FAIL_P_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_P_TTRI) | Time to exceed [FD_FAIL_P](#FD_FAIL_P) for failure detection (default 0.3s). | | [FD_FAIL_R_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_R_TTRI) | Time to exceed [FD_FAIL_R](#FD_FAIL_R) for failure detection (default 0.3s). | +### Motor Failure Trigger + +The failure detector can be configured to detect a motor failure while armed (and trigger an associated action) in the following conditions: + +- A 300 ms timeout occurs in telemetry from an ESC that was previously available. +- The input current in the telemetry of an ESC which was previously positive gets too low for more than [`FD_ACT_MOT_TOUT`](FD_ACT_MOT_TOUT) ms. + The "too low" condition is defined by: + + ```text + {esc current} < {parameter FD_ACT_MOT_C2T} * {motor command between 0 and 1} + ``` + +| 参数 | 描述 | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [FD_ACT_EN](../advanced_config/parameter_reference.md#FD_ACT_EN) | Enable/disable the motor failure trigger completely. | +| [FD_ACT_MOT_THR](../advanced_config/parameter_reference.md#FD_ACT_MOT_THR) | Minimum normalized [0,1] motor command below which motor under current is ignored. | +| [FD_ACT_MOT_C2T](../advanced_config/parameter_reference.md#FD_ACT_MOT_C2T) | Scale between normalized [0,1] motor command and expected minimally reported currrent when the rotor is healthy. | +| [FD_ACT_MOT_TOUT](../advanced_config/parameter_reference.md#FD_ACT_MOT_TOUT) | Time in miliseconds for which the under current detection condition needs to stay true. | +| [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) | Configure to not only warn about a motor failure but remove the first motor that detects a failure from the allocation effectiveness which turns off the motor and tries to operate the vehicle without it until disarming the next time. | + ### 外部自动触发系统(ATS) The [failure detector](#failure-detector), if [enabled](#CBRK_FLIGHTTERM), can also be triggered by an external ATS system. diff --git a/docs/zh/debug/failure_injection.md b/docs/zh/debug/failure_injection.md index e013753243..f6889c2bb6 100644 --- a/docs/zh/debug/failure_injection.md +++ b/docs/zh/debug/failure_injection.md @@ -9,7 +9,7 @@ Failure injection is disabled by default, and can be enabled using the [SYS_FAIL Failure injection still in development. At time of writing (PX4 v1.14): -- It can only be used in simulation (support for both failure injection in real flight is planned). +- Support may vary by failure type and between simulatiors and real vehicle. - It requires support in the simulator. It is supported in Gazebo Classic - Many failure types are not broadly implemented. @@ -19,7 +19,7 @@ At time of writing (PX4 v1.14): ## Failure System Command -Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 console/shell, specifying both the target and type of the failure. +Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 [console/shell](../debug/consoles.md) (such as the [QGC MAVLink Console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) or SITL _pxh shell_), specifying both the target and type of the failure. ### Syntax @@ -33,39 +33,46 @@ where: - _component_: - 传感器: - - `gyro`: Gyro. - - `accel`: Accelerometer. + - `gyro`: Gyroscope + - `accel`: Accelerometer - `mag`: Magnetometer - `baro`: Barometer - - `gps`: GPS + - `gps`: Global navigation satellite system - `optical_flow`: Optical flow. - - `vio`: Visual inertial odometry. + - `vio`: Visual inertial odometry - `distance_sensor`: Distance sensor (rangefinder). - - `airspeed`: Airspeed sensor. + - `airspeed`: Airspeed sensor - Systems: - - `battery`: Battery. - - `motor`: Motor. - - `servo`: Servo. - - `avoidance`: Avoidance. - - `rc_signal`: RC Signal. - - `mavlink_signal`: MAVLink signal (data telemetry). + - `battery`: Battery + - `motor`: Motor + - `servo`: Servo + - `avoidance`: Avoidance + - `rc_signal`: RC Signal + - `mavlink_signal`: MAVLink data telemetry connection - _failure_type_: - - `ok`: Publish as normal (Disable failure injection). - - `off`: Stop publishing. - - `stuck`: Report same value every time (_could_ indicate a malfunctioning sensor). - - `garbage`: Publish random noise. This looks like reading uninitialized memory. - - `wrong`: Publish invalid values (that still look reasonable/aren't "garbage"). - - `slow`: Publish at a reduced rate. - - `delayed`: Publish valid data with a significant delay. - - `intermittent`: Publish intermittently. + - `ok`: Publish as normal (Disable failure injection) + - `off`: Stop publishing + - `stuck`: Constantly report the same value which _can_ happen on a malfunctioning sensor + - `garbage`: Publish random noise. This looks like reading uninitialized memory + - `wrong`: Publish invalid values that still look reasonable/aren't "garbage" + - `slow`: Publish at a reduced rate + - `delayed`: Publish valid data with a significant delay + - `intermittent`: Publish intermittently - _instance number_ (optional): Instance number of affected sensor. 0 (default) indicates all sensors of specified type. -### Example +## MAVSDK Failure Plugin + +The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. +It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). + +The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection. + +## Example: RC signal To simulate losing RC signal without having to turn off your RC controller: -1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. 2. Enter the following commands on the MAVLink console or SITL _pxh shell_: ```sh @@ -76,9 +83,18 @@ To simulate losing RC signal without having to turn off your RC controller: failure rc_signal ok ``` -## MAVSDK Failure Plugin +## Example: Motor -The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. -It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). +To stop a motor mid-flight without the system anticipating it or excluding it from allocation effectiveness: -The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection. +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. +2. Enable [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) parameter to allow turning off motors. +3. Enter the following commands on the MAVLink console or SITL _pxh shell_: + + ```sh + # Turn off first motor + failure motor off -i 1 + + # Turn it back on + failure motor ok -i 1 + ``` diff --git a/docs/zh/dev_log/logging.md b/docs/zh/dev_log/logging.md index cfc8cc19a8..05ed21e709 100644 --- a/docs/zh/dev_log/logging.md +++ b/docs/zh/dev_log/logging.md @@ -161,7 +161,7 @@ There are different clients that support ulog streaming: - If log streaming does not start, make sure the `logger` is running (see above), and inspect the console output while starting. - If it still does not work, make sure that Mavlink 2 is used. Enforce it by setting MAV_PROTO_VER to 2. - Enforce it by setting `MAV_PROTO_VER` to 2. + `MAV_PROTO_VER` needs to be set to 2. - Log streaming uses a maximum of 70% of the configured MAVLink rate (`-r` parameter). 如果需要更大的速率,数据会丢失。 The currently used percentage can be inspected with `mavlink status` (1.8% is used in this example): diff --git a/docs/zh/dev_log/ulog_file_format.md b/docs/zh/dev_log/ulog_file_format.md index 177ebdfff4..80c4b720b9 100644 --- a/docs/zh/dev_log/ulog_file_format.md +++ b/docs/zh/dev_log/ulog_file_format.md @@ -502,6 +502,7 @@ Since the Definitions and Data Sections use the same message header format, they - [ulogreader](https://github.com/maxsun/ulogreader): Javascript, ULog reader and parser outputs log in JSON object format. - [Foxglove](https://foxglove.dev): an integrated visualization and diagnosis tool for robotics data that supports ULog files. - [TypeScript ULog parser](https://github.com/foxglove/ulog): TypeScript, ULog reader that outputs JS objects. +- [yule_log](https://crates.io/crates/yule_log): A streaming ULog parser written in Rust. ## 文件格式版本历史 diff --git a/docs/zh/dev_setup/dev_env.md b/docs/zh/dev_setup/dev_env.md index fadf7c8dca..b53b801540 100644 --- a/docs/zh/dev_setup/dev_env.md +++ b/docs/zh/dev_setup/dev_env.md @@ -2,15 +2,15 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (22.04/20.04/18.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 -- [Mac OS](../dev_setup/dev_env_mac.md) +- [macOS](../dev_setup/dev_env_mac.md) ## 支持的编译目标 下表显示了您可以在每个操作系统上构建何种 PX平台的固件编译。 -| 平台 | Linux (Ubuntu) | Mac | Windows | +| 平台 | Linux (Ubuntu) | macOS | Windows | | ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :-------------------------: | :-------------------------: | | **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | | **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | diff --git a/docs/zh/dev_setup/dev_env_mac.md b/docs/zh/dev_setup/dev_env_mac.md index 8d1b5a0c74..4c52a89da8 100644 --- a/docs/zh/dev_setup/dev_env_mac.md +++ b/docs/zh/dev_setup/dev_env_mac.md @@ -1,4 +1,4 @@ -# Mac 上的开发环境 +# macOS Development Environment MacOS 是受支持的 PX4 开发平台。 根据本文的指示构建的开发环境可以用编译: @@ -22,8 +22,8 @@ The "base" macOS setup installs the tools needed for building firmware, and incl ### Environment Setup :::details -Apple Silicon Macbook users! -If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 by setting up an x86 terminal: +Apple Silicon MacBook users! +If you have an Apple M1, M2 etc. MacBook, make sure to run the terminal as x86 by setting up an x86 terminal: 1. Locate the Terminal application within the Utilities folder (**Finder > Go menu > Utilities**) 2. Select _Terminal.app_ and right-click on it, then choose **Duplicate**. @@ -50,7 +50,7 @@ First set up the environment 2. Enforce Python 3 by appending the following lines to `~/.zshenv` ```sh - # Point pip3 to MacOS system python 3 pip + # Point pip3 to macOS system python 3 pip alias pip3=/usr/bin/pip3 ``` diff --git a/docs/zh/dronecan/ark_cannode.md b/docs/zh/dronecan/ark_cannode.md index 57cf74e5d4..994405ef9b 100644 --- a/docs/zh/dronecan/ark_cannode.md +++ b/docs/zh/dronecan/ark_cannode.md @@ -83,9 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter On the ARK CANnode, you may need to configure the following parameters: -| 参数 | 描述 | -| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED含义 diff --git a/docs/zh/dronecan/ark_flow.md b/docs/zh/dronecan/ark_flow.md index 84a6d8def2..50af8e5c9f 100644 --- a/docs/zh/dronecan/ark_flow.md +++ b/docs/zh/dronecan/ark_flow.md @@ -109,9 +109,10 @@ When optical flow is the only source of horizontal position/velocity, then lower On the ARK Flow, you may need to configure the following parameters: -| 参数 | 描述 | -| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED含义 diff --git a/docs/zh/dronecan/ark_flow_mr.md b/docs/zh/dronecan/ark_flow_mr.md index a7fa7ebb6f..6ad95d9e73 100644 --- a/docs/zh/dronecan/ark_flow_mr.md +++ b/docs/zh/dronecan/ark_flow_mr.md @@ -104,9 +104,10 @@ Set the following parameters in _QGroundControl_: You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself: -| 参数 | 描述 | -| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED含义 diff --git a/docs/zh/dronecan/ark_gps.md b/docs/zh/dronecan/ark_gps.md index 962760f754..5ffa097d86 100644 --- a/docs/zh/dronecan/ark_gps.md +++ b/docs/zh/dronecan/ark_gps.md @@ -91,9 +91,17 @@ If the sensor is not centred within the vehicle you will also need to define sen - Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true. - Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO). -- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus. - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity. +### ARK GPS Configuration + +You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself: + +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | + ## LED含义 You will see green, blue and red LEDs on the ARK GPS when it is being flashed, and a blinking green LED if it is running properly. diff --git a/docs/zh/dronecan/ark_rtk_gps.md b/docs/zh/dronecan/ark_rtk_gps.md index 75064c1780..a30768e7dd 100644 --- a/docs/zh/dronecan/ark_rtk_gps.md +++ b/docs/zh/dronecan/ark_rtk_gps.md @@ -85,7 +85,15 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked). - Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO). - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity. -- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus. + +### ARK RTK GPS Configuration + +You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself: + +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | ### Setting Up Rover and Fixed Base diff --git a/docs/zh/dronecan/index.md b/docs/zh/dronecan/index.md index 16915394f8..08929caba2 100644 --- a/docs/zh/dronecan/index.md +++ b/docs/zh/dronecan/index.md @@ -102,6 +102,10 @@ If the DNA is still running and certain devices need to be manually configured, :::info The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter. The parameter is set to 1 by default. + +Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the +[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID. +Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID. ::: :::warning @@ -288,6 +292,11 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i ![QGC Parameter showing selected DroneCAN node](../../assets/can/dronecan/qgc_can_parameters.png) +Common CANNODE parameters that you can configure include: + +- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information. +- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus. + ## Device Specific Setup Most DroneCAN nodes require no further setup, unless specifically noted in their device-specific documentation. diff --git a/docs/zh/dronecan/px4_cannode_fw.md b/docs/zh/dronecan/px4_cannode_fw.md index d96ad3e14c..23ce08461b 100644 --- a/docs/zh/dronecan/px4_cannode_fw.md +++ b/docs/zh/dronecan/px4_cannode_fw.md @@ -20,6 +20,26 @@ make ark_can-flow_default This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware. +## 配置 + +### Static Node ID + +By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller. +However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter. + +To configure a static node ID: + +1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration) +2. Reboot the device + +To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0. +Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior). + +:::warning +When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID. +Configuring two devices with the same ID will cause communication conflicts. +::: + ## 开发人员信息 This section has information that is relevant to developers who want to add support for new DroneCAN hardware to the PX4 Autopilot. diff --git a/docs/zh/flight_modes/offboard.md b/docs/zh/flight_modes/offboard.md index 63e474ed76..9560407f2c 100644 --- a/docs/zh/flight_modes/offboard.md +++ b/docs/zh/flight_modes/offboard.md @@ -62,6 +62,11 @@ bool thrust_and_torque bool direct_actuator ``` +:::warning +The following list shows the `OffboardControlMode` options for copter, fixed-wing, and VTOL. +For rovers see the [rover section](#rover). +::: + The fields are ordered in terms of priority such that `position` takes precedence over `velocity` and later fields, `velocity` takes precedence over `acceleration`, and so on. 第一个非零字段(从上到下) 定义了Offboard模式所需的有效估计以及可用的设定值消息。 For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `velocity estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message. @@ -90,20 +95,93 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values acceleration are used as feedforward terms for the inner loop controllers. - Acceleration setpoint (`acceleration` different from `NaN` and `position` and `velocity` set to `NaN`) - - 所有值都是基于NED(北, 东, 地)坐标系,位置、速度和加速的单位分别为\[m\], \[m/s\] 和\[m/s^2\] 。 + - All values are interpreted in NED (Nord, East, Down) coordinate system and the units are `[m]`, `[m/s]` and `[m/s^2]` for position, velocity and acceleration, respectively. - [px4_msgs::msg::VehicleAttitudeSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) - 支持以下输入组合: - quaternion `q_d` + thrust setpoint `thrust_body`. - Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in \[rad/s\]. + Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in `[rad/s]`. - - 姿态四元数表示无人机机体坐标系FRD(前、右、下) 与NED坐标系之间的旋转。 这个推力是在无人机体轴FRD坐标系下,并归一化为 \[-1, 1\] 。 + - 姿态四元数表示无人机机体坐标系FRD(前、右、下) 与NED坐标系之间的旋转。 + 这个推力是在无人机体轴FRD坐标系下,并归一化为 \[-1, 1\] 。 - [px4_msgs::msg::VehicleRatesSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleRatesSetpoint.msg) - 支持以下输入组合: - `roll`, `pitch`, `yaw` and `thrust_body`. - - 所有值都表示在无人机体轴FRD坐标系下。 角速率(roll, pitch, yaw) 单位为\[rad/s\] ,thrust_body归一化为 \[-1, 1\]。 + - 所有值都表示在无人机体轴FRD坐标系下。 + The rates are in `[rad/s]` while thrust_body is normalized in `[-1, 1]`. + +### 无人车 + +Rover modules must set the control mode using `OffboardControlMode` and use the appropriate messages to configure the corresponding setpoints. +The approach is similar to other vehicle types, but the allowed control mode combinations and setpoints are different: + +| Category | 用法 | Setpoints | +| -------------------------------------------------------------------------------------- | ----------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| (Recommended) [Rover Setpoints](#rover-setpoints) | General rover control | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md), [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md), [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md), [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md), [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md), [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) | +| [Actuator Setpoints](#actuator-setpoints) | Direct actuator control | [ActuatorMotors](../msg_docs/ActuatorMotors.md), [ActuatorServos](../msg_docs/ActuatorServos.md) | +| (Deprecated) [Trajectory Setpoint](#deprecated-trajectory-setpoint) | General vehicle control | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | + +#### Rover 设置点 + +滚动模块使用层次结构来传播设置点: + +![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg) + +The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (overriding them!). +这个层次结构有提供有效控制输入的明确规则: + +- Provide a position setpoint **or** +- “左”上的设置点之一(速度 **或** 节点) **和** “右”上的设置点之一(态度、速率 **或** 节点)。 + 所有“左”和“右”设置点的组合都是有效的。 + +The following are all valid setpoint combinations and their respective control flags that must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md) (set all others to _false_). +Additionally, for some combinations we require certain setpoints to be published with `NAN` values so that the setpoints of interest are not overridden by the rover module (due to the hierarchy above). +✓ are the relevant setpoints we publish, and ✗ are the setpoint that need to be published with `NAN` values. + +| Setpoint Combination | Control Flag | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md) | [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md) | [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) | [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md) | [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md) | [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) | +| -------------------- | ----------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------------- | ----------------------------------------------------- | ------------------------------------------------------------- | +| 安装位置 | 位置 | ✓ | | | | | | +| Speed + Attitude | 速度 | | ✓ | | ✓ | | | +| Speed + Rate | 速度 | | ✓ | | ✗ | ✓ | | +| Speed + Steering | 速度 | | ✓ | | ✗ | ✗ | ✓ | +| Throttle + Attitude | attitude | | | ✓ | ✓ | | | +| Throttle + Rate | body_rate | | | ✓ | | ✓ | | +| Throttle + Steering | thrust_and_torque | | | ✓ | | | ✓ | + +:::info +If you intend to use the rover setpoints, we recommend using the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) instead since it simplifies the publishing of these setpoints. +::: + +#### Actuator Setpoints + +Instead of controlling the vehicle using position, speed, rate and other setpoints, you can directly control the motors and actuators using [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md). +In [OffboardControlMode](../msg_docs/OffboardControlMode.md) set `direct_actuator` to _true_ and all other flags to _false_. + +:::info +This bypasses the rover modules including any limits on steering rates or accelerations and the inverse kinematics step. +We recommend using [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) and [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) instead for low level control (see [Rover Setpoints](#rover-setpoints)). +::: + +#### (Deprecated) Trajectory Setpoint + +:::warning +The [Rover Setpoints](#rover-setpoints) are a replacement for the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) and we highly recommend using those instead as they have a well defined behaviour and offer more flexibility. +::: + +The rover modules support the _position_, _velocity_ and _yaw_ fields of the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md). +However, only one of the fields is active at a time and is defined by the flags of [OffboardControlMode](../msg_docs/OffboardControlMode.md): + +| Control Mode Flag | Active Trajectory Setpoint Field | +| ----------------- | -------------------------------- | +| 位置 | 位置 | +| 速度 | 速度 | +| attitude | yaw | + +:::info +Ackermann rovers do not support the yaw setpoint. +::: ### Generic Vehicle @@ -116,8 +194,10 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - [px4_msgs::msg::ActuatorMotors](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) + [px4_msgs::msg::ActuatorServos](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg) - 直接控制电机输出和/或伺服系统(舵机)输出。 - - Currently works at lower level than then `control_allocator` module. Do not publish these messages when not in offboard mode. - - 所有值归一化为\[-1, 1\]。 For outputs that do not support negative values, negative entries map to `NaN`. + - Currently works at lower level than then `control_allocator` module. + Do not publish these messages when not in offboard mode. + - All the values normalized in `[-1, 1]`. + For outputs that do not support negative values, negative entries map to `NaN`. - `NaN` maps to disarmed. ## MAVLink 消息 @@ -207,41 +287,7 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding ### 无人车 -- [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `x`, `y`, `z`) - - Specify the _type_ of the setpoint in `type_mask`: - - ::: info - The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. - :: - - 值为: - - - 12288:悬停设定值(无人机足够接近设定值时会停止)。 - - - Velocity setpoint (only `vx`, `vy`, `vz`) - - - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) and [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED). - -- [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `lat_int`, `lon_int`, `alt`) - - - Specify the _type_ of the setpoint in `type_mask` (not part of the MAVLink standard). - 值为: - - 下面的比特位没有置位,是正常表现。 - - 12288:悬停设定值(无人机足够接近设定值时会停止)。 - - - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_GLOBAL](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL). - -- [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) - - 支持以下输入组合: - - Attitude/orientation (`SET_ATTITUDE_TARGET.q`) with thrust setpoint (`SET_ATTITUDE_TARGET.thrust`). - ::: info - Only the yaw setting is actually used/extracted. - -::: +Rover does not support a MAVLink offboard API (ROS2 is supported). ## Offboard参数 diff --git a/docs/zh/flight_modes_mc/altitude.md b/docs/zh/flight_modes_mc/altitude.md index e7ce6d130e..4ff9b639e8 100644 --- a/docs/zh/flight_modes_mc/altitude.md +++ b/docs/zh/flight_modes_mc/altitude.md @@ -43,9 +43,8 @@ The horizontal position of the vehicle can move due to wind (or pre-existing mom 该模式受以下参数影响: -| 参数 | 描述 | -| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | 最大垂直上升速度。 默认:3m/s。 | -| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 最大垂直下降速度。 默认:1m/s。 | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | -| `MPC_XXXX` | 大多数 MPC_xxx参数会影响此模式下的飞行行为(至少在某种程度上)。 For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | +| 参数 | 描述 | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | 最大垂直上升速度。 默认:3m/s。 | +| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 最大垂直下降速度。 默认:1m/s。 | +| `MPC_XXXX` | 大多数 MPC_xxx参数会影响此模式下的飞行行为(至少在某种程度上)。 For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | diff --git a/docs/zh/flight_modes_mc/position.md b/docs/zh/flight_modes_mc/position.md index b35ce39d7b..023c8b95b8 100644 --- a/docs/zh/flight_modes_mc/position.md +++ b/docs/zh/flight_modes_mc/position.md @@ -67,7 +67,6 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 最大垂直下降速度。 默认:1m/s。 | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | 触发第一阶段降速的高度。 Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | | [MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | 触发第二阶段降速的高度。 Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Value needs to be lower than "MPC_LAND_ALT1". Default 5m. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | | `MPC_XXXX` | 大多数 MPC_xxx参数会影响此模式下的飞行行为(至少在某种程度上)。 For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | | [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | 从摇杆输入到机体动作的转换策略。 From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). 其他选项允许操纵杆偏转直接控制地面速度,有或没有平滑和加速度限制。 | | [MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | 最大水平加速度。 | diff --git a/docs/zh/flight_modes_rover/api.md b/docs/zh/flight_modes_rover/api.md new file mode 100644 index 0000000000..1783ee9344 --- /dev/null +++ b/docs/zh/flight_modes_rover/api.md @@ -0,0 +1,29 @@ +# Apps & API + +The rover modules have been tested and integrated with a subset of the available [Apps & API](../middleware/index.md) methods. +We specifically provide guides for using [ROS 2](../ros2/index.md) to interface a companion computer with PX4 via [uXRCE-DDS](../middleware/uxrce_dds.md). + +| Method | 描述 | +| ---------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [PX4 ROS 2 Interface](#px4-ros-2-interface) (Recommended) | Register a custom mode and publish [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). | +| [ROS 2 Offboard Control](#ros-2-offboard-control) | Use the PX4 internal [Offboard Mode](../flight_modes/offboard.md) and publish messages defined in [dds_topics.yaml](../middleware/dds_topics.md). | + +## PX4 ROS 2 Interface + +We recommend the use of the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) which allows you to register a custom drive mode and exposes [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). + +By using these setpoints (instead of the PX4 internal rover setpoints), you are guaranteed to send valid control inputs to your vehicle and the control flags for the setpoints you are using are automatically set for you. +Registering a custom drive mode instead of using [ROS 2 Offboard Control](#ros-2-offboard-control) additionally provides the advantages listed [here](../concept/flight_modes.md#internal-vs-external-modes). + +To get familiar with this method, read through the guide for the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) where we also provide an example app for rover. + +## ROS 2 Offboard Control + +[ROS 2 Offboard Control](../ros2/offboard_control.md) uses the PX4 internal [Offboard Mode](../flight_modes/offboard.md). + +While you can subscribe/publish to all topics specified in [dds_topics.yaml](../middleware/dds_topics.md), not all rover modules support all of these topics (see [Supported Setpoints](../flight_modes/offboard.md#rover)). +Unlike the [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints) exposed through the [PX4 ROS 2 Interface](#px4-ros-2-interface), there is no guarantee that the published setpoints lead to a valid control input. + +In addition, the correct control mode flags must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md). +This requires a deeper understanding of PX4 and the structure of the rover modules. +For general information on setting up offboard mode read through [Offboard Mode](../flight_modes/offboard.md) and then consult [Supported Setpoints](../flight_modes/offboard.md#rover). diff --git a/docs/zh/frames_rover/index.md b/docs/zh/frames_rover/index.md index 79d212bdca..76b1749d4f 100644 --- a/docs/zh/frames_rover/index.md +++ b/docs/zh/frames_rover/index.md @@ -21,7 +21,7 @@ The supported frames can be seen in [Airframes Reference > Rover](../airframes/a ## Ackermann -<0/> <1/> + An Ackermann rover controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates. This kind of steering is used on most commercial vehicles, including cars, trucks etc. @@ -34,7 +34,7 @@ PX4 does not require that the vehicle uses the Ackermann geometry and will work ## Differential -<0/> <1/> + A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate. Forward motion is achieved by driving both wheels at the same speed in the same direction. @@ -48,7 +48,7 @@ The differential setup also work for rovers with skid or tank steering. ## Mecanum -<0/> <1/> + A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first. Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place. @@ -57,15 +57,17 @@ Each wheel is driven by its own motor, and by controlling the speed and directio ## See Also -- [Drive Modes](../flight_modes_rover/index.md). +- [Drive Modes](../flight_modes_rover/index.md) - [Configuration/Tuning](../config_rover/index.md) +- [Apps & API](../flight_modes_rover/api.md) - [Complete Vehicles](../complete_vehicles_rover/index.md) ## 仿真 -[Gazebo](../sim_gazebo_gz/index.md) provides simulations for ackermann and differential rovers: +PX4 provides synthetic simulation models for [Gazebo](../sim_gazebo_gz/index.md) of all three rover types to test the software and validate changes and new features: - [Ackermann rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) - [Differential rover](../sim_gazebo_gz/vehicles.md#differential-rover) +- [Mecanum rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) ![Rover gazebo simulation](../../assets/airframes/rover/rover_simulation.png) diff --git a/docs/zh/gps_compass/rtk_gps.md b/docs/zh/gps_compass/rtk_gps.md index 8ccdbf22ec..78e6358172 100644 --- a/docs/zh/gps_compass/rtk_gps.md +++ b/docs/zh/gps_compass/rtk_gps.md @@ -205,7 +205,7 @@ This should be enabled by default on recent builds. To ensure MAVLink2 is used: - Update the telemetry module firmware to the latest version (see [QGroundControl > Setup > Firmware](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/firmware.html)). -- Set [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) +- Ensure [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) is set to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) #### 调试 diff --git a/docs/zh/index.md b/docs/zh/index.md index 08346a3c55..e079c7da61 100644 --- a/docs/zh/index.md +++ b/docs/zh/index.md @@ -1,3 +1,8 @@ + +
# PX4 自动驾驶仪用户指南 @@ -8,17 +13,22 @@ _PX4_ 是一款专业级飞控。 它由来自业界和学术界的世界级开发商开发,并得到活跃的全球社区的支持,为从竞速和物流无人机到地面车辆和潜水艇的各种载具提供动力。 :::tip -这份指南包含组装、配置、安全使用 PX4 的设备的各种只是。 对贡献感兴趣吗 查看 [Development](development/development.md) 部分。 - +这份指南包含组装、配置、安全使用 PX4 的设备的各种只是。 +对贡献感兴趣吗 查看 [Development](development/development.md) 部分。 ::: +
+ :::warning + 本指南适用于_development_ version of PX4 (`main` 分支)。 使用 **版本** 选择器查找当前的 _稳定_ 版本。 自稳定版本发布以来的已记录变更,收录在不断更新的(releases/main.md ) 中。 ::: +
+ ## 如何开始? 所有用户都应该先阅读[基本概念](getting_started/px4_basic_concepts.md) ! diff --git a/docs/zh/middleware/dds_topics.md b/docs/zh/middleware/dds_topics.md index 73c45b3bf7..d3a770aae9 100644 --- a/docs/zh/middleware/dds_topics.md +++ b/docs/zh/middleware/dds_topics.md @@ -4,7 +4,7 @@ This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code. ::: -The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). +The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) and/or [zenoh](../modules/modules_driver.md#zenoh) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default). This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on. diff --git a/docs/zh/middleware/uxrce_dds.md b/docs/zh/middleware/uxrce_dds.md index fbf9244522..65b014b0c1 100644 --- a/docs/zh/middleware/uxrce_dds.md +++ b/docs/zh/middleware/uxrce_dds.md @@ -389,12 +389,12 @@ While most releases should support a very similar set of messages, to be certain Note that ROS 2/DDS needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The message definitions are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs), and they are automatically synchronized by CI on the `main` and release branches. -Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. -Therefore, +需要注意的是,PX4 源代码中的所有消息均存在于该代码仓库中,但只有在dds_topics.yaml文件中列出的消息,才会作为 ROS 2 话题可用。 +因此 -- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace. -- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. - Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. +- 如果您正在使用 PX4 的主要版本或发布版本,您可以通过克隆接口包[PX4/px4_msgs](https://github.com/PX4/px4_msgs)获得消息定义。 +- 如果您要创建或修改 uORB 消息,必须从 PX4 源代码树中手动更新工作空间中的消息。 + 一般来说,这意味着您将更新 [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml),克隆接口包。 然后手动同步,将新的/修改的消息定义从 [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)复制到它的 `msg` 文件夹。 Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/px4_ros_com/src/`, then the command might be: ```sh @@ -412,13 +412,13 @@ Therefore, Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)), at runtime, or through a parameter (which is useful for multi vehicle operations): -- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. - This technique can be used both in simulation and real vehicles. -- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation. +- 一种可能性是在从命令行启动[uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client)时使用 "-n" 选项。 + 这种技术既可用于模拟,也可用于实际机体。 +- 在开始模拟前,可以通过设置环境变量 `PX4_UXRCE_DDS_NS`来提供自定义命名空间 (仅限) :::info Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#dds-ros-2-services). -Therefore, commands like: +因此,命令如下: ```sh uxrce_dds_client start -n uav_1 @@ -430,7 +430,7 @@ uxrce_dds_client start -n uav_1 PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500 ``` -will generate topics under the namespaces: +将在以下命名空间下生成话题: ```sh /uav_1/fmu/in/ # for subscribers diff --git a/docs/zh/middleware/zenoh.md b/docs/zh/middleware/zenoh.md new file mode 100644 index 0000000000..f3d90420d6 --- /dev/null +++ b/docs/zh/middleware/zenoh.md @@ -0,0 +1,201 @@ +# Zenoh (PX4 ROS 2 rmw_zenoh) + + + +:::warning +Experimental +At the time of writing, PX4 Zenoh-pico is experimental, and hence subject to change. +::: + +PX4 supports Zenoh as an alternative mechanism (to DDS) for bridging uORB topics to [ROS 2](../ros2/user_guide.md) (via the ROS 2 [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh) middleware). +This allows uORB messages to be published and subscribed on a companion computer as though they were ROS 2 topics. +It provides a fast and lightweight way to connect PX4 to ROS 2, making it easier for applications to access vehicle telemetry and send control commands. + +The following guide describes the architecture and various options for setting up the Zenoh client and router. +In particular, it covers the options that are most important to PX4 users exploring Zenoh as an alternative communication layer for ROS 2. + +## 软件架构 + +The Zenoh-based middleware consists of a client running on PX4 and a Zenoh router running on the companion computer, with bi-directional data exchange between them over a UART, TCP, UDP, or multicast-UDP link. +The router acts as a broker and discovery service, enabling PX4 to publish and subscribe to topics in the global Zenoh data space. +This allows seamless integration with ROS 2 nodes using [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh), and supports flexible deployment across distributed systems. + +![Architecture PX4 Zenoh-Pico with ROS 2](../../assets/middleware/zenoh/architecture-px4-zenoh.svg) + +The client is the _PX4 Zenoh-Pico Node_ referred to above, which is implemented in the [PX4 `zenoh` module](../modules/modules_driver.md#zenoh). +This is based on Zenoh-Pico, a minimalistic version of [Eclipse Zenoh](https://zenoh.io/) (a data-centric protocol designed for real-time, distributed, and resource-constrained environments). + +The router suggested above is [zenohd](https://github.com/eclipse-zenoh/zenoh/tree/main/zenohd). + +:::info +UART is supported by Zenoh but has not yet implemented in the PX4 Zenoh-Pico node. +::: + +## ROS 2 Zenoh Bring-up on Linux Companion + +In order for PX4 uORB topics to be shared with ROS 2 applications, you will need the PX4 Zenoh-Pico Node client running on your FMU, connected to a Zenoh router running on the companion computer (or elsewhere in the network). + +First select Zenoh as the ROS 2 transport by setting the `RMW_IMPLEMENTATION` environment variable as shown: + +```sh +export RMW_IMPLEMENTATION=rmw_zenoh_cpp +``` + +Then start the Zenoh router using the command: + +```sh +ros2 run rmw_zenoh_cpp rmw_zenohd +``` + +For more information about the Zenoh Router see the [rmw_zenoh](https://github.com/ros2/rmw_zenoh?tab=readme-ov-file#start-the-zenoh-router) documentation. + +## PX4 Zenoh-Pico Node Setup + +### PX4 Firmware + +Before setting up the Zenoh communication, first make sure that your firmware contains the driver that implements the [`zenoh` driver](../modules/modules_driver.md#zenoh), which provides the implementation of the _PX4 Zenoh-Pico Node_. + +You can check if the module is present on your board by searching for the key `CONFIG_MODULES_ZENOH=y` in your board's `default.px4board` KConfig file. +For example, you can see that the module is present in `px4_fmu-v6xrt` build targets from [/boards/px4/fmu-v6xrt/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6xrt/default.px4board#L91). + +If `CONFIG_MODULES_ZENOH=y` is not preset you can add this key to your board configuration and rebuild. +Note that due to flash constraints you may need to remove other components in order to include the module (such as the [`uxrce_dds_client` module](../modules/modules_system.md#uxrce-dds-client), which you will not need if you are using Zenoh). + +The table below shows some of the PX4 targets that include Zenoh by default. + +| PX4 Target | 备注 | +| ---------------------- | -------------------------------------------------------------------------------------------------------------- | +| `px4_fmu-v6xrt` | For [FMUv6X-RT](../flight_controller/nxp_mr_vmu_rt1176.md) (reference platform for testing) | +| `nxp_tropic-community` | | +| `nxp_mr-tropic` | | +| `nxp_mr-canhubk344` | | +| `px4_sitl_zenoh` | Zenoh-enabled simulation build | +| `px4_fmu-v6x_zenoh` | Zenoh-enabled firmware for FMUv6X | + +Zenoh is not included in the default `px4_fmu-` targets for any firmware other than `px4_fmu-v6xrt` (`px4_sitl_zenoh` and `px4_fmu-v6x_zenoh` [are build variants](../dev_setup/building_px4.md#px4-make-build-targets)). + +:::tip +You can check if Zenoh is present at runtime by using QGroundControl to [find the parameter](../advanced_config/parameters.md#finding-a-parameter) [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE). +If present, the module is installed. +::: + +### Enable Zenoh on PX4 Startup + +Set the [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE) parameter to `1` to enable Zenoh on PX4 startup. + +### Configure Zenoh Network + +Set up PX4 to connect to the companion computer running `zenohd`. + +PX4's default IP address of the Zenoh daemon host is `10.41.10.1`. +If you're using a different IP for the Zenoh daemon, run the following command (replacing the address) in a PX4 shell and then reboot: + +```sh +zenoh config net client tcp/10.41.10.1:7447#iface=eth0 +``` + +Note that for the simulation target with Zeroh (`px4_sitl_zenoh`) you won't need to make any changes because the default IP address of the Zenoh daemon is set to `localhost`. + +:::warning +Any changes to the network configuration require a PX4 system reboot to take effect. +::: + +:::tip +See [PX4 Ethernet Setup](../advanced_config/ethernet_setup.md) for more information about Ethernet configuration. +::: + +### PX4 Zenoh-pico Node configuration + +The **default configuration** is auto-generated from the [dds_topics.yaml](../middleware/dds_topics.md) file in the PX4 repository. +This file specifies which uORB message definitions are to be published/subscribed by ROS 2 applications, and hence (indirectly) which topics are compiled into the zenoh module. + +To inspect the current Zenoh configuration: + +```sh +zenoh config +``` + +The PX4 Zenoh-pico node stores its configuration on the **SD card** under the `zenoh` folder. +This folder contains three key files: + +- **`net.txt`** – Defines the **Zenoh network configuration**. +- **`pub.csv`** – Maps **uORB topics to ROS2 topics** (used for publishing). +- **`sub.csv`** – Maps **ROS2 topics to uORB topics** (used for subscribing). + +### 4. Modifying Topic Mappings + +Zenoh topic mappings define how data flows between PX4's internal uORB topics and external ROS2 topics via Zenoh. +These mappings are stored in `pub.csv` and `sub.csv` on the SD card, and can be modified at runtime using the `zenoh config` CLI tool. + +:::warning +Any changes to the topic mappings require a PX4 system reboot to take effect. +::: + +There are two types of mappings you can modify: + +- **Publisher mappings**: Forward data from a uORB topic to a Zenoh topic. +- **Subscriber mappings**: Receive data from a Zenoh topic and publish it to a uORB topic. + +The main operations and their commands are: + +- Publish a uORB topic to a Zenoh topic: + + ```sh + zenoh config add publisher [uorb_instance] + ``` + +- Subscribe to a Zenoh topic and forward it to a uORB topic: + + ```sh + zenoh config add subscriber [uorb_instance] + ``` + +- Remove existing mappings: + + ```sh + zenoh config delete publisher + zenoh config delete subscriber + ``` + +After modifying the mappings, reboot PX4 to apply the changes. +The updated configuration will be loaded from the SD card during startup. + +## Communicating with PX4 from ROS 2 via Zenoh + +Once your PX4 FMU is publishing data into ROS 2, you can inspect the available topics and their contents using standard ROS 2 CLI tools: + +```sh +ros2 topic list(ROS 2 话题列表命令) +``` + +Check topic type and publishers/subscribers: + +```sh +ros2 topic info -v /fmu/out/vehicle_status +Type: px4_msgs/msg/VehicleStatus + +Publisher count: 1 + +Node name: px4_aabbcc00000000000000000000000000 +Node namespace: / +Topic type: px4_msgs/msg/VehicleStatus +Topic type hash: RIHS01_828bddbb7d4c2aa6ad93757955f6893be1ec5d8f11885ec7715bcdd76b5226c9 +Endpoint type: PUBLISHER +GID: 82.99.74.2c.b6.7d.93.44.91.4d.fe.14.93.58.40.16 +QoS profile: + Reliability: RELIABLE + History (Depth): KEEP_LAST (7) + Durability: VOLATILE + Lifespan: Infinite + Deadline: Infinite + Liveliness: AUTOMATIC + Liveliness lease duration: Infinite + +Subscription count: 0 +``` + +### PX4 ROS 2 Interface with Zenoh + +The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) works out of the box with Zenoh as a transport backend. +This means you can publish and subscribe to PX4 topics over Zenoh without changing your ROS 2 nodes or dealing with DDS configuration. +For setup details and supported message types, refer to the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md). diff --git a/docs/zh/modules/modules_driver_distance_sensor.md b/docs/zh/modules/modules_driver_distance_sensor.md index a1a88411f2..f330f01947 100644 --- a/docs/zh/modules/modules_driver_distance_sensor.md +++ b/docs/zh/modules/modules_driver_distance_sensor.md @@ -104,7 +104,7 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### 描述 -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html diff --git a/docs/zh/msg_docs/AirspeedValidated.md b/docs/zh/msg_docs/AirspeedValidated.md index 9034960626..61f607e7fa 100644 --- a/docs/zh/msg_docs/AirspeedValidated.md +++ b/docs/zh/msg_docs/AirspeedValidated.md @@ -1,29 +1,39 @@ # AirspeedValidated (UORB message) +Validated airspeed + +Provides information about airspeed (indicated, true, calibrated) and the source of the data. +Used by controllers, estimators and for airspeed reporting to operator. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) ```c +# Validated airspeed +# +# Provides information about airspeed (indicated, true, calibrated) and the source of the data. +# Used by controllers, estimators and for airspeed reporting to operator. + + uint32 MESSAGE_VERSION = 1 -uint64 timestamp # time since system start (microseconds) +uint64 timestamp # [us] Time since system start -float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid -float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid -float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid +float32 indicated_airspeed_m_s # [m/s] [@invalid NaN] Indicated airspeed (IAS) +float32 calibrated_airspeed_m_s # [m/s] [@invalid NaN] Calibrated airspeed (CAS) +float32 true_airspeed_m_s # [m/s] [@invalid NaN] True airspeed (TAS) -int8 airspeed_source # Source of currently published airspeed values -int8 DISABLED = -1 -int8 GROUND_MINUS_WIND = 0 -int8 SENSOR_1 = 1 -int8 SENSOR_2 = 2 -int8 SENSOR_3 = 3 -int8 SYNTHETIC = 4 +int8 airspeed_source # [@enum SOURCE] Source of currently published airspeed values +int8 SOURCE_DISABLED = -1 # Disabled +int8 SOURCE_GROUND_MINUS_WIND = 0 # Ground speed minus wind +int8 SOURCE_SENSOR_1 = 1 # Sensor 1 +int8 SOURCE_SENSOR_2 = 2 # Sensor 2 +int8 SOURCE_SENSOR_3 = 3 # Sensor 3 +int8 SOURCE_SYNTHETIC = 4 # Synthetic airspeed -# debug states -float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid -float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid -float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] -float32 throttle_filtered # filtered fixed-wing throttle [-] -float32 pitch_filtered # filtered pitch [rad] +float32 calibrated_ground_minus_wind_m_s # [m/s] [@invalid NaN] CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption +float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airspeed +float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative +float32 throttle_filtered # [-] Filtered fixed-wing throttle +float32 pitch_filtered # [rad] Filtered pitch ``` diff --git a/docs/zh/msg_docs/AutotuneAttitudeControlStatus.md b/docs/zh/msg_docs/AutotuneAttitudeControlStatus.md index 734a671ffd..31a47ef204 100644 --- a/docs/zh/msg_docs/AutotuneAttitudeControlStatus.md +++ b/docs/zh/msg_docs/AutotuneAttitudeControlStatus.md @@ -1,42 +1,59 @@ # AutotuneAttitudeControlStatus (UORB message) +Autotune attitude control status + +This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +and is subscribed to by the respective attitude controllers to command rate setpoints. + +The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AutotuneAttitudeControlStatus.msg) ```c -uint64 timestamp # time since system start (microseconds) +# Autotune attitude control status +# +# This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +# and is subscribed to by the respective attitude controllers to command rate setpoints. +# +# The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. -float32[5] coeff # coefficients of the identified discrete-time model -float32[5] coeff_var # coefficients' variance of the identified discrete-time model -float32 fitness # fitness of the parameter estimate -float32 innov -float32 dt_model +uint64 timestamp # [us] Time since system start -float32 kc -float32 ki -float32 kd -float32 kff -float32 att_p +float32[5] coeff # [-] Coefficients of the identified discrete-time model +float32[5] coeff_var # [-] Coefficients' variance of the identified discrete-time model +float32 fitness # [-] Fitness of the parameter estimate +float32 innov # [rad/s] Innovation (residual error between model and measured output) +float32 dt_model # [s] Model sample time used for identification -float32[3] rate_sp -float32 u_filt -float32 y_filt +float32 kc # [-] Proportional rate-loop gain (ideal form) +float32 ki # [-] Integral rate-loop gain (ideal form) +float32 kd # [-] Derivative rate-loop gain (ideal form) +float32 kff # [-] Feedforward rate-loop gain +float32 att_p # [-] Proportional attitude gain -uint8 STATE_IDLE = 0 -uint8 STATE_INIT = 1 -uint8 STATE_ROLL = 2 -uint8 STATE_ROLL_PAUSE = 3 -uint8 STATE_PITCH = 4 -uint8 STATE_PITCH_PAUSE = 5 -uint8 STATE_YAW = 6 -uint8 STATE_YAW_PAUSE = 7 -uint8 STATE_VERIFICATION = 8 -uint8 STATE_APPLY = 9 -uint8 STATE_TEST = 10 -uint8 STATE_COMPLETE = 11 -uint8 STATE_FAIL = 12 -uint8 STATE_WAIT_FOR_DISARM = 13 +float32[3] rate_sp # [rad/s] Rate setpoint commanded to the attitude controller. -uint8 state +float32 u_filt # [-] Filtered input signal (normalized torque setpoint) used in system identification. +float32 y_filt # [rad/s] Filtered output signal (angular velocity) used in system identification. + +uint8 state # [@enum STATE] Current state of the autotune procedure. +uint8 STATE_IDLE = 0 # Idle (not running) +uint8 STATE_INIT = 1 # Initialize filters and setup +uint8 STATE_ROLL_AMPLITUDE_DETECTION = 2 # FW only: determine required excitation amplitude (roll) +uint8 STATE_ROLL = 3 # Roll-axis excitation and model identification +uint8 STATE_ROLL_PAUSE = 4 # Pause to return to level flight +uint8 STATE_PITCH_AMPLITUDE_DETECTION = 5 # FW only: determine required excitation amplitude (pitch) +uint8 STATE_PITCH = 6 # Pitch-axis excitation and model identification +uint8 STATE_PITCH_PAUSE = 7 # Pause to return to level flight +uint8 STATE_YAW_AMPLITUDE_DETECTION = 8 # FW only: determine required excitation amplitude (yaw) +uint8 STATE_YAW = 9 # Yaw-axis excitation and model identification +uint8 STATE_YAW_PAUSE = 10 # Pause to return to level flight +uint8 STATE_VERIFICATION = 11 # Verify model and candidate gains +uint8 STATE_APPLY = 12 # Apply gains +uint8 STATE_TEST = 13 # Test gains in closed-loop +uint8 STATE_COMPLETE = 14 # Tuning completed successfully +uint8 STATE_FAIL = 15 # Tuning failed (model invalid or controller unstable) +uint8 STATE_WAIT_FOR_DISARM = 16 # Waiting for disarm before finalizing ``` diff --git a/docs/zh/msg_docs/ControlAllocatorStatus.md b/docs/zh/msg_docs/ControlAllocatorStatus.md index b355b772b6..4068e7b4f4 100644 --- a/docs/zh/msg_docs/ControlAllocatorStatus.md +++ b/docs/zh/msg_docs/ControlAllocatorStatus.md @@ -24,5 +24,6 @@ int8[16] actuator_saturation # Indicates actuator saturation status. # Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value. uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector +uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection ``` diff --git a/docs/zh/msg_docs/EstimatorStatusFlags.md b/docs/zh/msg_docs/EstimatorStatusFlags.md index 0ac832817d..aa7250fe1e 100644 --- a/docs/zh/msg_docs/EstimatorStatusFlags.md +++ b/docs/zh/msg_docs/EstimatorStatusFlags.md @@ -54,8 +54,9 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended -bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_gnss_fault # 45 - true if GNSS true if GNSS measurements (lat, lon, vel) have been declared faulty bool cs_yaw_manual # 46 - true if yaw has been set manually +bool cs_gnss_hgt_fault # 47 - true if GNSS true if GNSS measurements (alt) have been declared faulty # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/docs/zh/msg_docs/FailureDetectorStatus.md b/docs/zh/msg_docs/FailureDetectorStatus.md index 88e3ca4c24..a112a1e642 100644 --- a/docs/zh/msg_docs/FailureDetectorStatus.md +++ b/docs/zh/msg_docs/FailureDetectorStatus.md @@ -17,5 +17,6 @@ bool fd_motor float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed) uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures +uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection ``` diff --git a/docs/zh/msg_docs/GimbalDeviceAttitudeStatus.md b/docs/zh/msg_docs/GimbalDeviceAttitudeStatus.md index 2c8c6eca9b..0935029087 100644 --- a/docs/zh/msg_docs/GimbalDeviceAttitudeStatus.md +++ b/docs/zh/msg_docs/GimbalDeviceAttitudeStatus.md @@ -14,6 +14,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2 uint16 DEVICE_FLAGS_ROLL_LOCK = 4 uint16 DEVICE_FLAGS_PITCH_LOCK = 8 uint16 DEVICE_FLAGS_YAW_LOCK = 16 +uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 +uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 + float32[4] q float32 angular_velocity_x diff --git a/docs/zh/msg_docs/SensorGnssStatus.md b/docs/zh/msg_docs/SensorGnssStatus.md new file mode 100644 index 0000000000..70602b85fc --- /dev/null +++ b/docs/zh/msg_docs/SensorGnssStatus.md @@ -0,0 +1,19 @@ +# SensorGnssStatus (UORB message) + +Gnss quality indicators + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssStatus.msg) + +```c +# Gnss quality indicators + +uint64 timestamp # time since system start (microseconds) +uint32 device_id # unique device ID for the sensor that does not change between power cycles + +bool quality_available # Set to true if quality indicators are available +uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if not available +uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available +uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available +uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available + +``` diff --git a/docs/zh/msg_docs/SensorGps.md b/docs/zh/msg_docs/SensorGps.md index c8d09e9472..1b5fb3cf41 100644 --- a/docs/zh/msg_docs/SensorGps.md +++ b/docs/zh/msg_docs/SensorGps.md @@ -38,18 +38,26 @@ float32 vdop # Vertical dilution of precision int32 noise_per_ms # GPS noise per millisecond uint16 automatic_gain_control # Automatic gain control monitor -uint8 JAMMING_STATE_UNKNOWN = 0 -uint8 JAMMING_STATE_OK = 1 -uint8 JAMMING_STATE_WARNING = 2 -uint8 JAMMING_STATE_CRITICAL = 3 -uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical -int32 jamming_indicator # indicates jamming is occurring +uint8 JAMMING_STATE_UNKNOWN = 0 #default +uint8 JAMMING_STATE_OK = 1 +uint8 JAMMING_STATE_MITIGATED = 2 +uint8 JAMMING_STATE_DETECTED = 3 +uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected +int32 jamming_indicator # indicates jamming is occurring -uint8 SPOOFING_STATE_UNKNOWN = 0 -uint8 SPOOFING_STATE_NONE = 1 -uint8 SPOOFING_STATE_INDICATED = 2 -uint8 SPOOFING_STATE_MULTIPLE = 3 -uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical +uint8 SPOOFING_STATE_UNKNOWN = 0 #default +uint8 SPOOFING_STATE_OK = 1 +uint8 SPOOFING_STATE_MITIGATED = 2 +uint8 SPOOFING_STATE_DETECTED = 3 +uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected + +# Combined authentication state (e.g. Galileo OSNMA) +uint8 AUTHENTICATION_STATE_UNKNOWN = 0 #default +uint8 AUTHENTICATION_STATE_INITIALIZING = 1 +uint8 AUTHENTICATION_STATE_ERROR = 2 +uint8 AUTHENTICATION_STATE_OK = 3 +uint8 AUTHENTICATION_STATE_DISABLED = 4 +uint8 authentication_state # GPS signal authentication state float32 vel_m_s # GPS ground speed, (metres/sec) float32 vel_n_m_s # GPS North velocity, (metres/sec) @@ -63,6 +71,16 @@ uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp whi uint8 satellites_used # Number of satellites used +uint32 SYSTEM_ERROR_OK = 0 #default +uint32 SYSTEM_ERROR_INCOMING_CORRECTIONS = 1 +uint32 SYSTEM_ERROR_CONFIGURATION = 2 +uint32 SYSTEM_ERROR_SOFTWARE = 4 +uint32 SYSTEM_ERROR_ANTENNA = 8 +uint32 SYSTEM_ERROR_EVENT_CONGESTION = 16 +uint32 SYSTEM_ERROR_CPU_OVERLOAD = 32 +uint32 SYSTEM_ERROR_OUTPUT_CONGESTION = 64 +uint32 system_error # General errors with the connected GPS receiver + float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI]) float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI]) float32 heading_accuracy # heading accuracy (rad, [0, 2PI]) diff --git a/docs/zh/msg_docs/VehicleOdometry.md b/docs/zh/msg_docs/VehicleOdometry.md index d559ded6c7..4213c23337 100644 --- a/docs/zh/msg_docs/VehicleOdometry.md +++ b/docs/zh/msg_docs/VehicleOdometry.md @@ -1,41 +1,44 @@ # VehicleOdometry (UORB message) -Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +Vehicle odometry data + +Fits ROS REP 147 for aerial vehicles [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleOdometry.msg) ```c -# Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +# Vehicle odometry data +# +# Fits ROS REP 147 for aerial vehicles uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp sample -uint8 POSE_FRAME_UNKNOWN = 0 -uint8 POSE_FRAME_NED = 1 # NED earth-fixed frame -uint8 POSE_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference -uint8 pose_frame # Position and orientation frame of reference +uint8 pose_frame # [@enum POSE_FRAME] Position and orientation frame of reference +uint8 POSE_FRAME_UNKNOWN = 0 # Unknown frame +uint8 POSE_FRAME_NED = 1 # North-East-Down (NED) navigation frame. Aligned with True North. +uint8 POSE_FRAME_FRD = 2 # Forward-Right-Down (FRD) frame. Constant arbitrary heading offset from True North. Z is down. -float32[3] position # Position in meters. Frame of reference defined by local_frame. NaN if invalid/unknown -float32[4] q # Quaternion rotation from FRD body frame to reference frame. First value NaN if invalid/unknown +float32[3] position # [m] [@frame local frame] [@invalid NaN If invalid/unknown] Position. Origin is position of GC at startup. +float32[4] q # [-] [@invalid NaN First value if invalid/unknown] Attitude (expressed as a quaternion) relative to pose reference frame at current location. Follows the Hamiltonian convention (w, x, y, z, right-handed, passive rotations from body to world) -uint8 VELOCITY_FRAME_UNKNOWN = 0 -uint8 VELOCITY_FRAME_NED = 1 # NED earth-fixed frame -uint8 VELOCITY_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference -uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame -uint8 velocity_frame # Reference frame of the velocity data +uint8 velocity_frame # [@enum VELOCITY_FRAME] Reference frame of the velocity data +uint8 VELOCITY_FRAME_UNKNOWN = 0 # Unknown frame +uint8 VELOCITY_FRAME_NED = 1 # NED navigation frame at current position. +uint8 VELOCITY_FRAME_FRD = 2 # FRD navigation frame at current position. Constant arbitrary heading offset from True North. Z is down. +uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame -float32[3] velocity # Velocity in meters/sec. Frame of reference defined by velocity_frame variable. NaN if invalid/unknown +float32[3] velocity # [m/s] [@frame @velocity_frame] [@invalid NaN If invalid/unknown] Velocity. +float32[3] angular_velocity # [rad/s] [@frame @VELOCITY_FRAME_BODY_FRD] [@invalid NaN If invalid/unknown] Angular velocity in body-fixed frame -float32[3] angular_velocity # Angular velocity in body-fixed frame (rad/s). NaN if invalid/unknown +float32[3] position_variance # [m^2] Variance of position error +float32[3] orientation_variance # [rad^2] Variance of orientation/attitude error (expressed in body frame) +float32[3] velocity_variance # [m^2/s^2] Variance of velocity error -float32[3] position_variance -float32[3] orientation_variance -float32[3] velocity_variance - -uint8 reset_counter -int8 quality +uint8 reset_counter # [-] Reset counter. Counts reset events on attitude, velocity and position. +int8 quality # [-] [@invalid 0] Quality. Unused. # TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry # TOPICS estimator_odometry diff --git a/docs/zh/msg_docs/index.md b/docs/zh/msg_docs/index.md index 7b76ddabbf..dfed09c171 100644 --- a/docs/zh/msg_docs/index.md +++ b/docs/zh/msg_docs/index.md @@ -15,7 +15,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message -- [AirspeedValidated](AirspeedValidated.md) +- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed - [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply - [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request - [BatteryStatus](BatteryStatus.md) — Battery status @@ -70,7 +70,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [VehicleLandDetected](VehicleLandDetected.md) - [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles +- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data - [VehicleRatesSetpoint](VehicleRatesSetpoint.md) - [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander - [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE @@ -87,7 +87,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [AdcReport](AdcReport.md) - [Airspeed](Airspeed.md) — Airspeed data from sensors - [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector) -- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) +- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status - [BatteryInfo](BatteryInfo.md) — Battery information - [ButtonEvent](ButtonEvent.md) - [CameraCapture](CameraCapture.md) @@ -246,6 +246,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m change with board revisions and sensor updates. - [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor - [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. +- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators - [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds) - [SensorGyro](SensorGyro.md) diff --git a/docs/zh/releases/main.md b/docs/zh/releases/main.md index 6166e251c5..cd60a90e55 100644 --- a/docs/zh/releases/main.md +++ b/docs/zh/releases/main.md @@ -58,7 +58,10 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 仿真 -- TBD +- Overhaul rover simulation: + - Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107) + - Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113) + - Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117) ### Ethernet @@ -67,6 +70,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 - [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). +- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md). ### MAVLink @@ -89,6 +93,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 无人车 - Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)). +- Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)). +- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details). ### ROS 2 diff --git a/docs/zh/ros2/index.md b/docs/zh/ros2/index.md index a99b6c3963..0e35981d71 100644 --- a/docs/zh/ros2/index.md +++ b/docs/zh/ros2/index.md @@ -6,23 +6,23 @@ 小提示 PX4 开发团队强烈建议您使用此 ROS 版本,或将现有系统迁移至此 ROS 版本! -这是最新版本的 [ROS](https://www.ros.org/) (机器人操作系统)。 +这是最新版本的 [ROS](https://www.ros.org/)(机器人操作系统)。 它在 ROS “1” 的基础上进行了显著改进,尤其能够实现与 PX4 更深度、更低延迟的集成。 ::: ROS的优势在于拥有活跃的开发者生态系统 —— 该生态系统致力于解决各类常见的机器人技术问题,同时还能调用其他为 Linux 系统编写的软件库。 -例如,它可以用于 [computer vision](../computer_vision/index.md)解决问题。 +例如,它可以用于 [计算机试图](../computer_vision/index.md) 解决问题。 ROS 2 能够实现与 PX4 极深度的集成,你可以在 ROS 2 中创建飞行模式,这些模式与 PX4 内部原生飞行模式毫无区别;同时还能以高速率直接读取和写入 PX4 内部的 uORB 主题。 (尤其)建议在以下场景中使用:从伴飞计算机进行控制与通信(且低延迟至关重要时)、需借助 Linux 系统的现有库时,或编写新的高级飞行模式时。 ROS 2 与 PX4 之间的通信使用的中间件需实现 [XRCE-DDS protocol](../middleware/uxrce_dds.md). -这个中间件将以 ROS 2 消息和类型显示 PX4 [uORB messages](../msg_docs/index.md) 会转换为 ROS 2 消息和数据类型,从而切实支持从 ROS 2 工作流与节点直接访问 PX4。 +这个中间件将以 ROS 2 消息和类型显示 PX4 [uORB messages](../msg_docs/index.md) 会转换为 ROS 2 消息和数据类型,从而切实支持从 ROS 2 工作流与节点直接访问 PX4。 中间件使用 uORB 消息定义生成代码来序列化和反序列化来处理PX4 的收发消息。 这些相同的消息定义也用于 ROS 2 应用程序中以便能够解析这些消息。 :::info -ROS 2 也可以使用 [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros而不是 XRCE-DDS连接到 PX4。 +ROS 2 也可以使用 [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros)而不是 XRCE-DDS连接到 PX4。 该选项受 MAVROS 项目支持(本文档未对此进行说明)。 ::: @@ -33,9 +33,9 @@ ROS 2 也可以使用 [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavro 本节的主要主题是: -- ROS 2 用户指南: PX4 视角下的 ROS 2,包括安装、设置和如何构建与 PX4 通信的 ROS 2 应用。 -- [ROS 2 离板控制示例](../ros2/offboard_control.md):一个 C++ 教程示例显示如何在 [离板模式] (../flight_modes/offboard.md) 中使用 ROS 2 节点进行位置控制。 -- [ROS 2 多车辆模拟](../ros2/multi_vehicle.md):通过单独的ROS2 代理商连接到多极PX4 模拟的说明。 +- [ROS 2 用户指南](../ros2/user_guide.md): PX4 视角下的 ROS 2,包括安装、设置和如何构建与 PX4 通信的 ROS 2 应用。 +- [ROS 2 离板控制实例](../ros2/offboard_control.md):一个 C++ 教程示例显示如何在 [离板模式] (../flight_modes/offboard.md) 中使用 ROS 2 节点进行位置控制。 +- [ROS 2 多载具模拟](../ros2/multi_vehicle.md):通过单独的ROS2 代理商连接到多极PX4 模拟的说明。 - [PX4 ROS2 接口库](../ros2/px4_ros2_interface_lib.md):一个C++ 库,它与ROS2的 PX4 交互。 可以使用 ROS 2 创建和注册飞行模式,并从 ROS2 应用程序如VIO 系统发送位置估计数。 - [ROS 2 消息翻译节点](../ros2/px4_ros2_msg_translation_node.md):一个 ROS 2 消息翻译节点,它允许在 PX4 和 ROS 2 应用程序之间共享,这些应用程序被编译成不同的消息版本。 diff --git a/docs/zh/ros2/multi_vehicle.md b/docs/zh/ros2/multi_vehicle.md index a525a32445..16f02d9deb 100644 --- a/docs/zh/ros2/multi_vehicle.md +++ b/docs/zh/ros2/multi_vehicle.md @@ -1,54 +1,54 @@ -# 使用 ROS 2 进行多车辆模拟 +# 使用 ROS 2 的多载具模拟 -[XRCE-DDS](../middleware/uxrce_dds.md) 支持多个客户端通过 UDP 协议连接到同一个代理。 +[XRCE-DDS](../middleware/uxrce_dds.md)支持多个客户端通过 UDP 协议连接到同一个代理。 这在模拟中特别有用,因为只有一个代理需要启动。 ## 设置和要求 唯一的要求是 -- 能够在不依赖 ROS 2 的情况下,使用所需的仿真器([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) 和 [JMAVSim](../sim_jmavsim/multi_vehicle.md))运行多车辆仿真[multi-vehicle simulation](../simulation/multi-vehicle-simulation.md)。 -- 能够在单一车辆仿真中使用ROS 2(机器人操作系统 2) +- 能够在不依赖 ROS 2 的情况下,使用所需的仿真器([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md))运行多载具模拟 [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) 。 +- 能够在单一载具模拟中使用 [ROS 2](../ros2/user_guide.md) ## 工作原理 -在仿真中,每个 PX4 实例都会获得一个唯一的px4_instance编号,编号从0开始。 +在模拟中,每个 PX4 实例都会获得一个唯一的`px4_instance`编号,编号从`0`开始。 该值用于为 [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY)分配一个唯一值: ```sh -参数设置 UXRCE_DDS_KEY $(px4_instance+1)) +参数设置UXRCE_DDS_KEY $((px4_instance+1)) ``` :::info -通过这种方式,UXRCE_DDS_KEY 将始终与 [MAV_SYS_ID] 保持一致(../advanced_config/parameter_reference.md#MAV_SYS_ID) +通过这种方式, `UXRCE_DDS_KEY` 将始终与 [MAV_SYS_ID] 保持一致(../advanced_config/parameter_reference.md#MAV_SYS_ID) ::: -此外,当 px4_instance 大于 0 时,会添加一个格式为 px4_$px4_instance 的唯一 ROS 2 命名空间前缀: +此外,当 `px4_instance` 大于 0 时,会添加一个格式为 `px4_$px4_instance` 的唯一 ROS 2[namespace prefix](../middleware/uxrce_dds.md#customizing-the-namespace): ```sh uxrce_dds_ns="-n px4_$px4_instance" ``` :::info -环境变量 PX4_UXRCE_DDS_NS 若已设置,将覆盖上文所述的命名空间行为。 +环境变量`PX4_UXRCE_DDS_NS` 若已设置,将覆盖上文所述的命名空间行为。 ::: -第一个实例(px4_instance=0)没有额外的命名空间,此举是为了与真实载具上 xrce-dds 客户端的默认行为保持一致。 -这种不匹配可以通过手动使用 `PX4_UXRCE_DDS_NS` 来修复,或者通过从索引 `1` 中添加车辆而不是 `0` (这是Gazebo Classic的 [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) 的默认行为)。 +第一个实例(`px4_instance=0`)没有额外的命名空间,此举是为了与真实载具上 xrce-dds 客户端的默认行为保持一致。 +这种不匹配可以通过手动使用 `PX4_UXRCE_DDS_NS` 来修复,或者通过从索引 `1` 中添加车辆而不是 `0` (这是Gazebo Classic的 [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) 的默认行为)。 模拟中的默认客户端配置概述如下: -| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | 客户端命名空间 | +| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace | | ------------------ | -------------- | ---------------- | --------------------- | -| 未提供 | 0 | `px4_instance+1` | 无 | -| 已提供 | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | -| 未提供 | > 0 | `px4_instance+1` | `px4_${px4_instance}` | -| 已提供 | > 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| not provided | 0 | `px4_instance+1` | 无 | +| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| not provided | > 0 | `px4_instance+1` | `px4_${px4_instance}` | +| provided | > 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | ## 调整 `target_system` 值 -PX4 只在他们的 `target_system` 字段为 0 (路由通信) 或与 `MAV_SYS_ID` 一致时,才接受 [VehicleCommand](../msg_docs/VehicleCommand.md)。 +PX4 只在他们的 `target_system` 字段为 0`(路由通信) 或与`MAV_SYS_ID` 一致时,才接受[VehicleCommand](../msg_docs/VehicleCommand.md)。 在所有其他情况下,信息都被忽视。 -因此,当 ROS 2 节点需向 PX4 发送 VehicleCommand(载具指令)消息时,必须确保消息中填写了合适的 target_system(目标系统)字段值。 +因此,当 ROS 2 节点需向 PX4 发送`VehicleCommand`消息时,必须确保消息中填写了合适的`target_system\`字段值。 -例如,若你想向 px4_instance=2 的第三台飞行器发送指令,则需要在所有 VehicleCommand消息中设置 target_system=3。 +例如,若你想向 `px4_instance=2` 的第三台飞行器发送指令,则需要在所有`VehicleCommand`消息中设置 `target_system=3`。 diff --git a/docs/zh/ros2/offboard_control.md b/docs/zh/ros2/offboard_control.md index 03dcfc63dd..5ae2e2973d 100644 --- a/docs/zh/ros2/offboard_control.md +++ b/docs/zh/ros2/offboard_control.md @@ -1,6 +1,6 @@ # ROS 2 Offboard 控制示例 -以下的 C++ 示例展示了如何在 [离板模式] (../flight_modes/offboard.md) 中从 ROS 2 节点进行位置控制。 +以下的 C++ 示例展示了如何在[offboard mode](../flight_modes/offboard.md) 中从 ROS 2 节点进行多轴位置控制。 示例将首先发送设置点、进入offboard模式、解锁、起飞至5米,并悬停等待。 虽然简单,但它显示了如何使用offboard控制以及如何向无人机发送指令。 @@ -13,18 +13,18 @@ _Offboard_ control is dangerous. ::: :::info -ROS 与 PX4 存在若干不同的预设(假设),尤其是在坐标系约定([frame conventions])方面../ros/external_position_estimation.md#reference-frames-and-ros +ROS 与 PX4 存在若干不同的预设(假设),尤其是在 [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros) 当主题发布或订阅时,坐标系类型之间没有隐含转换! -这个例子按照PX4的预期在NED坐标系下发布位置。 -若要订阅来自在不同框架内发布的节点的数据(例如ENU, 这是ROS/ROS 2中的标准参考框架,使用 [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp)库中的辅助函数。 +这个例子按照 PX4 的预期在NED坐标系下发布位置。 +若要订阅来自在不同框架内发布的节点的数据(例如ENU, 这是ROS/ROS 2中的标准参考框架),使用[frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp)库中的辅助函数。 ::: -## 小試身手 +## 小试身手 -请遵循 ROS 2 用户指南 (../ros2/user_guide.md)中的说明,完成安装 PX4和运行模拟器,安装 ROS 2和启动 XRCE-DDS 代理(Agent)。 +按照 [ROS 2 用户指南](../ros2/user_guide.md)中的说明来安装PX 并运行多轴模拟器,安装ROS 2, 并启动XRCE-DDS代理。 -之后,我们可参照 ROS 2 用户指南 > 构建 ROS 2 工作空间 (../ros2/user_guide.md#build-ros-2-workspace)中的相似的步骤来运行这个例子。 +之后,我们可参照 [ROS 2 用户指南 > 构建 ROS 2 工作空间](../ros2/user_guide.md#build-ros-2-workspace)中的相似的步骤来运行这个例子。 :::tip 运行 ROS 2 节点前,请确保 QGC已连接到 PX4。 @@ -42,14 +42,14 @@ ROS 与 PX4 存在若干不同的预设(假设),尤其是在坐标系约 cd ~/ws_offboard_control/src/ ``` -3. 将 px4_msgs 代码仓库克隆到 /src 目录下(每个 ROS 2 PX4 工作空间都需要该仓库!): +3. 将[px4_msgs](https://github.com/PX4/px4_msgs)代码仓库克隆到 /src 目录下(每个 ROS 2 PX4 工作空间都需要该仓库!): ```sh git clone https://github.com/PX4/px4_msgs.git - #若未使用 PX4 的 main 分支,请切换到对应的发布分支 + # checkout the matching release branch if not using PX4 main. ``` -4. 将示例代码仓库 px4_ros_com (https://github.com/PX4/px4_ros_com)克隆到 /src 目录下: +4. 将示例代码仓库 [px4_ros_com](https://github.com/PX4/px4_ros_com)克隆到 /src 目录下: ```sh git clone https://github.com/PX4/px4_ros_com.git @@ -95,7 +95,7 @@ ROS 与 PX4 存在若干不同的预设(假设),尤其是在坐标系约 ros2 run px4_ros_com offboard_control ``` -飞行器将解锁、起飞至5米并悬停等待(永久)。 +飞行器将解锁、起飞至 5 米并悬停等待(永久)。 ## 实现 @@ -133,7 +133,7 @@ timer_ = this->create_wall_timer(100ms, timer_callback); ``` 循环运行在一个100毫秒计时器。 -在最初的 10 个循环中,它会调用 publish_offboard_control_mode() 和 publish_trajectory_setpoint() 这两个函数,向 PX4 发送 OffboardControlMode(离板控制模式)(../msg_docs/OffboardControlMode.md) 和 TrajectorySetpoint(轨迹设定点)(../msg_docs/TrajectorySetpoint.md) 消息。 +在最初的 10 个循环中,它会调用 `publish_offboard_control_mode()` 和 `publish_trajectory_setpoint()` 这两个函数,向 PX4 发送 OffboardControlMode[OffboardControlMode](../msg_docs/OffboardControlMode.md) 和 [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) 消息。 OffboardControlMode消息会持续发送,以便 PX4 切换到离板模式后允许解锁;而 TrajectorySetpoint消息会被忽略(直到载具处于离板模式) 10 个循环后,会调用 publish_vehicle_command() 函数切换至离板模式,并调用 arm() 函数对载具进行解锁。 @@ -213,7 +213,7 @@ void OffboardControl::publish_vehicle_command(uint16_t command, float param1, fl ``` :::info -[VehicleCommand](../msg_docs/VehicleCommand.md是命令PX4的最简单和最高效的方式之一。 通过订阅 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md),您也可以确认设置特定命令是否成功。 +[VehicleCommand](../msg_docs/VehicleCommand.md) 是命令PX4的最简单和最高效的方式之一。 通过订阅 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md),您也可以确认设置特定命令是否成功。 参数字段和 指令字段对应于 [MAVLink commands](https://mavlink.io/en/messages/common.html#mav_commands)以及他们的参数值 ::: diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index 3fa4820ae6..0095cf4d2f 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -24,7 +24,7 @@ Experimental 这些类对 PX4 所使用的内部设定点进行了抽象处理,因此可用于为未来的 PX4 和 ROS 版本提供统一的 ROS 2 接口。 PX4 ROS 2 模式相较于 PX4 内部模式,更易于实现和维护,并且在处理能力与既有代码库资源方面,能为开发者提供更丰富的支持。 -除非该模式属于安全关键型、对时序有严格要求或需要极高的更新速率,或者你的飞行器没有搭载伴随计算机,否则你应优先[考虑使用 PX4 ROS 2 模式,而非 PX4 内部模式](参考链接:../concept/flight_modes.md#internal-vs-external-modes)。 +除非该模式属于安全关键型、对时序有严格要求或需要极高的更新速率,或者你的飞行器没有搭载伴随计算机,否则你应优先[考虑使用 PX4 ROS 2 模式,而非 PX4 内部模式](../concept/flight_modes.md#internal-vs-external-modes)。 ## 综述 @@ -248,7 +248,7 @@ private: }; ``` -- `[1]`: 首先创建一个从 [`px4_ros2:::ModeBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeBase.html)继承的类。 +- `[1]`: 首先创建一个从 [`px4_ros2::ModeBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeBase.html)继承的类。 - `[2]`: 在构造函数中,我们传递模式名称。 这也使我们能够配置一些其他内容,例如替换飞行控制器的内置模式。 - `[3]`:我们在此处创建后续想要使用的所有对象。 这可以是 RC 输入、设置点类型(s)或遥测数据。 `*this` 作为`Context`传递给每个对象,将对象与模式联系起来。 @@ -327,7 +327,7 @@ private: }; ``` -- `[1]`: 首先创建一个从 [`px4_ros2::ModeExecutorBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html) 继承的类。 +- `[1]`: 首先创建一个继承 [`px4_ros2::ModeExecutorBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html)。 - `[2]`: 构造函数采用与执行器相关联的自定义模式,并传递给`ModeExecutorBase`的构造函数。 - `[3]`: 我们为想要运行的状态定义一个枚举。 - `[4]`: `onActivate` 在执行器激活时被调用。 此时,我们可以开始遍历这些状态了。 @@ -344,9 +344,10 @@ private: 以下章节提供了支持的设置点类型列表: -- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): 平滑的位置控制以及(可选的)航向控制 +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): 对横向和纵向固定翼动态的直接控制 - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype):直接控制发动机和飞行地面servo setpoints +- [Rover Setpoints](#rover-setpoints): 直接访问火星车控制设定值(位置、速度、姿态、速率、油门和转向)。 :::tip 其他设置点类型目前是实验性的,可在以下网址找到:[px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental)。 @@ -354,18 +355,20 @@ private: 您可以通过添加一个从 `px4_ros2::SetpointBase` 继承的类来添加您自己的 setpoint 类型, 根据设置点的要求设置配置标志,然后发布任何包含设置点的主题。 ::: -#### Go-to Setpoint (MulticopterGotoSetpointType) +#### 转到设置点 (MulticopterGotoSetpointType) + + :::info -This setpoint type is currently only supported for multicopters. +当前,此设定点类型仅支持多旋翼飞行器。 ::: -Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) setpoint type. -The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. +可通过[`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) 设定点类型,对位置设定点以及(可选的)航向设定点进行平滑控制。 +设定点类型会被传输至飞控主模块(FMU),该模块基于采用时间最优、最大加加速度轨迹构建的位置及航向平滑器。 -There is also a [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) class that allows to send setpoints in global coordinates. +还有一个 [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp), 该类支持在全局坐标系下发送设定点。 最简单的用法就是直接向update method中输入一个3D 位置 @@ -418,7 +421,7 @@ _goto_setpoint->update( ::: 使用[`px4_ros2::FwLateralLongitudinalSetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1FwLateralLongitudinalSetpointType.html)直接控制固定翼飞行器的横向与纵向动力学特性,即分别控制其侧向运动(转弯 / 倾斜)和前向 / 垂直运动(加速及爬升 / 下降)。 -这个设置点被传输到 PX4 [_FwLateralLongitudinalControl_module](../modules/modules_controller.md#fw-lat-lon-control),该模块会对横向与纵向输入进行解耦处理,同时确保不超出飞行器的各项限制范围。 +这个设置点被传输到 PX4 [_FwLateralLongitudinalControl_ module](../modules/modules_controller.md#fw-lat-lon-control),该模块会对横向与纵向输入进行解耦处理,同时确保不超出飞行器的各项限制范围。 为了控制载具,必须提供至少一个横向**和**一个纵向设定值: @@ -510,7 +513,7 @@ _fw_lateral_longitudinal_sett->upate(settpoint_ ##### 高级配置(可选) -你还可以传递一个[`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html) 结构体以及设定值,以覆盖默认的控制器设置和约束条件,例如俯仰角限制、油门限制以及目标下降 / 爬升速率。 +你还可以传递一个[`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html)结构体以及设定值,以覆盖默认的控制器设置和约束条件,例如俯仰角限制、油门限制以及目标下降 / 爬升速率。 这是针对高级用户的: ```cpp @@ -532,33 +535,67 @@ _fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); 所有配置字段都定义为 `std::optional`。 未设置的值将默认采用 PX4 的配置。 -更多关于配置选项的信息,请参阅 [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) 和 [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md)。 +更多关于配置选项的信息,请参阅 [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md)和 [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md)。 :::info 为保障安全,PX4 会自动将配置值限制在飞行器的约束范围内。 -例如,油门覆盖值会被限制在[`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN) -和 [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX)之间。 +例如,油门覆盖值会被限制在 [`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN) +和[`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX)之间。 ::: #### 直接执行器控制设定点(DirectActuatorsSetpointType) -可以使用 [px4_ros2::DirectActActorsSetpootType](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1DirectActuatorsSetpointType.html) 设置点类型直接控制执行器。 +可以使用 [px4_ros2::DirectActuatorsSetpointType](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1DirectActuatorsSetpointType.html) 设置点类型直接控制执行器。 电机和舵机可独立设置。 请注意,该分配(设置 / 指派)具有载具和配置特定性。 -例如,要控制一架四旋翼飞行器,你需要根据其 [输出配置] (../concept/control_allocation.md )来设置前 4 个电机。 +例如,要控制一架四旋翼飞行器,你需要根据其 [输出配置] (../concept/control_allocation.md)来设置前 4 个电机。 :::info 若你想控制的执行器并非用于控制飞行器的运动(例如,而是用于控制有效载荷舵机),请参阅 [below](#controlling-an-independent-actuator-servo)。 ::: +#### Rover 设置点 + + + +滚动模块使用层次结构来传播设置点: + +![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg) + +:::info +所提供的“highest”设定值将被用于 PX4 机器人模块中,以生成低于该值的设定值(并对其进行覆盖!)。 +这个层次结构有提供有效控制输入的明确规则: + +- 提供一个位置集点,**or** +- “左”上的设置点之一(速度 **或** 节点) **和** “右”上的设置点之一(态度、速率 **或** 节点)。 所有“左”和“右”设置点的组合都是有效的。 + +为了便于使用,我们以新的 SettpointType 的形式揭示这些有效的组合。 +::: + +通过控制界面暴露的 RoverSetpointTypes 是这些设置点的组合,导致有效的控制输入: + +| SetpointType | 安装位置 | Speed | 油门 | Attitude | 频率 | Steering | Control Flags | +| ----------------------------------------------------------------------------------------------------------------------------------- | --------------------------- | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------------ | +| [RoverPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverPositionSetpointType.html#details) | ✓ | (✓) | (✓) | (✓) | (✓) | (✓) | Position, Velocity, Attitude, Rate, Control Allocation | +| [RoverSpeedAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedAttitudeSetpointType.html) | | ✓ | (✓) | ✓ | (✓) | (✓) | Velocity, Attitude, Rate, Control Allocation | +| [RoverSpeedRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedRateSetpointType.html) | | ✓ | (✓) | | ✓ | (✓) | Velocity, Rate, Control Allocation | +| [RoverSpeedSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedSteeringSetpointType.html) | | ✓ | (✓) | | | ✓ | Velocity, Control Allocation | +| [RoverThrottleAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleAttitudeSetpointType.html) | | | ✓ | ✓ | (✓) | (✓) | Attitude, Rate, Control Allocation | +| [RoverThrottleRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleRateSetpointType.html) | | | ✓ | | ✓ | (✓) | Rate, Control Allocation | +| [RoverThrottleSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleSteeringSetpointType.html) | | | ✓ | | | ✓ | Control Allocation | + +✓ 是我们发布的设置点,(✓) 是根据上面的层次结构由 PX4 旋转模块内部生成的。 + +使用 `RoverSpeedAttitude SettpointType` 的特定驱动器模式示例为 [here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/rover_velocity)。 + ### 控制VTOL 要在外部飞行模式下控制VTOL,需确保根据当前飞行配置返回正确的设定值类型: -- 多旋翼模式:使用与多旋翼控制兼容的设定值类型。 For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). -- 固定翼形模式:使用 [`FwLateralLongitudinalSetpointType` ](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype)。 +- 多旋翼模式:使用与多旋翼控制兼容的设定值类型。 例如:要么[`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype)要么[`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html)。 +- 固定翼形模式:使用 [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype)。 只要VTOL在整个外部模式期间始终处于多旋翼模式或固定翼模式中的任意一种,就无需额外处理。 @@ -593,7 +630,7 @@ _fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); 要查询载具的当前状态,可在 px4_ros2::VTOL 对象上调用 getCurrentState() 方法。 -请参阅[此外部飞行模式实现](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol)有关如何使用此 API 的实际示例。 +请参阅[此外部飞行模式实现](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol) 有关如何使用此 API 的实际示例。 ### 控制独立执行器/Servo diff --git a/docs/zh/ros2/px4_ros2_interface_lib.md b/docs/zh/ros2/px4_ros2_interface_lib.md index 5be98766c8..e73f8efffe 100644 --- a/docs/zh/ros2/px4_ros2_interface_lib.md +++ b/docs/zh/ros2/px4_ros2_interface_lib.md @@ -14,10 +14,7 @@ Experimental 1. [Control Interface](./px4_ros2_control_interface.md) 允许开发者创建并动态注册使用 ROS2 编写的模式。 它为发送不同类型的设置点提供了课程,涵盖范围从高级导航任务一直到直接执行器控制。 2. [导航界面](./px4_ros2_navigation_interface.md) 允许从ROS 2应用程序(如VIO系统)向PX4发送车辆位置估计数。 - - +3. [Waypoint Missions](./px4_ros2_waypoint_missions.md) 允许航点飞行任务完全在ROS2中运行。 ## 在 ROS 2 工作区中安装 diff --git a/docs/zh/ros2/px4_ros2_msg_translation_node.md b/docs/zh/ros2/px4_ros2_msg_translation_node.md index c496de825e..f60083a53e 100644 --- a/docs/zh/ros2/px4_ros2_msg_translation_node.md +++ b/docs/zh/ros2/px4_ros2_msg_translation_node.md @@ -1,6 +1,6 @@ # PX4 ROS 2 消息翻译节点 -<0/> <1/> + 消息翻译节点允许针对不同版本的 PX4 消息编译的 ROS 2 应用程序与更新版本的 PX4 交互。 反之亦然,而不必更改应用程序或PX4一侧。 diff --git a/docs/zh/ros2/px4_ros2_waypoint_missions.md b/docs/zh/ros2/px4_ros2_waypoint_missions.md new file mode 100644 index 0000000000..d82fc2d543 --- /dev/null +++ b/docs/zh/ros2/px4_ros2_waypoint_missions.md @@ -0,0 +1,190 @@ +# PX4 ROS 2 Waypoint Missions + + + +The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) provides a high-level interface for executing ROS-based waypoint missions in ROS 2. +The main use-case is for creating missions where a custom behavior is required, such as a pickup action within a mission. + +:::warning +ROS 2 missions are not compatible with MAVLink mission definitions, plan files, or ground stations. +They completely bypass the existing PX4 mission mode and waypoint logic, and cannot be planned or displayed within a ground station. +::: + +ROS 2 waypoint missions are effectively special PX4 ROS 2 custom modes that are run based on the content of a [JSON mission definition](#mission-definition). +Mission definitions can contain actions that reference existing PX4 modes, such as Takeoff mode or RTL, and can also be extended with arbitrary custom actions written in ROS. +A [mode executor](px4_ros2_control_interface.md#mode-executor) is used to schedule the modes. + +Mission definitions can be hard coded in the custom mission mode (either in code or statically loaded from a JSON string), or directly generated within the application. +They can also be dynamically loaded based on modification of a particular JSON file — this allows for building a more generic mission framework with a fixed set of custom actions. +The file can then be written by any other application, for example a HTTP or MAVFTP server. + +The current implementation only supports multicopters but is designed to be extendable to any other vehicle type. + +## Comparison to PX4/MAVLink Missions + +There are some benefits and drawbacks to using ROS-based missions, which are provided in the following paragraphs. + +### Benefits + +- Allows to extend mission capabilities by registering custom actions. +- More control over how the mission is executed. + A custom trajectory executor can be implemented, which can use any of the existing PX4 setpoint types to track the trajectory. +- Reduced complexity on the flight controller side by running non-safety-critical and non-real-time code on a more high-level companion computer. +- It can be extended to support other trajectory types, like Bezier or Dubin curves. + +### Drawbacks + +- QGroundControl currently does not display the mission or progress during execution, and cannot upload or download a mission. + Therefore you will need another mechanism to provide a mission, such as from a web server, a custom GCS, or by generating it directly inside the application. +- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-multicoptergotosetpointtype), which only works for multicopters, and VTOL in MC mode). + It is designed to be extendable to any other vehicle type. + +## 综述 + +This diagram provides a conceptual overview of the main classes and their interactions: + +![Waypoint missions overview diagram](../../assets/middleware/ros2/px4_ros2_interface_lib/waypoint_missions.svg) + + + +Missions can be defined in [JSON](#mission-definition), either as a file, or directly inside the application. +There is a file change monitor (`MissionFileMonitor`), that can be used to automatically load a mission from a specific file whenever it is created by another application (e.g. upload via MAVFTP or a cloud service). + +The **`MissionExecutor`** class contains the state machine to progress the mission index, and is at the core of the implementation: + +- Internally, it builds on top of the [Modes and Mode Executors](px4_ros2_control_interface.md#overview) and registers itself through a custom mode and executor with PX4. +- It handles switching in and out of missions: it gets activated when the user switches to the custom mode that represents the mission and the vehicle is armed. + The mode name can be customized (`My Mission` in the example below). + The mission can be paused, which makes the vehicle switch into _Hold mode_. + To resume the mission, the custom mode has to be selected again. +- When an action switches into another mode (for example Takeoff), QGroundControl will display this mode until it is completed. + The mission executor will then automatically continue. +- Custom actions can be registered. +- The mission can be set. + It then checks that all the actions which the mission defines are available and can be run. +- The state can be stored persistently by providing a file name, allowing for battery swapping. + +The **`ActionInterface`** is an interface class for custom actions. +They are identified by a name, and any number of these can be registered with the `MissionExecutor`. +A custom action is then run whenever a mission item with matching name is executed, and any extra arguments from the JSON definition are passed as arguments (for example an altitude for a takeoff action). +Actions can call other actions, run any mode (PX4 or external by its ID), run a trajectory, or run any other external action before deciding when to continue the mission. + +There is a set of default actions, for example for RTL, Land, etc. +These simply trigger the corresponding PX4 mode. +They can be disabled or replaced with custom implementations. +There are also some special actions (which can be replaced as well): + +- `OnFailure`: this is called in case of a failure, e.g. a mode switch failed, a non-existing action is called (by another action) or by an explicit call to `MissionExecutor::abort()`. + The default is to run RTL, with fallback to Land. +- `OnResume`: this is called when resuming a mission (either from the ground or in-air). + It handles a number of cases: + - when called with an argument `action="storeState"`: this can be used to store the current position when the mission is deactivated, so it can be resumed from the same position. + Currently it does not store anything. + - otherwise, when called without a valid mission index or 0, it directly continues. + - otherwise, when called while in-air, it also directly continues. + - otherwise, if landed and if the current mission item is an action that supports resuming from landed, it continues to let the action handle the resuming. + - otherwise, if landed, it finds the takeoff action from the mission, runs it, and then flies to the previous waypoint from the current index to continue the mission. +- `ChangeSettings`: this can be used to change the mission settings, such as the velocity. + The settings are applied to all following items in the mission. + +The **`TrajectoryExecutorInterface`** is an interface class to execute segments of a trajectory. +It can use any setpoint that PX4 and the current vehicle supports for tracking the trajectory. +This class is vehicle-type specific. +The current default implementation (`multicopter::WaypointTrajectoryExecutor`) uses a Goto setpoint (and thus is limited to multicopters). +The default can be replaced with a custom implementation. + +## 用法 + +The following provides a small example. +It defines a custom action and a mission that uses it. + +```c++ +class CustomAction : public px4_ros2::ActionInterface { +public: + CustomAction(px4_ros2::ModeBase & mode) : _node(mode.node()) { } + + std::string name() const override {return "customAction";} + + void run( + const std::shared_ptr & handler, + const px4_ros2::ActionArguments & arguments, + const std::function & on_completed) override + { + RCLCPP_INFO(_node.get_logger(), "Running custom action"); + // Do something... + + on_completed(); + } +private: + rclcpp::Node & _node; +}; + +class MyMission { +public: + MyMission(const std::shared_ptr & node) : _node(node) + { + const auto mission = px4_ros2::Mission(nlohmann::json::parse(R"( + { + "version": 1, + "mission": { + "items": [ + { + "type": "takeoff" + }, + { + "type": "navigation", + "navigationType": "waypoint", + "x": 47.3977419, + "y": 8.5455939, + "z": 500, + "frame": "global" + }, + { + "type": "navigation", + "navigationType": "waypoint", + "x": 47.39791657, + "y": 8.54595214, + "z": 500, + "frame": "global" + }, + { + "type": "customAction" + }, + { + "type": "rtl" + } + ] + } + } +)")); + _mission_executor = std::make_unique("My Mission", + px4_ros2::MissionExecutor::Configuration().addCustomAction(), *node); + + if (!_mission_executor->doRegister()) { + throw std::runtime_error("Failed to register mission executor"); + } + _mission_executor->setMission(mission); + + _mission_executor->onProgressUpdate([&](int current_index) { + RCLCPP_INFO(_node->get_logger(), "Current mission index: %i", current_index); + }); + _mission_executor->onCompleted([&] { + RCLCPP_INFO(_node->get_logger(), "Mission completed callback"); + }); + } + +private: + std::shared_ptr _node; + std::unique_ptr _mission_executor; +}; +``` + +A full example with a few custom actions can be found under [github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/mission/include](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/mission/include). + +## Mission Definition + +The mission JSON file can contain mission defaults and a list of mission items, including user-defined types with custom arguments. +Waypoint coordinates currently need to be defined in global frame, and other frame types might be added in future. + +The schema can be found under [github.com/Auterion/px4-ros2-interface-lib/blob/main/mission/schema.yaml](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/mission/schema.yaml). +It provides more details and can be used to validate a JSON file. diff --git a/docs/zh/ros2/user_guide.md b/docs/zh/ros2/user_guide.md index 4fe01ae40d..773bc92193 100644 --- a/docs/zh/ros2/user_guide.md +++ b/docs/zh/ros2/user_guide.md @@ -9,7 +9,7 @@ ROS 2-PX4 架构在ROS 2和PX4之间进行了深度整合。 允许 ROS 2 订阅 [migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) 解释您需要做什么来将ROS2 应用程序从 PX4 v1.13 迁移到 PX4 v1.14。 -如果您仍然在 PX4 v1.13 上工作,请按照[PX4 v1.13 文档](https://docs.px4.io/v1.13/en/ros/ros2_comm.html)中的说明操作。 +如果您仍然在 PX4 v1.13 上工作,请按照[PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html)中的说明操作。 @@ -17,17 +17,17 @@ ROS 2-PX4 架构在ROS 2和PX4之间进行了深度整合。 允许 ROS 2 订阅 ## 综述 -得益于 uXRCE-DDS(../middleware/uxrce_dds.md) 通信中间件的使用,ROS 2 的应用流程非常简单直接。 +得益于 [uXRCE-DDS](../middleware/uxrce_dds.md) 通信中间件的使用,ROS 2 的应用流程非常简单直接。 ![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg) -uXRCE-DDS 中间件由两部分组成:一部分是运行在 PX4 上的客户端,另一部分是运行在伴飞计算机上的代理;二者之间通过串口、UDP、TCP或自定义链路进行双向数据交换。 +uXRCE-DDS 中间件由两部分组成:一部分是运行在 PX4 上的客户端,另一部分是运行在机载计算机上的代理;二者之间通过串口、UDP、TCP或自定义链路进行双向数据交换。 代理充当客户端的代理角色,以便在全局 DDS 数据空间中发布和订阅主题。 PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) 是在构建时生成,并且默认包含在 PX4 固件中。 -它包含“通用”XRCE-DDS客户端代码和它用来发布到/来自uORB主题的 PX4 特定转换代码。 +它包含“通用”XRCE-DDS客户端代码和它用来发布到来自uORB主题的 PX4 特定转换代码。 生成到客户端中的 uORB 消息子集在 [dds_topics.yaml](../middleware/dds_topics.md)中说明。 生成器使用源代码树中的 uORB 消息定义:[PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) 用于生成发送 ROS 2 消息的代码。 @@ -38,7 +38,7 @@ ROS 2 应用程序需要在一个工作空间中构建,该工作空间需包 这需要[ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md)运行ROS 2 消息转换节点,以确保消息能够正确转换和交互。 需要注意的是,微型XRCE-DDS _agent_ 本身并不依赖客户端代码。 -它可以从 [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent)中单独构建,或者作为ROS构建的一部分,或者作为snap包安装。 +它可以从 [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent) 中单独构建,或者作为ROS构建的一部分,或者作为snap包安装。 在使用 ROS 2 时,您通常需要同时启动客户端和代理。 需要注意的是,uXRCE-DDS 客户端默认已内置到固件中,但除仿真器构建版本外,不会自动启动。 @@ -72,7 +72,7 @@ ROS 2 应用程序需要在一个工作空间中构建,该工作空间需包 若要使用该仿真器,你需要安装 PX4 开发工具链。 :::info -唯一依赖于ROS2的 PX4 是一组信息定义,它从 [px4_msgs](https://github.com/PX4/px4_msgs)获取。 +唯一依赖于ROS2的 PX4 是一组信息定义,它从[px4_msgs](https://github.com/PX4/px4_msgs)获取。 您只需要安装 PX4 当您需要模拟器时(如我们在本指南中所做的那样), 或者如果您正在创建一个发布自定义uORB主题的构建。 ::: @@ -313,7 +313,7 @@ px4_msgs 代码仓库中的分支均以特定名称命名,这些名称与不 换句话说,它会让刚刚构建好的可执行文件在当前终端中可用。 :::info -[ROS2 beginner tutorials](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay)建议您 _open a new terminal_来运行您的可执行文件。 +[ROS2 初学者教程](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#source-the-overlay)建议您_打开一个新的终端来运行您的可执行文件。 ::: 在新终端中: @@ -376,7 +376,7 @@ accelerometer_integral_dt: 4739 #### (可选) 启动转化节点 -<0/> <1/> + 此示例由 PX4 和ROS 2 版本构建,它们使用相同的消息定义。 若你要使用不兼容的 [message versions](../middleware/uorb.md#message-versioning),则在运行示例之前,还需要安装并运行[Message Translation Node](./px4_ros2_msg_translation_node.md): @@ -448,60 +448,60 @@ See [REP105: Coordinate Frames for Mobile Platforms](https://www.ros.org/reps/re ![Reference frames](../../assets/lpe/ref_frames.png) -The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly specified in the associated message definition. -Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions. +除非在相关消息定义中明确指定,否则所有PX4 话题均采用 FRD(即 NED)坐标系约定。 +因此,想要与 PX4 进行交互的 ROS 2 节点,必须妥善处理坐标系约定问题。 -- To rotate a vector from ENU to NED two basic rotations must be performed: - - first a pi/2 rotation around the `Z`-axis (up), - - then a pi rotation around the `X`-axis (old East/new North). +- 要将一个向量从ENU坐标系旋转到NED坐标系,必须执行两个基本旋转操作: + - 首先是绕 Z 轴(朝上方向)旋转 π/2 弧度。 + - 然后是绕 X 轴(原东向 / 新北向)旋转 π 弧度 -- To rotate a vector from NED to ENU two basic rotations must be performed: +- 要将一个向量从NED坐标系旋转到ENU坐标系,必须执行两个基本旋转操作: -- - first a pi/2 rotation around the `Z`-axis (down), - - then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent. +- - 首先是绕 Z 轴(朝下方向)旋转 π/2 弧度。 + - 然后是绕 X 轴(原北向 / 新东向)旋转 π 弧度。 需注意,这两种最终得到的操作在数学上是等效的 -- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient. +- 将向量从 FLU坐标系旋转到 FRD坐标系,仅需绕 X 轴(朝前方向)旋转 π 弧度即可。 -- To rotate a vector from FRD to FLU a pi rotation around the `X`-axis (front) is sufficient. +- 将向量从 FRD坐标系旋转到 FLU坐标系,仅需绕 X 轴(朝前方向)旋转 π 弧度即可。 -Examples of vectors that require rotation are: +需要进行旋转处理的向量示例包括: -- all fields in [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message; ENU to NED conversion is required before sending them. -- all fields in [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) message; FLU to FRD conversion is required before sending them. +- [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md)消息中的所有字段;发送这些字段前,需先将其从 ENU坐标系转换为 NED坐标系。 +- [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md)消息中的所有字段;发送这些字段前,需先将其从 FLU坐标系转换为 FRD坐标系。 -Similarly to vectors, also quaternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion. +与向量类似,用于表示飞行器(机体坐标系)相对于(w.r.t.)姿态的四元数也是如此。 (相对于)世界坐标系(的四元数)需要进行转换。 -[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) provides the shared library [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) to easily perform such conversions. +[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) 提供了名为 [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h)的共享库,可便捷地执行此类转换操作。 -### ROS, Gazebo and PX4 time synchronization +### ROS, Gazebo 和 PX4 时间同步 -By default, time synchronization between ROS 2 and PX4 is automatically managed by the [uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) and time synchronization statistics are available listening to the bridged topic `/fmu/out/timesync_status`. -When the uXRCE-DDS client runs on a flight controller and the agent runs on a companion computer this is the desired behavior as time offsets, time drift, and communication latency, are computed and automatically compensated. +默认情况下,ROS 2 与 PX4 之间的时间同步由[uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) 自动管理;若需查看时间同步统计信息,可监听已桥接的话题 /fmu/out/timesync_status。 +当 uXRCE-DDS 客户端运行在飞控器上,且代理运行在机载计算机上时,这便是理想的运行状态 —— 此时时间偏移、时间漂移以及通信延迟会被自动计算并补偿。 -For Gazebo simulations the GZBridge sets the PX4 time on every sim step (see [Change simulation speed](../sim_gazebo_gz/index.md#change-simulation-speed)). -Note that this is different from the [simulation lockstep](../sim_gazebo_classic/index.md#lockstep) procedure adopted with Gazebo Classic. +在 Gazebo 仿真中,GZBridge 会在每个仿真步长(sim step)为 PX4 设置时间[Change simulation speed](../sim_gazebo_gz/index.md#change-simulation-speed)。 +需注意,这与 Gazebo Classic所采用的仿真锁步[simulation lockstep](../sim_gazebo_classic/index.md#lockstep)流程不同。 -ROS2 users have then two possibilities regarding the [time source](https://design.ros2.org/articles/clock_and_time.html) of their nodes. +对于 ROS 2 用户而言,其节点的[time source](https://design.ros2.org/articles/clock_and_time.html)有两种选择。 -#### ROS2 nodes use the OS clock as time source +#### ROS2 节点使用操作系统时钟作为时间源 -This scenario, which is the one considered in this page and in the [offboard_control](./offboard_control.md) guide, is also the standard behaviour of the ROS2 nodes. -The OS clock acts as time source and therefore it can be used only when the simulation real time factor is very close to one. -The time synchronizer of the uXRCE-DDS client then bridges the OS clock on the ROS2 side with the Gazebo clock on the PX4 side. -No further action is required by the user. +本文档以及[offboard_control](./offboard_control.md)指南中所采用的便是此场景,同时,该场景也是 ROS 2 节点的标准行为 +操作系统时钟作为时间来源,因此它只能在模拟实时系数非常接近时才能使用。 +uXRCE-DDS 客户端的时间同步器随后会将 ROS 2 端的操作系统时钟(OS clock)与 PX4 端的 Gazebo 时钟进行桥接同步。 +用户不需要进一步操作。 -#### ROS2 nodes use the Gazebo clock as time source +#### ROS2 节点使用 Gazebo 时钟作为时间源 -In this scenario, ROS2 also uses the Gazebo `/clock` topic as time source. -This approach makes sense if the Gazebo simulation is running with real time factor different from one, or if ROS2 needs to directly interact with Gazebo. -On the ROS2 side, direct interaction with Gazebo is achieved by the [ros_gz_bridge](https://github.com/gazebosim/ros_gz) package of the [ros_gz](https://github.com/gazebosim/ros_gz) repository. +在这种情况下,ROS2还使用Gazebo\`/时钟主题作为时间来源。 +若 Gazebo 仿真的实时因子不为 1,或 ROS 2 需直接与 Gazebo 交互,则该方法具有合理性。 +在 ROS 2 端,可通过[ros_gz](https://github.com/gazebosim/ros_gz)代码仓库中的[ros_gz_bridge](https://github.com/gazebosim/ros_gz) 功能包,实现与 Gazebo 的直接交互。 -Use the following commands to install the correct ROS 2/gz interface packages (not just the bridge) for the ROS2 and Gazebo version(s) supported by PX4. +请使用以下命令,为 PX4 所支持的 ROS 2 和 Gazebo 版本安装正确的 ROS 2/gz 接口功能包(不仅限于桥接功能包)。 :::: tabs :::tab humble -To install the bridge for use with ROS 2 "Humble" and Gazebo Harmonic (on Ubuntu 22.04): +在 Ubuntu 22.04 系统上,若需安装用于搭配 ROS 2 “Humble”与 Gazebo Harmonic的桥接功能包,可执行以下操作: ```sh sudo apt install ros-humble-ros-gzharmonic @@ -510,9 +510,9 @@ sudo apt install ros-humble-ros-gzharmonic ::: :::tab foxy -First you will need to [install Gazebo Garden](../sim_gazebo_gz/index.md#installation-ubuntu-linux), as by default Foxy comes with Gazebo Classic 11. +首先,您需要 [install Gazebo Garden](../sim_gazebo_gz/index.md#installation-ubuntu-linux),因为默认情况下,Foxy预装的是 Gazebo Classic 11 -Then to install the interface packages for use with ROS 2 "Foxy" and Gazebo (Ubuntu 20.04): +接下来,若要在 Ubuntu 20.04 系统上安装用于搭配 ROS 2 "Foxy"与 Gazebo的桥接功能包,操作如下: ```sh sudo apt install ros-foxy-ros-gzgarden @@ -523,40 +523,40 @@ sudo apt install ros-foxy-ros-gzgarden :::: :::info -The [repo](https://github.com/gazebosim/ros_gz#readme) and [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs show the package versions that need to be installed depending on your ROS2 and Gazebo versions. +[repo](https://github.com/gazebosim/ros_gz#readme) 和 [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) README显示了需要安装的软件包版本,取决于您的 ROS2 和 Gazebo 版本。 ::: -Once the packages are installed and sourced, the node `parameter_bridge` provides the bridging capabilities and can be used to create an unidirectional `/clock` bridge: +功能包安装并完成环境配置后,parameter_bridge节点会提供桥接能力,可用于创建一个单向的/clock桥接。 ```sh ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock ``` -At this point, every ROS2 node must be instructed to use the newly bridged `/clock` topic as time source instead of the OS one, this is done by setting the parameter `use_sim_time` (of _each_ node) to `true` (see [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)). +此时,必须指示每个 ROS 2 节点使用新桥接的/clock话题作为时间源,而非操作系统时钟(OS clock);要实现这一点,需将(每个节点的)use_sim_time参数设置为true(详见[ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html))。 -This concludes the modifications required on the ROS2 side. On the PX4 side, you are only required to stop the uXRCE-DDS time synchronization, setting the parameter [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) to `false`. -By doing so, Gazebo will act as main and only time source for both ROS2 and PX4. +至此,ROS 2 端所需的修改已全部完成。 在 PX4 端,你只需停止 uXRCE-DDS 时间同步功能,将参数[UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT)设置为false即可。 +通过此操作,Gazebo 将成为 ROS 2 和 PX4 两者共同的、唯一的主时间源。 -## ROS 2 Example Applications +## ROS 2 示例应用程序 ### ROS 2 Listener -The ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) in the [px4_ros_com](https://github.com/PX4/px4_ros_com) repo demonstrate how to write ROS nodes to listen to topics published by PX4. +[px4_ros_com](https://github.com/PX4/px4_ros_com中的 ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) repo展示了如何编写 ROS 节点,以监听由 PX4 发布的话题 -Here we consider the [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) node under `px4_ros_com/src/examples/listeners`, which subscribes to the [SensorCombined](../msg_docs/SensorCombined.md) message. +此处我们以 px4_ros_com/src/examples/listeners 路径下的 [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) 节点为例,该节点会订阅 [SensorCombined](../msg_docs/SensorCombined.md) 消息。 :::info -[Build ROS 2 Workspace](#build-ros-2-workspace) shows how to build and run this example. +[Build ROS 2 Workspace](#build-ros-2-workspace) 显示如何构建和运行这个例子。 ::: -The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the `SensorCombined` message to which the node subscribes: +代码首先导入了与 ROS 2 中间件进行交互所需的 C++ 库,以及该节点所订阅的SensorCombined消息对应的头部文件: ```cpp -#include -#include +#include <0> +#include <1> ``` -Then it creates a `SensorCombinedListener` class that subclasses the generic `rclcpp::Node` base class. +随后,代码创建了一个 SensorCombinedListener 类,该类继承自通用的 rclcpp::Node 基类。 ```cpp /** @@ -566,7 +566,7 @@ class SensorCombinedListener : public rclcpp::Node { ``` -This creates a callback function for when the `SensorCombined` uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received. +这会创建一个回调函数,用于处理SensorCombined uORB 消息(当前以微型 XRCE-DDS 消息格式传输)的接收事件;每当接收到该消息时,该函数会输出消息字段的内容 ```cpp public: @@ -595,12 +595,12 @@ public: ``` :::info -The subscription sets a QoS profile based on `rmw_qos_profile_sensor_data`. -This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. -For more information see: [ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings), +该订阅会基于 rmw_qos_profile_sensor_data 设置一个 QoS 配置文件。 +之所以需要这样做,是因为 ROS 2 订阅者的默认 QoS(服务质量)配置文件,与 PX4 发布者的配置文件不兼容。 +欲了解更多信息,请参阅:[ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings), ::: -The lines below create a publisher to the `SensorCombined` uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the `fmu/sensor_combined/out` ROS 2 topic. +以下代码行创建了一个发布者,用于向 SensorCombined uORB 话题发布数据;该发布者可与一个或多个兼容的 ROS 2 订阅者匹配,这些订阅者监听的是 fmu/sensor_combined/out ROS 2 话题。 ````cpp private: @@ -623,14 +623,14 @@ int main(int argc, char *argv[]) } ```` -This particular example has an associated launch file at [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). -This allows it to be launched using the [`ros2 launch`](#ros2-launch) command. +此特殊示例在[launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py).有一个相关的启动文件。 +这使得它可以通过 [`ros2 launch`](#ros2-launch) 命令启动 -### ROS 2 Advertiser +### ROS 2 发布者 -A ROS 2 advertiser node publishes data into the DDS/RTPS network (and hence to the PX4 Autopilot). +一个 ROS 2 发布者节点会将数据发布到 DDS/RTPS 网络中(进而传递给 PX4 自动驾驶仪)。 -Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/advertisers`, first we import required headers, including the `debug_vect` msg header. +以 px4_ros_com/src/advertisers 路径下的 debug_vect_advertiser.cpp(文件)为例,首先我们会导入所需的headers,其中包括 `debug_vect` msg header。 ```cpp #include @@ -640,15 +640,15 @@ Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/adve using namespace std::chrono_literals; ``` -Then the code creates a `DebugVectAdvertiser` class that subclasses the generic `rclcpp::Node` base class. +随后,代码创建了一个 DebugVectAdvertiser 类,该类继承自通用的 rclcpp::Node 基类。 ```cpp class DebugVectAdvertiser : public rclcpp::Node { ``` -The code below creates a function for when messages are to be sent. -The messages are sent based on a timed callback, which sends two messages per second based on a timer. +这段代码创建了一个用来发送消息的回调函数。 +发送消息的回调函数由定时器触发的,每秒钟发送两次消息。 ```cpp public: @@ -676,7 +676,7 @@ private: }; ``` -The instantiation of the `DebugVectAdvertiser` class as a ROS node is done on the `main` function. +这段代码在 main 函数中将 DebugVectAdvertiser 类实例化成一个ROS节点。 ```cpp int main(int argc, char *argv[]) @@ -693,31 +693,31 @@ int main(int argc, char *argv[]) ### Offboard控制 -[ROS 2 Offboard control example](../ros2/offboard_control.md) provides a complete C++ reference example of how to use [offboard control](../flight_modes/offboard.md) of PX4 with ROS2. +[ROS 2 Offboard control example](../ros2/offboard_control.md)提供了一个完整的 C++ 参考示例,说明如何使用 PX4 的 [offboard control](../flight_modes/offboard.md) 与 ROS 2。 -[Python ROS2 offboard examples with PX4](https://github.com/Jaeyoung-Lim/px4-offboard) (Jaeyoung-Lim/px4-offboard) provides a similar example for Python, and includes the scripts: +[Python ROS2 offboard examples with PX4](https://github.com/Jaeyoung-Lim/px4-offboard) (Jaeyoung-Lim/px4-offboard) 为Python 提供了一个类似的示例,并包含脚本: -- `offboard_control.py`: Example of offboard position control using position setpoints -- `visualizer.py`: Used for visualizing vehicle states in Rviz +- `offboard_control.py`: 使用位置设定值进行离板位置控制的示例 +- “visualizer.py\`:用于可视化载体状态的 Rviz -## Using Flight Controller Hardware +## 使用飞行控制器硬件 -ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. -The only difference is that you need to start both the agent _and the client_, with settings appropriate for the communication channel. +在飞行控制器上运行的 PX4 号ROS2与在模拟器上运行的 PX4 几乎相同。 +唯一的区别是您需要同时启动agent _and the client_,并设置适合通信频道。 -For more information see [Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client). +更多信息详见[Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client) -## Custom uORB Topics +## 自定义 uORB 主题 -ROS 2 needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. -The definition are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) and they are automatically synchronized by CI on the `main` and release branches. -Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. -Therefore, +ROS 2需要有用于在 PX4 固件中创建 uXRCE-DDS客户端模块的 _sam_message 定义,以便解释消息。 +这些定义存储在 ROS 2 接口包[PX4/px4_msgs](https://github.com/PX4/px4_msgs)中,并且会通过CI在 main(主)分支和发布分支上自动同步。 +需要注意的是,PX4 源代码中的所有消息均存在于该代码仓库中,但只有在dds_topics.yaml文件中列出的消息,才会作为 ROS 2 话题可用。 +因此 -- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace. -- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. - Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. - Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/ros2_ws/src/`, then the command might be: +- 如果您正在使用 PX4 的主要版本或发布版本,您可以通过克隆接口包[PX4/px4_msgs](https://github.com/PX4/px4_msgs)获得消息定义。 +- 如果您要创建或修改 uORB 消息,必须从 PX4 源代码树中手动更新工作空间中的消息。 + 一般来说,这意味着您将更新 [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml),克隆接口包。 然后手动同步,将新的/修改的消息定义从 [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)复制到它的 `msg` 文件夹。 + 假定PX4-Autopilot在你的主目录`~`中,而`px4_msgs`则在`~/ros2_ws/src/`中,命令可能是: ```sh rm ~/ros2_ws/src/px4_msgs/msg/*.msg @@ -725,22 +725,22 @@ Therefore, ``` ::: info - Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages. - For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml). + 从技术角度而言,[dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) 这个文件完整定义了 PX4 uORB 话题与 ROS 2 消息之间的对应关系。 + 欲了解更多信息,请参阅[uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml)。 ::: ## Customizing the Namespace -Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations): +自定义主题和服务命名空间可以在构建时间(更改 [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml))或运行时间(对多载体操作有用): -- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. - This technique can be used both in simulation and real vehicles. -- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation. +- 一种可能性是在从命令行启动[uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client)时使用 "-n" 选项。 + 这种技术既可用于模拟,也可用于实际机体。 +- 在开始模拟前,可以通过设置环境变量 `PX4_UXRCE_DDS_NS`来提供自定义命名空间 (仅限) :::info -Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#px4-ros-2-service-servers). -Therefore, commands like: +更改运行时的命名空间将会将所需的命名空间作为一个前缀附加到 [dds_topics.yaml](../middleware/dds_topics.md) 中所有的 "topic " 字段和所有 [service servers](#px4-ros-2-service-servers)。 +因此,命令如下: ```sh uxrce_dds_client start -n uav_1 @@ -752,7 +752,7 @@ uxrce_dds_client start -n uav_1 PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500 ``` -will generate topics under the namespaces: +将在以下命名空间下生成话题: ```sh /uav_1/fmu/in/ # for subscribers @@ -766,27 +766,27 @@ will generate topics under the namespaces: PX4 uXRCE-DDS middleware supports [ROS 2 services](https://docs.ros.org/en/jazzy/Concepts/Basic/About-Services.html). -Services are remote procedure calls, from one node to another, that return a result. +服务(Services)是一种远程过程调用(remote procedure calls),由一个节点发起,向另一个节点请求调用,最终会返回一个结果。 A service server is the entity that will accept a remote procedure request, perform some computation on it, and return the result. They simplify communication between ROS 2 nodes and PX4 by grouping the request and response behaviour, and ensuring that replies are only returned to the specific requesting user. -This is much easier that publishing the request, subscribing to the reply, and filtering out any unwanted responses. +这比发布请求、订阅回复并过滤掉所有不需要的响应要容易得多。 -The service servers that are built into the PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module include: +构建在 PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) 模块中的服务服务器包括: - `/fmu/vehicle_command` (definition: [`px4_msgs::srv::VehicleCommand`](https://github.com/PX4/px4_msgs/blob/main/srv/VehicleCommand.srv).) - This service can be called by ROS 2 applications to send PX4 [VehicleCommand](../msg_docs/VehicleCommand.md) uORB messages and receive PX4 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) uORB messages in response. + 此服务可以被 ROS 2 应用程序调用来发送 PX4[VehicleCommand](../msg_docs/VehicleCommand.md) uORB 消息,并相应接收 PX4 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md)uORB 消息。 -All PX4 service names follow the convention `{extra_namespace}/fmu/{server_specific_name}` where `{extra_namespace}` is the same [custom namespace](#customizing-the-namespace) that can be given to the PX4 topics. +所有 PX4 服务名称均遵循 `{extra_namespace}/fmu/{server_specific_name}` 这一约定,其中 {extra_namespace} 与可分配给 PX4 话题的 [custom namespace](#customizing-the-namespace)相同。 -Details and specific examples are provided in the following sections. +具体细节和示例将在以下章节中提供。 -### VehicleCommand service +### 载体指挥服务 -This can be used to send commands to the vehicle, such as "take off", "land", change mode, and "orbit", and receive a response. +这可用于向飞行器发送指令(例如 “起飞”“着陆”“切换模式” 和 “盘旋”),并接收响应。 -The service type is defined in [`px4_msgs::srv::VehicleCommand`](https://github.com/PX4/px4_msgs/blob/main/srv/VehicleCommand.srv) as: +服务类型在 [`px4_msgs::srv::VehicleCommand`](https://github.com/PX4/px4_msgs/blob/main/srv/VehicleCommand.srv) 中定义如下: ```txt VehicleCommand request @@ -794,30 +794,30 @@ VehicleCommand request VehicleCommandAck reply ``` -Users can make service requests by sending [VehicleCommand](../msg_docs/VehicleCommand.md) messages, and receive a [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) message in response. -The service ensures that only the `VehicleCommandAck` reply generated for the specific request made by the user is sent back. +用户可通过发送 [VehicleCommand](../msg_docs/VehicleCommand.md)消息发起服务请求,并会收到一条[VehicleCommandAck](../msg_docs/VehicleCommandAck.md) 消息作为响应。 +该服务可确保仅将针对用户发起的特定请求所生成的 VehicleCommandAck回复返回。 -#### VehicleCommand Service Offboard Control Example +#### 载体指挥服务离板控制示例 -A complete _offboard control_ example using the VehicleCommand service is provided by the [offboard_control_srv](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control_srv.cpp) node available in the `px4_ros_com` package. +在 px4_ros_com 功能包中,有一个[offboard_control_srv](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control_srv.cpp) 节点,该节点提供了一个完整的、使用 VehicleCommand 服务实现离板控制的示例。 -The example closely follows the _offboard control_ example described in [ROS 2 Offboard Control Example](../ros2/offboard_control.md) but uses the `VehicleCommand` service to request mode changes, vehicle arming and vehicle disarming. +该示例与[ROS 2 Offboard Control Example](../ros2/offboard_control.md) 中描述的离板控制示例高度相似,但使用 VehicleCommand 服务来请求模式切换、飞行器上锁和飞行器解锁。 -First the ROS 2 application declares a service client of type `px4_msgs::srv::VehicleCommand` using `rclcpp::Client()` as shown (this is the same approach used for all ROS2 service clients): +首先,ROS 2 应用程序会使用 rclcpp::Client() 声明一个类型为 px4_msgs::srv::VehicleCommand 的服务客户端,具体如下(所有 ROS 2 服务客户端均采用此方法) ```cpp -rclcpp::Client::SharedPtr vehicle_command_client_; +rclcpp::Client<0>::SharedPtr vehicle_command_client_; ``` -Then the client is initialized to the right ROS 2 service (`/fmu/vehicle_command`). -As the application assumes the standard PX4 namespace is used, the code to do this looks like this: +然后客户端初始化到正确的 ROS 2 服务 (`/fmu/vehicle_command` )。 +当应用程序假设使用标准的 PX4 命名空间时,这样做的代码看起来就像这样: ```cpp vehicle_command_client_{this->create_client("/fmu/vehicle_command")} ``` -After that, the client can be used to send any vehicle command request. -For example, the `arm()` function is used to request the vehicle to arm: +此后,客户可以用来发送任何机体命令请求。 +例如,`arm()`函数用于请求机体放置: ```cpp void OffboardControl::arm() @@ -827,7 +827,7 @@ void OffboardControl::arm() } ``` -where `request_vehicle_command` handles formatting the request and sending it over in _asynchronous_ [mode](https://docs.ros.org/en/humble/How-To-Guides/Sync-Vs-Async.html#asynchronous-calls): +`request_vehicle_command`处理请求格式化并在_asynchronous_ [mode](https://docs.ros.org/en/humble/How-To-Guides/Sync-Vs-Async.html#asynchronous-calls): ```cpp void OffboardControl::request_vehicle_command(uint16_t command, float param1, float param2) @@ -853,7 +853,7 @@ void OffboardControl::request_vehicle_command(uint16_t command, float param1, fl } ``` -The response is finally captured asynchronously by the `response_callback` method which checks for the request result: +最终,响应由 response_callback 方法以异步方式捕获,该方法会检查请求结果: ```cpp void OffboardControl::response_callback( @@ -872,20 +872,20 @@ void OffboardControl::response_callback( ## ros2 CLI -The [ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) is a useful tool for working with ROS. -You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have `px4_msg` in the workspace. -The command also lets you launch more complex ROS systems via a launch file. -A few possibilities are demonstrated below. +[ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html)是一个有用的工具来处理ROS。 +例如,您可以使用它快速检查话题是否正在发布;如果您的工作空间中包含 px4_msg,还可以详细查看这些话题的内容。 +该命令还允许您通过启动文件(launch file)启动更复杂的 ROS 系统。 +下文显示了几种可能性。 -### ros2 topic list +### ros2 topic list(ROS 2 话题列表命令) -Use `ros2 topic list` to list the topics visible to ROS 2: +使用 ros2 topic list 命令列出 ROS 2 可识别的话题: ```sh -ros2 topic list +ros2 topic list(ROS 2 话题列表命令) ``` -If PX4 is connected to the agent, the result will be a list of topic types: +若 PX4 已连接至代理,输出结果将是一份话题类型列表: ```sh /fmu/in/obstacle_distance @@ -894,19 +894,19 @@ If PX4 is connected to the agent, the result will be a list of topic types: ... ``` -Note that the workspace does not need to build with `px4_msgs` for this to succeed; topic type information is part of the message payload. +请注意,工作区不需要使用 px4_msgs 构建才能成功;主题类型信息是消息有效载荷的一部分。 ### ros2 topic echo -Use `ros2 topic echo` to show the details of a particular topic. +使用 `ros2 topic echo`"来显示特定主题的详细信息。 -Unlike with `ros2 topic list`, for this to work you must be in a workspace has built the `px4_msgs` and sourced `local_setup.bash` so that ROS can interpret the messages. +与 ros2 topic list 命令不同,要让该功能正常工作,你必须处于一个已编译 px4_msgs且已执行 local_setup.bash 脚本的工作空间中,这样 ROS 才能解析相关消息 ```sh ros2 topic echo /fmu/out/vehicle_status ``` -The command will echo the topic details as they update. +该命令将在主题细节更新时响应它们的详细信息。 ```sh --- @@ -927,14 +927,14 @@ hil_state: 0 ### ros2 topic hz -You can get statistics about the rates of messages using `ros2 topic hz`. -For example, to get the rates for `SensorCombined`: +你可以使用 ros2 topic hz 命令获取消息速率相关的统计信息。 +例如,获取`SensorCombined`速率: ```sh ros2 topic hz /fmu/out/sensor_combined ``` -The output will look something like: +输出会看起来像这样: ```sh average rate: 248.187 @@ -953,30 +953,30 @@ min: 0.000s max: 0.012s std dev: 0.00148s window: 3960 ### ros2 launch -The `ros2 launch` command is used to start a ROS 2 launch file. -For example, above we used `ros2 launch px4_ros_com sensor_combined_listener.launch.py` to start the listener example. +ros2 launch 命令用于启动一个 ROS 2 启动文件 +例如,前面我们使用 ros2 launch px4_ros_com sensor_combined_listener.launch.py 命令启动了监听器示例。 -You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components. +你并非必须使用启动文件,但如果你的 ROS 2 系统较为复杂,需要启动多个组件,那么启动文件会非常实用。 -For information about launch files see [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html) +关于启动文件的信息,请参阅 [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html) ## 故障处理 -### Missing dependencies +### 缺少依赖项 -The standard installation should include all the tools needed by ROS 2. +标准安装应包含 ROS 2 所需的所有工具。 -If any are missing, they can be added separately: +如果有任何缺失,可以单独添加: -- **`colcon`** build tools should be in the development tools. - It can be installed using: +- **`colcon`** 构建工具应该在开发工具中。 + 可以使用以下方式安装它: ```sh sudo apt install python3-colcon-common-extensions ``` -- The Eigen3 library used by the transforms library should be in the both the desktop and base packages. - It should be installed as shown: +- 变换库(transforms library)所使用的 Eigen3 库,应同时存在于桌面版(desktop)功能包和基础版(base)功能包中。 + 它应该安装在显示中: :::: tabs @@ -1002,10 +1002,10 @@ If any are missing, they can be added separately: ### ros_gz_bridge not publishing on the \clock topic -If your [ROS2 nodes use the Gazebo clock as time source](../ros2/user_guide.md#ros2-nodes-use-the-gazebo-clock-as-time-source) but the `ros_gz_bridge` node doesn't publish anything on the `/clock` topic, you may have the wrong version installed. -This might happen if you install ROS 2 Humble with the default "Ignition Fortress" packages, rather than using those for PX4, which uses "Gazebo Harmonic". +如果你的[ROS2 nodes use the Gazebo clock as time source](../ros2/user_guide.md#ros2-nodes-use-the-gazebo-clock-as-time-source) 但`ros_gz_bridge` 节点没有发布任何关于\`/时钟' 主题的内容。 您可能安装了错误的版本。 +若你在安装 ROS 2 Humble 时,使用的是默认的 “Ignition Fortress” 功能包,而非 PX4 所使用的、适配 “Gazebo Harmonic” 的功能包,就可能出现这种情况。 -The following commands uninstall the default Ignition Fortress topics and install the correct bridge and other interface topics for **Gazebo Harmonic** with ROS2 **Humble**: +以下命令会卸载默认的 Ignition Fortress 功能包,并为搭配 ROS 2 Humble 版本的 Gazebo Harmonic 安装正确的桥接功能包及其他接口功能包: ```bash # Remove the wrong version (for Ignition Fortress) @@ -1015,7 +1015,7 @@ sudo apt remove ros-humble-ros-gz sudo apt install ros-humble-ros-gzharmonic ``` -## Additional information +## 更多信息 - [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube) - [DDS and ROS middleware implementations](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations) diff --git a/docs/zh/sensor/inertial_navigation_systems.md b/docs/zh/sensor/inertial_navigation_systems.md index 12cf108625..36b0fb97e8 100644 --- a/docs/zh/sensor/inertial_navigation_systems.md +++ b/docs/zh/sensor/inertial_navigation_systems.md @@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) +- [MicroStrain](../sensor/microstrain.md): Includes VRU, AHRS, INS, and GNSS/INS devices. - [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. - [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. diff --git a/docs/zh/sensor/microstrain.md b/docs/zh/sensor/microstrain.md new file mode 100644 index 0000000000..c3191ed484 --- /dev/null +++ b/docs/zh/sensor/microstrain.md @@ -0,0 +1,219 @@ +# MicroStrain (INS, IMU, VRU, AHRS) + +MicroStrain by HBK provides high-performance inertial sensors engineered for reliability and precision in challenging environments. +Widely used across industries like aerospace, robotics, industrial automation, and research, MicroStrain sensors are optimized for real-time, accurate motion tracking and orientation data. + +![CV7](../../assets/hardware/sensors/inertial/microstrain_3dm_cv7_hbk.png) + +The driver currently supports the following hardware: + +- [`MicroStrain CV7-AR`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/vertical-reference-units--vru-/3dm-cv7-ar): Inertial Measurement Unit (IMU) and Vertical Reference Unit (VRU) +- [`MicroStrain CV7-AHRS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/attitude-and-heading-reference-systems--ahrs-/3dm-cv7-ahrs): Inertial Measurement Unit (IMU) and Attitude Heading Reference System (AHRS) +- [`MicroStrain CV7-INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS). +- [`MicroStrain CV7-GNSS/INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-gnss-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS) combined with dual multiband (GNSS) receivers. + +PX4 can use these sensors to provide raw IMU data for EKF2 or to replace EKF2 as an external INS. +For more information, including user manuals and datasheets, please refer to the sensors product page. + +## 购买渠道 + +MicroStrain sensors can be purchased through HBK's official [MicroStrain product page](https://www.hbkworld.com/en/products/transducers/inertial-sensors) or through authorized distributors globally. +For large orders, custom requirements, or technical inquiries, reach out directly to [sales](https://www.hbkworld.com/en/contact-us/contact-sales-microstrain) + +## 硬件安装 + +### 布线 + +Connect the main UART port of the MicroStrain sensor to any unused serial port on the flight controller. +This port needs to be specified while starting the device. + +### Mounting + +The MicroStrain sensor can be mounted in any orientation. +The default coordinate system uses X for the front, Y for the right, and Z for down, with directions marked on the device. + +## Firmware Configuration + +### PX4 配置 + +To use the MicroStrain driver: + +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`. + +2. Configure the driver mode by setting [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) + + - To use the MicroStrain sensor to provide raw IMU data to EKF2 + + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 0 + 2. Update the [EKF2_MULTI_IMU](../advanced_config/parameter_reference.md#EKF2_MULTI_IMU) parameter to account for the added MicroStrain sensor. + 3. Enable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 1 + 4. To prioritize MicroStrain sensor output, adjust the priority level of individual sensors from 0-100 using the following parameters: + + - [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO) + - [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO) + - [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO) + - [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO) + + where `n` corresponds to the index of the corresponding sensor. + + ::: tip + Sensors can be identified by their device id, which can be found by checking the parameters: + + - [CAL_ACCn_ID](../advanced_config/parameter_reference.md#CAL_ACC0_ID) + - [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) + - [CAL_MAGn_ID](../advanced_config/parameter_reference.md#CAL_MAG0_ID) + - [CAL_BAROn_ID](../advanced_config/parameter_reference.md#CAL_BARO0_ID) + + +::: + + - To use the MicroStrain sensor as an external INS + 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 1 + 2. Disable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 0 + +3. Reboot and start the driver + - `microstrain start -d ` + - To start the driver automatically when the flight controller powers on, set [SENS_MS_CFG](../advanced_config/parameter_reference.md#SENS_MS_CFG) to the sensor’s connected port. + +## MicroStrain Configuration + +1. Rates: + + - By default, accel and gyro data are published at 500 Hz, magnetometer at 50 Hz, and barometric pressure at 50 Hz. + This can be changed by adjusting the following parameters: + + - [MS_IMU_RATE_HZ](../advanced_config/parameter_reference.md#MS_IMU_RATE_HZ) + - [MS_MAG_RATE_HZ](../advanced_config/parameter_reference.md#MS_MAG_RATE_HZ) + - [MS_BARO_RATE_HZ](../advanced_config/parameter_reference.md#MS_BARO_RATE_HZ) + + - Global position, local position, attitude and odometry will be published at 250 Hz by default. + This can be configured via: + + - [MS_FILT_RATE_HZ](../advanced_config/parameter_reference.md#MS_FILT_RATE_HZ) + + - For the CV7-GNSS/INS, the GNSS receiver 1 and 2 will publish data at 5Hz by default. + This can be changed using: + + - [MS_GNSS_RATE_HZ](../advanced_config/parameter_reference.md#MS_GNSS_RATE_HZ) + + - The driver will automatically configure data outputs based on the specific sensor model and available data streams. + + - The driver is scheduled to run at twice the fastest configured data rate. + +2. Aiding measurements: + + - If supported, GNSS position and velocity aiding are always enabled. + + - Internal/external magnetometer and heading aiding, as well as optical flow aiding, are disabled by default. They can be enabled using the following parameters: + + - [MS_INT_MAG_EN](../advanced_config/parameter_reference.md#MS_INT_MAG_EN) + - [MS_INT_HEAD_EN](../advanced_config/parameter_reference.md#MS_INT_HEAD_EN) + - [MS_EXT_HEAD_EN](../advanced_config/parameter_reference.md#MS_EXT_HEAD_EN) + - [MS_EXT_MAG_EN](../advanced_config/parameter_reference.md#MS_EXT_MAG_EN) + - [MS_OPT_FLOW_EN](../advanced_config/parameter_reference.md#MS_OPT_FLOW_EN) + + - The aiding frames for external sources can be configured using the following parameters: + + - [MS_EHEAD_YAW](../advanced_config/parameter_reference.md#MS_EHEAD_YAW) + - [MS_EMAG_ROLL](../advanced_config/parameter_reference.md#MS_EMAG_ROLL) + - [MS_EMAG_PTCH](../advanced_config/parameter_reference.md#MS_EMAG_PTCH) + - [MS_EMAG_YAW](../advanced_config/parameter_reference.md#MS_EMAG_YAW) + - [MS_OFLW_OFF_X](../advanced_config/parameter_reference.md#MS_OFLW_OFF_X) + - [MS_OFLW_OFF_Y](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Y) + - [MS_OFLW_OFF_Z](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Z) + - [SENS_FLOW_ROT](../advanced_config/parameter_reference.md#SENS_FLOW_ROT) + + - The uncertainty for optical flow and external magnetometer aiding must be specified using the following parameters: + + - [MS_EMAG_UNCERT](../advanced_config/parameter_reference.md#MS_EMAG_UNCERT) + - [MS_OFLW_UNCERT](../advanced_config/parameter_reference.md#MS_OFLW_UNCERT) + + ::: tip + + 1. When optical flow aiding is enabled, the sensor uses the `vehicle_optical_flow_vel` output from the flight controller as a body-frame velocity aiding measurement. + 2. If the MicroStrain sensor does not support these aiding sources but they are enabled, sensor initialization will fail. + + +::: + +3. Initial heading alignment: + + - Initial heading alignment is set to kinematic by default. This can be changed by adjusting + + - [MS_ALIGNMENT](../advanced_config/parameter_reference.md#MS_ALIGNMENT) + +4. GNSS Aiding Source Control (GNSS/INS only) + + - The Source of the GNSS aiding data can be configured using: + + - [MS_GNSS_AID_SRC](../advanced_config/parameter_reference.md#MS_GNSS_AID_SRC) + +5. Sensor to vehicle transform: + + - If the sensor is mounted in an orientation different from the vehicle frame. A sensor to vehicle transform can be enabled using + + - [MS_SVT_EN](../advanced_config/parameter_reference.md#MS_SVT_EN) + + - The transform is defined using the following parameters + + - [MS_SENSOR_ROLL](../advanced_config/parameter_reference.md#MS_SENSOR_ROLL) + - [MS_SENSOR_PTCH](../advanced_config/parameter_reference.md#MS_SENSOR_PTCH) + - [MS_SENSOR_YAW](../advanced_config/parameter_reference.md#MS_SENSOR_YAW) + +6. IMU ranges: + + - The accelerometer and gyroscope ranges on the device are configurable using: + + - [MS_ACCEL_RANGE](../advanced_config/parameter_reference.md#MS_ACCEL_RANGE) + - [MS_GYRO_RANGE](../advanced_config/parameter_reference.md#MS_GYRO_RANGE) + + ::: tip + Available range settings depend on the specific [sensor](https://www.hbkworld.com/en/products/transducers/inertial-sensors) and can be found in the corresponding user manual. + By default, the ranges are not changed. + + +::: + +7. GNSS Lever arm offsets: + + - The lever arm offset for the external GNSS receiver can be configured using: + + - [MS_GNSS_OFF1_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_X) + - [MS_GNSS_OFF1_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Y) + - [MS_GNSS_OFF1_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Z) + + - For dual-antenna configurations, the second GNSS receiver’s offset is configured using: + + - [MS_GNSS_OFF2_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_X) + - [MS_GNSS_OFF2_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Y) + - [MS_GNSS_OFF2_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Z) + +## Published Data + +The MicroStrain driver continuously publishes sensor data to the following uORB topics: + +- [sensor_accel](../msg_docs/SensorAccel.md) +- [sensor_gyro](../msg_docs/SensorGyro.md) +- [sensor_mag](../msg_docs/SensorMag.md) +- [sensor_baro](../msg_docs/SensorBaro.md) + +For GNSS/INS devices, GPS data is also published to: + +- [sensor_gps](../msg_docs/SensorGps.md) + +If used as an external INS replacing EKF2, it publishes: + +- [vehicle_global_position](../msg_docs/VehicleGlobalPosition.md) +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) +- [vehicle_odometry](../msg_docs/VehicleOdometry.md) + +otherwise the same data is published to the following topics + +- `external_ins_global_position` +- `external_ins_attitude` +- `external_ins_local_position` + +:::tip +Published topics can be viewed using the `listener` command. +::: diff --git a/docs/zh/sim_gazebo_gz/index.md b/docs/zh/sim_gazebo_gz/index.md index 127701dc05..f9dfc91f12 100644 --- a/docs/zh/sim_gazebo_gz/index.md +++ b/docs/zh/sim_gazebo_gz/index.md @@ -20,6 +20,8 @@ See [Simulation](../simulation/index.md) for general information about simulator Gazebo Harmonic is installed by default on Ubuntu 22.04 as part of the normal [development environment setup](../dev_setup/dev_env_linux_ubuntu.md#simulation-and-nuttx-pixhawk-targets). +Gazebo versions Harmonic, Ionic, and Jetty are supported on Ubuntu 24.04. The latest installed Gazebo release is used by default. + :::info The PX4 installation scripts are based on the instructions: [Binary Installation on Ubuntu](https://gazebosim.org/docs/harmonic/install_ubuntu/) (gazebosim.org). ::: @@ -48,22 +50,23 @@ This runs both the PX4 SITL instance and the Gazebo client. The supported vehicles and `make` commands are listed below. Note that all gazebo make targets have the prefix `gz_`. -| Vehicle | 通信 | `PX4_SYS_AUTOSTART` | -| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------- | ------------------- | -| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4011 | -| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | -| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | -| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | -| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | -| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | -| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | -| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | -| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | -| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | -| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_r1_rover` | 4009 | -| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 4012 | -| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | -| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| Vehicle | 通信 | `PX4_SYS_AUTOSTART` | +| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------- | ------------------- | +| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4011 | +| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | +| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | +| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | +| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | +| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | +| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | +| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | +| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | +| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | +| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | +| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_rover_differential` | 50000 | +| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 51000 | +| [Mecanum Rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) | `make px4_sitl gz_rover_mecanum` | 52000 | All [vehicle models](../sim_gazebo_gz/vehicles.md) (and [worlds](#specify-world)) are included as a submodule from the [Gazebo Models Repository](../sim_gazebo_gz/gazebo_models.md) repository. diff --git a/docs/zh/sim_gazebo_gz/vehicles.md b/docs/zh/sim_gazebo_gz/vehicles.md index a449199159..ba9b16be4a 100644 --- a/docs/zh/sim_gazebo_gz/vehicles.md +++ b/docs/zh/sim_gazebo_gz/vehicles.md @@ -185,7 +185,7 @@ make px4_sitl gz_tiltrotor [Differential Rover](../frames_rover/index.md#differential) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. ```sh -make px4_sitl gz_r1_rover +make px4_sitl gz_rover_differential ``` ![Differential Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_differential.png) @@ -199,3 +199,13 @@ make px4_sitl gz_rover_ackermann ``` ![Ackermann Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_ackermann.png) + +### Mecanum Rover + +[Mecanum Rover](../frames_rover/index.md#mecanum) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. + +```sh +make px4_sitl gz_rover_mecanum +``` + +![Mecanum Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_mecanum.png) diff --git a/docs/zh/telemetry/telemetry_wifi.md b/docs/zh/telemetry/telemetry_wifi.md index b1f435c36d..84d13ddd32 100644 --- a/docs/zh/telemetry/telemetry_wifi.md +++ b/docs/zh/telemetry/telemetry_wifi.md @@ -1,6 +1,6 @@ # WiFi 数传电台 -WiFi telemetry enables MAVLink communication between a WiFi radio on a vehicle and a GCS.\ +WiFi telemetry enables MAVLink communication between a WiFi radio on a vehicle and a GCS. WiFi typically offers shorter range than a normal telemetry radio, but supports higher data rates, and makes it easier to support FPV/video feeds. Usually only a single radio unit for the vehicle is needed (assuming the ground station already has WiFi). diff --git a/docs/zh/test_and_ci/test_flights.md b/docs/zh/test_and_ci/test_flights.md index 094b9cb45f..654ab39b1e 100644 --- a/docs/zh/test_and_ci/test_flights.md +++ b/docs/zh/test_and_ci/test_flights.md @@ -28,5 +28,7 @@ These are run by the test team as part of release testing, and for more signific - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) -- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_07 - Optical Flow Low Mount](../test_cards/mc_07_optical_flow_low_mount.md) - [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) +- [MC_09 - VIO (Visual-Inertial Odometry)](../test_cards/mc_09_vio.md) +- [MC_10 - Optical Flow / GPS Mixed](../test_cards/mc_10_optical_flow_gps_mixed.md) diff --git a/docs/zh/test_cards/mc_06_optical_flow.md b/docs/zh/test_cards/mc_06_optical_flow.md index c63bebba16..a5c415366c 100644 --- a/docs/zh/test_cards/mc_06_optical_flow.md +++ b/docs/zh/test_cards/mc_06_optical_flow.md @@ -2,25 +2,23 @@ ## Objective -To test that optical flow works as expected +Test that optical flow works as expected ## Preflight -Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation -([Setup Information here](../sensor/optical_flow.md)) +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation ([setup information here](../sensor/optical_flow.md)) -Ensure there are no other sources of positioning besides optical flow +Ensure there are no other sources of positioning besides optical flow: - [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` - [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` - [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` -- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into Altitude / Position mode while still on the ground ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -28,7 +26,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -38,6 +36,16 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates +❏ Varying height terrain + +    ❏ Put boxes on the ground to create varying heights in terrain + +    ❏ Take off in position mode and fly over the boxes such that the downward facing rangefinder varies in value + +    ❏ Do a few passes with varying amounts of time over the boxes (1-30 seconds if possible) + +    ❏ Drone should not raise in height when flying over boxes + ## 降落 ❏ Land in either Position or Altitude mode with the throttle below 40% @@ -47,7 +55,8 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## 预期成果 - 当油门升高时,起飞应该是平稳的 -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering (over surface with many features) +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - 在上述任何飞行模式中都不应出现振荡 +- Drone should not raise in height when flying over boxes - 着陆时,直升机不应在地面上反弹 diff --git a/docs/zh/test_cards/mc_07_optical_flow_low_mount.md b/docs/zh/test_cards/mc_07_optical_flow_low_mount.md new file mode 100644 index 0000000000..d6458d7adc --- /dev/null +++ b/docs/zh/test_cards/mc_07_optical_flow_low_mount.md @@ -0,0 +1,45 @@ +# Test MC_07 - Optical Flow Low Sensor + +## Objective + +Test that optical flow works as expected with a low mounted optical flow sensor + +## Preflight + +Ensure that the drone's optical flow sensor is mounted more than an inch off of the ground + +Ensure that [MPC_THR_MIN](../advanced_config/parameter_reference.md#MPC_THR_MIN) is tuned correctly for landing + +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` + +Ensure that the drone can go into [Position mode](../flight_modes_mc/position.md) while still on the ground + +## Flight Tests + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 降落 + +❏ Land in Position mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 预期成果 + +- 当油门升高时,起飞应该是平稳的 +- Drone should stay in Position mode, NOT fall into [altitude](../flight_modes_mc/altitude.md) mode diff --git a/docs/zh/test_cards/mc_08_dshot.md b/docs/zh/test_cards/mc_08_dshot.md index 2f0ef74bdb..ca740ca877 100644 --- a/docs/zh/test_cards/mc_08_dshot.md +++ b/docs/zh/test_cards/mc_08_dshot.md @@ -6,22 +6,22 @@ Regression test for DSHOT working with PX4 ## Preflight -- Ensure vehicle is using a DSHOT ESC. +- Ensure vehicle is using a DSHOT ESC - Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled - Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) - Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked ## Flight Tests -❏ Stabilized Flight mode +❏ [Stabilized mode](../flight_modes_mc/manual_stabilized.md) -    ❏ Takeoff in stabilized flight mode to ensure correct motor spin +    ❏ Takeoff in stabilized mode to ensure correct motor spin     ❏ Pitch/Roll/Yaw response 1:1     ❏ Throttle response 1:1 -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -41,6 +41,6 @@ Regression test for DSHOT working with PX4 - Download flight logs - Load into Data Plot Juggler -- Ensure data is logged for esc_status/esc.0x/esc_rpm +- Ensure data is logged for `esc_status`/`esc.0x`/`esc_rpm` ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/zh/test_cards/mc_09_vio.md b/docs/zh/test_cards/mc_09_vio.md new file mode 100644 index 0000000000..a1438f8967 --- /dev/null +++ b/docs/zh/test_cards/mc_09_vio.md @@ -0,0 +1,52 @@ +# Test MC_09 - VIO (Visual-Inertial Odometry) + +## Objective + +Test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 降落 + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 预期成果 + +- 当油门升高时,起飞应该是平稳的 +- Drone should hold altitude in Altitude mode without wandering +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- 在上述任何飞行模式中都不应出现振荡 +- 着陆时,直升机不应在地面上反弹 diff --git a/docs/zh/test_cards/mc_10_optical_flow_gps_mixed.md b/docs/zh/test_cards/mc_10_optical_flow_gps_mixed.md new file mode 100644 index 0000000000..61097c8568 --- /dev/null +++ b/docs/zh/test_cards/mc_10_optical_flow_gps_mixed.md @@ -0,0 +1,74 @@ +# Test MC_10 - Optical Flow / GPS Mixed + +## Objective + +Test that optical flow mixed with GPS works as expected + +## Preflight + +[Setup optical flow and GPS](../sensor/optical_flow.md) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `7` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `1` +- [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF): `1` (GPS) + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +❏ GPS Cutout + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Open QGC and navigate to MAVLink Console + +    ❏ Type `gps off` to disable GPS + +    ❏ Drone should maintain position hold via optical flow + +❏ GPS Degredation + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Fly under a metal surface (or other GPS blocking structure) + +    ❏ Ensure drone does not lose position hold or start drifting + +    ❏ Fly out of metal structure to regain GPS + +❏ GPS Acquisition + +    ❏ Takeoff in position mode in non-GPS environment + +    ❏ Fly into a GPS rich environment (outdoors) + +    ❏ Ensure drone acquires GPS position + +## 预期成果 + +- 当油门升高时,起飞应该是平稳的 +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Drone should hold position in GPS rich environment as well as non-GPS environment +- 在上述任何飞行模式中都不应出现振荡 diff --git a/msg/GimbalDeviceAttitudeStatus.msg b/msg/GimbalDeviceAttitudeStatus.msg index 0007a1c03d..72eca870f3 100644 --- a/msg/GimbalDeviceAttitudeStatus.msg +++ b/msg/GimbalDeviceAttitudeStatus.msg @@ -9,6 +9,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2 uint16 DEVICE_FLAGS_ROLL_LOCK = 4 uint16 DEVICE_FLAGS_PITCH_LOCK = 8 uint16 DEVICE_FLAGS_YAW_LOCK = 16 +uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 +uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 + float32[4] q float32 angular_velocity_x diff --git a/msg/versioned/VehicleStatus.msg b/msg/versioned/VehicleStatus.msg index 0dffdc2c92..185076a5d6 100644 --- a/msg/versioned/VehicleStatus.msg +++ b/msg/versioned/VehicleStatus.msg @@ -13,20 +13,16 @@ uint8 ARMING_STATE_ARMED = 2 uint8 latest_arming_reason uint8 latest_disarming_reason -uint8 ARM_DISARM_REASON_TRANSITION_TO_STANDBY = 0 uint8 ARM_DISARM_REASON_STICK_GESTURE = 1 uint8 ARM_DISARM_REASON_RC_SWITCH = 2 uint8 ARM_DISARM_REASON_COMMAND_INTERNAL = 3 uint8 ARM_DISARM_REASON_COMMAND_EXTERNAL = 4 uint8 ARM_DISARM_REASON_MISSION_START = 5 -uint8 ARM_DISARM_REASON_SAFETY_BUTTON = 6 -uint8 ARM_DISARM_REASON_AUTO_DISARM_LAND = 7 -uint8 ARM_DISARM_REASON_AUTO_DISARM_PREFLIGHT = 8 -uint8 ARM_DISARM_REASON_KILL_SWITCH = 9 -uint8 ARM_DISARM_REASON_LOCKDOWN = 10 -uint8 ARM_DISARM_REASON_FAILURE_DETECTOR = 11 -uint8 ARM_DISARM_REASON_SHUTDOWN = 12 -uint8 ARM_DISARM_REASON_UNIT_TEST = 13 +uint8 ARM_DISARM_REASON_LANDING = 6 +uint8 ARM_DISARM_REASON_PREFLIGHT_INACTION = 7 +uint8 ARM_DISARM_REASON_KILL_SWITCH = 8 +uint8 ARM_DISARM_REASON_RC_BUTTON = 13 +uint8 ARM_DISARM_REASON_FAILSAFE = 14 uint64 nav_state_timestamp # time when current nav_state activated diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index b8a6c3268a..d50ffd3544 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit b8a6c3268a20e126c83b84ebc5598f9318994200 +Subproject commit d50ffd354495ce5d30814dba41d2eb70a32b8fa3 diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/hw_description.h index e6d854bef3..09559f950b 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/hw_description.h +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/hw_description.h @@ -46,10 +46,34 @@ namespace Timer { + + +// Just to keep def extract_timer(line): happy enum Timer { - EMIOS0 = 0, - EMIOS1, - EMIOS2, + EMIOS0_Channel0, + EMIOS0_Channel1, + EMIOS0_Channel2, + EMIOS0_Channel3, + EMIOS0_Channel4, + EMIOS0_Channel5, + EMIOS0_Channel6, + EMIOS0_Channel7, + EMIOS1_Channel0, + EMIOS1_Channel1, + EMIOS1_Channel2, + EMIOS1_Channel3, + EMIOS1_Channel4, + EMIOS1_Channel5, + EMIOS1_Channel6, + EMIOS1_Channel7, + EMIOS2_Channel0, + EMIOS2_Channel1, + EMIOS2_Channel2, + EMIOS2_Channel3, + EMIOS2_Channel4, + EMIOS2_Channel5, + EMIOS2_Channel6, + EMIOS2_Channel7, }; enum Channel { Channel0 = 0, @@ -70,11 +94,37 @@ struct TimerChannel { static inline constexpr uint32_t timerBaseRegister(Timer::Timer timer) { switch (timer) { - case Timer::EMIOS0: return S32K3XX_EMIOS0_BASE; + case Timer::EMIOS0_Channel0: + case Timer::EMIOS0_Channel1: + case Timer::EMIOS0_Channel2: + case Timer::EMIOS0_Channel3: + case Timer::EMIOS0_Channel4: + case Timer::EMIOS0_Channel5: + case Timer::EMIOS0_Channel6: + case Timer::EMIOS0_Channel7: + return S32K3XX_EMIOS0_BASE; - case Timer::EMIOS1: return S32K3XX_EMIOS1_BASE; - case Timer::EMIOS2: return S32K3XX_EMIOS2_BASE; + + case Timer::EMIOS1_Channel0: + case Timer::EMIOS1_Channel1: + case Timer::EMIOS1_Channel2: + case Timer::EMIOS1_Channel3: + case Timer::EMIOS1_Channel4: + case Timer::EMIOS1_Channel5: + case Timer::EMIOS1_Channel6: + case Timer::EMIOS1_Channel7: + return S32K3XX_EMIOS1_BASE; + + case Timer::EMIOS2_Channel0: + case Timer::EMIOS2_Channel1: + case Timer::EMIOS2_Channel2: + case Timer::EMIOS2_Channel3: + case Timer::EMIOS2_Channel4: + case Timer::EMIOS2_Channel5: + case Timer::EMIOS2_Channel6: + case Timer::EMIOS2_Channel7: + return S32K3XX_EMIOS2_BASE; } return 0; diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer.h index d6e0ad6eb5..e569349dd5 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer.h +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer.h @@ -45,7 +45,7 @@ #pragma once __BEGIN_DECLS /* configuration limits */ -#define MAX_IO_TIMERS 1 +#define MAX_IO_TIMERS 8 #define MAX_TIMER_IO_CHANNELS 8 #define MAX_LED_TIMERS 2 @@ -88,6 +88,7 @@ typedef struct io_timers_t { uint32_t vectorno_12_15; /* IRQ number */ uint32_t vectorno_16_19; /* IRQ number */ uint32_t vectorno_20_23; /* IRQ number */ + uint32_t channel; } io_timers_t; typedef struct io_timers_channel_mapping_element_t { diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer_hw_description.h index b689593a53..724d944792 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer_hw_description.h +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer_hw_description.h @@ -55,15 +55,7 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t ret.timer_channel = (int)timer.channel + 1; // find timer index - ret.timer_index = 0xff; - const uint32_t timer_base = timerBaseRegister(timer.timer); - - for (int i = 0; i < MAX_IO_TIMERS; ++i) { - if (io_timers_conf[i].base == timer_base) { - ret.timer_index = i; - break; - } - } + ret.timer_index = timer.channel; constexpr_assert(ret.timer_index != 0xff, "Timer not found"); @@ -80,13 +72,20 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t * Ch20 - Ch23 = vectorno - 5 */ -static inline constexpr io_timers_t initIOTimer(Timer::Timer timer) +static inline constexpr io_timers_t initIOTimer(Timer::Timer timer, Timer::Channel channel) { bool nuttx_config_timer_enabled = false; io_timers_t ret{}; switch (timer) { - case Timer::EMIOS0: + case Timer::EMIOS0_Channel0: + case Timer::EMIOS0_Channel1: + case Timer::EMIOS0_Channel2: + case Timer::EMIOS0_Channel3: + case Timer::EMIOS0_Channel4: + case Timer::EMIOS0_Channel5: + case Timer::EMIOS0_Channel6: + case Timer::EMIOS0_Channel7: ret.base = S32K3XX_EMIOS0_BASE; ret.clock_register = 0; ret.clock_bit = 0; @@ -96,12 +95,20 @@ static inline constexpr io_timers_t initIOTimer(Timer::Timer timer) ret.vectorno_12_15 = S32K3XX_IRQ_EMIOS0_12_15; ret.vectorno_16_19 = S32K3XX_IRQ_EMIOS0_16_19; ret.vectorno_20_23 = S32K3XX_IRQ_EMIOS0_20_23; + ret.channel = channel; #ifdef CONFIG_S32K3XX_EMIOS0 nuttx_config_timer_enabled = true; #endif break; - case Timer::EMIOS1: + case Timer::EMIOS1_Channel0: + case Timer::EMIOS1_Channel1: + case Timer::EMIOS1_Channel2: + case Timer::EMIOS1_Channel3: + case Timer::EMIOS1_Channel4: + case Timer::EMIOS1_Channel5: + case Timer::EMIOS1_Channel6: + case Timer::EMIOS1_Channel7: ret.base = S32K3XX_EMIOS1_BASE; ret.clock_register = 0; ret.clock_bit = 0; @@ -116,7 +123,15 @@ static inline constexpr io_timers_t initIOTimer(Timer::Timer timer) #endif break; - case Timer::EMIOS2: + + case Timer::EMIOS2_Channel0: + case Timer::EMIOS2_Channel1: + case Timer::EMIOS2_Channel2: + case Timer::EMIOS2_Channel3: + case Timer::EMIOS2_Channel4: + case Timer::EMIOS2_Channel5: + case Timer::EMIOS2_Channel6: + case Timer::EMIOS2_Channel7: ret.base = S32K3XX_EMIOS2_BASE; ret.clock_register = 0; ret.clock_bit = 0; diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/io_timer.c b/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/io_timer.c index 2a3a0afce5..1a56a5338a 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/io_timer.c +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/io_timer.c @@ -868,6 +868,11 @@ int io_timer_set_ccr(unsigned channel, uint16_t value) } else { //FIXME why multiple by 2 + + if ((rC(channels_timer(channel), channel) & EMIOS_C_UCPRE_MASK) == 0) { + value = value * 4; + } + /* configure the channel */ irqstate_t flags = px4_enter_critical_section(); rA(channels_timer(channel), timer_io_channels[channel].timer_channel - 1) = EMIOS_A(value * 2); diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/pwm_servo.c b/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/pwm_servo.c index 6f613b2149..6178c86c64 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/pwm_servo.c +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/pwm_servo.c @@ -128,13 +128,13 @@ int up_pwm_servo_set_rate_group_update(unsigned channel, unsigned rate) if (rate != 0) { - /* limit update rate to 1..10000Hz; somewhat arbitrary but safe */ + /* limit update rate to 1..20000Hz; somewhat arbitrary but safe */ if (rate < 1) { return -ERANGE; } - if (rate > 10000) { + if (rate > 20000) { return -ERANGE; } } diff --git a/platforms/posix/CMakeLists.txt b/platforms/posix/CMakeLists.txt index 71c546b9ec..5b94634f57 100644 --- a/platforms/posix/CMakeLists.txt +++ b/platforms/posix/CMakeLists.txt @@ -87,7 +87,7 @@ install( DIRECTORY ${PROJECT_SOURCE_DIR}/posix-configs ${PROJECT_SOURCE_DIR}/test - ${CMAKE_BINARY_DIR}/etc + ${PX4_BINARY_DIR}/etc ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} DESTINATION ${PROJECT_NAME} @@ -201,6 +201,14 @@ elseif("${PX4_BOARD}" MATCHES "sitl") ${PROJECT_NAME}/build/px4_sitl_default ) + # gazebo files + install( + FILES + ${PROJECT_SOURCE_DIR}/Tools/simulation/gz/server.config + DESTINATION + ${PROJECT_NAME}/Tools/simulation/gz + ) + # gazebo dirs install( DIRECTORY diff --git a/src/drivers/uavcannode/UavcanNode.cpp b/src/drivers/uavcannode/UavcanNode.cpp index 505bf4272c..f82f693e06 100644 --- a/src/drivers/uavcannode/UavcanNode.cpp +++ b/src/drivers/uavcannode/UavcanNode.cpp @@ -547,7 +547,7 @@ void UavcanNode::Run() */ if (_dyn_node_id_client.isAllocationComplete()) { - PX4_INFO("Got node ID %d", _dyn_node_id_client.getAllocatedNodeID().get()); + PX4_INFO("Assigned node ID %d", _dyn_node_id_client.getAllocatedNodeID().get()); _node.setNodeID(_dyn_node_id_client.getAllocatedNodeID()); _init_state = Allocated; @@ -824,6 +824,24 @@ extern "C" int uavcannode_start(int argc, char *argv[]) } } + // Use a static node ID if the parameter is set and in range + int32_t cannode_node_id = 0; + param_get(param_find("CANNODE_NODE_ID"), &cannode_node_id); + + if (cannode_node_id < 0 || cannode_node_id > uavcan::NodeID::Max) { + PX4_ERR("Invalid static node ID %ld, using dynamic allocation", cannode_node_id); + node_id = 0; + + } else { + node_id = cannode_node_id; + } + + // Persist the node ID for the bootloader + bootloader_app_shared_t shared_write = {}; + shared_write.node_id = node_id; + shared_write.bus_speed = 0; // we always want to autobaud + bootloader_app_shared_write(&shared_write, BootLoader); + if ( #if defined(SUPPORT_ALT_CAN_BOOTLOADER) board_booted_by_px4() && diff --git a/src/drivers/uavcannode/uavcannode_params.c b/src/drivers/uavcannode/uavcannode_params.c index 8546989954..6e7dc0bf28 100644 --- a/src/drivers/uavcannode/uavcannode_params.c +++ b/src/drivers/uavcannode/uavcannode_params.c @@ -31,6 +31,15 @@ * ****************************************************************************/ +/** + * UAVCAN CAN node ID (0 for dynamic allocation). + * + * @min 0 + * @max 127 + * @group UAVCAN + */ +PARAM_DEFINE_INT32(CANNODE_NODE_ID, 0); + /** * UAVCAN CAN bus bitrate. * diff --git a/src/lib/adsb/AdsbConflict.cpp b/src/lib/adsb/AdsbConflict.cpp index 08d13e12a4..976b322796 100644 --- a/src/lib/adsb/AdsbConflict.cpp +++ b/src/lib/adsb/AdsbConflict.cpp @@ -77,7 +77,7 @@ void AdsbConflict::detect_traffic_conflict(double lat_now, double lon_now, float && (fabsf(_crosstrack_error.distance) < _conflict_detection_params.crosstrack_separation); const bool _crosstrack_separation_check = (fabsf(alt_now - _transponder_report.altitude) < - _conflict_detection_params.crosstrack_separation); + _conflict_detection_params.vertical_separation); bool collision_time_check = false; diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index c3cbc2578a..acd73c1447 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -442,13 +442,9 @@ "type": "uint8_t", "description": "Reason for arming/disarming", "entries": { - "0": { - "name": "transition_to_standby", - "description": "Transition to standby" - }, "1": { "name": "stick_gesture", - "description": "Stick gesture" + "description": "stick gesture" }, "2": { "name": "rc_switch", @@ -467,36 +463,20 @@ "description": "mission start" }, "6": { - "name": "auto_disarm_land", + "name": "landing", "description": "landing" }, "7": { - "name": "auto_disarm_preflight", - "description": "auto preflight disarming" + "name": "preflight_inaction", + "description": "preflight inaction" }, "8": { "name": "kill_switch", "description": "kill switch" }, - "9": { - "name": "lockdown", - "description": "lockdown" - }, - "10": { - "name": "failure_detector", - "description": "failure detector" - }, - "11": { - "name": "shutdown", - "description": "shutdown request" - }, - "12": { - "name": "unit_test", - "description": "unit tests" - }, "13": { "name": "rc_button", - "description": "RC (button)" + "description": "RC button" }, "14": { "name": "failsafe", diff --git a/src/lib/version/px_update_git_header.py b/src/lib/version/px_update_git_header.py index bd1836fb03..024563b598 100755 --- a/src/lib/version/px_update_git_header.py +++ b/src/lib/version/px_update_git_header.py @@ -129,8 +129,12 @@ if (os.path.exists('src/modules/mavlink/mavlink/.git')): if (os.path.exists('platforms/nuttx/NuttX/nuttx/.git')): nuttx_git_tags = subprocess.check_output('git -c versionsort.suffix=- tag --sort=v:refname'.split(), cwd='platforms/nuttx/NuttX/nuttx', stderr=subprocess.STDOUT).decode('utf-8').strip() - nuttx_git_tag = re.findall(r'nuttx-[0-9]+\.[0-9]+\.[0-9]+', nuttx_git_tags)[-1].replace("nuttx-", "v") - nuttx_git_tag = re.sub('-.*', '.0', nuttx_git_tag) + # may be empty if shallow clone + if (len(nuttx_git_tags) > 0): + nuttx_git_tag = re.findall(r'nuttx-[0-9]+\.[0-9]+\.[0-9]+', nuttx_git_tags)[-1].replace("nuttx-", "v") + nuttx_git_tag = re.sub('-.*', '.0', nuttx_git_tag) + else: + nuttx_git_tag = "v0.0.0" nuttx_git_version = subprocess.check_output('git rev-parse --verify HEAD'.split(), cwd='platforms/nuttx/NuttX/nuttx', stderr=subprocess.STDOUT).decode('utf-8').strip() nuttx_git_version_short = nuttx_git_version[0:16] diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 663223c9bf..4f6bfa0faf 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -511,10 +511,30 @@ extern "C" __EXPORT int commander_main(int argc, char *argv[]) static constexpr const char *arm_disarm_reason_str(arm_disarm_reason_t calling_reason) { - switch (calling_reason) { - case arm_disarm_reason_t::transition_to_standby: return ""; + static_assert((uint8_t)arm_disarm_reason_t::stick_gesture == vehicle_status_s::ARM_DISARM_REASON_STICK_GESTURE, + "(dis)arm enum mismatch"); + static_assert((uint8_t)arm_disarm_reason_t::rc_switch == vehicle_status_s::ARM_DISARM_REASON_RC_SWITCH, + "(dis)arm enum mismatch"); + static_assert((uint8_t)arm_disarm_reason_t::command_internal == vehicle_status_s::ARM_DISARM_REASON_COMMAND_INTERNAL, + "(dis)arm enum mismatch"); + static_assert((uint8_t)arm_disarm_reason_t::command_external == vehicle_status_s::ARM_DISARM_REASON_COMMAND_EXTERNAL, + "(dis)arm enum mismatch"); + static_assert((uint8_t)arm_disarm_reason_t::mission_start == vehicle_status_s::ARM_DISARM_REASON_MISSION_START, + "(dis)arm enum mismatch"); + static_assert((uint8_t)arm_disarm_reason_t::landing == vehicle_status_s::ARM_DISARM_REASON_LANDING, + "(dis)arm enum mismatch"); + static_assert( + (uint8_t)arm_disarm_reason_t::preflight_inaction == vehicle_status_s::ARM_DISARM_REASON_PREFLIGHT_INACTION, + "(dis)arm enum mismatch"); + static_assert((uint8_t)arm_disarm_reason_t::kill_switch == vehicle_status_s::ARM_DISARM_REASON_KILL_SWITCH, + "(dis)arm enum mismatch"); + static_assert((uint8_t)arm_disarm_reason_t::rc_button == vehicle_status_s::ARM_DISARM_REASON_RC_BUTTON, + "(dis)arm enum mismatch"); + static_assert((uint8_t)arm_disarm_reason_t::failsafe == vehicle_status_s::ARM_DISARM_REASON_FAILSAFE, + "(dis)arm enum mismatch"); - case arm_disarm_reason_t::stick_gesture: return "Stick gesture"; + switch (calling_reason) { + case arm_disarm_reason_t::stick_gesture: return "stick gesture"; case arm_disarm_reason_t::rc_switch: return "RC switch"; @@ -524,21 +544,13 @@ static constexpr const char *arm_disarm_reason_str(arm_disarm_reason_t calling_r case arm_disarm_reason_t::mission_start: return "mission start"; - case arm_disarm_reason_t::auto_disarm_land: return "landing"; + case arm_disarm_reason_t::landing: return "landing"; - case arm_disarm_reason_t::auto_disarm_preflight: return "auto preflight disarming"; + case arm_disarm_reason_t::preflight_inaction: return "auto preflight disarming"; case arm_disarm_reason_t::kill_switch: return "kill-switch"; - case arm_disarm_reason_t::lockdown: return "lockdown"; - - case arm_disarm_reason_t::failure_detector: return "failure detector"; - - case arm_disarm_reason_t::shutdown: return "shutdown request"; - - case arm_disarm_reason_t::unit_test: return "unit tests"; - - case arm_disarm_reason_t::rc_button: return "RC (button)"; + case arm_disarm_reason_t::rc_button: return "RC button"; case arm_disarm_reason_t::failsafe: return "failsafe"; } @@ -1944,21 +1956,7 @@ void Commander::run() _vehicle_status.timestamp = hrt_absolute_time(); _vehicle_status_pub.publish(_vehicle_status); - // failure_detector_status publish - failure_detector_status_s fd_status{}; - fd_status.fd_roll = _failure_detector.getStatusFlags().roll; - fd_status.fd_pitch = _failure_detector.getStatusFlags().pitch; - fd_status.fd_alt = _failure_detector.getStatusFlags().alt; - fd_status.fd_ext = _failure_detector.getStatusFlags().ext; - fd_status.fd_arm_escs = _failure_detector.getStatusFlags().arm_escs; - fd_status.fd_battery = _failure_detector.getStatusFlags().battery; - fd_status.fd_imbalanced_prop = _failure_detector.getStatusFlags().imbalanced_prop; - fd_status.fd_motor = _failure_detector.getStatusFlags().motor; - fd_status.imbalanced_prop_metric = _failure_detector.getImbalancedPropMetric(); - fd_status.motor_failure_mask = _failure_detector.getMotorFailures(); - fd_status.motor_stop_mask = _failure_detector.getMotorStopMask(); - fd_status.timestamp = hrt_absolute_time(); - _failure_detector_status_pub.publish(fd_status); + _failure_detector.publishStatus(); } checkWorkerThread(); @@ -2299,35 +2297,19 @@ void Commander::handleAutoDisarm() if (_auto_disarm_landed.get_state() && !_multicopter_throw_launch.isThrowLaunchInProgress()) { if (_have_taken_off_since_arming) { - disarm(arm_disarm_reason_t::auto_disarm_land); + disarm(arm_disarm_reason_t::landing); } else { - disarm(arm_disarm_reason_t::auto_disarm_preflight); + disarm(arm_disarm_reason_t::preflight_inaction); } } } // Auto disarm after 5 seconds if kill switch is engaged - bool auto_disarm = _actuator_armed.kill; - - // auto disarm if locked down to avoid user confusion - // skipped in HITL where lockdown is enabled for safety - if (_vehicle_status.hil_state != vehicle_status_s::HIL_STATE_ON) { - auto_disarm |= _actuator_armed.lockdown; - } - - //don't disarm if throw launch is in progress - auto_disarm &= !_multicopter_throw_launch.isThrowLaunchInProgress(); - - _auto_disarm_killed.set_state_and_update(auto_disarm, hrt_absolute_time()); + _auto_disarm_killed.set_state_and_update(_actuator_armed.kill, hrt_absolute_time()); if (_auto_disarm_killed.get_state()) { - if (_actuator_armed.kill) { - disarm(arm_disarm_reason_t::kill_switch, true); - - } else { - disarm(arm_disarm_reason_t::lockdown, true); - } + disarm(arm_disarm_reason_t::kill_switch, true); } } else { diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index e079d13ee8..e4f0fef7ca 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -54,7 +54,6 @@ #include #include #include -#include #include #include #include @@ -313,7 +312,6 @@ private: // Publications uORB::Publication _actuator_armed_pub{ORB_ID(actuator_armed)}; uORB::Publication _actuator_test_pub{ORB_ID(actuator_test)}; - uORB::Publication _failure_detector_status_pub{ORB_ID(failure_detector_status)}; uORB::Publication _vehicle_command_ack_pub{ORB_ID(vehicle_command_ack)}; uORB::Publication _vehicle_command_pub{ORB_ID(vehicle_command)}; uORB::Publication _vehicle_control_mode_pub{ORB_ID(vehicle_control_mode)}; diff --git a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp index 863b7e9b6b..cbd59351ba 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp @@ -86,9 +86,21 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter) const float high_error_threshold = 5.4f; const auto now = hrt_absolute_time(); + + bool old_state_low = _voltage_low_hysteresis.get_state(); + bool old_state_high = _voltage_high_hysteresis.get_state(); + _voltage_low_hysteresis.set_state_and_update(avionics_power_rail_voltage < low_error_threshold, now); _voltage_high_hysteresis.set_state_and_update(avionics_power_rail_voltage > high_error_threshold, now); + if (_voltage_low_hysteresis.get_state() && !old_state_low) { + _latest_low_failure_val = avionics_power_rail_voltage; + } + + if (_voltage_high_hysteresis.get_state() && !old_state_high) { + _latest_high_failure_val = avionics_power_rail_voltage; + } + if (_voltage_low_hysteresis.get_state()) { /* EVENT @@ -101,11 +113,11 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter) */ reporter.healthFailure(NavModes::All, health_component_t::system, events::ID("check_avionics_power_low"), - events::Log::Error, "Avionics Power low: {1:.2} Volt", avionics_power_rail_voltage, low_error_threshold); + events::Log::Error, "Avionics Power low: {1:.2} Volt", _latest_low_failure_val, low_error_threshold); if (reporter.mavlink_log_pub()) { mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Avionics Power low: %6.2f Volt", - (double)avionics_power_rail_voltage); + (double)_latest_low_failure_val); } } else if (_voltage_high_hysteresis.get_state()) { @@ -119,11 +131,11 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter) */ reporter.healthFailure(NavModes::All, health_component_t::system, events::ID("check_avionics_power_high"), - events::Log::Error, "Avionics Power high: {1:.2} Volt", avionics_power_rail_voltage, high_error_threshold); + events::Log::Error, "Avionics Power high: {1:.2} Volt", _latest_high_failure_val, high_error_threshold); if (reporter.mavlink_log_pub()) { mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Avionics Power high: %6.2f Volt", - (double)avionics_power_rail_voltage); + (double)_latest_high_failure_val); } } diff --git a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp index 76d8b9aae0..e14d75d67e 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp @@ -57,4 +57,7 @@ private: (ParamInt) _param_cbrk_supply_chk, (ParamInt) _param_com_power_count ) + + float _latest_low_failure_val = 0.0f; + float _latest_high_failure_val = 0.0f; }; diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp index d1008d3253..f16505e4a2 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * Copyright (c) 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,11 +33,6 @@ #include "rcCalibrationCheck.hpp" -/** - * Maximum deadzone value - */ -#define RC_INPUT_MAX_DEADZONE_US 500 - /** * Minimum value */ @@ -61,9 +56,6 @@ RcCalibrationChecks::RcCalibrationChecks() snprintf(nbuf, sizeof(nbuf), "RC%d_MAX", i + 1); _param_handles[i].max = param_find(nbuf); - - snprintf(nbuf, sizeof(nbuf), "RC%d_DZ", i + 1); - _param_handles[i].dz = param_find(nbuf); } updateParams(); @@ -84,7 +76,6 @@ void RcCalibrationChecks::checkAndReport(const Context &context, Report &reporte float param_min = _param_values[i].min; float param_max = _param_values[i].max; float param_trim = _param_values[i].trim; - float param_dz = _param_values[i].dz; /* assert min..center..max ordering */ if (param_min < RC_INPUT_LOWEST_MIN_US) { @@ -148,22 +139,6 @@ void RcCalibrationChecks::checkAndReport(const Context &context, Report &reporte (int)param_trim, (int)param_max); } } - - /* assert deadzone is sane */ - if (param_dz > RC_INPUT_MAX_DEADZONE_US) { - /* EVENT - * @description - * Recalibrate the RC. - */ - reporter.armingCheckFailure(NavModes::All, health_component_t::remote_control, - events::ID("check_rc_dz_too_high"), - events::Log::Error, "RC calibration for channel {1} invalid: DZ greater than {2}", i + 1, RC_INPUT_MAX_DEADZONE_US); - - if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: RC ERROR: RC%d_DZ > %u", i + 1, - RC_INPUT_MAX_DEADZONE_US); - } - } } } @@ -176,11 +151,9 @@ void RcCalibrationChecks::updateParams() _param_values[i].min = 0.0f; _param_values[i].max = 0.0f; _param_values[i].trim = 0.0f; - _param_values[i].dz = RC_INPUT_MAX_DEADZONE_US * 2.0f; param_get(_param_handles[i].min, &_param_values[i].min); param_get(_param_handles[i].trim, &_param_values[i].trim); param_get(_param_handles[i].max, &_param_values[i].max); - param_get(_param_handles[i].dz, &_param_values[i].dz); } } diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp index 6a2d30a83f..d0b4a80d8d 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -53,13 +53,11 @@ private: param_t min; param_t trim; param_t max; - param_t dz; }; struct ParamValues { float min; float trim; float max; - float dz; }; ParamHandles _param_handles[input_rc_s::RC_INPUT_MAX_CHANNELS]; diff --git a/src/modules/commander/UserModeIntention.cpp b/src/modules/commander/UserModeIntention.cpp index 556bddbd18..2085995d6c 100644 --- a/src/modules/commander/UserModeIntention.cpp +++ b/src/modules/commander/UserModeIntention.cpp @@ -77,7 +77,8 @@ bool UserModeIntention::change(uint8_t user_intended_nav_state, ModeChangeSource // Special case termination state: even though this mode prevents arming, // still don't switch out of it after disarm and thus store it in _nav_state_after_disarming. - if (!_health_and_arming_checks.modePreventsArming(user_intended_nav_state) + if ((!_health_and_arming_checks.modePreventsArming(user_intended_nav_state) + && !isTakeOffIntended(user_intended_nav_state)) || user_intended_nav_state == vehicle_status_s::NAVIGATION_STATE_TERMINATION) { _nav_state_after_disarming = user_intended_nav_state; } diff --git a/src/modules/commander/UserModeIntention.hpp b/src/modules/commander/UserModeIntention.hpp index cfb4e3998b..e37bf467b1 100644 --- a/src/modules/commander/UserModeIntention.hpp +++ b/src/modules/commander/UserModeIntention.hpp @@ -91,6 +91,7 @@ public: private: bool isArmed() const { return _vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED; } + bool isTakeOffIntended(uint8_t user_intented_nav_state) const {return user_intented_nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF || user_intented_nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF;} const vehicle_status_s &_vehicle_status; const HealthAndArmingChecks &_health_and_arming_checks; diff --git a/src/modules/commander/failure_detector/FailureDetector.cpp b/src/modules/commander/failure_detector/FailureDetector.cpp index 34eb92089a..0c93f303a7 100644 --- a/src/modules/commander/failure_detector/FailureDetector.cpp +++ b/src/modules/commander/failure_detector/FailureDetector.cpp @@ -51,7 +51,7 @@ bool FailureDetector::update(const vehicle_status_s &vehicle_status, const vehic { _failure_injector.update(); - failure_detector_status_u status_prev = _status; + failure_detector_status_u status_prev = _failure_detector_status; if (vehicle_control_mode.flag_control_attitude_enabled) { updateAttitudeStatus(vehicle_status); @@ -61,10 +61,10 @@ bool FailureDetector::update(const vehicle_status_s &vehicle_status, const vehic } } else { - _status.flags.roll = false; - _status.flags.pitch = false; - _status.flags.alt = false; - _status.flags.ext = false; + _failure_detector_status.flags.roll = false; + _failure_detector_status.flags.pitch = false; + _failure_detector_status.flags.alt = false; + _failure_detector_status.flags.ext = false; } // esc_status subscriber is shared between subroutines @@ -77,7 +77,7 @@ bool FailureDetector::update(const vehicle_status_s &vehicle_status, const vehic updateEscsStatus(vehicle_status, esc_status); } - if (_param_fd_actuator_en.get()) { + if (_param_fd_act_en.get()) { updateMotorStatus(vehicle_status, esc_status); } } @@ -86,7 +86,25 @@ bool FailureDetector::update(const vehicle_status_s &vehicle_status, const vehic updateImbalancedPropStatus(); } - return _status.value != status_prev.value; + return _failure_detector_status.value != status_prev.value; +} + +void FailureDetector::publishStatus() +{ + failure_detector_status_s failure_detector_status{}; + failure_detector_status.fd_roll = _failure_detector_status.flags.roll; + failure_detector_status.fd_pitch = _failure_detector_status.flags.pitch; + failure_detector_status.fd_alt = _failure_detector_status.flags.alt; + failure_detector_status.fd_ext = _failure_detector_status.flags.ext; + failure_detector_status.fd_arm_escs = _failure_detector_status.flags.arm_escs; + failure_detector_status.fd_battery = _failure_detector_status.flags.battery; + failure_detector_status.fd_imbalanced_prop = _failure_detector_status.flags.imbalanced_prop; + failure_detector_status.fd_motor = _failure_detector_status.flags.motor; + failure_detector_status.imbalanced_prop_metric = _imbalanced_prop_lpf.getState(); + failure_detector_status.motor_failure_mask = _motor_failure_esc_timed_out_mask | _motor_failure_esc_under_current_mask; + failure_detector_status.motor_stop_mask = _failure_injector.getMotorStopMask(); + failure_detector_status.timestamp = hrt_absolute_time(); + _failure_detector_status_pub.publish(failure_detector_status); } void FailureDetector::updateAttitudeStatus(const vehicle_status_s &vehicle_status) @@ -132,8 +150,8 @@ void FailureDetector::updateAttitudeStatus(const vehicle_status_s &vehicle_statu _pitch_failure_hysteresis.set_state_and_update(pitch_status, time_now); // Update status - _status.flags.roll = _roll_failure_hysteresis.get_state(); - _status.flags.pitch = _pitch_failure_hysteresis.get_state(); + _failure_detector_status.flags.roll = _roll_failure_hysteresis.get_state(); + _failure_detector_status.flags.pitch = _pitch_failure_hysteresis.get_state(); } } @@ -152,7 +170,7 @@ void FailureDetector::updateExternalAtsStatus() _ext_ats_failure_hysteresis.set_hysteresis_time_from(false, 100_ms); // 5 consecutive pulses at 50hz _ext_ats_failure_hysteresis.set_state_and_update(ats_trigger_status, time_now); - _status.flags.ext = _ext_ats_failure_hysteresis.get_state(); + _failure_detector_status.flags.ext = _ext_ats_failure_hysteresis.get_state(); } } @@ -175,13 +193,13 @@ void FailureDetector::updateEscsStatus(const vehicle_status_s &vehicle_status, c _esc_failure_hysteresis.set_state_and_update(is_esc_failure, time_now); if (_esc_failure_hysteresis.get_state()) { - _status.flags.arm_escs = true; + _failure_detector_status.flags.arm_escs = true; } } else { // reset ESC bitfield _esc_failure_hysteresis.set_state_and_update(false, time_now); - _status.flags.arm_escs = false; + _failure_detector_status.flags.arm_escs = false; } } @@ -237,7 +255,7 @@ void FailureDetector::updateImbalancedPropStatus() const float metric_lpf = _imbalanced_prop_lpf.update(metric); const bool is_imbalanced = metric_lpf > _param_fd_imb_prop_thr.get(); - _status.flags.imbalanced_prop = is_imbalanced; + _failure_detector_status.flags.imbalanced_prop = is_imbalanced; } } } @@ -255,10 +273,9 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, // First wait for some ESC telemetry that has the required fields. Before that happens, don't check this ESC // Then check - const hrt_abstime time_now = hrt_absolute_time(); - // Only check while armed if (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) { + const hrt_abstime now = hrt_absolute_time(); const int limited_esc_count = math::min(esc_status.esc_count, esc_status_s::CONNECTED_ESC_MAX); actuator_motors_s actuator_motors{}; @@ -282,9 +299,7 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, } // Check for telemetry timeout - const hrt_abstime telemetry_age = time_now - cur_esc_report.timestamp; - const bool esc_timed_out = telemetry_age > 300_ms; - + const bool esc_timed_out = now > cur_esc_report.timestamp + 300_ms; const bool esc_was_valid = _motor_failure_esc_valid_current_mask & (1 << i_esc); const bool esc_timeout_currently_flagged = _motor_failure_esc_timed_out_mask & (1 << i_esc); @@ -309,13 +324,13 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, esc_throttle = fabsf(actuator_motors.control[i_esc]); } - const bool throttle_above_threshold = esc_throttle > _param_fd_motor_throttle_thres.get(); + const bool throttle_above_threshold = esc_throttle > _param_fd_act_mot_thr.get(); const bool current_too_low = cur_esc_report.esc_current < esc_throttle * - _param_fd_motor_current2throttle_thres.get(); + _param_fd_act_mot_c2t.get(); if (throttle_above_threshold && current_too_low && !esc_timed_out) { if (_motor_failure_undercurrent_start_time[i_esc] == 0) { - _motor_failure_undercurrent_start_time[i_esc] = time_now; + _motor_failure_undercurrent_start_time[i_esc] = now; } } else { @@ -325,7 +340,7 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, } if (_motor_failure_undercurrent_start_time[i_esc] != 0 - && (time_now - _motor_failure_undercurrent_start_time[i_esc]) > _param_fd_motor_time_thres.get() * 1_ms + && now > (_motor_failure_undercurrent_start_time[i_esc] + (_param_fd_act_mot_tout.get() * 1_ms)) && (_motor_failure_esc_under_current_mask & (1 << i_esc)) == 0) { // Set flag _motor_failure_esc_under_current_mask |= (1 << i_esc); @@ -336,13 +351,13 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, bool critical_esc_failure = (_motor_failure_esc_timed_out_mask != 0 || _motor_failure_esc_under_current_mask != 0); - if (critical_esc_failure && !(_status.flags.motor)) { + if (critical_esc_failure && !(_failure_detector_status.flags.motor)) { // Add motor failure flag to bitfield - _status.flags.motor = true; + _failure_detector_status.flags.motor = true; - } else if (!critical_esc_failure && _status.flags.motor) { + } else if (!critical_esc_failure && _failure_detector_status.flags.motor) { // Reset motor failure flag - _status.flags.motor = false; + _failure_detector_status.flags.motor = false; } } else { // Disarmed @@ -352,6 +367,6 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, } _motor_failure_esc_under_current_mask = 0; - _status.flags.motor = false; + _failure_detector_status.flags.motor = false; } } diff --git a/src/modules/commander/failure_detector/FailureDetector.hpp b/src/modules/commander/failure_detector/FailureDetector.hpp index d84581ca5e..78b4861a7a 100644 --- a/src/modules/commander/failure_detector/FailureDetector.hpp +++ b/src/modules/commander/failure_detector/FailureDetector.hpp @@ -51,16 +51,18 @@ #include // subscriptions -#include #include +#include #include +#include +#include +#include #include #include #include #include #include #include -#include union failure_detector_status_u { struct { @@ -85,11 +87,9 @@ public: ~FailureDetector() = default; bool update(const vehicle_status_s &vehicle_status, const vehicle_control_mode_s &vehicle_control_mode); - const failure_detector_status_u &getStatus() const { return _status; } - const decltype(failure_detector_status_u::flags) &getStatusFlags() const { return _status.flags; } - float getImbalancedPropMetric() const { return _imbalanced_prop_lpf.getState(); } - uint16_t getMotorFailures() const { return _motor_failure_esc_timed_out_mask | _motor_failure_esc_under_current_mask; } - uint16_t getMotorStopMask() { return _failure_injector.getMotorStopMask(); } + const failure_detector_status_u &getStatus() const { return _failure_detector_status; } + + void publishStatus(); private: void updateAttitudeStatus(const vehicle_status_s &vehicle_status); @@ -98,7 +98,7 @@ private: void updateMotorStatus(const vehicle_status_s &vehicle_status, const esc_status_s &esc_status); void updateImbalancedPropStatus(); - failure_detector_status_u _status{}; + failure_detector_status_u _failure_detector_status{}; systemlib::Hysteresis _roll_failure_hysteresis{false}; systemlib::Hysteresis _pitch_failure_hysteresis{false}; @@ -124,6 +124,8 @@ private: uORB::Subscription _vehicle_imu_status_sub{ORB_ID(vehicle_imu_status)}; uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)}; + uORB::Publication _failure_detector_status_pub{ORB_ID(failure_detector_status)}; + FailureInjector _failure_injector; DEFINE_PARAMETERS( @@ -137,9 +139,9 @@ private: (ParamInt) _param_fd_imb_prop_thr, // Actuator failure - (ParamBool) _param_fd_actuator_en, - (ParamFloat) _param_fd_motor_throttle_thres, - (ParamFloat) _param_fd_motor_current2throttle_thres, - (ParamInt) _param_fd_motor_time_thres + (ParamBool) _param_fd_act_en, + (ParamFloat) _param_fd_act_mot_thr, + (ParamFloat) _param_fd_act_mot_c2t, + (ParamInt) _param_fd_act_mot_tout ) }; diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 7aeadeab55..fb6dfa0282 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -520,12 +520,36 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma const unsigned int calibration_points_maxcount = worker_data.calibration_sides * worker_data.calibration_points_perside; + uORB::SubscriptionMultiArray mag_sub{ORB_ID::sensor_mag}; + int mag_available_enabled_count = 0; + for (uint8_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { - uORB::SubscriptionData mag_sub{ORB_ID(sensor_mag), cur_mag}; + if (!mag_sub[cur_mag].advertised()) { + continue; + } - if (mag_sub.advertised() && (mag_sub.get().device_id != 0) && (mag_sub.get().timestamp > 0)) { - worker_data.calibration[cur_mag].set_device_id(mag_sub.get().device_id); + sensor_mag_s mag_data; + + if (!mag_sub[cur_mag].copy(&mag_data) || mag_data.device_id == 0) { + continue; + } + + int calibration_index = calibration::FindCurrentCalibrationIndex("MAG", mag_data.device_id); + + if (calibration_index >= 0) { + int priority = calibration::GetCalibrationParamInt32("MAG", "PRIO", calibration_index); + + if (priority != 0) { + ++mag_available_enabled_count; + } + + } else { + ++mag_available_enabled_count; + } + + if ((mag_data.device_id != 0) && (mag_data.timestamp > 0)) { + worker_data.calibration[cur_mag].set_device_id(mag_data.device_id); } // reset calibration index to match uORB numbering @@ -547,6 +571,11 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma } } + if (mag_available_enabled_count <= 0) { + calibration_log_critical(mavlink_log_pub, "Failed: No magnetometer available or enabled"); + return calibrate_return_error; + } + if (result == calibrate_return_ok) { result = calibrate_from_orientation(mavlink_log_pub, // uORB handle to write output worker_data.side_data_collected, // Sides to calibrate diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel.h b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel.h index d392246888..10d6b64cf4 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel.h +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_vel.h @@ -57,7 +57,7 @@ public: virtual ~ExternalVisionVel() = default; virtual bool fuseVelocity(estimator_aid_source3d_s &aid_src, float gate) { - _ekf.fuseLocalFrameVelocity(aid_src, aid_src.timestamp, _measurement, + _ekf.fuseLocalFrameVelocity(aid_src, _sample.time_us, _measurement, _measurement_var, gate); return aid_src.fused; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 1a8466c96d..80ef94b9fc 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -1019,6 +1019,7 @@ private: void resetQuatStateYaw(float yaw, float yaw_variance); void propagateQuatReset(const Quatf &quat_before_reset); void resetYawByFusion(float yaw, float yaw_variance); + void resetHorizontalVelocityToMatchYaw(float delta_yaw); HeightSensor _height_sensor_ref{HeightSensor::UNKNOWN}; PositionSensor _position_sensor_ref{PositionSensor::GNSS}; diff --git a/src/modules/ekf2/EKF/yaw_fusion.cpp b/src/modules/ekf2/EKF/yaw_fusion.cpp index fd723613dd..56bd1c1112 100644 --- a/src/modules/ekf2/EKF/yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/yaw_fusion.cpp @@ -140,6 +140,10 @@ void Ekf::resetQuatStateYaw(const float yaw, const float yaw_variance) _time_last_heading_fuse = _time_delayed_us; propagateQuatReset(quat_before_reset); + + // rotate horizontal velocity by the yaw change + const float yaw_diff = wrap_pi(yaw - getEulerYaw(quat_before_reset)); + resetHorizontalVelocityToMatchYaw(yaw_diff); } void Ekf::propagateQuatReset(const Quatf &quat_before_reset) @@ -189,4 +193,16 @@ void Ekf::resetYawByFusion(const float yaw, const float yaw_variance) fuseYaw(aid_src_status, H_YAW, reset_yaw); propagateQuatReset(quat_before_reset); + + resetHorizontalVelocityToMatchYaw(-aid_src_status.innovation); +} + +void Ekf::resetHorizontalVelocityToMatchYaw(const float delta_yaw) +{ + if (!isNorthEastAidingActive() && fabsf(delta_yaw) > 0.3f) { + const matrix::Dcm2f R_yaw(delta_yaw); + const Vector2f vel_rotated = R_yaw * Vector2f(_state.vel); + const float vel_var = fmaxf(P(State::vel.idx, State::vel.idx), P(State::vel.idx + 1, State::vel.idx + 1)); + resetHorizontalVelocityTo(vel_rotated, vel_var); + } } diff --git a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv index 2d7f7c2aca..35f3071e4e 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -67,22 +67,22 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0057,-0.052,0,0,-4.9e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-4.9e+02,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6590000,1,-0.0093,-0.011,0.00016,0.0037,0.0057,-0.099,0,0,-4.9e+02,-0.0014,-0.0057,-7.6e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6690000,1,-0.0093,-0.011,9.4e-05,0.0046,0.0053,-0.076,0,0,-4.9e+02,-0.0014,-0.0057,-7.6e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6790000,0.71,0.0012,-0.014,0.71,0.0049,0.0052,-0.11,0,0,-4.9e+02,-0.0014,-0.0057,-7.5e-05,0,0,-7e-05,0.21,8e-05,0.43,3.5e-05,0.00033,-0.0024,0,0,-4.9e+02,0.0013,0.0013,0.053,0.18,0.18,0.6,0.11,0.11,0.2,7.8e-05,7.7e-05,2.4e-06,0.04,0.04,0.04,0.0015,0.0012,0.0014,0.0018,0.0015,0.0014,1,1,1.7 -6890000,0.71,0.0013,-0.014,0.7,0.00052,0.0065,-0.12,0,0,-4.9e+02,-0.0015,-0.0057,-7.6e-05,0,0,-9.8e-05,0.21,1.3e-05,0.43,6.1e-07,0.00089,-0.00086,0,0,-4.9e+02,0.0013,0.0013,0.047,0.21,0.21,0.46,0.13,0.14,0.18,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.00065,0.0013,0.0017,0.0014,0.0013,1,1,1.8 -6990000,0.71,0.0013,-0.014,0.71,-0.00025,0.0048,-0.12,0,0,-4.9e+02,-0.0014,-0.0057,-7.7e-05,-2.8e-05,-0.00025,-0.00041,0.21,-3.9e-05,0.43,-0.00025,0.00056,-0.00042,0,0,-4.9e+02,0.0013,0.0013,0.044,0.23,0.24,0.36,0.17,0.17,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00044,0.0013,0.0017,0.0013,0.0013,1,1,1.8 -7090000,0.71,0.0012,-0.014,0.71,-0.00081,0.0013,-0.13,0,0,-4.9e+02,-0.0014,-0.0057,-7.9e-05,0.0002,-0.00056,-0.00078,0.21,-3.8e-05,0.43,-0.00038,0.00025,-0.00041,0,0,-4.9e+02,0.0013,0.0013,0.043,0.27,0.27,0.29,0.2,0.21,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00034,0.0013,0.0017,0.0013,0.0013,1,1,1.8 -7190000,0.71,0.0013,-0.014,0.71,-0.0025,0.0021,-0.15,0,0,-4.9e+02,-0.0014,-0.0057,-7.8e-05,0.00014,-0.0005,-0.00057,0.21,-3.1e-05,0.43,-0.00036,0.00035,-0.00045,0,0,-4.9e+02,0.0013,0.0013,0.042,0.3,0.31,0.24,0.25,0.25,0.15,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00027,0.0013,0.0016,0.0013,0.0013,1,1,1.8 -7290000,0.71,0.0015,-0.014,0.71,-0.0044,0.01,-0.15,0,0,-4.9e+02,-0.0015,-0.0057,-7.5e-05,-0.00022,-0.00021,-0.0012,0.21,-3.3e-05,0.43,-0.00035,0.00077,-0.00038,0,0,-4.9e+02,0.0013,0.0013,0.042,0.34,0.35,0.2,0.3,0.31,0.14,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00023,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7390000,0.71,0.0016,-0.014,0.71,-0.0037,0.015,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.3e-05,-0.00029,-4.1e-05,-0.0014,0.21,-2.9e-05,0.43,-0.00035,0.00086,-0.00031,0,0,-4.9e+02,0.0013,0.0013,0.041,0.38,0.39,0.18,0.37,0.37,0.13,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0002,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7490000,0.71,0.0015,-0.014,0.71,-0.0038,0.012,-0.16,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00019,-7.7e-05,-0.0022,0.21,-2.2e-05,0.43,-0.00032,0.00079,-0.00042,0,0,-4.9e+02,0.0013,0.0013,0.041,0.43,0.43,0.15,0.44,0.45,0.12,7.6e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00017,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7590000,0.71,0.0017,-0.014,0.71,-0.0034,0.021,-0.17,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00024,0.0002,-0.003,0.21,-2.1e-05,0.43,-0.00035,0.00087,-0.00026,0,0,-4.9e+02,0.0013,0.0013,0.04,0.48,0.48,0.14,0.53,0.53,0.12,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00015,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7690000,0.71,0.0017,-0.014,0.71,-0.0046,0.018,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00025,0.00018,-0.0051,0.21,-1.8e-05,0.43,-0.00033,0.00084,-0.00033,0,0,-4.9e+02,0.0014,0.0013,0.04,0.53,0.53,0.13,0.63,0.63,0.11,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00014,0.0013,0.0016,0.0013,0.0013,1,1,2 -7790000,0.71,0.0017,-0.014,0.71,-0.011,0.017,-0.16,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00037,5.8e-05,-0.0071,0.21,-1.7e-05,0.43,-0.00034,0.00079,-0.00038,0,0,-4.9e+02,0.0014,0.0013,0.04,0.58,0.58,0.12,0.74,0.74,0.11,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00013,0.0013,0.0016,0.0013,0.0013,1,1,2 -7890000,0.71,0.0017,-0.014,0.71,-0.011,0.022,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.2e-05,-0.00039,0.0002,-0.0096,0.21,-1.6e-05,0.43,-0.00035,0.00079,-0.0003,0,0,-4.9e+02,0.0014,0.0014,0.04,0.64,0.63,0.11,0.87,0.86,0.1,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00012,0.0013,0.0016,0.0013,0.0013,1,1,2 -7990000,0.71,0.0017,-0.014,0.71,-0.0091,0.023,-0.16,0,0,-4.9e+02,-0.0016,-0.0056,-7.1e-05,-0.00038,0.00028,-0.011,0.21,-1.4e-05,0.43,-0.00035,0.00086,-0.00038,0,0,-4.9e+02,0.0014,0.0014,0.04,0.7,0.68,0.1,1,0.99,0.099,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00011,0.0013,0.0016,0.0013,0.0013,1,1,2 -8090000,0.71,0.0017,-0.014,0.71,-0.0051,0.025,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-6.9e-05,-0.00031,0.00035,-0.011,0.21,-1.2e-05,0.43,-0.00034,0.0009,-0.00035,0,0,-4.9e+02,0.0014,0.0014,0.04,0.76,0.74,0.1,1.2,1.1,0.097,7e-05,7.3e-05,2.4e-06,0.04,0.04,0.037,0.0013,0.0001,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8190000,0.71,0.0018,-0.014,0.71,-0.014,0.029,-0.18,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00045,0.00036,-0.013,0.21,-1.2e-05,0.43,-0.00036,0.00085,-0.00036,0,0,-4.9e+02,0.0014,0.0014,0.04,0.82,0.79,0.099,1.4,1.3,0.094,6.8e-05,7.2e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8290000,0.71,0.0017,-0.014,0.71,-0.018,0.023,-0.17,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00057,0.00031,-0.017,0.21,-1e-05,0.43,-0.00032,0.00079,-0.00034,0,0,-4.9e+02,0.0014,0.0014,0.039,0.88,0.84,0.097,1.6,1.5,0.091,6.6e-05,7.1e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +6790000,0.71,0.0012,-0.014,0.71,-0.0056,0.0034,-0.11,0,0,-4.9e+02,-0.0014,-0.0057,-7.5e-05,0,0,-7e-05,0.21,8e-05,0.43,3.5e-05,0.00033,-0.0024,0,0,-4.9e+02,0.0013,0.0013,0.053,0.18,0.18,0.6,0.1,0.1,0.2,7.8e-05,7.7e-05,2.4e-06,0.04,0.04,0.04,0.0015,0.0012,0.0014,0.0018,0.0015,0.0014,1,1,1.7 +6890000,0.71,0.0013,-0.014,0.7,-0.0076,0.0039,-0.12,0,0,-4.9e+02,-0.0015,-0.0057,-7.6e-05,0,0,-9.8e-05,0.21,1.3e-05,0.43,6.1e-07,0.00089,-0.00086,0,0,-4.9e+02,0.0013,0.0013,0.047,0.18,0.18,0.46,0.1,0.1,0.18,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.00065,0.0013,0.0017,0.0014,0.0013,1,1,1.8 +6990000,0.71,0.0013,-0.014,0.71,-0.0078,0.0042,-0.12,0,0,-4.9e+02,-0.0014,-0.0057,-7.7e-05,-2.8e-05,-0.00025,-0.00041,0.21,-3.9e-05,0.43,-0.00025,0.00056,-0.00042,0,0,-4.9e+02,0.0013,0.0013,0.044,0.19,0.19,0.36,0.11,0.11,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00044,0.0013,0.0017,0.0013,0.0013,1,1,1.8 +7090000,0.71,0.0012,-0.014,0.71,-0.0084,0.0028,-0.13,0,0,-4.9e+02,-0.0014,-0.0057,-7.9e-05,0.0002,-0.00056,-0.00078,0.21,-3.8e-05,0.43,-0.00038,0.00025,-0.00041,0,0,-4.9e+02,0.0013,0.0013,0.043,0.2,0.2,0.29,0.12,0.12,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00034,0.0013,0.0017,0.0013,0.0013,1,1,1.8 +7190000,0.71,0.0013,-0.014,0.71,-0.01,0.0027,-0.15,0,0,-4.9e+02,-0.0014,-0.0057,-7.8e-05,0.00014,-0.0005,-0.00057,0.21,-3.1e-05,0.43,-0.00036,0.00035,-0.00045,0,0,-4.9e+02,0.0013,0.0013,0.042,0.21,0.21,0.24,0.14,0.14,0.15,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00027,0.0013,0.0016,0.0013,0.0013,1,1,1.8 +7290000,0.71,0.0015,-0.014,0.71,-0.012,0.0052,-0.15,0,0,-4.9e+02,-0.0015,-0.0057,-7.5e-05,-0.00022,-0.00021,-0.0012,0.21,-3.3e-05,0.43,-0.00035,0.00077,-0.00038,0,0,-4.9e+02,0.0013,0.0013,0.042,0.22,0.23,0.2,0.16,0.16,0.14,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00023,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7390000,0.71,0.0016,-0.014,0.71,-0.012,0.0081,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.3e-05,-0.00029,-4.1e-05,-0.0014,0.21,-2.9e-05,0.43,-0.00035,0.00086,-0.00031,0,0,-4.9e+02,0.0013,0.0013,0.041,0.24,0.25,0.18,0.18,0.18,0.13,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0002,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7490000,0.71,0.0015,-0.014,0.71,-0.013,0.0071,-0.16,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00019,-7.7e-05,-0.0022,0.21,-2.2e-05,0.43,-0.00032,0.00079,-0.00042,0,0,-4.9e+02,0.0013,0.0013,0.041,0.27,0.27,0.15,0.21,0.21,0.12,7.6e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00017,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7590000,0.71,0.0017,-0.014,0.71,-0.014,0.012,-0.17,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00024,0.0002,-0.003,0.21,-2.1e-05,0.43,-0.00035,0.00087,-0.00026,0,0,-4.9e+02,0.0013,0.0013,0.04,0.29,0.29,0.14,0.25,0.25,0.12,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00015,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7690000,0.71,0.0017,-0.014,0.71,-0.015,0.011,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00025,0.00018,-0.0051,0.21,-1.8e-05,0.43,-0.00033,0.00084,-0.00033,0,0,-4.9e+02,0.0014,0.0013,0.04,0.32,0.32,0.13,0.29,0.29,0.11,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00014,0.0013,0.0016,0.0013,0.0013,1,1,2 +7790000,0.71,0.0017,-0.014,0.71,-0.019,0.011,-0.16,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00037,5.8e-05,-0.0071,0.21,-1.7e-05,0.43,-0.00034,0.00079,-0.00038,0,0,-4.9e+02,0.0014,0.0013,0.04,0.36,0.36,0.12,0.34,0.34,0.11,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00013,0.0013,0.0016,0.0013,0.0013,1,1,2 +7890000,0.71,0.0017,-0.014,0.71,-0.02,0.015,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.2e-05,-0.00039,0.0002,-0.0096,0.21,-1.6e-05,0.43,-0.00035,0.00079,-0.0003,0,0,-4.9e+02,0.0014,0.0014,0.04,0.39,0.39,0.11,0.4,0.4,0.1,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00012,0.0013,0.0016,0.0013,0.0013,1,1,2 +7990000,0.71,0.0017,-0.014,0.71,-0.02,0.017,-0.16,0,0,-4.9e+02,-0.0016,-0.0056,-7.1e-05,-0.00038,0.00028,-0.011,0.21,-1.4e-05,0.43,-0.00035,0.00086,-0.00038,0,0,-4.9e+02,0.0014,0.0014,0.04,0.43,0.43,0.1,0.47,0.47,0.099,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00011,0.0013,0.0016,0.0013,0.0013,1,1,2 +8090000,0.71,0.0017,-0.014,0.71,-0.018,0.019,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-6.9e-05,-0.00031,0.00035,-0.011,0.21,-1.2e-05,0.43,-0.00034,0.0009,-0.00035,0,0,-4.9e+02,0.0014,0.0014,0.04,0.47,0.47,0.1,0.55,0.55,0.097,7e-05,7.3e-05,2.4e-06,0.04,0.04,0.037,0.0013,0.0001,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8190000,0.71,0.0018,-0.014,0.71,-0.024,0.021,-0.18,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00045,0.00036,-0.013,0.21,-1.2e-05,0.43,-0.00036,0.00085,-0.00036,0,0,-4.9e+02,0.0014,0.0014,0.04,0.52,0.51,0.099,0.64,0.64,0.094,6.8e-05,7.2e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8290000,0.71,0.0017,-0.014,0.71,-0.027,0.018,-0.17,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00057,0.00031,-0.017,0.21,-1e-05,0.43,-0.00032,0.00079,-0.00034,0,0,-4.9e+02,0.0014,0.0014,0.039,0.56,0.55,0.097,0.74,0.74,0.091,6.6e-05,7.1e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 8390000,0.71,0.0017,-0.014,0.71,-0.0012,0.00048,-0.17,0,0,-4.9e+02,-0.0015,-0.0056,-7.1e-05,-0.00052,0.00039,-0.021,0.21,-9.6e-06,0.43,-0.00031,0.00084,-0.00031,0,0,-4.9e+02,0.0014,0.0014,0.039,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,7e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 8490000,0.71,0.0017,-0.014,0.71,-0.0029,0.0026,-0.17,0,0,-4.9e+02,-0.0015,-0.0056,-7.2e-05,-0.00052,0.00039,-0.025,0.21,-9.3e-06,0.43,-0.00032,0.0008,-0.00028,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.089,6.2e-05,6.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 8590000,0.71,0.0022,-0.014,0.71,-0.00042,0.00097,-0.17,0,0,-4.9e+02,-0.0017,-0.0057,-7e-05,-0.00052,0.00039,-0.029,0.21,-1.2e-05,0.43,-0.00043,0.00076,-0.00028,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.088,6e-05,6.8e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index 3b9312e0f6..5a479f0ba8 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -69,10 +69,10 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6690000,1,-0.0088,-0.011,0.00052,0.0022,0.018,-0.044,0,0,-4.9e+02,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6790000,1,-0.0089,-0.011,0.00049,0.003,0.016,-0.043,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6890000,1,-0.0087,-0.011,0.0004,0.0023,0.016,-0.039,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -6990000,0.98,-0.0067,-0.012,0.18,0.0025,0.011,-0.037,0,0,-4.9e+02,-0.0015,-0.0056,-9.4e-05,0,0,-0.13,0.21,-0.00049,0.44,0.00044,-0.0011,0.00036,0,0,-4.9e+02,0.0012,0.0012,0.054,0.16,0.17,0.031,0.1,0.1,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0015,0.0012,0.0014,0.0015,0.0018,0.0014,1,1,1.8 -7090000,0.98,-0.0065,-0.012,0.18,0.00012,0.018,-0.038,0,0,-4.9e+02,-0.0016,-0.0056,-9.4e-05,0,0,-0.13,0.2,-0.00015,0.44,-0.00019,-0.00047,0.00017,0,0,-4.9e+02,0.0013,0.0013,0.048,0.18,0.19,0.03,0.13,0.13,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0024,0.0014,0.00067,0.0013,0.0014,0.0016,0.0013,1,1,1.8 -7190000,0.98,-0.0065,-0.012,0.18,-6.6e-05,0.019,-0.037,0,0,-4.9e+02,-0.0016,-0.0056,-9.4e-05,-6.3e-05,3.4e-05,-0.13,0.2,-0.0001,0.43,-0.00018,-0.00052,-3.3e-06,0,0,-4.9e+02,0.0013,0.0013,0.046,0.21,0.21,0.029,0.16,0.16,0.065,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00044,0.0013,0.0014,0.0016,0.0013,1,1,1.8 -7290000,0.98,-0.0064,-0.012,0.18,-0.00068,0.024,-0.034,0,0,-4.9e+02,-0.0016,-0.0057,-9.4e-05,-0.0003,0.00019,-0.13,0.2,-7.3e-05,0.43,-0.00037,-0.00044,6.5e-05,0,0,-4.9e+02,0.0014,0.0013,0.044,0.24,0.24,0.028,0.19,0.19,0.064,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00033,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +6990000,0.98,-0.0067,-0.012,0.18,-0.0032,0.013,-0.037,0,0,-4.9e+02,-0.0015,-0.0056,-9.4e-05,0,0,-0.13,0.21,-0.00049,0.44,0.00044,-0.0011,0.00036,0,0,-4.9e+02,0.0012,0.0012,0.054,0.16,0.16,0.031,0.097,0.097,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0015,0.0012,0.0014,0.0015,0.0018,0.0014,1,1,1.8 +7090000,0.98,-0.0065,-0.012,0.18,-0.0041,0.017,-0.038,0,0,-4.9e+02,-0.0016,-0.0056,-9.4e-05,0,0,-0.13,0.2,-0.00015,0.44,-0.00019,-0.00047,0.00017,0,0,-4.9e+02,0.0013,0.0013,0.048,0.16,0.16,0.03,0.1,0.1,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0024,0.0014,0.00067,0.0013,0.0014,0.0016,0.0013,1,1,1.8 +7190000,0.98,-0.0065,-0.012,0.18,-0.0046,0.019,-0.037,0,0,-4.9e+02,-0.0016,-0.0056,-9.4e-05,-6.3e-05,3.4e-05,-0.13,0.2,-0.0001,0.43,-0.00018,-0.00052,-3.3e-06,0,0,-4.9e+02,0.0013,0.0013,0.046,0.16,0.16,0.029,0.11,0.11,0.065,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00044,0.0013,0.0014,0.0016,0.0013,1,1,1.8 +7290000,0.98,-0.0064,-0.012,0.18,-0.0041,0.023,-0.034,0,0,-4.9e+02,-0.0016,-0.0057,-9.4e-05,-0.0003,0.00019,-0.13,0.2,-7.3e-05,0.43,-0.00037,-0.00044,6.5e-05,0,0,-4.9e+02,0.0014,0.0013,0.044,0.17,0.17,0.028,0.12,0.12,0.064,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00033,0.0013,0.0014,0.0016,0.0013,1,1,1.9 7390000,0.98,-0.0063,-0.012,0.18,-0.0015,0.00095,-0.032,0,0,-4.9e+02,-0.0016,-0.0057,-9.4e-05,-0.00036,0.00036,-0.13,0.2,-5.7e-05,0.43,-0.00048,-0.0004,8.9e-05,0,0,-4.9e+02,0.0014,0.0014,0.043,25,25,0.027,1e+02,1e+02,0.064,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00027,0.0013,0.0014,0.0016,0.0013,1,1,1.9 7490000,0.98,-0.0063,-0.012,0.18,0.00098,0.0035,-0.026,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-4.5e-05,0.43,-0.00042,-0.00038,-7.8e-05,0,0,-4.9e+02,0.0015,0.0014,0.043,25,25,0.026,1e+02,1e+02,0.063,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00022,0.0013,0.0014,0.0016,0.0013,1,1,1.9 7590000,0.98,-0.0064,-0.012,0.18,0.0021,0.0061,-0.023,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-3.8e-05,0.43,-0.00035,-0.00039,-8.8e-06,0,0,-4.9e+02,0.0015,0.0015,0.042,25,25,0.025,51,51,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00019,0.0013,0.0014,0.0016,0.0013,1,1,1.9 diff --git a/src/modules/ekf2/test/test_EKF_mag.cpp b/src/modules/ekf2/test/test_EKF_mag.cpp index ca4f440c62..32fccea707 100644 --- a/src/modules/ekf2/test/test_EKF_mag.cpp +++ b/src/modules/ekf2/test/test_EKF_mag.cpp @@ -214,3 +214,60 @@ TEST_F(EkfMagTest, suddenInclinationChange) EXPECT_FALSE(_ekf_wrapper.isIntendingMagHeadingFusion()); EXPECT_FALSE(_ekf_wrapper.isIntendingMag3DFusion()); } + +TEST_F(EkfMagTest, velocityRotationOnYawReset) +{ + // GIVEN: Mag fusion is active and vehicle is flying with airspeed + const float initial_mag_heading = M_PI_F / 4.f; // 45 degrees + Vector3f mag_data(0.2f * cosf(initial_mag_heading), -0.2f * sinf(initial_mag_heading), 0.4f); + _sensor_simulator._mag.setData(mag_data); + _sensor_simulator.runSeconds(_init_duration_s); + + _ekf->set_in_air_status(true); + _ekf->set_vehicle_at_rest(false); + _ekf->set_is_fixed_wing(true); + + const float airspeed_body = 15.0f; // 15 m/s airspeed in body X direction + _sensor_simulator.startAirspeedSensor(); + _sensor_simulator._airspeed.setData(airspeed_body, airspeed_body); + + _ekf_wrapper.enableBetaFusion(); + _sensor_simulator.runSeconds(3); + + // initial state + const Vector3f vel_before = _ekf->getVelocity(); + const float yaw_before = _ekf_wrapper.getYawAngle(); + const matrix::Dcm2f R_ned_to_body_before(-yaw_before); + const Vector2f vel_body_before = R_ned_to_body_before * Vector2f(vel_before); + + // WHEN: Mag heading suddenly changes by more than 0.3 rad (90 degrees) + const float new_mag_heading = yaw_before + M_PI_F / 2.f; + mag_data = Vector3f(0.2f * cosf(new_mag_heading), -0.2f * sinf(new_mag_heading), 0.4f); + _sensor_simulator._mag.setData(mag_data); + _sensor_simulator.runSeconds(8.f); + + // THEN: the yaw should be reset to the new mag heading + const float yaw_after = _ekf_wrapper.getYawAngle(); + EXPECT_NEAR(yaw_after, new_mag_heading, radians(5.0f)) + << "Yaw after: " << degrees(yaw_after) + << " Expected: " << degrees(new_mag_heading); + + // AND: the NED velocity should be rotated to maintain consistent body-frame velocity + const Vector3f vel_after = _ekf->getVelocity(); + + // Calculate body-frame velocity after reset + const matrix::Dcm2f R_ned_to_body_after(-yaw_after); + const Vector2f vel_body_after = R_ned_to_body_after * Vector2f(vel_after); + + // Body-frame velocity should remain approximately the same + EXPECT_NEAR(vel_body_before(0), vel_body_after(0), 1.0f) + << "Body-frame velocity X before: " << vel_body_before(0) + << " after: " << vel_body_after(0); + EXPECT_NEAR(vel_body_before(1), vel_body_after(1), 1.0f) + << "Body-frame velocity Y before: " << vel_body_before(1) + << " after: " << vel_body_after(1); + + // Verify that the yaw change was sufficient to trigger velocity rotation (> 0.3 rad) + const float yaw_change = fabsf(wrap_pi(yaw_after - yaw_before)); + EXPECT_GT(yaw_change, 0.3f) << "Yaw change: " << degrees(yaw_change) << " deg"; +} diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index 2eceae9353..47807bffb6 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -612,6 +612,7 @@ State FlightTaskAuto::_getCurrentState() const Vector3f u_prev_to_target = (_triplet_target - _triplet_prev_wp).unit_or_zero(); const Vector3f prev_to_pos = _position - _triplet_prev_wp; const Vector3f pos_to_target = _triplet_target - _position; + // Calculate the closest point to the vehicle position on the line prev_wp - target _closest_pt = _triplet_prev_wp + u_prev_to_target * (prev_to_pos * u_prev_to_target); @@ -629,10 +630,9 @@ State FlightTaskAuto::_getCurrentState() // Previous is in front return_state = State::previous_infront; - } else if ((_position - _closest_pt).longerThan(_target_acceptance_radius)) { + } else if (_type != WaypointType::land && (_position - _closest_pt).longerThan(_target_acceptance_radius)) { // Vehicle too far from the track return_state = State::offtrack; - } return return_state; diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp index 73df2a8683..9c5647f1a5 100644 --- a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp @@ -827,6 +827,12 @@ void FwLateralLongitudinalControl::updateLongitudinalControlConfiguration(const } else { _long_configuration.sink_rate_target = _param_sinkrate_target.get(); } + + if (PX4_ISFINITE(configuration_in.speed_weight)) { + _long_configuration.speed_weight = math::constrain(configuration_in.speed_weight, 0.f, 2.f); + } else { + _long_configuration.speed_weight = _param_t_spdweight.get(); + } } float FwLateralLongitudinalControl::getLoadFactor() const diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp index 590054ae89..87b94b1bf3 100644 --- a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp @@ -157,6 +157,7 @@ private: (ParamFloat) _param_fw_t_vert_acc, (ParamFloat) _param_ste_rate_time_const, (ParamFloat) _param_seb_rate_ff, + (ParamFloat) _param_t_spdweight, (ParamFloat) _param_speed_standard_dev, (ParamFloat) _param_speed_rate_standard_dev, (ParamFloat) _param_process_noise_standard_dev, diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index 45aa9b1cc8..4701863c07 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -92,6 +92,7 @@ target_sources(mavlink_c target_include_directories(mavlink_c INTERFACE ${MAVLINK_LIBRARY_DIR} + ${MAVLINK_LIBRARY_DIR}/../ ${MAVLINK_LIBRARY_DIR}/${CONFIG_MAVLINK_DIALECT} ${MAVLINK_LIBRARY_DIR}/${MAVLINK_DIALECT_UAVIONIX} ) diff --git a/src/modules/mavlink/mavlink b/src/modules/mavlink/mavlink index 33af200d25..342530b83c 160000 --- a/src/modules/mavlink/mavlink +++ b/src/modules/mavlink/mavlink @@ -1 +1 @@ -Subproject commit 33af200d25ec6f0925b49b1ba82bbf1294ea5f72 +Subproject commit 342530b83c215654f12988ab682111281d2e71f0 diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 3b4c39a73e..0d5b771761 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -187,12 +187,7 @@ Mavlink::mavlink_update_parameters() { updateParams(); - int32_t proto = _param_mav_proto_ver.get(); - - if (_protocol_version_switch != proto) { - _protocol_version_switch = proto; - set_proto_version(proto); - } + setProtocolVersion(_param_mav_proto_ver.get()); if (_param_mav_type.get() < 0 || _param_mav_type.get() >= MAV_TYPE_ENUM_END) { _param_mav_type.set(0); @@ -277,16 +272,13 @@ Mavlink::set_instance_id() return false; } -void -Mavlink::set_proto_version(unsigned version) +void Mavlink::setProtocolVersion(uint8_t version) { - if ((version == 1 || version == 0) && - ((_protocol_version_switch == 0) || (_protocol_version_switch == 1))) { + if (version == 1) { get_status()->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; _protocol_version = 1; - } else if (version == 2 && - ((_protocol_version_switch == 0) || (_protocol_version_switch == 2))) { + } else { get_status()->flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1); _protocol_version = 2; } @@ -1156,13 +1148,7 @@ Mavlink::send_protocol_version() //memcpy(&msg.spec_version_hash, &mavlink_spec_git_version_binary, sizeof(msg.spec_version_hash)); memcpy(&msg.library_version_hash, &mavlink_lib_git_version_binary, sizeof(msg.library_version_hash)); - // Switch to MAVLink 2 - int curr_proto_ver = _protocol_version; - set_proto_version(2); - // Send response - if it passes through the link its fine to use MAVLink 2 mavlink_msg_protocol_version_send_struct(get_channel(), &msg); - // Reset to previous value - set_proto_version(curr_proto_ver); } int @@ -3055,7 +3041,7 @@ Mavlink::display_status() } printf("\tForwarding: %s\n", get_forwarding_on() ? "On" : "Off"); - printf("\tMAVLink version: %" PRId32 "\n", _protocol_version); + printf("\tMAVLink version: %" PRId8 "\n", _protocol_version); printf("\ttransport protocol: "); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 0379bd2c11..cdf079f9db 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -109,22 +109,10 @@ class Mavlink final : public ModuleParams { public: - /** - * Constructor - */ Mavlink(); - - /** - * Destructor, also kills the mavlinks task. - */ ~Mavlink(); - /** - * Start the mavlink task. - * - * @return OK on success. - */ - static int start(int argc, char *argv[]); + static int start(int argc, char *argv[]); bool running() const { return _task_running.load(); } bool should_exit() const { return _task_should_exit.load(); } @@ -134,70 +122,40 @@ public: _receiver.request_stop(); } - /** - * Display the mavlink status. - */ - void display_status(); + void display_status(); + void display_status_streams(); - /** - * Display the status of all enabled streams. - */ - void display_status_streams(); + static int stop_command(int argc, char *argv[]); + static int stream_command(int argc, char *argv[]); - static int stop_command(int argc, char *argv[]); - static int stream_command(int argc, char *argv[]); + static int instance_count(); + static Mavlink *new_instance(); + static Mavlink *get_instance_for_device(const char *device_name); - static int instance_count(); + mavlink_message_t *get_buffer() { return &_mavlink_buffer; } + mavlink_status_t *get_status() { return &_mavlink_status; } - static Mavlink *new_instance(); + void setProtocolVersion(uint8_t version); + uint8_t getProtocolVersion() const { return _protocol_version; }; - static Mavlink *get_instance_for_device(const char *device_name); + static int destroy_all_instances(); + static int get_status_all_instances(bool show_streams_status); + static bool serial_instance_exists(const char *device_name, Mavlink *self); - mavlink_message_t *get_buffer() { return &_mavlink_buffer; } + static bool component_was_seen(int system_id, int component_id, Mavlink &self); + static void forward_message(const mavlink_message_t *msg, Mavlink *self); - mavlink_status_t *get_status() { return &_mavlink_status; } + bool check_events() const { return _should_check_events.load(); } + void check_events_enable() { _should_check_events.store(true); } + void check_events_disable() { _should_check_events.store(false); } - /** - * Set the MAVLink version - * - * Currently supporting v1 and v2 - * - * @param version MAVLink version - */ - void set_proto_version(unsigned version); + bool sending_parameters() const { return _sending_parameters.load(); } + void set_sending_parameters(bool sending) { _sending_parameters.store(sending); } - static int destroy_all_instances(); + int get_uart_fd() const { return _uart_fd; } - static int get_status_all_instances(bool show_streams_status); - - static bool serial_instance_exists(const char *device_name, Mavlink *self); - - static bool component_was_seen(int system_id, int component_id, Mavlink &self); - - static void forward_message(const mavlink_message_t *msg, Mavlink *self); - - bool check_events() const { return _should_check_events.load(); } - void check_events_enable() { _should_check_events.store(true); } - void check_events_disable() { _should_check_events.store(false); } - - bool sending_parameters() const { return _sending_parameters.load(); } - void set_sending_parameters(bool sending) { _sending_parameters.store(sending); } - - int get_uart_fd() const { return _uart_fd; } - - /** - * Get the MAVLink system id. - * - * @return The system ID of this vehicle - */ - int get_system_id() const { return mavlink_system.sysid; } - - /** - * Get the MAVLink component id. - * - * @return The component ID of this vehicle - */ - int get_component_id() const { return mavlink_system.compid; } + int get_system_id() const { return mavlink_system.sysid; } + int get_component_id() const { return mavlink_system.compid; } const char *_device_name{DEFAULT_DEVICE_NAME}; @@ -620,8 +578,7 @@ private: uint64_t _last_write_success_time{0}; uint64_t _last_write_try_time{0}; uint64_t _mavlink_start_time{0}; - int32_t _protocol_version_switch{-1}; - int32_t _protocol_version{0}; + uint8_t _protocol_version = 0; ///< after initialization the only values are 1 and 2 unsigned _bytes_tx{0}; unsigned _bytes_txerr{0}; diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index a391b0e38e..60841a34e6 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2015-2018 PX4 Development Team. All rights reserved. + * Copyright (c) 2015-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -38,6 +38,7 @@ * @author Anton Babushkin * @author Lorenz Meier * @author Beat Kueng + * @author Hamish Willee */ #include @@ -116,6 +117,9 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) _send_all_index = -1; } + /* Error report that _HASH_CHECK parameter is read-only */ + send_error(MAV_PARAM_ERROR_READ_ONLY, name, -1, msg->sysid, msg->compid); + /* No other action taken, return */ return; } @@ -125,10 +129,17 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) if (param == PARAM_INVALID) { PX4_ERR("unknown param: %s", name); + send_error(MAV_PARAM_ERROR_DOES_NOT_EXIST, name, -1, msg->sysid, msg->compid); + + } else if (!((set.param_type == MAV_PARAM_TYPE_INT32) || (set.param_type == MAV_PARAM_TYPE_REAL32))) { + PX4_ERR("param type unsupported: %s", name); + send_error(MAV_PARAM_ERROR_TYPE_UNSUPPORTED, name, -1, msg->sysid, msg->compid); } else if (!((param_type(param) == PARAM_TYPE_INT32 && set.param_type == MAV_PARAM_TYPE_INT32) || (param_type(param) == PARAM_TYPE_FLOAT && set.param_type == MAV_PARAM_TYPE_REAL32))) { PX4_ERR("param types mismatch param: %s", name); + send_error(MAV_PARAM_ERROR_TYPE_MISMATCH, name, -1, msg->sysid, msg->compid); + } else { // According to the mavlink spec we should always acknowledge a write operation. @@ -200,18 +211,32 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) /* enforce null termination */ name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; /* attempt to find parameter and send it */ - send_param(param_find_no_notification(name)); + + const int result = send_param(param_find_no_notification(name)); + + if (result == 1) { + PX4_ERR("Unknown param name: %s", name); + send_error(MAV_PARAM_ERROR_DOES_NOT_EXIST, name, -1, msg->sysid, msg->compid); + + } else if (result == 2) { + PX4_ERR("Failed loading param from storage: %s", name); + send_error(MAV_PARAM_ERROR_READ_FAIL, name, -1, msg->sysid, msg->compid); + } } } else { + /* when index is >= 0, send this parameter again */ int ret = send_param(param_for_used_index(req_read.param_index)); if (ret == 1) { - PX4_ERR("unknown param ID: %i", req_read.param_index); + PX4_ERR("Unknown param index: %i", req_read.param_index); + send_error(MAV_PARAM_ERROR_DOES_NOT_EXIST, nullptr, req_read.param_index, msg->sysid, msg->compid); } else if (ret == 2) { - PX4_ERR("failed loading param from storage ID: %i", req_read.param_index); + PX4_ERR("Failed loading param from storage index: %i", req_read.param_index); + send_error(MAV_PARAM_ERROR_READ_FAIL, nullptr, req_read.param_index, msg->sysid, msg->compid); + } } } @@ -474,6 +499,7 @@ MavlinkParametersManager::send_one() int MavlinkParametersManager::send_param(param_t param, int component_id) { + if (param == PARAM_INVALID) { return 1; } @@ -549,7 +575,7 @@ MavlinkParametersManager::send_param(param_t param, int component_id) mavlink_msg_param_value_send_struct(_mavlink.get_channel(), &msg); } else { - // Re-pack the message with a different component ID + // Re-pack the message with a passed component ID mavlink_message_t mavlink_packet; mavlink_msg_param_value_encode_chan(mavlink_system.sysid, component_id, _mavlink.get_channel(), &mavlink_packet, &msg); _mavlink_resend_uart(_mavlink.get_channel(), &mavlink_packet); @@ -560,6 +586,57 @@ MavlinkParametersManager::send_param(param_t param, int component_id) return 0; } + +int MavlinkParametersManager:: send_error(MAV_PARAM_ERROR error, const char *param_id, const int param_index, + const int target_sysid, const int target_compid, + int component_id) +{ + /* no free TX buf to send this param error message */ + if (_mavlink.get_free_tx_buf() < MAVLINK_MSG_ID_PARAM_ERROR_LEN) { + return 1; + } + + mavlink_param_error_t msg; + msg.target_system = target_sysid; + msg.target_component = target_compid; + msg.error = error; + + if (param_index > -1) { // param_id is not used + + msg.param_index = param_index; + + } else { +#if defined(__GNUC__) && __GNUC__ >= 8 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstringop-truncation" +#endif + /* + * coverity[buffer_size_warning : FALSE] + * + * The MAVLink spec does not require the string to be NUL-terminated if it + * has length 16. In this case the receiving end needs to terminate it + * when copying it. + */ + strncpy(msg.param_id, param_id, MAVLINK_MSG_PARAM_ERROR_FIELD_PARAM_ID_LEN); +#if defined(__GNUC__) && __GNUC__ >= 8 +#pragma GCC diagnostic pop +#endif/* code */ + } + + /* default component ID */ + if (component_id < 0) { + mavlink_msg_param_error_send_struct(_mavlink.get_channel(), &msg); + + } else { + // Re-pack the message with a different component ID + mavlink_message_t mavlink_packet; + mavlink_msg_param_error_encode_chan(mavlink_system.sysid, component_id, _mavlink.get_channel(), &mavlink_packet, &msg); + _mavlink_resend_uart(_mavlink.get_channel(), &mavlink_packet); + } + + return 0; +} + #if defined(CONFIG_MAVLINK_UAVCAN_PARAMETERS) bool MavlinkParametersManager::send_uavcan() diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h index 478c487881..c43052c020 100644 --- a/src/modules/mavlink/mavlink_parameters.h +++ b/src/modules/mavlink/mavlink_parameters.h @@ -112,6 +112,14 @@ protected: int send_param(param_t param, int component_id = -1); + /** + * Send error message. + * /// @return true if a error message was sent + */ + int send_error(MAV_PARAM_ERROR error, const char *param_id = nullptr, + const int param_index = -1, int target_system = -1, + int target_component = -1, int component_id = -1); + #if defined(CONFIG_MAVLINK_UAVCAN_PARAMETERS) /** * Send UAVCAN params diff --git a/src/modules/mavlink/mavlink_params.c b/src/modules/mavlink/mavlink_params.c index 8a793f5e5f..f616bd01d6 100644 --- a/src/modules/mavlink/mavlink_params.c +++ b/src/modules/mavlink/mavlink_params.c @@ -52,11 +52,10 @@ PARAM_DEFINE_INT32(MAV_COMP_ID, 1); /** * MAVLink protocol version * @group MAVLink - * @value 0 Default to 1, switch to 2 if GCS sends version 2 - * @value 1 Always use version 1 - * @value 2 Always use version 2 + * @value 1 Version 1 with auto-upgrade to v2 if detected + * @value 2 Version 2 */ -PARAM_DEFINE_INT32(MAV_PROTO_VER, 0); +PARAM_DEFINE_INT32(MAV_PROTO_VER, 2); /** * MAVLink SiK Radio ID diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 4673ed6e72..a54e425d9d 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -3228,10 +3228,11 @@ MavlinkReceiver::run() for (ssize_t i = 0; i < nread; i++) { if (mavlink_parse_char(_mavlink.get_channel(), buf[i], &msg, &_status)) { - /* check if we received version 2 and request a switch. */ - if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) { - /* this will only switch to proto version 2 if allowed in settings */ - _mavlink.set_proto_version(2); + // If we receive a complete MAVLink 2 packet, also switch the outgoing protocol version + if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) + && _mavlink.getProtocolVersion() != 2) { + PX4_INFO("Upgrade to MAVLink v2 because of incoming packet"); + _mavlink.setProtocolVersion(2); } switch (_mavlink.get_mode()) { diff --git a/src/modules/mavlink/module.yaml b/src/modules/mavlink/module.yaml index fa2fe38834..a8eee0d093 100644 --- a/src/modules/mavlink/module.yaml +++ b/src/modules/mavlink/module.yaml @@ -201,3 +201,40 @@ parameters: num_instances: *max_num_config_instances default: [0.015, 0.015, 0.015] reboot_required: true + + MAV_S_MODE: + description: + short: MAVLink Mode for SOM to FMU communication channel + long: | + The MAVLink Mode defines the set of streamed messages (for example the + vehicle's attitude) and their sending rates. + + type: enum + values: + 0: Normal + #1: Custom + 2: Onboard + #3: OSD + #4: Magic + 5: Config + #6: Iridium + 7: Minimal + #8: External Vision + #9: External Vision Minimal + #10: Gimbal + 11: Onboard Low Bandwidth + #12: uAvionix + 13: Low Bandwidth + # We shadow the modes that can block the FMU to SOM connection + reboot_required: true + default: 11 + + MAV_S_FORWARD: + description: + short: Enable MAVLink forwarding on TELEM2 + long : | + TELEM2 on Skynode only. + + type: boolean + reboot_required: true + default: false diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 08a200eda0..68226b17a7 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -263,6 +263,10 @@ void Mission::setActiveMissionItems() pos_sp_triplet->next.valid = false; } + } else if (_mission_item.nav_cmd == NAV_CMD_DELAY) { + // Invalidate next waypoint to ensure vehicle holds position and doesn't try to track ahead + pos_sp_triplet->next.valid = false; + } else { handleVtolTransition(new_work_item_type, next_mission_items, num_found_items); } diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 69ca9896d4..3430bc0162 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1083,7 +1083,7 @@ int Navigator::task_spawn(int argc, char *argv[]) _task_id = px4_task_spawn_cmd("navigator", SCHED_DEFAULT, SCHED_PRIORITY_NAVIGATION, - PX4_STACK_ADJUSTED(2200), + PX4_STACK_ADJUSTED(2230), (px4_main_t)&run_trampoline, (char *const *)argv); diff --git a/src/modules/rc_update/params.c b/src/modules/rc_update/params.c index d764ae5d34..3709a3a841 100644 --- a/src/modules/rc_update/params.c +++ b/src/modules/rc_update/params.c @@ -87,18 +87,6 @@ PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f); */ PARAM_DEFINE_FLOAT(RC1_REV, 1.0f); -/** - * RC channel 1 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @unit us - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f); - /** * RC channel 2 minimum * @@ -148,18 +136,6 @@ PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f); */ PARAM_DEFINE_FLOAT(RC2_REV, 1.0f); -/** - * RC channel 2 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @unit us - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f); - /** * RC channel 3 minimum * @@ -209,18 +185,6 @@ PARAM_DEFINE_FLOAT(RC3_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC3_REV, 1.0f); -/** - * RC channel 3 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @unit us - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC3_DZ, 10.0f); - /** * RC channel 4 minimum * @@ -270,18 +234,6 @@ PARAM_DEFINE_FLOAT(RC4_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC4_REV, 1.0f); -/** - * RC channel 4 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @unit us - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC4_DZ, 10.0f); - /** * RC channel 5 minimum * @@ -331,17 +283,6 @@ PARAM_DEFINE_FLOAT(RC5_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC5_REV, 1.0f); -/** - * RC channel 5 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC5_DZ, 10.0f); - /** * RC channel 6 minimum * @@ -391,17 +332,6 @@ PARAM_DEFINE_FLOAT(RC6_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC6_REV, 1.0f); -/** - * RC channel 6 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC6_DZ, 10.0f); - /** * RC channel 7 minimum * @@ -451,17 +381,6 @@ PARAM_DEFINE_FLOAT(RC7_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC7_REV, 1.0f); -/** - * RC channel 7 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC7_DZ, 10.0f); - /** * RC channel 8 minimum * @@ -511,17 +430,6 @@ PARAM_DEFINE_FLOAT(RC8_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC8_REV, 1.0f); -/** - * RC channel 8 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC8_DZ, 10.0f); - /** * RC channel 9 minimum * @@ -571,17 +479,6 @@ PARAM_DEFINE_FLOAT(RC9_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC9_REV, 1.0f); -/** - * RC channel 9 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC9_DZ, 0.0f); - /** * RC channel 10 minimum * @@ -631,17 +528,6 @@ PARAM_DEFINE_FLOAT(RC10_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC10_REV, 1.0f); -/** - * RC channel 10 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC10_DZ, 0.0f); - /** * RC channel 11 minimum * @@ -691,17 +577,6 @@ PARAM_DEFINE_FLOAT(RC11_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC11_REV, 1.0f); -/** - * RC channel 11 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC11_DZ, 0.0f); - /** * RC channel 12 minimum * @@ -751,17 +626,6 @@ PARAM_DEFINE_FLOAT(RC12_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC12_REV, 1.0f); -/** - * RC channel 12 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC12_DZ, 0.0f); - /** * RC channel 13 minimum * @@ -811,17 +675,6 @@ PARAM_DEFINE_FLOAT(RC13_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC13_REV, 1.0f); -/** - * RC channel 13 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC13_DZ, 0.0f); - /** * RC channel 14 minimum * @@ -871,17 +724,6 @@ PARAM_DEFINE_FLOAT(RC14_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC14_REV, 1.0f); -/** - * RC channel 14 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f); - /** * RC channel 15 minimum * @@ -931,17 +773,6 @@ PARAM_DEFINE_FLOAT(RC15_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC15_REV, 1.0f); -/** - * RC channel 15 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC15_DZ, 0.0f); - /** * RC channel 16 minimum * @@ -991,17 +822,6 @@ PARAM_DEFINE_FLOAT(RC16_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC16_REV, 1.0f); -/** - * RC channel 16 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC16_DZ, 0.0f); - /** * RC channel 17 minimum * @@ -1051,17 +871,6 @@ PARAM_DEFINE_FLOAT(RC17_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC17_REV, 1.0f); -/** - * RC channel 17 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC17_DZ, 0.0f); - /** * RC channel 18 minimum * @@ -1111,17 +920,6 @@ PARAM_DEFINE_FLOAT(RC18_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC18_REV, 1.0f); -/** - * RC channel 18 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f); - /** * RC channel count * diff --git a/src/modules/rc_update/rc_update.cpp b/src/modules/rc_update/rc_update.cpp index 7c8960a357..52d65bf915 100644 --- a/src/modules/rc_update/rc_update.cpp +++ b/src/modules/rc_update/rc_update.cpp @@ -87,10 +87,6 @@ RCUpdate::RCUpdate() : /* channel reverse */ snprintf(nbuf, sizeof(nbuf), "RC%d_REV", i + 1); _parameter_handles.rev[i] = param_find(nbuf); - - /* channel deadzone */ - snprintf(nbuf, sizeof(nbuf), "RC%d_DZ", i + 1); - _parameter_handles.dz[i] = param_find(nbuf); } // RC to parameter mapping for changing parameters with RC @@ -145,10 +141,6 @@ void RCUpdate::updateParams() float rev = 0.f; param_get(_parameter_handles.rev[i], &rev); _parameters.rev[i] = (rev < 0.f); - - float dz = 0.f; - param_get(_parameter_handles.dz[i], &dz); - _parameters.dz[i] = dz; } for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) { @@ -449,12 +441,9 @@ void RCUpdate::Run() const float min = _parameters.min[i]; const float trim = _parameters.trim[i]; const float max = _parameters.max[i]; - const float dz = _parameters.dz[i]; // piecewise linear function to apply RC calibration - _rc.channels[i] = math::interpolateNXY(value, - {min, trim - dz, trim + dz, max}, - {-1.f, 0.f, 0.f, 1.f}); + _rc.channels[i] = math::interpolateNXY(value, {min, trim, max}, {-1.f, 0.f, 1.f}); if (_parameters.rev[i]) { _rc.channels[i] = -_rc.channels[i]; @@ -725,11 +714,11 @@ int RCUpdate::print_status() PX4_INFO_RAW("Running\n"); if (_channel_count_max > 0) { - PX4_INFO_RAW(" # MIN MAX TRIM DZ REV\n"); + PX4_INFO_RAW(" # MIN MAX TRIM REV\n"); for (int i = 0; i < _channel_count_max; i++) { - PX4_INFO_RAW("%2d %4d %4d %4d %3d %3d\n", i, _parameters.min[i], _parameters.max[i], _parameters.trim[i], - _parameters.dz[i], _parameters.rev[i]); + PX4_INFO_RAW("%2d %4d %4d %4d %3d\n", + i, _parameters.min[i], _parameters.max[i], _parameters.trim[i], _parameters.rev[i]); } } diff --git a/src/modules/rc_update/rc_update.h b/src/modules/rc_update/rc_update.h index 812408debe..2ebdebb4c0 100644 --- a/src/modules/rc_update/rc_update.h +++ b/src/modules/rc_update/rc_update.h @@ -148,7 +148,6 @@ protected: uint16_t min[RC_MAX_CHAN_COUNT]; uint16_t trim[RC_MAX_CHAN_COUNT]; uint16_t max[RC_MAX_CHAN_COUNT]; - uint16_t dz[RC_MAX_CHAN_COUNT]; bool rev[RC_MAX_CHAN_COUNT]; int32_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; @@ -159,7 +158,6 @@ protected: param_t trim[RC_MAX_CHAN_COUNT]; param_t max[RC_MAX_CHAN_COUNT]; param_t rev[RC_MAX_CHAN_COUNT]; - param_t dz[RC_MAX_CHAN_COUNT]; param_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; param_t rc_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; /**< param handles for the parameters which are bound diff --git a/src/modules/simulation/gz_bridge/GZGimbal.cpp b/src/modules/simulation/gz_bridge/GZGimbal.cpp index 451f846563..ca0cd08c3e 100644 --- a/src/modules/simulation/gz_bridge/GZGimbal.cpp +++ b/src/modules/simulation/gz_bridge/GZGimbal.cpp @@ -100,11 +100,15 @@ void GZGimbal::gimbalIMUCallback(const gz::msgs::IMU &IMU_data) pthread_mutex_lock(&_node_mutex); static const matrix::Quatf q_FLU_to_FRD = matrix::Quatf(0.0f, 1.0f, 0.0f, 0.0f); + static const matrix::Quatf q_ENU_to_NED = matrix::Quatf(0.0f, cosf(M_PI_4_F), cosf(M_PI_4_F), 0.0f); + + // Get the gimbal orientation. Gimbal frame is FLU in Gazebo, reference frame is ENU in Gazebo const matrix::Quatf q_gimbal_FLU = matrix::Quatf(IMU_data.orientation().w(), IMU_data.orientation().x(), IMU_data.orientation().y(), IMU_data.orientation().z()); - _q_gimbal = q_FLU_to_FRD * q_gimbal_FLU * q_FLU_to_FRD.inversed(); + + _q_gimbal = q_ENU_to_NED * q_gimbal_FLU * q_FLU_to_FRD.inversed(); matrix::Vector3f rate = q_FLU_to_FRD.rotateVector(matrix::Vector3f(IMU_data.angular_velocity().x(), IMU_data.angular_velocity().y(), @@ -206,13 +210,11 @@ void GZGimbal::publishDeviceInfo() void GZGimbal::publishDeviceAttitude() { - // TODO handle flags - gimbal_device_attitude_status_s gimbal_att{}; gimbal_att.target_system = 0; // Broadcast gimbal_att.target_component = 0; // Broadcast - gimbal_att.device_flags = 0; + gimbal_att.device_flags = gimbal_device_attitude_status_s::DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME; _q_gimbal.copyTo(gimbal_att.q); gimbal_att.angular_velocity_x = _gimbal_rate[0]; gimbal_att.angular_velocity_y = _gimbal_rate[1]; @@ -231,7 +233,7 @@ void GZGimbal::publishJointCommand(gz::transport::Node::Publisher &publisher, co float new_stp = computeJointSetpoint(att_stp, rate_stp, last_stp, dt); new_stp = math::constrain(new_stp, min_stp, max_stp); last_stp = new_stp; - msg.set_data(new_stp); + msg.set_data((double)new_stp); publisher.Publish(msg); } diff --git a/src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp b/src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp index ae53bb637a..38c1c1dfde 100644 --- a/src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp +++ b/src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp @@ -117,8 +117,8 @@ bool GZMixingInterfaceServo::init(const std::string &model_name) return false; } - double min_val = get_servo_angle_min(i); - double max_val = get_servo_angle_max(i); + double min_val = (double)get_servo_angle_min(i); + double max_val = (double)get_servo_angle_max(i); _angle_min_rad.push_back(min_val); _angular_range_rad.push_back(max_val - min_val); } diff --git a/src/modules/simulation/gz_plugins/gstreamer/CMakeLists.txt b/src/modules/simulation/gz_plugins/gstreamer/CMakeLists.txt index bb453df805..4397463b5c 100644 --- a/src/modules/simulation/gz_plugins/gstreamer/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/gstreamer/CMakeLists.txt @@ -67,4 +67,8 @@ else() PRIVATE ${GSTREAMER_CFLAGS} PRIVATE ${GSTREAMER_APP_CFLAGS} ) + + if (NOT CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT) + install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION lib/px4_gz_plugins) + endif() endif() diff --git a/src/modules/simulation/gz_plugins/moving_platform_controller/CMakeLists.txt b/src/modules/simulation/gz_plugins/moving_platform_controller/CMakeLists.txt index 88e2da59cb..243a92af53 100644 --- a/src/modules/simulation/gz_plugins/moving_platform_controller/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/moving_platform_controller/CMakeLists.txt @@ -50,3 +50,7 @@ target_include_directories(${PROJECT_NAME} PUBLIC ${CMAKE_CURRENT_BINARY_DIR} PUBLIC px4_gz_msgs ) + +if (NOT CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT) + install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION lib/px4_gz_plugins) +endif() diff --git a/src/modules/simulation/gz_plugins/moving_platform_controller/MovingPlatformController.cpp b/src/modules/simulation/gz_plugins/moving_platform_controller/MovingPlatformController.cpp index f8f1ab26e2..80568aaf84 100644 --- a/src/modules/simulation/gz_plugins/moving_platform_controller/MovingPlatformController.cpp +++ b/src/modules/simulation/gz_plugins/moving_platform_controller/MovingPlatformController.cpp @@ -240,7 +240,7 @@ void MovingPlatformController::updateWrenchCommand( if (accel_xy > max_accel) { const float scaling = max_accel / accel_xy; - _force += feedback_force * gz::math::Vector3d(scaling, scaling, 1.); + _force += feedback_force * gz::math::Vector3d((double)scaling, (double)scaling, 1.); } else { _force += feedback_force; diff --git a/src/modules/simulation/gz_plugins/optical_flow/CMakeLists.txt b/src/modules/simulation/gz_plugins/optical_flow/CMakeLists.txt index a03ee39598..62d9c7c959 100644 --- a/src/modules/simulation/gz_plugins/optical_flow/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/optical_flow/CMakeLists.txt @@ -63,3 +63,7 @@ target_include_directories(${PROJECT_NAME} ) add_dependencies(${PROJECT_NAME} OpticalFlow) + +if (NOT CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT) + install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION lib/px4_gz_plugins) +endif() diff --git a/src/modules/simulation/gz_plugins/optical_flow/OpticalFlowSensor.hpp b/src/modules/simulation/gz_plugins/optical_flow/OpticalFlowSensor.hpp index 497fd79276..e566ec190e 100644 --- a/src/modules/simulation/gz_plugins/optical_flow/OpticalFlowSensor.hpp +++ b/src/modules/simulation/gz_plugins/optical_flow/OpticalFlowSensor.hpp @@ -64,8 +64,8 @@ private: int _integration_time_us; // Camera - double _horizontal_fov {0.0}; - double _vertical_fov {0.0}; + //double _horizontal_fov {0.0}; + //double _vertical_fov {0.0}; cv::Mat _last_image_gray; uint32_t _last_image_timestamp {0}; diff --git a/src/modules/simulation/gz_plugins/optical_flow/optical_flow.cmake b/src/modules/simulation/gz_plugins/optical_flow/optical_flow.cmake index 8ac1c1f649..2dcc7d074d 100644 --- a/src/modules/simulation/gz_plugins/optical_flow/optical_flow.cmake +++ b/src/modules/simulation/gz_plugins/optical_flow/optical_flow.cmake @@ -35,19 +35,24 @@ include(ExternalProject) find_package(OpenCV REQUIRED) if(NOT TARGET OpticalFlow) + if(CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT) + set(OPTICAL_FLOW_INSTALL_PREFIX "${CMAKE_BINARY_DIR}/OpticalFlow/install") + else() + set(OPTICAL_FLOW_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + endif() + ExternalProject_Add(OpticalFlow GIT_REPOSITORY https://github.com/PX4/PX4-OpticalFlow.git GIT_TAG master PREFIX ${CMAKE_BINARY_DIR}/OpticalFlow - INSTALL_DIR ${CMAKE_BINARY_DIR}/OpticalFlow/install - CMAKE_ARGS -DCMAKE_INSTALL_PREFIX= - BUILD_BYPRODUCTS ${CMAKE_BINARY_DIR}/OpticalFlow/install/lib/libOpticalFlow.so + INSTALL_DIR ${OPTICAL_FLOW_INSTALL_PREFIX} + CMAKE_ARGS -DCMAKE_INSTALL_PREFIX=${OPTICAL_FLOW_INSTALL_PREFIX} + BUILD_BYPRODUCTS ${OPTICAL_FLOW_INSTALL_PREFIX}/lib/libOpticalFlow.so UPDATE_DISCONNECTED ON BUILD_ALWAYS OFF STEP_TARGETS build ) - ExternalProject_Get_Property(OpticalFlow install_dir) - set(OpticalFlow_INCLUDE_DIRS ${install_dir}/include CACHE INTERNAL "") - set(OpticalFlow_LIBS ${install_dir}/lib/libOpticalFlow.so CACHE INTERNAL "") + set(OpticalFlow_INCLUDE_DIRS ${OPTICAL_FLOW_INSTALL_PREFIX}/include CACHE INTERNAL "") + set(OpticalFlow_LIBS ${OPTICAL_FLOW_INSTALL_PREFIX}/lib/libOpticalFlow.so CACHE INTERNAL "") endif() diff --git a/src/modules/simulation/gz_plugins/template_plugin/CMakeLists.txt b/src/modules/simulation/gz_plugins/template_plugin/CMakeLists.txt index a0caaf2b33..f948736523 100644 --- a/src/modules/simulation/gz_plugins/template_plugin/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/template_plugin/CMakeLists.txt @@ -66,3 +66,7 @@ target_include_directories(${PROJECT_NAME} # Add dependencies if needed # add_dependencies(${PROJECT_NAME} ExternalDependency) + +if (NOT CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT) + install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION lib/px4_gz_plugins) +endif() diff --git a/src/modules/uxrce_dds_client/CMakeLists.txt b/src/modules/uxrce_dds_client/CMakeLists.txt index e5fc481543..fba4ca45cf 100644 --- a/src/modules/uxrce_dds_client/CMakeLists.txt +++ b/src/modules/uxrce_dds_client/CMakeLists.txt @@ -63,7 +63,6 @@ else() endif() include(ExternalProject) - ExternalProject_Add( libmicroxrceddsclient_project PREFIX ${microxrceddsclient_build_dir} @@ -139,7 +138,6 @@ else() # -DDEBUG_BUILD ${MAX_CUSTOM_OPT_LEVEL} SRCS - ${CMAKE_CURRENT_BINARY_DIR}/dds_topics.h uxrce_dds_client.cpp uxrce_dds_client.h vehicle_command_srv.cpp diff --git a/src/modules/uxrce_dds_client/dds_topics.yaml b/src/modules/uxrce_dds_client/dds_topics.yaml index ef7ba8fc0b..dc6cc1f2cf 100644 --- a/src/modules/uxrce_dds_client/dds_topics.yaml +++ b/src/modules/uxrce_dds_client/dds_topics.yaml @@ -62,6 +62,7 @@ publications: - topic: /fmu/out/vehicle_attitude type: px4_msgs::msg::VehicleAttitude + rate_limit: 50. - topic: /fmu/out/vehicle_control_mode type: px4_msgs::msg::VehicleControlMode @@ -84,6 +85,7 @@ publications: - topic: /fmu/out/vehicle_odometry type: px4_msgs::msg::VehicleOdometry + rate_limit: 100. - topic: /fmu/out/vehicle_status type: px4_msgs::msg::VehicleStatus @@ -104,6 +106,10 @@ publications: type: px4_msgs::msg::Wind rate_limit: 1. + - topic: /fmu/out/gimbal_device_attitude_status + type: px4_msgs::msg::GimbalDeviceAttitudeStatus + rate_limit: 20. + # Create uORB::Publication subscriptions: - topic: /fmu/in/register_ext_component_request diff --git a/src/modules/zenoh/Kconfig b/src/modules/zenoh/Kconfig index 6e98efc2e5..ae050c6ad8 100644 --- a/src/modules/zenoh/Kconfig +++ b/src/modules/zenoh/Kconfig @@ -19,7 +19,7 @@ if MODULES_ZENOH config ZENOH_DEFAULT_LOCATOR string "Zenoh default mode" default "tcp/127.0.0.1:7447" if PLATFORM_POSIX - default "" if !PLATFORM_POSIX + default "tcp/10.41.10.1:7447#iface=eth0" if !PLATFORM_POSIX config ZENOH_RMW_LIVELINESS bool "[EXPERIMENTAL] rmw_zenoh liveliness implemenation" diff --git a/src/modules/zenoh/module.yaml b/src/modules/zenoh/module.yaml index 25e658f9f3..095e1f4dc8 100644 --- a/src/modules/zenoh/module.yaml +++ b/src/modules/zenoh/module.yaml @@ -6,9 +6,12 @@ parameters: ZENOH_ENABLE: description: - short: Zenoh Enable - long: Zenoh + short: Enable Zenoh + long: | + Set true (1) to start the Zenoh driver module (a.k.a the "Zenoh-Pico Node"). + See https://docs.px4.io/main/en/middleware/zenoh and + https://docs.px4.io/main/en/modules/modules_driver.html#zenoh category: System - type: int32 + type: boolean reboot_required: true default: 0