Vertical laser beams appearing higher the further away it goes

Issue #4 resolved
Bo Chen created an issue

Hi,

I'm having issues with the plugin:

The reflected lasers that hit the ground do not appear to be hitting the ground, but a bit higher than the ground. the further away you go, the more off the laser seems to be from the ground. If I tilt the laser and let it hit the ground horizontally, then it doesn't have this issue. Something seems to be wrong with the vertical laser beam calculation?

Regards, Bo

Comments (13)

  1. Bo Chen reporter

    Just to illustrate a bit better what I mean I attach another screenshot. There you can see the pointcloud2 in RVIZ, colored by Z axis. You can see the points from the normal positioned velodyne go up in Z value although it is a plain ground without any elevation or so. The horizontally positioned velodyne hits the ground normal, without this strange distortion.

  2. Bo Chen reporter

    I found the error! In your GazeboRosVelodyneLaser.cpp, line 371 should be: double pAngle = j * pDiff / (verticalRayCount -1) + verticalMinAngle.Radian();

    instead of double pAngle = 0.5*(vja+vjb) * pDiff / (verticalRayCount -1) + verticalMinAngle.Radian();

  3. philinedonner

    Hi Bo Chen,

    I got confused by the same "bended ground" as well. However, as far as I understand, within the plugin the ground truth range readings from gazebo are "manipulated" by averaging 4 ground truth ranges (the following one of the same layer and two from the layer above). As a result the pointcloud gets biased to higher z values, but also has modified x and y values.

    If you would like to get the "ground truth" pointcloud, replace

      r = (1 - vb) * ((1 - hb) * r1 + hb * r2)     +     vb  * ((1 - hb) * r3 + hb * r4);
    

    by

    if GAZEBO_MAJOR_VERSION >= 7

      r = std::min(parent_ray_sensor_->LaserShape()->GetRange(i + j * rayCount) , maxRange);
    

    else

      r = std::min(parent_ray_sensor_->GetLaserShape()->GetRange(i + j * rayCount) , maxRange);
    

    endif

      r = std::max(r, minRange);
    

    and set

      double yAngle =  i * yDiff / (rayCount -1) + minAngle.Radian();
      double pAngle =  j * pDiff / (verticalRayCount -1) + verticalMinAngle.Radian();
    

    We are still wondering what the reason for this interpolation was: was this done to simulate the behavior of a real sensor, where the increased size of the beam leads to a bended ground as well? I'd assume that this implementation still only makes sense, if the sensor looks towards the ground (not to the ceiling), and if the layers are close to each other?

    Thank you for your insight! Philine

  4. Bo Chen reporter

    Hi Philine,

    Interesting! I'll try out your new code next week!

    I didn't implement this, so unfortunately I don't know the reasons behind that implementation.

    What I can say is that this is definitely not how the real velodyne sensors behave in ROS, at least not now with the current driver in kinetic.

    Regards, Bo

  5. Kevin Hallenbeck

    We removed the interpolation option, and points now appear on the ground. What do you guys think?

    @bchen87 @philinedonner

  6. Bo Chen reporter

    @kmhallen it seems to be fixed, thanks for that!

    However, I notices another odd behaviour now: When the vehicle moves forward, the laserbeams in the front somehow disappear. But maybe it is unrelated to this issue?

    Screenshot from 2017-09-01 17-24-17.png

  7. Kevin Hallenbeck

    @bchen87 Unrelated, but there were some self-collisions from Gazebo in the direction of motion. It should be fixed with commit 565f3e5.

  8. Log in to comment