From cb4992b33ea0c213ad3051f38026cfa683303ab3 Mon Sep 17 00:00:00 2001 From: wep21 Date: Tue, 22 Apr 2025 22:08:47 +0900 Subject: [PATCH 1/3] add livox ros driver2 Signed-off-by: wep21 --- .../add_package_xml.patch | 55 ++++++++ .../bld_ament_cmake.bat | 1 + .../build_ament_cmake.sh | 1 + .../fix_livox_interfaces.patch | 41 ++++++ .../ros-jazzy-livox-ros-driver2/recipe.yaml | 120 ++++++++++++++++++ pixi.toml | 2 +- 6 files changed, 219 insertions(+), 1 deletion(-) create mode 100644 additional_recipes/ros-jazzy-livox-ros-driver2/add_package_xml.patch create mode 120000 additional_recipes/ros-jazzy-livox-ros-driver2/bld_ament_cmake.bat create mode 120000 additional_recipes/ros-jazzy-livox-ros-driver2/build_ament_cmake.sh create mode 100644 additional_recipes/ros-jazzy-livox-ros-driver2/fix_livox_interfaces.patch create mode 100644 additional_recipes/ros-jazzy-livox-ros-driver2/recipe.yaml diff --git a/additional_recipes/ros-jazzy-livox-ros-driver2/add_package_xml.patch b/additional_recipes/ros-jazzy-livox-ros-driver2/add_package_xml.patch new file mode 100644 index 00000000..625433a6 --- /dev/null +++ b/additional_recipes/ros-jazzy-livox-ros-driver2/add_package_xml.patch @@ -0,0 +1,55 @@ +From 318d447b347d87ce2087c40dd6ad169643fc32d9 Mon Sep 17 00:00:00 2001 +From: wep21 +Date: Tue, 22 Apr 2025 21:53:53 +0900 +Subject: [PATCH] add package.xml + +Signed-off-by: wep21 +--- + package.xml | 35 +++++++++++++++++++++++++++++++++++ + 1 file changed, 35 insertions(+) + create mode 100644 package.xml + +diff --git a/package.xml b/package.xml +new file mode 100644 +index 0000000..96f5762 +--- /dev/null ++++ b/package.xml +@@ -0,0 +1,35 @@ ++ ++ ++ ++ livox_ros_driver2 ++ 1.0.0 ++ The ROS device driver for Livox 3D LiDARs, for ROS2 ++ feng ++ MIT ++ ++ ament_cmake_auto ++ rosidl_default_generators ++ rosidl_interface_packages ++ ++ rclcpp ++ rclcpp_components ++ std_msgs ++ sensor_msgs ++ rcutils ++ pcl_conversions ++ rcl_interfaces ++ libpcl-all-dev ++ ++ rosbag2 ++ rosidl_default_runtime ++ ++ ament_lint_auto ++ ament_lint_common ++ ++ git ++ apr ++ ++ ++ ament_cmake ++ ++ +-- +2.39.5 (Apple Git-154) + diff --git a/additional_recipes/ros-jazzy-livox-ros-driver2/bld_ament_cmake.bat b/additional_recipes/ros-jazzy-livox-ros-driver2/bld_ament_cmake.bat new file mode 120000 index 00000000..54cca50d --- /dev/null +++ b/additional_recipes/ros-jazzy-livox-ros-driver2/bld_ament_cmake.bat @@ -0,0 +1 @@ +../../bld_ament_cmake.bat \ No newline at end of file diff --git a/additional_recipes/ros-jazzy-livox-ros-driver2/build_ament_cmake.sh b/additional_recipes/ros-jazzy-livox-ros-driver2/build_ament_cmake.sh new file mode 120000 index 00000000..6f1a50db --- /dev/null +++ b/additional_recipes/ros-jazzy-livox-ros-driver2/build_ament_cmake.sh @@ -0,0 +1 @@ +../../build_ament_cmake.sh \ No newline at end of file diff --git a/additional_recipes/ros-jazzy-livox-ros-driver2/fix_livox_interfaces.patch b/additional_recipes/ros-jazzy-livox-ros-driver2/fix_livox_interfaces.patch new file mode 100644 index 00000000..8ee0bf3d --- /dev/null +++ b/additional_recipes/ros-jazzy-livox-ros-driver2/fix_livox_interfaces.patch @@ -0,0 +1,41 @@ +From f7f4c8b08fc51cb087722894f48165e3c5b57eb4 Mon Sep 17 00:00:00 2001 +From: wep21 +Date: Wed, 23 Apr 2025 00:33:32 +0900 +Subject: [PATCH] fix livox interfaces target + +--- + CMakeLists.txt | 12 +++--------- + 1 file changed, 3 insertions(+), 9 deletions(-) + +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 99a8ccc..ae9c928 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -282,15 +282,9 @@ else(ROS_EDITION STREQUAL "ROS2") + target_include_directories(${PROJECT_NAME} PRIVATE ${livox_sdk_INCLUDE_DIRS}) + + # get include directories of custom msg headers +- if(HUMBLE_ROS STREQUAL "humble") +- rosidl_get_typesupport_target(cpp_typesupport_target ++ rosidl_get_typesupport_target(cpp_typesupport_target + ${LIVOX_INTERFACES} "rosidl_typesupport_cpp") +- target_link_libraries(${PROJECT_NAME} "${cpp_typesupport_target}") +- else() +- set(LIVOX_INTERFACE_TARGET "${LIVOX_INTERFACES}__rosidl_typesupport_cpp") +- add_dependencies(${PROJECT_NAME} ${LIVOX_INTERFACES}) +- get_target_property(LIVOX_INTERFACES_INCLUDE_DIRECTORIES ${LIVOX_INTERFACE_TARGET} INTERFACE_INCLUDE_DIRECTORIES) +- endif() ++ target_link_libraries(${PROJECT_NAME} "${cpp_typesupport_target}") + + # include file direcotry + target_include_directories(${PROJECT_NAME} PUBLIC +@@ -333,4 +327,4 @@ else(ROS_EDITION STREQUAL "ROS2") + launch_ROS2 + ) + +-endif() +\ No newline at end of file ++endif() +-- +2.43.0 + diff --git a/additional_recipes/ros-jazzy-livox-ros-driver2/recipe.yaml b/additional_recipes/ros-jazzy-livox-ros-driver2/recipe.yaml new file mode 100644 index 00000000..1bb2f278 --- /dev/null +++ b/additional_recipes/ros-jazzy-livox-ros-driver2/recipe.yaml @@ -0,0 +1,120 @@ +package: + name: ros-jazzy-livox-ros-driver2 + version: 1.2.4 + +source: + git: https://github.com/Livox-SDK/livox_ros_driver2.git + tag: 1.2.4 + target_directory: ros-jazzy-livox-ros-driver2/src/work + patches: + - add_package_xml.patch + - fix_livox_interfaces.patch + +build: + script: ${{ '$RECIPE_DIR/build_ament_cmake.sh' if unix else '%RECIPE_DIR%\\bld_ament_cmake.bat' }} + number: 6 + post_process: + - files: + - '*.pc' + regex: (?:-L|-I)?"?([^;\s]+/sysroot/) + replacement: $$(CONDA_BUILD_SYSROOT_S) + - files: + - '*.cmake' + regex: ([^;\s"]+/sysroot) + replacement: $$ENV{CONDA_BUILD_SYSROOT} + - files: + - '*.cmake' + regex: ([^;\s"]+/MacOSX\d*\.?\d*\.sdk) + replacement: $$ENV{CONDA_BUILD_SYSROOT} + +about: + homepage: https://github.com/Livox-SDK/livox_ros_driver2 + license: MIT + summary: | + Livox device driver under Ros(Compatible with ros and ros2), support Lidar HAP and Mid-360. + +extra: + recipe-maintainers: + - ros-forge + +requirements: + build: + - ${{ compiler('cxx') }} + - ${{ compiler('c') }} + - ${{ stdlib('c') }} + - ninja + - python + - setuptools + - git + - if: unix + then: + - patch + - make + - coreutils + - if: win + then: + - m2-patch + - if: osx + then: + - tapi + - if: build_platform != target_platform + then: + - pkg-config + - cmake + - cython + - if: build_platform != target_platform + then: + - python + - cross-python_${{ target_platform }} + - numpy + host: + - if: build_platform == target_platform + then: + - pkg-config + - eigen + - libboost-devel + - livox-sdk2 + - numpy + - pcl + - pip + - python + - ros-jazzy-ament-cmake + - ros-jazzy-ament-cmake-auto + - ros-jazzy-ament-lint-auto + - ros-jazzy-ament-lint-common + - ros-jazzy-pcl-conversions + - ros-jazzy-rclcpp + - ros-jazzy-rclcpp-components + - ros-jazzy-ros-environment + - ros-jazzy-ros-workspace + - ros-jazzy-rosidl-default-generators + - ros-jazzy-sensor-msgs + - ros2-distro-mutex 0.8.* jazzy_* + - vtk-base + - if: linux + then: + - libgl-devel + - libopengl-devel + - if: unix + then: + - xorg-libx11 + - xorg-libxext + run: + - eigen + - libboost-devel + - pcl + - python + - ros-jazzy-pcl-conversions + - ros-jazzy-rclcpp + - ros-jazzy-rclcpp-components + - ros-jazzy-ros-workspace + - ros-jazzy-sensor-msgs + - ros2-distro-mutex 0.8.* jazzy_* + - vtk-base + - if: osx and x86_64 + then: + - __osx >=${{ MACOSX_DEPLOYMENT_TARGET|default('10.14') }} + - if: unix + then: + - xorg-libx11 + - xorg-libxext diff --git a/pixi.toml b/pixi.toml index 3b6fd8f0..8a9f2074 100644 --- a/pixi.toml +++ b/pixi.toml @@ -34,7 +34,7 @@ vinca = { git ="https://github.com/RoboStack/vinca.git", rev = "cbb8eba834ce3834 [feature.beta.tasks] generate-recipes = { cmd = "vinca -m", depends-on = ["rename-file"] } remove-file = { cmd = "rm vinca.yaml; rm -rf recipes" } -build_additional_recipes = { cmd = "rattler-build build --recipe-dir ./additional_recipes -m ./conda_build_config.yaml --skip-existing" } +build_additional_recipes = { cmd = "rattler-build build --recipe-dir ./additional_recipes -m ./conda_build_config.yaml --skip-existing -c robostack-jazzy -c https://repo.prefix.dev/conda-forge" } build = { cmd = "rattler-build build --recipe-dir ./recipes -m ./conda_build_config.yaml -c robostack-jazzy -c https://repo.prefix.dev/conda-forge --skip-existing", depends-on = ["build_additional_recipes", "generate-recipes"] } build_one_package = { cmd = "cp ./patch/$PACKAGE.*patch ./recipes/$PACKAGE/patch/; rattler-build build --recipe ./recipes/$PACKAGE/recipe.yaml -m ./conda_build_config.yaml -c robostack-jazzy -c https://repo.prefix.dev/conda-forge", env = { PACKAGE = "ros-jazzy-ros-workspace" } } create_snapshot = { cmd = "vinca-snapshot -d jazzy -o rosdistro_snapshot.yaml" } From a8b6c4bad33a82aa9e43b761d521708effb5b1b3 Mon Sep 17 00:00:00 2001 From: wep21 Date: Sun, 11 May 2025 18:39:57 +0900 Subject: [PATCH 2/3] update workflow Signed-off-by: wep21 --- .github/workflows/testpr.yml | 32 ++++++++++++++++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/.github/workflows/testpr.yml b/.github/workflows/testpr.yml index 71e90f82..96adf22b 100644 --- a/.github/workflows/testpr.yml +++ b/.github/workflows/testpr.yml @@ -13,14 +13,21 @@ jobs: include: - os: ubuntu-latest platform: linux-64 + additional_recipes: + - "ros-jazzy-livox-ros-driver2" - os: ubuntu-24.04-arm platform: linux-aarch64 + additional_recipes: + - "ros-jazzy-livox-ros-driver2" - os: macos-13 platform: osx-64 + additional_recipes: [] - os: macos-14 platform: osx-arm64 + additional_recipes: [] - os: windows-2019 platform: win-64 + additional_recipes: [] runs-on: ${{ matrix.os }} @@ -116,30 +123,55 @@ jobs: else echo "RECIPE_CREATED=1" >> $GITHUB_OUTPUT fi + - name: Build additional recipes for linux-64 + shell: bash -l {0} + if: matrix.platform == 'linux-64' + run: | + echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform linux-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for linux-64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'linux-64' run: | env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes --target-platform linux-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir recipes --target-platform linux-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing + - name: Build additional recipes for linux-aarch64 + shell: bash -l {0} + if: matrix.platform == 'linux-aarch64' + run: | + echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform linux-aarch64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for linux-aarch64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'linux-aarch64' run: | env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes --target-platform linux-aarch64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir recipes --target-platform linux-aarch64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing + - name: Build additional recipes for osx-64 + shell: bash -l {0} + if: matrix.platform == 'osx-64' + run: | + echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform osx-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for osx-64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'osx-64' run: | env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes --target-platform osx-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir recipes --target-platform osx-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing + - name: Build additional recipes for osx-arm64 + shell: bash -l {0} + if: matrix.platform == 'osx-arm64' + run: | + echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform osx-arm64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for osx-arm64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'osx-arm64' run: | env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes --target-platform osx-arm64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir recipes --target-platform osx-arm64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing + - name: Build additional recipes for win-64 + shell: bash -l {0} + if: matrix.platform == 'win-64' + run: | + echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform win-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for win-64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'win-64' From d15726afe97c0c459e116cf54919e21a6c661f0f Mon Sep 17 00:00:00 2001 From: wep21 Date: Tue, 13 May 2025 23:24:32 +0900 Subject: [PATCH 3/3] update workflow Signed-off-by: wep21 --- .github/workflows/testpr.yml | 29 ++++------------------------- 1 file changed, 4 insertions(+), 25 deletions(-) diff --git a/.github/workflows/testpr.yml b/.github/workflows/testpr.yml index 96adf22b..4bbbe263 100644 --- a/.github/workflows/testpr.yml +++ b/.github/workflows/testpr.yml @@ -112,6 +112,10 @@ jobs: mkdir -p recipes $HOME/.pixi/bin/pixi run -e beta -v vinca --platform win-64 -m -n ls -la recipes + - name: Copy additional recipes which have been changed into recipes + shell: bash -l {0} + run: | + echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ cp -r additional_recipes/@ recipes/ - name: Check if there are packages to be built id: newrecipecheck shell: bash -l {0} @@ -123,55 +127,30 @@ jobs: else echo "RECIPE_CREATED=1" >> $GITHUB_OUTPUT fi - - name: Build additional recipes for linux-64 - shell: bash -l {0} - if: matrix.platform == 'linux-64' - run: | - echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform linux-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for linux-64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'linux-64' run: | env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes --target-platform linux-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir recipes --target-platform linux-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - - name: Build additional recipes for linux-aarch64 - shell: bash -l {0} - if: matrix.platform == 'linux-aarch64' - run: | - echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform linux-aarch64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for linux-aarch64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'linux-aarch64' run: | env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes --target-platform linux-aarch64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir recipes --target-platform linux-aarch64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - - name: Build additional recipes for osx-64 - shell: bash -l {0} - if: matrix.platform == 'osx-64' - run: | - echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform osx-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for osx-64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'osx-64' run: | env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes --target-platform osx-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir recipes --target-platform osx-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - - name: Build additional recipes for osx-arm64 - shell: bash -l {0} - if: matrix.platform == 'osx-arm64' - run: | - echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform osx-arm64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for osx-arm64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'osx-arm64' run: | env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes --target-platform osx-arm64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir recipes --target-platform osx-arm64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - - name: Build additional recipes for win-64 - shell: bash -l {0} - if: matrix.platform == 'win-64' - run: | - echo '${{ toJson(matrix.additional_recipes) }}' | jq -r ".[]" | xargs -I@ env -i $HOME/.pixi/bin/pixi run -e beta rattler-build build --recipe-dir additional_recipes/@ --target-platform win-64 -m ./conda_build_config.yaml -c robostack-jazzy -c conda-forge --skip-existing - name: Build recipes for win-64 shell: bash -l {0} if: steps.newrecipecheck.outputs.RECIPE_CREATED == 1 && matrix.platform == 'win-64'