SICKAG / sick_safetyscanners

ROS driver for SICK safety laser scanners
https://www.sick.com/de/en/opto-electronic-protective-devices/safety-laser-scanners/c/g187225
Apache License 2.0
61 stars 59 forks source link

angular_resolution in field_data service response seems inplausible #60

Closed chr-wurm closed 3 years ago

chr-wurm commented 4 years ago

this might be connected with #48

The response to the /field_data service contains for each field:

ranges: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.069000005722046, 1.069000005722046, 1.069000005722046, 1.0700000524520874,  
[...]
0.0, 0.0, 0.0, 0.0, 0]
    start_angle: -1.5707963705062866
    angular_resolution: 7.074021368680405e-07
    protective_field: True

the ranges array holds 1651 values. I though I could reconstruct the field in cartesian coordinates by assuming the angle for each range like this:

angle = index * angular_resolution + start_angle

however, as the maximum index is 1650, this only covers an angle of 1.167 rad or 0.067 deg. Is the angular_resolution value really in rad, and is it correct?

puck-fzi commented 4 years ago

Is the angular_resolution value really in rad, and is it correct?

Since ROS uses radians as type it should be in radians. So the first part i would answer with a yes, for is it correct, apparently as your calculations state it is not. I am assuming you have a larger angle then 1.167 rad enabled currently?

Which laserscanner are you using? and what is your start and end angel configuration?

chr-wurm commented 4 years ago

this is the header of the extended_laser_scan topic:

---
laser_scan: 
  header: 
    seq: 0
    stamp: 
      secs: 1599571517
      nsecs: 359297999
    frame_id: "laser_front_link"
  angle_min: -2.399827718734741
  angle_max: 2.158421754837036
  angle_increment: 0.0029088794253766537
  time_increment: 1.4000000192027073e-05
  scan_time: 0.029999999329447746
  range_min: 0.10000000149011612
  range_max: 40.0

it is the nanoScan3 , version 1.8.0.24

chr-wurm commented 4 years ago

using (275 / len(ranges)) * pi / 180 as angular_resolution works

puck-fzi commented 4 years ago

With 275 being the maximum angle of the scanner in degrees?

And yes i agree this will work, however I want to make sure, that the error is in the code or if its in the data from the sensor. Since the angular resolution is send by the sensor and then parsed by the driver.

chr-wurm commented 4 years ago

yes, exactly, I took the full angular range. Thanks for your investigation!

echeng22 commented 3 years ago

If it helps in the investigation, we noticed that this issue appeared after updating to 1.0.5, where the angular resolution was in the 10^-7 scale. We've reverted back to 1.0.3 (the version we were using originally), and the angular resolution looks reasonable again.

We're looking to check if 1.0.6 also has the issue; I'll post updates after we've tried it out.

puck-fzi commented 3 years ago

That would be great. I'll pass the insight along, that there might be errors in the different firmware versions. Thanks for your insights.

puck-fzi commented 3 years ago

Hi @echeng22 quick question, with version you mean the ROS driver version or the firmaware version?

echeng22 commented 3 years ago

@puck-fzi The version of the ROS driver.

puck-fzi commented 3 years ago

Sorry that this took some time. I think i found the error in parsing and this should be resolved in the commit https://github.com/SICKAG/sick_safetyscanners/commit/884f946d3d45a210abc1aabcf9bdef459d723847

nguyendo1403 commented 1 year ago

@chr-wurm Can you show me command when you use /field_data service, please? Thank you. I use Sick Microscan3 with ROS and i want to change monitoring case, can you help me.