图为智盒同时连接Mid360和HAP激光雷达
1、使用x86架构的设备连接Mid360
拿到新的Mid360需要进行一下操作:
-
使用网线连接Mid360与x86架构的设备,配置ip地址
-
开放本机ipv4地址为192.168.1.5,子网掩码255.255.255.0, 网关192.168.1.1
-
Mid360初始ip地址为192.168.1.1xx,xx为SN码最后两位,ping 192.168.1.1xx测试是否能访问到雷达,如果能ping通执行以下操作:
- 在Livox官网下载Livox Viewer2。通过livox Viewer2连接Mid360,在Viewer2中点击设置按钮,修改雷达ip地址。从上到下依次为:
192.168.1.101
,255.255.255.0
,192.168.1.1
,192.168.1.5
。 - 修改完成后保存
- 在Livox官网下载Livox Viewer2。通过livox Viewer2连接Mid360,在Viewer2中点击设置按钮,修改雷达ip地址。从上到下依次为:
2、使用图为智盒连接HAP和Mid360
-
连接HAP和MID360到交换机上,交换机连接图为智盒。
-
开放图为智盒ipv4地址为192.168.1.5,子网掩码255.255.255.0,网关192.168.1.1
-
修改Livox_ros_driver2/config/mixed_HAP_MID360_config.json文件,修改完成后如下:
{ "lidar_summary_info" : { "lidar_type": 8 }, "HAP": { "lidar_net_info" : { "cmd_data_port": 56000, "push_msg_port": 0, "point_data_port": 57000, "imu_data_port": 58000, "log_data_port": 59000 }, "host_net_info" : { "cmd_data_ip" : "192.168.1.5", "cmd_data_port": 56000, "push_msg_ip": "", "push_msg_port": 0, "point_data_ip": "192.168.1.5", "point_data_port": 57000, "imu_data_ip" : "192.168.1.5", "imu_data_port": 58000, "log_data_ip" : "", "log_data_port": 59000 } }, "MID360": { "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", "cmd_data_port": 56101, "push_msg_ip": "192.168.1.5", "push_msg_port": 56201, "point_data_ip": "192.168.1.5", "point_data_port": 56301, "imu_data_ip" : "192.168.1.5", "imu_data_port": 56401, "log_data_ip" : "", "log_data_port": 56501 } }, "lidar_configs" : [ { "ip" : "192.168.1.100", "pcl_data_type" : 1, "pattern_mode" : 0, "extrinsic_parameter" : { "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "x": 0, "y": 0, "z": 0 } }, { "ip" : "192.168.1.101", "pcl_data_type" : 1, "pattern_mode" : 0, "extrinsic_parameter" : { "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "x": 0, "y": 0, "z": 0 } } ] }
-
修改Livox_ros_driver2/launch_ROS1/rviz_mixed.launch文件,修改完成后如下:
<launch> <!--user configure parameters for ros start--> <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"/> <!--这里改成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="true"/> <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"/> <!--user configure parameters for ros end--> <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_driver2)/config/mixed_HAP_MID360_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_publisher2" pkg="livox_ros_driver2" type="livox_ros_driver2_node" required="true" output="screen" args="$(arg cmdline_arg)"/> <group if="$(arg rviz_enable)"> <node name="livox_rviz" pkg="rviz" type="rviz" respawn="true" args="-d $(find livox_ros_driver2)/config/display_point_cloud_ROS1.rviz"/> </group> <group if="$(arg rosbag_enable)"> <node pkg="rosbag" type="record" name="record" output="screen" args="-a"/> </group> </launch>
-
执行
roslaunch livox_ros_driver2 rviz_mixed.launch
可以同时查看到两个topic雷达