SICKAG / sick_scan_xd

A versatile driver for a wide range of SICK LiDAR and RADAR devices, providing support for both Linux (native, ROS 1, ROS 2) and Windows (native, ROS 2) platforms.
Apache License 2.0
107 stars 87 forks source link

LMS1000 LiDAR in ROS only recording at 75hz despite explicitly being told to record at 150hz #126

Closed mcguiremichael closed 1 year ago

mcguiremichael commented 1 year ago

We are running the SICK LMS1000 lidar with ros1 melodic. We launch the sensor with the following command.

roslaunch sick_scan sick_lms_1xxx_v2.launch hostname:=169.254.6.195 scan_freq:=150 ang_res:=0.75

No other changes are made to the default launch file used.

This is the output from running the roslaunch command.

Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://earthsense-Alienware-m15:42721/

SUMMARY
========

PARAMETERS
 * /rosdistro: melodic
 * /rosversion: 1.14.13
 * /sick_lms_1xxx/add_transform_xyz_rpy: 0,0,0,0,0,0
 * /sick_lms_1xxx/ang_res: 0.75
 * /sick_lms_1xxx/client_authorization_pw: F4724744
 * /sick_lms_1xxx/cloud_topic: cloud
 * /sick_lms_1xxx/frame_id: cloud
 * /sick_lms_1xxx/hostname: 169.254.6.195
 * /sick_lms_1xxx/intensity: True
 * /sick_lms_1xxx/intensity_resolution_16bit: False
 * /sick_lms_1xxx/lfp_meanfilter: 2
 * /sick_lms_1xxx/lfp_medianfilter: 1
 * /sick_lms_1xxx/max_ang: 2.391
 * /sick_lms_1xxx/message_monitoring_enabled: True
 * /sick_lms_1xxx/min_ang: -2.391
 * /sick_lms_1xxx/min_intensity: 0.0
 * /sick_lms_1xxx/port: 2112
 * /sick_lms_1xxx/range_filter_handling: 0
 * /sick_lms_1xxx/range_max: 25.0
 * /sick_lms_1xxx/range_min: 0.0
 * /sick_lms_1xxx/read_timeout_millisec_default: 5000
 * /sick_lms_1xxx/read_timeout_millisec_kill_node: 150000
 * /sick_lms_1xxx/read_timeout_millisec_startup: 120000
 * /sick_lms_1xxx/scan_freq: 150.0
 * /sick_lms_1xxx/scanner_type: sick_lms_1xxx
 * /sick_lms_1xxx/start_services: True
 * /sick_lms_1xxx/timelimit: 5
 * /sick_lms_1xxx/use_generation_timestamp: True

NODES
  /
    sick_lms_1xxx (sick_scan/sick_generic_caller)

auto-starting new master
process[master]: started with pid [11620]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to aa4eaef0-6531-11ed-bdcd-e4b97aef6f09
process[rosout-1]: started with pid [11631]
started core service [/rosout]
process[sick_lms_1xxx-2]: started with pid [11638]
[ INFO] [1668549951.002749762]: sick_generic_caller V. 2.8.11
[ INFO] [1668549951.003419151]: Program argument 1: /home/earthsense/catkin_ws/devel_isolated/sick_scan/lib/sick_scan/sick_generic_caller
[ INFO] [1668549951.003432711]: Program argument 2: __log:=/home/earthsense/.ros/log/aa4eaef0-6531-11ed-bdcd-e4b97aef6f09/sick_lms_1xxx-2.log
[ INFO] [1668549951.003439804]: Program argument 3: __name:=sick_lms_1xxx
[ INFO] [1668549951.003448507]: ==========================================
[ INFO] [1668549951.007623361]: Range filter configuration: range_min=0, range_max=25, range_filter_handling=0
[ INFO] [1668549951.009405394]: Start initialising scanner [Ip: 169.254.6.195] [Port:2112]
[ INFO] [1668549951.037924948]: Publishing lidar pointcloud2 to cloud
[ INFO] [1668549951.037951940]: Publishing on topic "/cloud"
[ INFO] [1668549951.038304089]: Publishing on topic "/sick_lms_1xxx/imu"
[ INFO] [1668549951.038598661]: Publishing on topic "/sick_lms_1xxx/encoder"
[ INFO] [1668549951.038845535]: Publishing on topic "/sick_lms_1xxx/scan"
[ INFO] [1668549951.039363206]: SickCloudTransform: add_transform_xyz_rpy = (0,0,0,0,0,0)
[ INFO] [1668549951.039391023]: SickCloudTransform: azimuth_offset = 0 [deg]
[ INFO] [1668549951.039404787]: SickCloudTransform: additional 3x3 rotation matrix = { (1,0,0), (0,1,0), (0,0,1) }
[ INFO] [1668549951.039415909]: SickCloudTransform: apply 3x3 rotation = false
[ INFO] [1668549951.039424311]: SickCloudTransform: additional translation = (0,0,0)
[ INFO] [1668549951.039457029]: sick_scan_xd: Tcp::open: connecting to 169.254.6.195:2112 ...
[ INFO] [1668549951.040166486]: sick_scan_xd Tcp::open: connected to 169.254.6.195:2112
[ INFO] [1668549951.040189322]: SickThread TcpRecvThread started.
[ INFO] [1668549951.041289468]: Parameter setting for <active_echo: 0>
[ INFO] [1668549951.041773072]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549951.044144070]: Receiving: <STX>sRA SCdevicestate \x01<ETX>
[ INFO] [1668549951.044209039]: checkColaDialect: lidar response in configured Cola-dialect Cola-B
[ INFO] [1668549951.244488707]: Sending  : <STX><STX><STX><STX><Len=0023>sMN SetAccessMode 0x03 0xf4 0x72 0x47 0x44 CRC:<0xb3>
[ INFO] [1668549951.247176536]: Receiving: <STX>sAN SetAccessMode \x01<ETX>
[ INFO] [1668549951.447424588]: Sending  : <STX><STX><STX><STX><Len=0015>sWN EIHstCola 0x01 CRC:<0x09>
[ INFO] [1668549951.448712219]: Receiving: <STX>sWA EIHstCola <ETX>
[ INFO] [1668549951.648928215]: Sending  : <STX><STX><STX><STX><Len=0015>sMN LMCstopmeas CRC:<0x10>
[ INFO] [1668549951.654035197]: Receiving: <STX>sAN LMCstopmeas \x00<ETX>
[ INFO] [1668549951.854211024]: Sending  : <STX><STX><STX><STX><Len=0033>sWN SetActiveApplications 0x00 0x01 0x46 0x45 0x56 0x4c 0x00 CRC:<0x35>
[ INFO] [1668549951.855175024]: Receiving: <STX>sWA SetActiveApplications <ETX>
[ INFO] [1668549952.055364783]: Sending  : <STX><STX><STX><STX><Len=0033>sWN SetActiveApplications 0x00 0x01 0x52 0x41 0x4e 0x47 0x01 CRC:<0x37>
[ INFO] [1668549952.056186974]: Receiving: <STX>sWA SetActiveApplications <ETX>
[ INFO] [1668549952.256333075]: Sending  : <STX><STX><STX><STX><Len=0015>sRN DeviceIdent CRC:<0x25>
[ INFO] [1668549952.257395573]: Receiving: <STX>sRA DeviceIdent \x00\x08\x4c\x4d\x53\x31\x78\x78\x78\x43\x0...
[ INFO] [1668549952.257503322]: Deviceinfo LMS1xxxC V2.2.1.0R found and supported by this driver.
[ INFO] [1668549952.457760718]: Sending  : <STX><STX><STX><STX><Len=0016>sRN SerialNumber CRC:<0x4c>
[ INFO] [1668549952.459192594]: Receiving: <STX>sRA SerialNumber \x00\x08\x32\x32\x33\x34\x30\x30\x34\x34<E...
[ INFO] [1668549952.659447132]: Sending  : <STX><STX><STX><STX><Len=0019>sRN FirmwareVersion CRC:<0x24>
[ INFO] [1668549952.660347334]: Receiving: <STX>sRA FirmwareVersion \x00\x09\x56\x20\x32\x2e\x32\x2e\x31\x2...
[ INFO] [1668549952.860537320]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549952.861411478]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549953.061599640]: Sending  : <STX><STX><STX><STX><Len=0010>sRN ODoprh CRC:<0x41>
[ INFO] [1668549953.062438180]: Receiving: <STX>sRA ODoprh \x00\x00\x00\x4a<ETX>
[ INFO] [1668549953.263284412]: Sending  : <STX><STX><STX><STX><Len=0010>sRN ODpwrc CRC:<0x52>
[ INFO] [1668549953.264207847]: Receiving: <STX>sRA ODpwrc \x00\x00\x00\x04<ETX>
[ INFO] [1668549953.465046010]: Sending  : <STX><STX><STX><STX><Len=0016>sRN LocationName CRC:<0x55>
[ INFO] [1668549953.465865178]: Receiving: <STX>sRA LocationName \x00\x0b\x53\x4e\x20\x32\x32\x33\x34\x30\x...
[ INFO] [1668549953.666568816]: Sending  : <STX><STX><STX><STX><Len=0022>sWN LFPmeanfilter 0x01 0x00 0x02 0x00 CRC:<0x34>
[ INFO] [1668549953.667513930]: Receiving: <STX>sWA LFPmeanfilter <ETX>
[ INFO] [1668549953.867675201]: Sending  : <STX><STX><STX><STX><Len=0023>sWN LFPmedianfilter 0x01 0x00 0x03 CRC:<0x38>
[ INFO] [1668549953.868470742]: Receiving: <STX>sWA LFPmedianfilter <ETX>
[ INFO] [1668549953.868516084]: Sending  : <STX><STX><STX><STX><Len=0018>sRN LMPoutputRange CRC:<0x5e>
[ INFO] [1668549953.869622128]: Receiving: <STX>sRA LMPoutputRange \x00\x01\x00\x00\x1d\x4c\xff\xf8\xad\x00...
[ INFO] [1668549953.869695473]: Angle resolution of scanner is 0.75 [deg]  (in 1/10000th deg: 7500)
[ INFO] [1668549953.869738730]: [From:To] -48 [deg] to 228 [deg] (in 1/10000th deg: from -480000 to 2280000)
[ INFO] [1668549953.869763389]: MIN_ANG: -2.391 [rad] -136.994 [deg]
[ INFO] [1668549953.869784238]: MAX_ANG: 2.391 [rad] 136.994 [deg]
[ INFO] [1668549953.869808770]: Angular start/stop settings for LMS 1000 not reliable.

[ INFO] [1668549953.869828408]: Sending  : <STX><STX><STX><STX><Len=0018>sRN LMPoutputRange CRC:<0x5e>
[ INFO] [1668549953.870509519]: Receiving: <STX>sRA LMPoutputRange \x00\x01\x00\x00\x1d\x4c\xff\xf8\xad\x00...
[ INFO] [1668549953.870553780]: Angle resolution of scanner is 0.75 [deg]  (in 1/10000th deg: 7500)
[ INFO] [1668549953.872537471]: MIN_ANG (after command verification): -2.40855 [rad] -138 [deg]
[ INFO] [1668549953.872571122]: MAX_ANG (after command verification): 2.40855 [rad] 138 [deg]
[ INFO] [1668549953.872616132]: Sending  : <STX><STX><STX><STX><Len=0032>sWN LMDscandatacfg 0x07 0x00 0x01 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x01 0x00 0x01 CRC:<0x44>
[ INFO] [1668549953.873253347]: Receiving: <STX>sWA LMDscandatacfg <ETX>
[ INFO] [1668549953.873292761]: Sending  : <STX><STX><STX><STX><Len=0018>sRN LMDscandatacfg CRC:<0x67>
[ INFO] [1668549953.874461304]: Receiving: <STX>sRA LMDscandatacfg \x07\x00\x01\x00\x00\x00\x00\x00\x00\x00...
[ INFO] [1668549953.875208851]: Sending mLMPsetscancfg request: { scan_frequency=15000, active_sector_cnt=1, angular_resolution[0]=7500, start_angle[0]=-480000, stop_angle[0]=2280000 }
[ INFO] [1668549953.875254574]: Sending  : <STX><STX><STX><STX><Len=0037>sMN mLMPsetscancfg 0x00 0x00 0x3a 0x98 0x00 0x01 0x00 0x00 0x1d 0x4c 0xff 0xf8 0xad 0x00 0x00 0x22 0xca 0x40 CRC:<0xa3>
[ INFO] [1668549953.876104653]: Receiving: <STX>sAN mLMPsetscancfg \x00\x00\x00\x3a\x98\x00\x01\x00\x00\x1d...
[ INFO] [1668549953.876175360]: LMPscancfg reply: "sAN mLMPsetscancfg \x00\x00\x00\x3a\x98\x00\x01\x00\x00\x1d\x4c\xff\xf8\xad\x00\x00\x22\xca\x40"
[ INFO] [1668549953.876197613]: LMPscancfg: { scan_frequency=15000, active_sector_cnt=1, angular_resolution[0]=7500, start_angle[0]=-480000, stop_angle[0]=2280000 }
[ INFO] [1668549953.876244607]: sAN mLMPsetscancfg: scan frequency = 150 Hz, angular resolution = 0.75 deg.
[ INFO] [1668549953.876282090]: Sending  : <STX><STX><STX><STX><Len=0014>sRN LMPscancfg CRC:<0x63>
[ INFO] [1668549953.877190621]: Receiving: <STX>sRA LMPscancfg \x00\x00\x3a\x98\x00\x01\x00\x00\x1d\x4c\xff...
[ INFO] [1668549953.877246916]: LMPscancfg reply: "sRA LMPscancfg \x00\x00\x3a\x98\x00\x01\x00\x00\x1d\x4c\xff\xf8\xad\x00\x00\x22\xca\x40"
[ INFO] [1668549953.877262360]: LMPscancfg: { scan_frequency=15000, active_sector_cnt=1, angular_resolution[0]=7500, start_angle[0]=-480000, stop_angle[0]=2280000 }
[ INFO] [1668549953.877301201]: sRA LMPscancfg: scan frequency = 150 Hz, angular resolution = 0.75 deg.
[ INFO] [1668549953.877987665]: Sending  : <STX><STX><STX><STX><Len=0016>sMN LMCstartmeas CRC:<0x68>
[ INFO] [1668549953.891715578]: Receiving: <STX>sAN LMCstartmeas \x00<ETX>
[ INFO] [1668549953.891830759]: Sending  : <STX><STX><STX><STX><Len=0007>sMN Run CRC:<0x19>
[ INFO] [1668549953.892778620]: Receiving: <STX>sAN Run \x01<ETX>
[ INFO] [1668549953.892859083]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549953.894308188]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549953.894372816]: Waiting for scanner ready state since 0 secs
[ INFO] [1668549954.894535451]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549954.895574662]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549954.895628138]: Waiting for scanner ready state since 1 secs
[ INFO] [1668549955.895771301]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549955.896828997]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549955.896864386]: Waiting for scanner ready state since 2 secs
[ INFO] [1668549956.896996705]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549956.897844094]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549956.897937240]: Waiting for scanner ready state since 3 secs
[ INFO] [1668549957.898074757]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549957.899034409]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549957.899061162]: Waiting for scanner ready state since 4 secs
[ INFO] [1668549958.899299620]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549958.900264693]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549958.900291636]: Waiting for scanner ready state since 5 secs
[ INFO] [1668549959.900427842]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549959.901363570]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549959.901397175]: Waiting for scanner ready state since 6 secs
[ INFO] [1668549960.901591896]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549960.902572367]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549960.902614516]: Waiting for scanner ready state since 7 secs
[ INFO] [1668549961.902758931]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549961.903597156]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549961.903648335]: Waiting for scanner ready state since 8 secs
[ INFO] [1668549962.903794917]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549962.904663322]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549962.904698448]: Waiting for scanner ready state since 9 secs
[ INFO] [1668549963.904945482]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549963.906107128]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549963.906195218]: Waiting for scanner ready state since 10 secs
[ INFO] [1668549964.906349289]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549964.907154966]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549964.907188751]: Waiting for scanner ready state since 11 secs
[ INFO] [1668549965.907288105]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549965.908208298]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549965.908239088]: Waiting for scanner ready state since 12 secs
[ INFO] [1668549966.908382901]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549966.909206472]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549966.909235432]: Waiting for scanner ready state since 13 secs
[ INFO] [1668549967.909368175]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549967.910190773]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549967.910218135]: Waiting for scanner ready state since 14 secs
[ INFO] [1668549968.910376904]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549968.911376360]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549968.911436891]: Waiting for scanner ready state since 15 secs
[ INFO] [1668549969.911610593]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549969.912610736]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549969.912679703]: Waiting for scanner ready state since 16 secs
[ INFO] [1668549970.912837579]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549970.913711788]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549970.913741688]: Waiting for scanner ready state since 17 secs
[ INFO] [1668549971.913944918]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549971.915000668]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549971.915079207]: Waiting for scanner ready state since 18 secs
[ INFO] [1668549972.915232134]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549972.916049739]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549972.916094417]: Waiting for scanner ready state since 19 secs
[ INFO] [1668549973.916227812]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549973.917108935]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549973.917136566]: Waiting for scanner ready state since 20 secs
[ INFO] [1668549974.917273932]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549974.918143243]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549974.918177092]: Waiting for scanner ready state since 21 secs
[ INFO] [1668549975.918441871]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549975.919667475]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549975.919708662]: Waiting for scanner ready state since 22 secs
[ INFO] [1668549976.919852890]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549976.920812323]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549976.920867939]: Waiting for scanner ready state since 23 secs
[ INFO] [1668549977.921075065]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549977.922082319]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549977.922219835]: Waiting for scanner ready state since 24 secs
[ INFO] [1668549978.922390108]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549978.923066027]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549978.923095187]: Waiting for scanner ready state since 25 secs
[ INFO] [1668549979.923315829]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549979.924381109]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549979.924483532]: Waiting for scanner ready state since 26 secs
[ INFO] [1668549980.924624928]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549980.925477197]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549980.925506144]: Waiting for scanner ready state since 27 secs
[ INFO] [1668549981.925677825]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549981.926709134]: Receiving: <STX>sRA SCdevicestate \x00<ETX>
[ INFO] [1668549981.926804093]: Waiting for scanner ready state since 28 secs
[ INFO] [1668549982.926941616]: Sending  : <STX><STX><STX><STX><Len=0017>sRN SCdevicestate CRC:<0x30>
[ INFO] [1668549982.928033829]: Receiving: <STX>sRA SCdevicestate \x01<ETX>
[ INFO] [1668549982.928064533]: Scanner ready for measurement after 29 [sec]
[ INFO] [1668549982.928081597]: Sending  : <STX><STX><STX><STX><Len=0017>sEN LMDscandata 0x01 CRC:<0x33>
[ INFO] [1668549982.928913287]: Receiving: <STX>sEA LMDscandata \x01<ETX>
[ INFO] [1668549982.930207966]: SickScanServices: service "/sick_lms_1xxx/ColaMsg" created ("/sick_lms_1xxx/ColaMsg")
[ INFO] [1668549982.930903235]: SickScanServices: service "/sick_lms_1xxx/ECRChangeArr" created ("/sick_lms_1xxx/ECRChangeArr")
[ INFO] [1668549982.931806851]: SickScanServices: service "/sick_lms_1xxx/LIDoutputstate" created ("/sick_lms_1xxx/LIDoutputstate")
[ INFO] [1668549982.932767540]: SickScanServices: service "/sick_lms_1xxx/SCdevicestate" created ("/sick_lms_1xxx/SCdevicestate")
[ INFO] [1668549982.933415681]: SickScanServices: service "/sick_lms_1xxx/SCreboot" created ("/sick_lms_1xxx/SCreboot")
[ INFO] [1668549982.934071013]: SickScanServices: service "/sick_lms_1xxx/SCsoftreset" created ("/sick_lms_1xxx/SCsoftreset")
[ INFO] [1668549982.934602444]: SickScanServices: service "/sick_lms_1xxx/SickScanExit" created ("/sick_lms_1xxx/SickScanExit")
[ INFO] [1668549982.934631487]: SickScanServices: ros services initialized
[ INFO] [1668549982.934648950]: Setup completed, sick_scan_xd is up and running. Pointcloud is published on topic "cloud"`

After launch we recorded the cloud outputs to a rosbag. However, after running rosbag info, we only see 75 messages per second.

path:        test_sick_lms1000_4_2022-11-15-16-05-53.bag
version:     2.0
duration:    1:28s (88s)
start:       Nov 15 2022 16:06:22.94 (1668549982.94)
end:         Nov 15 2022 16:07:51.18 (1668550071.18)
size:        38.3 MB
messages:    6615
compression: none [51/51 chunks]
types:       sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181]
topics:      /cloud   6615 msgs    : sensor_msgs/PointCloud2

If it was recording at 150hz as we had asked it to, it would be around 13200 messages in an 88 second rosbag.

What could be causing this? The settings in SOPAS were also set to 150hz.

We tried adjusting the power settings to the sensor and that made no difference.

Thank you.

aiplemaSICKAG commented 1 year ago

Hello, thank you for reporting this. We are trying to reproduce the behavior on an equivalent sensor and find the cause of the error and will come back to you.

Best regards, Manuel

aiplemaSICKAG commented 1 year ago

Hello, we think we found the source of your problem. Currently, the default launch file has the mean filter activated and configured to take the average of 2 measurements. This leads to the sensor delivering measurements at half the scan frequency. You can deactivate it by changing line 93 to <param name="lfp_meanfilter" type="int" value="0" />. Note: the name of the "scan frequency" parameter is a bit misleading. With the mean filter deactivated and the output interval set to 1 in Sopas ET, scans will always be sent at 150 Hz. The difference is whether the scans are interlaced or not (see p. 22 and following in the operating instructions https://cdn.sick.com/media/docs/3/43/443/operating_instructions_lms1104c_111031s01_2d_lidar_sensors_en_im0079443.pdf ).

Best regards, Manuel

rostest commented 1 year ago

Thanks for your feedback! Mean and median filter settings are deactivated in default launchfile configuration in branch https://github.com/SICKAG/sick_scan_xd/tree/feature/lms1000_configuration and will be merged in the next release.

michael1309 commented 1 year ago

Solved due to investigation and documentation update.