Skip to content

Commit

Permalink
修改launch,多用sep的launch,mid-100并不一定能够为r3live使用
Browse files Browse the repository at this point in the history
  • Loading branch information
zengy5 committed Sep 27, 2023
2 parents 73b7059 + c757a5d commit 89bb24c
Show file tree
Hide file tree
Showing 4 changed files with 92 additions and 0 deletions.
6 changes: 6 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
<<<<<<< HEAD
# Livox ROS Driver([览沃ROS驱动程序中文说明](https://github.com/Livox-SDK/livox_ros_driver/blob/master/README_CN.md))

livox_ros_driver is a new ROS package, specially used to connect LiDAR products produced by Livox. The driver can be run under ubuntu 14.04/16.04/18.04 operating system with ROS environment (indigo, kinetic, melodic) installed. Tested hardware platforms that can run livox_ros_driver include: Intel x86 cpu platforms, and some ARM64 hardware platforms (such as nvida TX2 / Xavier, etc.).
Expand Down Expand Up @@ -287,3 +288,8 @@ You can get support from Livox with the following methods :

* Send email to [email protected] with a clear description of your problem and your setup
* Report issue on github
=======
# livox_ros_driver_zyx
livox时间同步的driver
修改了pointcloud2和customMsg的时间戳,与系统时间同步
>>>>>>> c757a5dcdefb4e7a64c9bf343732668e418e5783
File renamed without changes.
43 changes: 43 additions & 0 deletions launch/livox_hub_cloud_sep.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
<launch>

<arg name="lvx_file_path" default="livox_test.lvx"/>
<arg name="bd_list" default="100000000000000"/>
<arg name="xfer_format" default="0"/>
<arg name="multi_topic" default="1"/>
<arg name="data_src" default="1"/>
<arg name="publish_freq" default="10.0"/>
<arg name="output_type" default="0"/>
<arg name="rviz_enable" default="false"/>
<arg name="rosbag_enable" default="false"/>
<arg name="cmdline_arg" default="$(arg bd_list)"/>
<arg name="msg_frame_id" default="livox_frame"/>
<arg name="lidar_bag" default="true"/>
<arg name="imu_bag" default="true"/>

<param name="xfer_format" value="$(arg xfer_format)"/>
<param name="multi_topic" value="$(arg multi_topic)"/>
<param name="data_src" value="$(arg data_src)"/>
<param name="publish_freq" type="double" value="$(arg publish_freq)"/>
<param name="output_data_type" value="$(arg output_type)"/>
<param name="cmdline_str" type="string" value="$(arg bd_list)"/>
<param name="cmdline_file_path" type="string" value="$(arg lvx_file_path)"/>
<param name="user_config_path" type="string" value="$(find livox_ros_driver)/config/livox_hub_config.json"/>
<param name="frame_id" type="string" value="$(arg msg_frame_id)"/>
<param name="enable_lidar_bag" type="bool" value="$(arg lidar_bag)"/>
<param name="enable_imu_bag" type="bool" value="$(arg imu_bag)"/>

<node name="livox_lidar_publisher" pkg="livox_ros_driver"
type="livox_ros_driver_node" required="true"
output="screen" args="$(arg cmdline_arg)"/>

<group if="$(arg rviz_enable)">
<node name="rviz" pkg="rviz" type="rviz" respawn="true"
args="-d $(find livox_ros_driver)/config/display_hub_points.rviz"/>
</group>

<group if="$(arg rosbag_enable)">
<node pkg="rosbag" type="record" name="record" output="screen"
args="-a"/>
</group>

</launch>
43 changes: 43 additions & 0 deletions launch/livox_lidar_msg_sep.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
<launch>

<arg name="lvx_file_path" default="livox_test.lvx"/>
<arg name="bd_list" default="100000000000000"/>
<arg name="xfer_format" default="1"/>
<arg name="multi_topic" default="1"/>
<arg name="data_src" default="0"/>
<arg name="publish_freq" default="10.0"/>
<arg name="output_type" default="0"/>
<arg name="rviz_enable" default="false"/>
<arg name="rosbag_enable" default="false"/>
<arg name="cmdline_arg" default="$(arg bd_list)"/>
<arg name="msg_frame_id" default="livox_frame"/>
<arg name="lidar_bag" default="true"/>
<arg name="imu_bag" default="true"/>

<param name="xfer_format" value="$(arg xfer_format)"/>
<param name="multi_topic" value="$(arg multi_topic)"/>
<param name="data_src" value="$(arg data_src)"/>
<param name="publish_freq" type="double" value="$(arg publish_freq)"/>
<param name="output_data_type" value="$(arg output_type)"/>
<param name="cmdline_str" type="string" value="$(arg bd_list)"/>
<param name="cmdline_file_path" type="string" value="$(arg lvx_file_path)"/>
<param name="user_config_path" type="string" value="$(find livox_ros_driver)/config/livox_lidar_config.json"/>
<param name="frame_id" type="string" value="$(arg msg_frame_id)"/>
<param name="enable_lidar_bag" type="bool" value="$(arg lidar_bag)"/>
<param name="enable_imu_bag" type="bool" value="$(arg imu_bag)"/>

<node name="livox_lidar_publisher" pkg="livox_ros_driver"
type="livox_ros_driver_node" required="true"
output="screen" args="$(arg cmdline_arg)"/>

<group if="$(arg rviz_enable)">
<node name="rviz" pkg="rviz" type="rviz" respawn="true"
args="-d $(find livox_ros_driver)/config/display_lidar_points.rviz"/>
</group>

<group if="$(arg rosbag_enable)">
<node pkg="rosbag" type="record" name="record" output="screen"
args="-a"/>
</group>

</launch>

0 comments on commit 89bb24c

Please sign in to comment.