Skip to content

gabrieldse/mod_mid360_simulation_plugin

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

17 Commits
 
 
 
 
 
 
 
 

Repository files navigation

Mid360_simulation_plugin

Plugin for the simulation of the Livox Mid-360 based on the official plugin

Main changes:

  • Support for ROS Noetic
  • Support for Gazebo 11
  • Standalone
    • No need to install the livox ros driver
    • No need to install the livox sdk
  • Support for custom message formats
  • Corrected the distortion of the point cloud

plot

On the left you can see the point cloud generated by the original plugin, on the right the point cloud generated by this plugin. The distortion is clearly visible in the left image.

Build instructions

Tested on

OS COMPILER Cmake version
Ubuntu 20.04 GCC >= 9.4 > 3.16.3
  1. Clone this repo into your catkin workspace src folder.
cd ~/catkin_ws/src
git clone https://github.com/fratopa/Mid360_simulation_plugin.git
  1. Build the plugin.
cd ~/catkin_ws
source opt/ros/noetic/setup.bash
catkin build -DCMAKE_BUILD_TYPE=Release

Usage instructions

To add the plugin to your robot model add the following lines to your sdf file create a link and then attach the sensor to the link as such:

<!-- LIDAR sensor -->
    <link name="link_lidar">
    <visual>
      <origin xyz="0 0 5.0e-05" rpy="0 0 0"/>
      <geometry>
        <!-- The default unity of meshes is meters in gazebo but millimeter for other mesh softwares -->
        <mesh filename="$(find sqdr_simulator_media)/media/models/lidar_unitree_l1/meshes/lidar_unitree_l1.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </visual>
  </link>

    <!-- SENSOR PLUGIN -->
    <gazebo reference="link_lidar">
      <sensor type="ray" name="laser_livox">
          <!-- To center the plugin at the center of the mesh -->
          <pose>0.01 0.015 0.02 0 0 0</pose>
          <visualize>true</visualize>
          <!-- 11 for the unitree l1 and 10 for the livox mid 360 -->
          <update_rate>11</update_rate>
         
          <plugin name="gazebo_ros_laser_controller" filename="liblivox_laser_simulation.so">
            <ray>
              <scan>
                 <!-- These parameters are only for the visualization
                 horizontal or vertical samples is the amount showed lines.
                 Do not change the resolution or min_angle/max_angle -->
                <horizontal>
                  <samples>100</samples>
                  <resolution>1</resolution>
                  <min_angle>-3.1415926535897931</min_angle>
                  <max_angle>3.1415926535897931</max_angle>
                </horizontal>
                <vertical>
                  <samples>100</samples>
                  <resolution>1</resolution>
                  <min_angle>-3.1415926535897931</min_angle>
                  <max_angle>3.1415926535897931</max_angle>
                </vertical>
                <!-- End of visualisation parameters -->
              </scan>
              
              <range>
                <min>1</min> <!-- <min>0.05</min>  -->
                <max>30</max>
                <!-- <resolution>1</resolution>  --> <!-- apparently useless -->
              </range>

              <noise>
                <type>gaussian</type>
                <mean>0.0</mean>
                <!-- FOR some reason the noise is not working  -->
                <stddev>0.1</stddev>
              </noise>
            </ray>

              <noise_stddev>0.002</noise_stddev>
              <noise_angle_stddev>0.02</noise_angle_stddev>
              <mean>0.0</mean>

              <visualize>false</visualize>
              <!-- Samples in points per second*** -->
              <samples>2160</samples>
              <!-- Downsample: 
              1 or less  = full samples
              2 = 1/2 of the points
              5 = 1/5 of the points -->
              <downsample>1</downsample>

              <!-- Here you change the CSV file of the correct scan patter.
              e.g mid360-real-centr.csv,
              unitree_polar.csv  -->
              <csv_file_name>unitree_polar.csv</csv_file_name>

              <!-- Types of pointcloud type:
              0 = SENSOR_MSG_POINT_CLOUD
              1 = SENSOR_MSG_POINT_CLOUD2_POINTXYZ
              2 = SENSOR_MSG_POINT_CLOUD2_LIVOXPOINTXYZRTLT
              3 = livox_laser_simulation_CUSTOM_MSG
               -->
              <publish_pointcloud_type>2</publish_pointcloud_type>
              <!-- Currently not implemented -->
              <robotNamespace>$(arg robotNamespace)</robotNamespace>
              <ros_topic>/unilidar/cloud</ros_topic>
              <frameName>unilidar_lidar</frameName>

          </plugin>
        </sensor>
    </gazebo> 

Parameters

The main parameters you may want to change are:

  • visualize: If set to true the plugin will visualize the laser in gazebo, this is usefull for debugging but you may consider turning this off to improve performances.
  • downsample: The higher the downsample factor the fewer points will be generated. this parameter can be usefull to reduce the computational load of the simulation.
  • publish_pointcloud_type: This changes the format in which the pointcloud will be published:
    • 0: The pointcloud will be published as a sensor_msgs::PointCloud message
    • 1: The pointcloud will be published as a sensor_msgs::pointcloud2 message with fields x, y, z
    • 2 (default): The pointcloud will be published as a sensor_msgs::pointcloud2 message with fields x, y, z, intensity, tag, line, timestamp.
    • 3: The pointcloud will be published in the Livox custom message format.
    offset_time: 
    x: 
    y: 
    z: 
    reflectivity: 
    tag: 
    line: 
    
    

Run instructions

To verify that the plugin is working correctly you can run the minimal example:

source ~/catkin_ws/devel/setup.bash
roslaunch livox_laser_simulation test_pattern.launch

This will launch the plugin with a test pattern. You should see a point cloud in RViz and a gazebo window with a spinning laser.

Citation

If you use this plugin in your research, please cite the following paper:

@Article{isprs-archives-XLVIII-1-W1-2023-539-2023,
AUTHOR = {Vultaggio, F. and d'Apolito, F. and Sulzbachner, C. and Fanta-Jende, P.},
TITLE = {SIMULATION OF LOW-COST MEMS-LIDAR AND ANALYSIS OF ITS EFFECT ON THE PERFORMANCES OF STATE-OF-THE-ART SLAMS},
JOURNAL = {The International Archives of the Photogrammetry, Remote Sensing and Spatial Information Sciences},
VOLUME = {XLVIII-1/W1-2023},
YEAR = {2023},
PAGES = {539--545},
URL = {https://isprs-archives.copernicus.org/articles/XLVIII-1-W1-2023/539/2023/},
DOI = {10.5194/isprs-archives-XLVIII-1-W1-2023-539-2023}
}

About

Modification of the fratopa/Mid360_simulation_plugin to add unitree l1 support on ROS 1 Noetic

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Contributors 2

  •  
  •