ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Explanation on sensor_msgs/LaserScan and time

asked 2018-05-16 11:20:27 -0600

erenaud gravatar image

updated 2018-05-16 14:21:08 -0600

Hi everyone !

I am currently working on LaserScan messages and I don't quite understand how time related attributes should be filled. If I look at the documentation :

Header header            # timestamp in the header is the acquisition time of 
                     # the first ray in the scan.
                     #
                     # in frame frame_id, angles are measured around 
                     # the positive Z axis (counterclockwise, if Z is up)
                     # with zero angle being forward along the x axis

float32 angle_min        # start angle of the scan [rad]
float32 angle_max        # end angle of the scan [rad]
float32 angle_increment  # angular distance between measurements [rad]

float32 time_increment   # time between measurements [seconds] - if your scanner
                         # is moving, this will be used in interpolating position
                         # of 3d points
float32 scan_time        # time between scans [seconds]

float32 range_min        # minimum range value [m]
float32 range_max        # maximum range value [m]

float32[] ranges         # range data [m] (Note: values < range_min or > range_max should be discarded)
float32[] intensities    # intensity data [device-specific units].  If your
                         # device does not provide intensities, please leave
                         # the array empty.

I understand that scan_time is the total duration of one scan (i.e. duration of my n measurements) and that time_increment is the duration of one measurement (so scan_time = time_increment x n).

But then, I began to play around with this bag file, which replay Laser Scan messages ( https://github.com/mlab-upenn/f1_10_c... ), and I realized that my assumption are not right. By doing :

rostopic echo /scan

I got one of the message:

header: 
  seq: 40906
  stamp: 
    secs: 1458504920
    nsecs: 148172000
  frame_id: "laser"
angle_min: -1.57079637051
angle_max: 1.56643295288
angle_increment: 0.00436332309619
time_increment: 1.73611115315e-05
scan_time: 0.0250000003725
range_min: 0.0230000000447
range_max: 60.0

I know I have n=720 measurements, because I watched for ranges size and because:

full_angle/angle_increment = (1.56643295288+1.57079637051) / 0.00436332309619 = 719 (+ 1 for the first element).

But when I do the same with time, I get 2 x n as result:

scan_time/time_increment = 0.0250000003725÷1.73611115315×10^05 = 1440

So why is that ? Am I missing something ?

This bag file seems correct, beacause I managed to reproduce the simulation as the author did in a video ( https://www.youtube.com/watch?v=3C_eR... ).

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
4

answered 2018-05-16 12:35:37 -0600

scan_time will only be equal to time_increment x number_of_samples if it is a full 360 degree scan.

In the case of the message you showed it is only a 180 degree scan therefore the scan time is twicetime_increment x number_of_samples.

As described scan_time is # time between scans [seconds] not the duration of the scan. Think of scan time as the time taken for a full rotation of the sensor even if it's only producing data for part of that revolution.

edit flag offensive delete link more

Comments

Oh okay, thanks ! So does it mean that a device that produces laser scan messages MUST be constantly rotating ? So I can't have a laser travelling from -pi/2 to pi/2 ? If yes, can I have a laser measuring from -pi/2 to pi/2 and then pi/2 to -pi/2 and so on ?

erenaud gravatar image erenaud  ( 2018-05-17 03:07:05 -0600 )edit

I have another question. Let's say I have a laser scan that is actually doing a full 360° scan. But when placed below the robot, the wheels are obstrucating parts of the field. Let's say that I can't scan from -pi/4 to -3pi/4 and pi/4 to 3pi/4. What should I do then ? Several messages ? Use filters?

erenaud gravatar image erenaud  ( 2018-05-17 03:11:56 -0600 )edit
1

All of the real world laser scanners I can think of have a rotating element, the mechanics of these sensors has driven the design of this sensor message.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-05-17 07:58:01 -0600 )edit
1

As described in the message definition the scan time is the time between scans, it doesn't make any assumptions about how they are produced so you could scan from -/+ pi with no delays using a rotating prism design. Some high performance 3d scanners do just this.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-05-17 08:01:52 -0600 )edit
1

Finally if you had a 360 degree scanner under your robot then you don't need to do anything. If the wheels are closer than the minimum sensing distance there will simply be null values for those samples.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-05-17 08:04:19 -0600 )edit

Okay, thank you for your help !

erenaud gravatar image erenaud  ( 2018-05-17 08:39:09 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2018-05-16 11:20:27 -0600

Seen: 3,558 times

Last updated: May 16 '18