Closed comwise closed 4 years ago
Start angle [1/10000°] Value for start angle must always be greater than Stop angle of previous sector. Set to 0 if sector is inactive (not used). Values for LMSxxx are fixed. Int_32 4 LMS1xx -450000d (FFF92230h) FF F9 22 30 LMS5xx -50000d (FFFF3CB0h) FF FF 3C B0
Stop angle [1/10000°] Value for stop angle musst always be greater than start angle of previous sector. Set to 0 if sector is inactive (not used). Values for LMSxxx are fixed. Int_32 4 LMS1xx +2250000d (225510h) 00 22 55 10 LMS5xx +1850000d (1C3A90h) 00 1C 3A 90
thanks for your resolve it
We will check this issue in the next couple of days. Are you able to setup the lidar with the default launch file (maybe direct after repowering) without any problems (e.g. without observing sFA 4)?
We will check this issue in the next couple of days. Are you able to setup the lidar with the default launch file (maybe direct after repowering) without any problems (e.g. without observing sFA 4)?
yes , i launch lidar with the deafult file, but i added two params: scan_freq and ang_res, beausce i want to modify these param
With the most recent release in the Master-Branch you can now adjust the lidar scan frequency and angular resolution. To check the successful setup, you can use the ROS tools. Even though we assume that you know how to check the settings, you will find some screenshots to verify them:
a) Scan rate:
rostopic hz /cloud
b) Angular Resolution:
rostopic echo /cloud|grep width
Expected Value: (scan opening angle/(ang.-resolution)+1)
270/0.25+1=1081
c) scan opening angle checked by rviz top view
Please note that changing the scan frequency means a new triggering of the motor electronics. Therefore the internal test procedure is started in the control logic and it may take some time until the scanner has reached the new speed with sufficient reliability. During the adjustment process the indicator LEDs of the lidar are switched to red. After the LED shows green, scan data is also published.
We used this launch file for testing.
<?xml version="1.0"?>
<!-- FOR FUTURE USE. NOT SUPPORTED NOW. DO NOT USE IT. -->
<launch>
<arg name="hostname" default="192.168.0.1" />
<!-- robot_description and robot_state_publisher hier evtl. einbauen -->
<node name="sick_lms_1xx" pkg="sick_scan" type="sick_generic_caller" respawn="false" output="screen">
<!-- default values: -->
<!--
<param name="intensity" type="bool" value="True" />
<param name="skip" type="int" value="0" />
<param name="frame_id" type="str" value="laser" />
<param name="time_offset" type="double" value="-0.001" />
<param name="publish_datagram" type="bool" value="False" />
<param name="subscribe_datagram" type="bool" value="false" />
<param name="device_number" type="int" value="0" />
<param name="range_min" type="double" value="0.05" />
-->
<param name="intensity" type="bool" value="False" />
<param name="intensity_resolution_16bit" type="bool" value="false" />
<param name="min_ang" type="double" value="-2.35619" />
<param name="max_ang" type="double" value="2.35619" />
<param name="frame_id" type="str" value="laser" />
<param name="use_binary_protocol" type="bool" value="false" />
<param name="scanner_type" type="string" value="sick_lms_1xx"/>
<param name="range_max" type="double" value="25.0" />
<param name="hostname" type="string" value="$(arg hostname)" />
<param name="port" type="string" value="2112" />
<param name="timelimit" type="int" value="120" />
<param name="scan_freq" type="double" value="25" />
<param name="ang_res" type="double" value="0.25" />
</node>
</launch>
@michael1309 thanks very much , i can change scan_freq and ang_res params now
when i set this param to laser, it reported the following log:
[ INFO] [1584495563.876945347]: Sending :sRN LMPoutputRange
[ INFO] [1584495563.879261595]: Receiving: sRA LMPoutputRange 1 1388 FFFC2F70 1F47D0
[ INFO] [1584495563.879457273]: Angle resolution of scanner is 0.50000 [deg] (in 1/10000th deg: 0x1388)
[ INFO] [1584495563.879544910]: [From:To] -25.00000 [deg] to 205.00000 [deg] (in 1/10000th deg: from 0xFFFC2F70 to 0x1F47D0)
[ INFO] [1584495563.879616148]: MIN_ANG: -2.007 [rad] -115.000 [deg]
[ INFO] [1584495563.879683571]: MAX_ANG: 2.007 [rad] 115.000 [deg]
[ INFO] [1584495563.879804712]: Sending : sWN LMPoutputRange 1 1388 FFFC2F70 1F47D0
[ INFO] [1584495563.882082287]: Receiving: sWA LMPoutputRange
[ INFO] [1584495563.882279222]: Sending : sRN LMPoutputRange
[ INFO] [1584495563.884564053]: Receiving: sRA LMPoutputRange 1 1388 FFFC2F70 1F47D0
[ INFO] [1584495563.884754502]: Angle resolution of scanner is 0.50000 [deg] (in 1/10000th deg: 0x1388)
[ INFO] [1584495563.887661722]: MIN_ANG (after command verification): -2.007 [rad] -115.000 [deg]
[ INFO] [1584495563.887788922]: MAX_ANG (after command verification): 2.007 [rad] 115.000 [deg]
[ INFO] [1584495563.887940769]: Sending : sWN LMDscandatacfg 01 00 1 00 0 0 00 0 0 0 1 1
[ INFO] [1584495563.890463336]: Receiving: sWA LMDscandatacfg
[ INFO] [1584495563.890650425]: Sending : sRN LMDscandatacfg
[ INFO] [1584495563.893171444]: Receiving: sRA LMDscandatacfg 1 0 1 0 0 0 0 0 0 0 1 1
[ INFO] [1584495563.895676297]: Sending : sMN mLMPsetscancfg 5000 1 5000 0 0
[ INFO] [1584495563.898385098]: Receiving: sFA 4
[ERROR] [1584495563.898672974]: Error Sopas answer mismatch Error unexpected Sopas Answer for request sMN mLMPsetscancfg 5000 1 5000 0 0Answer= >>>sFA 4<<<
[ INFO] [1584495563.899003303]: Sending : sRN LMPscancfg
[ INFO] [1584495563.900394159]: Receiving: sRA LMPscancfg 1388 1 1388 FFF92230 225510
[ INFO] [1584495563.900775948]: Sending : sMN LMCstartmeas
[ INFO] [1584495563.913811601]: Receiving: sAN LMCstartmeas 0
my laser is sick lms1xx , when i set scan frequency 50 hz and angle resolution 0.5, response is sfa 4 the laser readme : Sopas_Error_LOCALCONDITIONFAILED Local condition violated, e.g. giving a value that exceeds the minimum or maximum allowed value for this variable
when i set scan frequency 25 hz and angle resolution 0.5
[ INFO] [1584437996.630613063]: Sending :sMN mLMPsetscancfg 2500 1 5000 0 0
[ INFO] [1584437996.632880401]: Receiving: sFA 4
[ INFO] [1584437996.633114136]: Sending : sRN LMPscancfg
[ERROR] [1584437996.632999278]: Error Sopas answer mismatch Error unexpected Sopas Answer for request sMN mLMPsetscancfg 2500 1 5000 0 0Answer= >>>sFA 4<<<
[ INFO] [1584437996.635355144]: Receiving: sRA LMPscancfg 1388 1 1388 FFF92230 225510
yes it is same problem,i look up the reference manual