Skip to content

Commit cb4992b

Browse files
committed
add livox ros driver2
Signed-off-by: wep21 <[email protected]>
1 parent 9155338 commit cb4992b

File tree

6 files changed

+219
-1
lines changed

6 files changed

+219
-1
lines changed
Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
From 318d447b347d87ce2087c40dd6ad169643fc32d9 Mon Sep 17 00:00:00 2001
2+
From: wep21 <[email protected]>
3+
Date: Tue, 22 Apr 2025 21:53:53 +0900
4+
Subject: [PATCH] add package.xml
5+
6+
Signed-off-by: wep21 <[email protected]>
7+
---
8+
package.xml | 35 +++++++++++++++++++++++++++++++++++
9+
1 file changed, 35 insertions(+)
10+
create mode 100644 package.xml
11+
12+
diff --git a/package.xml b/package.xml
13+
new file mode 100644
14+
index 0000000..96f5762
15+
--- /dev/null
16+
+++ b/package.xml
17+
@@ -0,0 +1,35 @@
18+
+<?xml version="1.0"?>
19+
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
20+
+<package format="3">
21+
+ <name>livox_ros_driver2</name>
22+
+ <version>1.0.0</version>
23+
+ <description>The ROS device driver for Livox 3D LiDARs, for ROS2</description>
24+
+ <maintainer email="[email protected]">feng</maintainer>
25+
+ <license>MIT</license>
26+
+
27+
+ <buildtool_depend>ament_cmake_auto</buildtool_depend>
28+
+ <build_depend>rosidl_default_generators</build_depend>
29+
+ <member_of_group>rosidl_interface_packages</member_of_group>
30+
+
31+
+ <depend>rclcpp</depend>
32+
+ <depend>rclcpp_components</depend>
33+
+ <depend>std_msgs</depend>
34+
+ <depend>sensor_msgs</depend>
35+
+ <depend>rcutils</depend>
36+
+ <depend>pcl_conversions</depend>
37+
+ <depend>rcl_interfaces</depend>
38+
+ <depend>libpcl-all-dev</depend>
39+
+
40+
+ <exec_depend>rosbag2</exec_depend>
41+
+ <exec_depend>rosidl_default_runtime</exec_depend>
42+
+
43+
+ <test_depend>ament_lint_auto</test_depend>
44+
+ <test_depend>ament_lint_common</test_depend>
45+
+
46+
+ <depend>git</depend>
47+
+ <depend>apr</depend>
48+
+
49+
+ <export>
50+
+ <build_type>ament_cmake</build_type>
51+
+ </export>
52+
+</package>
53+
--
54+
2.39.5 (Apple Git-154)
55+
Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
../../bld_ament_cmake.bat
Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
../../build_ament_cmake.sh
Lines changed: 41 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,41 @@
1+
From f7f4c8b08fc51cb087722894f48165e3c5b57eb4 Mon Sep 17 00:00:00 2001
2+
From: wep21 <[email protected]>
3+
Date: Wed, 23 Apr 2025 00:33:32 +0900
4+
Subject: [PATCH] fix livox interfaces target
5+
6+
---
7+
CMakeLists.txt | 12 +++---------
8+
1 file changed, 3 insertions(+), 9 deletions(-)
9+
10+
diff --git a/CMakeLists.txt b/CMakeLists.txt
11+
index 99a8ccc..ae9c928 100644
12+
--- a/CMakeLists.txt
13+
+++ b/CMakeLists.txt
14+
@@ -282,15 +282,9 @@ else(ROS_EDITION STREQUAL "ROS2")
15+
target_include_directories(${PROJECT_NAME} PRIVATE ${livox_sdk_INCLUDE_DIRS})
16+
17+
# get include directories of custom msg headers
18+
- if(HUMBLE_ROS STREQUAL "humble")
19+
- rosidl_get_typesupport_target(cpp_typesupport_target
20+
+ rosidl_get_typesupport_target(cpp_typesupport_target
21+
${LIVOX_INTERFACES} "rosidl_typesupport_cpp")
22+
- target_link_libraries(${PROJECT_NAME} "${cpp_typesupport_target}")
23+
- else()
24+
- set(LIVOX_INTERFACE_TARGET "${LIVOX_INTERFACES}__rosidl_typesupport_cpp")
25+
- add_dependencies(${PROJECT_NAME} ${LIVOX_INTERFACES})
26+
- get_target_property(LIVOX_INTERFACES_INCLUDE_DIRECTORIES ${LIVOX_INTERFACE_TARGET} INTERFACE_INCLUDE_DIRECTORIES)
27+
- endif()
28+
+ target_link_libraries(${PROJECT_NAME} "${cpp_typesupport_target}")
29+
30+
# include file direcotry
31+
target_include_directories(${PROJECT_NAME} PUBLIC
32+
@@ -333,4 +327,4 @@ else(ROS_EDITION STREQUAL "ROS2")
33+
launch_ROS2
34+
)
35+
36+
-endif()
37+
\ No newline at end of file
38+
+endif()
39+
--
40+
2.43.0
41+
Lines changed: 120 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,120 @@
1+
package:
2+
name: ros-jazzy-livox-ros-driver2
3+
version: 1.2.4
4+
5+
source:
6+
git: https://github.com/Livox-SDK/livox_ros_driver2.git
7+
tag: 1.2.4
8+
target_directory: ros-jazzy-livox-ros-driver2/src/work
9+
patches:
10+
- add_package_xml.patch
11+
- fix_livox_interfaces.patch
12+
13+
build:
14+
script: ${{ '$RECIPE_DIR/build_ament_cmake.sh' if unix else '%RECIPE_DIR%\\bld_ament_cmake.bat' }}
15+
number: 6
16+
post_process:
17+
- files:
18+
- '*.pc'
19+
regex: (?:-L|-I)?"?([^;\s]+/sysroot/)
20+
replacement: $$(CONDA_BUILD_SYSROOT_S)
21+
- files:
22+
- '*.cmake'
23+
regex: ([^;\s"]+/sysroot)
24+
replacement: $$ENV{CONDA_BUILD_SYSROOT}
25+
- files:
26+
- '*.cmake'
27+
regex: ([^;\s"]+/MacOSX\d*\.?\d*\.sdk)
28+
replacement: $$ENV{CONDA_BUILD_SYSROOT}
29+
30+
about:
31+
homepage: https://github.com/Livox-SDK/livox_ros_driver2
32+
license: MIT
33+
summary: |
34+
Livox device driver under Ros(Compatible with ros and ros2), support Lidar HAP and Mid-360.
35+
36+
extra:
37+
recipe-maintainers:
38+
- ros-forge
39+
40+
requirements:
41+
build:
42+
- ${{ compiler('cxx') }}
43+
- ${{ compiler('c') }}
44+
- ${{ stdlib('c') }}
45+
- ninja
46+
- python
47+
- setuptools
48+
- git
49+
- if: unix
50+
then:
51+
- patch
52+
- make
53+
- coreutils
54+
- if: win
55+
then:
56+
- m2-patch
57+
- if: osx
58+
then:
59+
- tapi
60+
- if: build_platform != target_platform
61+
then:
62+
- pkg-config
63+
- cmake
64+
- cython
65+
- if: build_platform != target_platform
66+
then:
67+
- python
68+
- cross-python_${{ target_platform }}
69+
- numpy
70+
host:
71+
- if: build_platform == target_platform
72+
then:
73+
- pkg-config
74+
- eigen
75+
- libboost-devel
76+
- livox-sdk2
77+
- numpy
78+
- pcl
79+
- pip
80+
- python
81+
- ros-jazzy-ament-cmake
82+
- ros-jazzy-ament-cmake-auto
83+
- ros-jazzy-ament-lint-auto
84+
- ros-jazzy-ament-lint-common
85+
- ros-jazzy-pcl-conversions
86+
- ros-jazzy-rclcpp
87+
- ros-jazzy-rclcpp-components
88+
- ros-jazzy-ros-environment
89+
- ros-jazzy-ros-workspace
90+
- ros-jazzy-rosidl-default-generators
91+
- ros-jazzy-sensor-msgs
92+
- ros2-distro-mutex 0.8.* jazzy_*
93+
- vtk-base
94+
- if: linux
95+
then:
96+
- libgl-devel
97+
- libopengl-devel
98+
- if: unix
99+
then:
100+
- xorg-libx11
101+
- xorg-libxext
102+
run:
103+
- eigen
104+
- libboost-devel
105+
- pcl
106+
- python
107+
- ros-jazzy-pcl-conversions
108+
- ros-jazzy-rclcpp
109+
- ros-jazzy-rclcpp-components
110+
- ros-jazzy-ros-workspace
111+
- ros-jazzy-sensor-msgs
112+
- ros2-distro-mutex 0.8.* jazzy_*
113+
- vtk-base
114+
- if: osx and x86_64
115+
then:
116+
- __osx >=${{ MACOSX_DEPLOYMENT_TARGET|default('10.14') }}
117+
- if: unix
118+
then:
119+
- xorg-libx11
120+
- xorg-libxext

pixi.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ vinca = { git ="https://github.com/RoboStack/vinca.git", rev = "cbb8eba834ce3834
3434
[feature.beta.tasks]
3535
generate-recipes = { cmd = "vinca -m", depends-on = ["rename-file"] }
3636
remove-file = { cmd = "rm vinca.yaml; rm -rf recipes" }
37-
build_additional_recipes = { cmd = "rattler-build build --recipe-dir ./additional_recipes -m ./conda_build_config.yaml --skip-existing" }
37+
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" }
3838
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"] }
3939
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" } }
4040
create_snapshot = { cmd = "vinca-snapshot -d jazzy -o rosdistro_snapshot.yaml" }

0 commit comments

Comments
 (0)