RobustFieldAutonomyLab / LeGO-LOAM

LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain
BSD 3-Clause "New" or "Revised" License
2.35k stars 1.11k forks source link

Setting up a Quanergy M8 Lidar #161

Closed jmachuca77 closed 4 years ago

jmachuca77 commented 4 years ago

Hi I am trying to set up this package to work with the Quanergy M8, however I am not having good results with the standard setup. The Quanergy lidar has 8 beams at 10hz it has an angular resolution of 0.06deg, the lowest beam is at -18.25 deg and the highest beam at 3.2 deg. So I have the following settings:

    laser:
        num_vertical_scans: 8
        num_horizontal_scans: 6000
        ground_scan_index: 0
        vertical_angle_bottom: -18.25       # degrees
        vertical_angle_top: 3.2             # degrees
        sensor_mount_angle: 0               # degrees
        scan_period: 0.1                    # seconds

When the package starts as long as its driving in a straight like it works ok, but as soon as it turns it gets lost. Im not sure if I have something setup wrong or if its something else. I am wondering if the problem is that the beams are not at equidistant angles. And if that is the problem is there a way to modify the code to cope with that?

You can find a couple of bag files on these links: rightCircuit.bag leftCircuit.bag

This is the launch file I am using:

<launch>

    <!--- Sim Time -->
    <param name="/use_sim_time" value="true" />

    <!--- Run Rviz-->
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find lego_loam)/launch/test.rviz" />

    <!--- TF -->
    <node pkg="tf" type="static_transform_publisher" name="camera_init_to_map"  args="0     0 0     1.570795    0           1.5$
    <node pkg="tf" type="static_transform_publisher" name="sensor_to_camera"    args="0     0 0     -1.570795   -1.570795   0  $
    <node pkg="tf" type="static_transform_publisher" name="base_link_to_camera" args="0 0 0 -1.570795   -1.570795   0          $

    <!--- LeGO-LOAM -->
    <node pkg="lego_loam" type="imageProjection"    name="imageProjection"    output="screen">
<!--
        <remap from="/Sensor/points" to="/velodyne_points"/>
        <remap from="/mavros/imu/data" to="/imu/data"/>
-->
    </node>
    <node pkg="lego_loam" type="featureAssociation" name="featureAssociation" output="screen"/>
    <node pkg="lego_loam" type="mapOptmization"     name="mapOptmization"     output="screen"/>
    <node pkg="lego_loam" type="transformFusion"    name="transformFusion"    output="screen"/>

</launch>

and these are the mods I've made to the utility.h file:

extern const string pointCloudTopic = "/Sensor/points";
extern const string imuTopic = "/mavros/imu/data";

// Quanergy M8
extern const int N_SCAN = 8;
extern const int Horizon_SCAN = 6000;
extern const float ang_res_x = 0.06;
extern const float ang_res_y = 3.2;
extern const float ang_bottom = 18.25;
extern const int groundScanInd = 7;

// Modified these values because of the lower number of scan lines
extern const int segmentValidPointNum = 3;
extern const int segmentValidLineNum = 2;
extern const int surfFeatureNum = 3;

//Modified in order to allow it to detect features further away (lidar range is 100m)
extern const float nearestFeatureSearchSqDist = 70;

extern const float historyKeyframeSearchRadius = 10.0; // key frame that is within n meters from current pose will be considerd for loop closure

Here are the relevant parts of the spec sheet: Timestamp The timestamp for each packet occurs when the last firing of the packet has been completed, that is, after the firing of beam 7.

Position The encoder position occurs when the first firing of the packet has been completed, that is, after the firing of beam 0.

Laser Firing The M8-PoE+ sensor spins at 10 Hz (at its default and recommended setting). The lasers fire at a constant rate of exactly 53,828 Hz. The lasers do not fire simultaneously, but in a sequence to avoid interference. The firing sequence is 0, 4, 2, 6, 1, 5, 3, 7, where 0 is the lowest downward-looking beam, and 7 is the highest upward-looking beam. There is no horizontal or vertical angle offset.

Beam Angles The pointcloud_generator_m8 source code specifies beam separation angles (Figure 18), from bottom angle to top, in radians, as follows:

const double M8_VERTICAL_ANGLES[] = { -0.318505,
                                      -0.2692,
                                      -0.218009,
                                      -0.165195, 
                                      -0.111003, 
                                      -0.0557982, 
                                       0.f, 
                                       0.0557982 };

Screen Shot 2020-01-27 at 3 55 34 PM

The values in the code are designed for working with optics. In round numbers, the vertical field of view is 20 degrees, the theoretical value for beam spacing is 3 degrees, and the top beam is about +3 degrees. The laser firing position is shown in Figure 19.

Screen Shot 2020-01-27 at 4 01 18 PM

7. Q: If I change the rotational speed of the M8-PoE+ sensor within the 5-20 Hz valid range, what happens to the laser fire timing? Does rotational speed affect heat production? A: Changing the frame rate does not affect laser fire timing, nor does it have a significant effect on heat production. The angular resolution will change as a result of the changed rotational speed under constant firing timing. The 10 Hz frame rate (recommended for most applications) corresponds to 0.06 degree angular resolution.

TixiaoShan commented 4 years ago

Hi @jmachuca77 I took a brief look at your dataset and have a few problems.

  1. The lidar rotation rate is not always constant at 10Hz. It only rotates at around 4Hz.
  2. The Quanergy M8 Lidar specs I found online is different from the one you provided. Probably you are using a different version of M8?
    extern const int N_SCAN = 8;
    extern const int Horizon_SCAN = 6000;
    extern const float ang_res_x = 0.06;
    extern const float ang_res_y = 2.857;
    extern const float ang_bottom = 17;
    extern const int groundScanInd = 4;
  3. Since the lidar is so sparse, the segmentation won't work very well. I suggest change line to labelMat.at<int>(i,j) = 1; to skip segmentation completely.
jmachuca77 commented 4 years ago

Ok, thanks I'll give that a try. I have not seen issues with the rate on the vehicle, maybe a problem with the bagfile or the recording... I'll check. About the spec, what I posted is from the lidar you found, but from the user manual

jmachuca77 commented 4 years ago

Sorry for the delay, I tried the modifications, however the results were very similar to what I have before. The forward movement seems ok, but as soon as I get to a turn it fails to register that correctly, what should be a 90 degree turn, seems more like a 45 deg turn.

This is with the setting for the lidar you posted on point 2 above and the suggested change on point 3 BadLegoLoamTrajectory1

This is with my settings for the lidar and your suggested change on point 3 above. BadTrajectoryLeGO-LOAM

jmachuca77 commented 4 years ago

seems like it initially does the turn correctly, but then drifts off by 45 deg.

TixiaoShan commented 4 years ago

seems like it initially does the turn correctly, but then drifts off by 45 deg.

Are you using IMU with it? If yes, have you tried to not use the IMU?

cristianrubioa commented 3 years ago

Hi @jmachuca77 Could you share with me a brief example of the Quanergy M8 Lidar bag files, please! At first, I think I am generating bag files wrong, could you guide me through the process to achieve a good bag file for this Lidar sensor.

Your help will help me a lot !