Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS2 Migration #105

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
.vscode
build
package.xml
__pycache__
20 changes: 9 additions & 11 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -222,8 +222,10 @@ else(ROS_EDITION STREQUAL "ROS2")
# further dependencies manually.
# find_package(<dependency> REQUIRED)
find_package(ament_cmake_auto REQUIRED)
find_package(livox_sdk2 REQUIRED)
ament_auto_find_build_dependencies()
find_package(PCL REQUIRED)
find_package(pcl_conversions REQUIRED)
find_package(std_msgs REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(rosidl_default_generators REQUIRED)
Expand All @@ -246,7 +248,7 @@ else(ROS_EDITION STREQUAL "ROS2")
)

## make sure the livox_lidar_sdk_shared library is installed
find_library(LIVOX_LIDAR_SDK_LIBRARY liblivox_lidar_sdk_shared.so /usr/local/lib REQUIRED)
find_library(LIVOX_LIDAR_SDK_LIBRARY liblivox_lidar_sdk_shared.so REQUIRED)

##
find_path(LIVOX_LIDAR_SDK_INCLUDE_DIR
Expand Down Expand Up @@ -282,15 +284,11 @@ 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
${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()

rosidl_get_typesupport_target(cpp_typesupport_target
${LIVOX_INTERFACES} "rosidl_typesupport_cpp")
target_link_libraries(${PROJECT_NAME} "${cpp_typesupport_target}")


# include file direcotry
target_include_directories(${PROJECT_NAME} PUBLIC
Expand Down Expand Up @@ -330,7 +328,7 @@ else(ROS_EDITION STREQUAL "ROS2")

ament_auto_package(INSTALL_TO_SHARE
config
launch_ROS2
launch
)

endif()
29 changes: 14 additions & 15 deletions config/MID360_config.json
Original file line number Diff line number Diff line change
@@ -1,34 +1,34 @@
{
"lidar_summary_info" : {
"lidar_summary_info": {
"lidar_type": 8
},
"MID360": {
"lidar_net_info" : {
"lidar_net_info": {
"cmd_data_port": 56100,
"push_msg_port": 56200,
"point_data_port": 56300,
"imu_data_port": 56400,
"log_data_port": 56500
},
"host_net_info" : {
"cmd_data_ip" : "192.168.1.5",
"host_net_info": {
"cmd_data_ip": "192.168.1.50",
"cmd_data_port": 56101,
"push_msg_ip": "192.168.1.5",
"push_msg_ip": "192.168.1.50",
"push_msg_port": 56201,
"point_data_ip": "192.168.1.5",
"point_data_ip": "192.168.1.50",
"point_data_port": 56301,
"imu_data_ip" : "192.168.1.5",
"imu_data_ip": "192.168.1.50",
"imu_data_port": 56401,
"log_data_ip" : "",
"log_data_ip": "",
"log_data_port": 56501
}
},
"lidar_configs" : [
"lidar_configs": [
{
"ip" : "192.168.1.12",
"pcl_data_type" : 1,
"pattern_mode" : 0,
"extrinsic_parameter" : {
"ip": "192.168.1.175",
"pcl_data_type": 1,
"pattern_mode": 0,
"extrinsic_parameter": {
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0,
Expand All @@ -38,5 +38,4 @@
}
}
]
}

}
47 changes: 47 additions & 0 deletions launch/livox_mid360_driver.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
import launch

################### user configure parameters for ros2 start ###################
xfer_format = 0 # 0-Pointcloud2(PointXYZRTL), 1-customized pointcloud format
multi_topic = 0 # 0-All LiDARs share the same topic, 1-One LiDAR one topic
data_src = 0 # 0-lidar, others-Invalid data src
publish_freq = 10.0 # freqency of publish, 5.0, 10.0, 20.0, 50.0, etc.
output_type = 0
frame_id = "livox_frame"
lvx_file_path = "/home/livox/livox_test.lvx"
cmdline_bd_code = "livox0000000001"

config_path = os.path.join(get_package_share_directory("livox_ros_driver2"), "config")
user_config_path = os.path.join(config_path, "MID360_config.json")
################### user configure parameters for ros2 end #####################

livox_ros2_params = [
{"xfer_format": xfer_format},
{"multi_topic": multi_topic},
{"data_src": data_src},
{"publish_freq": publish_freq},
{"output_data_type": output_type},
{"frame_id": frame_id},
{"lvx_file_path": lvx_file_path},
{"user_config_path": user_config_path},
{"cmdline_input_bd_code": cmdline_bd_code},
]


def generate_launch_description():
livox_driver = Node(
package="livox_ros_driver2",
executable="livox_ros_driver2_node",
name="livox_lidar_publisher",
output="screen",
parameters=livox_ros2_params,
)

return LaunchDescription(
[
livox_driver,
]
)
57 changes: 57 additions & 0 deletions launch/msg_HAP_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
import launch

################### user configure parameters for ros2 start ###################
xfer_format = 1 # 0-Pointcloud2(PointXYZRTL), 1-customized pointcloud format
multi_topic = 0 # 0-All LiDARs share the same topic, 1-One LiDAR one topic
data_src = 0 # 0-lidar, others-Invalid data src
publish_freq = 10.0 # freqency of publish, 5.0, 10.0, 20.0, 50.0, etc.
output_type = 0
frame_id = "livox_frame"
lvx_file_path = "/home/livox/livox_test.lvx"
cmdline_bd_code = "livox0000000001"

cur_path = os.path.split(os.path.realpath(__file__))[0] + "/"
cur_config_path = cur_path + "../config"
rviz_config_path = os.path.join(cur_config_path, "livox_lidar.rviz")
user_config_path = os.path.join(cur_config_path, "HAP_config.json")
################### user configure parameters for ros2 end #####################

livox_ros2_params = [
{"xfer_format": xfer_format},
{"multi_topic": multi_topic},
{"data_src": data_src},
{"publish_freq": publish_freq},
{"output_data_type": output_type},
{"frame_id": frame_id},
{"lvx_file_path": lvx_file_path},
{"user_config_path": user_config_path},
{"cmdline_input_bd_code": cmdline_bd_code},
]


def generate_launch_description():
livox_driver = Node(
package="livox_ros_driver2",
executable="livox_ros_driver2_node",
name="livox_lidar_publisher",
output="screen",
parameters=livox_ros2_params,
)

return LaunchDescription(
[
livox_driver,
# launch.actions.RegisterEventHandler(
# event_handler=launch.event_handlers.OnProcessExit(
# target_action=livox_rviz,
# on_exit=[
# launch.actions.EmitEvent(event=launch.events.Shutdown()),
# ]
# )
# )
]
)
56 changes: 56 additions & 0 deletions launch/msg_MID360_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
import launch

################### user configure parameters for ros2 start ###################
xfer_format = 1 # 0-Pointcloud2(PointXYZRTL), 1-customized pointcloud format
multi_topic = 0 # 0-All LiDARs share the same topic, 1-One LiDAR one topic
data_src = 0 # 0-lidar, others-Invalid data src
publish_freq = 10.0 # freqency of publish, 5.0, 10.0, 20.0, 50.0, etc.
output_type = 0
frame_id = "livox_frame"
lvx_file_path = "/home/livox/livox_test.lvx"
cmdline_bd_code = "livox0000000001"

cur_path = os.path.split(os.path.realpath(__file__))[0] + "/"
cur_config_path = cur_path + "../config"
user_config_path = os.path.join(cur_config_path, "MID360_config.json")
################### user configure parameters for ros2 end #####################

livox_ros2_params = [
{"xfer_format": xfer_format},
{"multi_topic": multi_topic},
{"data_src": data_src},
{"publish_freq": publish_freq},
{"output_data_type": output_type},
{"frame_id": frame_id},
{"lvx_file_path": lvx_file_path},
{"user_config_path": user_config_path},
{"cmdline_input_bd_code": cmdline_bd_code},
]


def generate_launch_description():
livox_driver = Node(
package="livox_ros_driver2",
executable="livox_ros_driver2_node",
name="livox_lidar_publisher",
output="screen",
parameters=livox_ros2_params,
)

return LaunchDescription(
[
livox_driver,
# launch.actions.RegisterEventHandler(
# event_handler=launch.event_handlers.OnProcessExit(
# target_action=livox_rviz,
# on_exit=[
# launch.actions.EmitEvent(event=launch.events.Shutdown()),
# ]
# )
# )
]
)
65 changes: 65 additions & 0 deletions launch/rviz_HAP_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
import launch

################### user configure parameters for ros2 start ###################
xfer_format = 0 # 0-Pointcloud2(PointXYZRTL), 1-customized pointcloud format
multi_topic = 0 # 0-All LiDARs share the same topic, 1-One LiDAR one topic
data_src = 0 # 0-lidar, others-Invalid data src
publish_freq = 10.0 # freqency of publish, 5.0, 10.0, 20.0, 50.0, etc.
output_type = 0
frame_id = "livox_frame"
lvx_file_path = "/home/livox/livox_test.lvx"
cmdline_bd_code = "livox0000000001"

cur_path = os.path.split(os.path.realpath(__file__))[0] + "/"
cur_config_path = cur_path + "../config"
rviz_config_path = os.path.join(cur_config_path, "display_point_cloud_ROS2.rviz")
user_config_path = os.path.join(cur_config_path, "HAP_config.json")
################### user configure parameters for ros2 end #####################

livox_ros2_params = [
{"xfer_format": xfer_format},
{"multi_topic": multi_topic},
{"data_src": data_src},
{"publish_freq": publish_freq},
{"output_data_type": output_type},
{"frame_id": frame_id},
{"lvx_file_path": lvx_file_path},
{"user_config_path": user_config_path},
{"cmdline_input_bd_code": cmdline_bd_code},
]


def generate_launch_description():
livox_driver = Node(
package="livox_ros_driver2",
executable="livox_ros_driver2_node",
name="livox_lidar_publisher",
output="screen",
parameters=livox_ros2_params,
)

livox_rviz = Node(
package="rviz2",
executable="rviz2",
output="screen",
arguments=["--display-config", rviz_config_path],
)

return LaunchDescription(
[
livox_driver,
livox_rviz,
# launch.actions.RegisterEventHandler(
# event_handler=launch.event_handlers.OnProcessExit(
# target_action=livox_rviz,
# on_exit=[
# launch.actions.EmitEvent(event=launch.events.Shutdown()),
# ]
# )
# )
]
)
Loading