diff --git a/.github/workflows/build_test_macos.yml b/.github/workflows/build_test_macos.yml index 8954032e79..7ef3004fa9 100644 --- a/.github/workflows/build_test_macos.yml +++ b/.github/workflows/build_test_macos.yml @@ -21,7 +21,7 @@ jobs: - name: Before Install run: | brew update; - git clone -b release-1.10.0 https://github.com/google/googletest + git clone -b v1.15.2 https://github.com/google/googletest git clone https://github.com/mavlink/c_library_v2.git /usr/local/include/mavlink - name: Install run: | diff --git a/.github/workflows/firmware_build_test.yml b/.github/workflows/firmware_build_test.yml deleted file mode 100644 index dd5f4135a4..0000000000 --- a/.github/workflows/firmware_build_test.yml +++ /dev/null @@ -1,87 +0,0 @@ -name: Firmware Build and SITL Tests - -on: - push: - branches: - - main - pull_request: - branches: - - '*' - -jobs: - Firmware-build: - runs-on: ubuntu-latest - strategy: - fail-fast: false - matrix: - model: - - "iris" - - "standard_vtol" - container: - image: px4io/px4-dev-simulation-focal:2021-05-31 - options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined - steps: - - name: Checkout Firmware main - uses: actions/checkout@v2.3.1 - with: - repository: PX4/Firmware - ref: main - path: Firmware - fetch-depth: 0 - submodules: recurvise - - name: Checkout matching branch on PX4/Firmware if possible - run: | - git checkout ${{github.head_ref}} || echo "Firmware branch: ${{github.head_ref}} not found, using main instead" - git submodule update --init --recursive - working-directory: Firmware - - name: Configure Firmware to include current sitl_gazebo version - working-directory: Firmware/Tools/simulation/gazebo-classic/sitl_gazebo-classic - run: | - git fetch origin pull/${{github.event.pull_request.number}}/head:${{github.head_ref}} || echo "Couldn't find the feature branch of the pull request, using default branch" - git checkout ${{github.head_ref}} - - name: Download MAVSDK - working-directory: Firmware - run: wget "https://github.com/mavlink/MAVSDK/releases/download/v$(cat test/mavsdk_tests/MAVSDK_VERSION)/libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb" - - name: Install MAVSDK - working-directory: Firmware - run: dpkg -i "libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb" - - name: Prepare ccache timestamp - id: ccache_cache_timestamp - shell: cmake -P {0} - run: | - string(TIMESTAMP current_date "%Y-%m-%d-%H;%M;%S" UTC) - message("::set-output name=timestamp::${current_date}") - - name: ccache cache files - uses: actions/cache@v2 - with: - path: ~/.ccache - key: sitl_tests-${{matrix.config.build_type}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: sitl_tests-${{matrix.config.build_type}}-ccache- - - name: setup ccache - run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z - - name: Build Firmware - working-directory: Firmware - env: - DONT_RUN: 1 - GIT_SUBMODULES_ARE_EVIL: 1 - run: make px4_sitl_default gazebo_iris - - name: ccache post-run px4/firmware - run: ccache -s - - name: Build MAVSDK tests - working-directory: Firmware - env: - DONT_RUN: 1 - GIT_SUBMODULES_ARE_EVIL: 1 - run: make px4_sitl_default gazebo_iris mavsdk_tests - - name: ccache post-run mavsdk_tests - run: ccache -s - - name: Run SITL tests - working-directory: Firmware - run: test/mavsdk_tests/mavsdk_test_runner.py --speed-factor 20 --abort-early --model ${{matrix.model}} test/mavsdk_tests/configs/sitl.json diff --git a/src/gazebo_camera_manager_plugin.cpp b/src/gazebo_camera_manager_plugin.cpp index 3f1cb22f3d..4c0d374198 100644 --- a/src/gazebo_camera_manager_plugin.cpp +++ b/src/gazebo_camera_manager_plugin.cpp @@ -657,7 +657,8 @@ void CameraManagerPlugin::_handle_request_camera_settings(const mavlink_message_ 0, // time_boot_ms _mode, // Camera Mode 1.0E2 * (_zoom - 1.0)/ (_maxZoom - 1.0), // Zoom level - NAN); // Focus level + NAN, // Focus level + 0); // MAVLink camera with its own component ID _send_mavlink_message(&msg, srcaddr); } @@ -678,18 +679,19 @@ void CameraManagerPlugin::_handle_request_video_stream_status(const mavlink_mess mavlink_message_t msg; mavlink_msg_video_stream_status_pack_chan( _systemID, - _componentID, // Component ID + _componentID, // Component ID MAVLINK_COMM_1, &msg, static_cast(sid), // Stream ID VIDEO_STREAM_STATUS_FLAGS_RUNNING, // Flags (It's always running) 30, // Frame rate - _width, // Horizontal resolution + _width, // Horizontal resolution _height, // Vertical resolution 2048, // Bit rate (made up) 0, // Rotation (none) - 90 // FOV (made up) - ); + 90, // FOV (made up) + 0); // MAVLink camera with its own component ID + _send_mavlink_message(&msg, srcaddr); } @@ -801,7 +803,8 @@ void CameraManagerPlugin::_send_capture_status(struct sockaddr* srcaddr) interval, // image interval recording_time_ms, // recording time in ms available_mib, // available storage capacity - _imageCounter); // total number of images + _imageCounter, // total number of images + 0); // MAVLink camera with its own component ID _send_mavlink_message(&msg, srcaddr); }