SICKAG / sick_scan_xd

Based on the sick_scan drivers for ROS1, sick_scan_xd merges sick_scan, sick_scan2 and sick_scan_base repositories. The driver supports both Linux (native, ROS1, ROS2) and Windows (native and ROS2).
Apache License 2.0
104 stars 84 forks source link

MRS1000 Connection problem with ROS2 #373

Closed IMN-Robotics closed 2 months ago

IMN-Robotics commented 2 months ago

Hello,

i am trying to get laser data from a MRS1104C Scanner with the library. I tried two different systems with ROS2 foxy (Ubuntu 20.04) and humble (Ubuntu 22.04) but i am getting the following error on both every time i connect:

[WARN] [1722428354.953188512] [sick_scan_xd]: Error Sopas answer mismatch: Error unexpected Sopas answer for request <STX><STX><STX><STX><Len=0026>sWN ScanLayerFilter 0x00 0x04 0x01..., received answer: "sFA\x00\x03", expected patterns: "sWA ScanLayerFilter","sAN ScanLayerFilter" [WARN] [1722428359.953888461] [sick_scan_xd]: Timeout during waiting for new datagram [WARN] [1722428359.954051081] [sick_scan_xd]: Error Sopas answer mismatch: Error unexpected Sopas answer for request <STX><STX><STX><STX><Len=0026>sWN ScanLayerFilter 0x00 0x04 0x01..., received answer: "", expected patterns: "sWA ScanLayerFilter","sAN ScanLayerFilter"

I configured the scanner via SOPAS ET to use the IP address 192.168.1.179, the Host Port (Parameters) to CoLa Binary for Port 2112, then saved to EEPROM, restarted and used the following launch command: ros2 run sick_scan_xd sick_generic_caller ./src/sick_scan_xd-develop/launch/sick_mrs_1xxx.launch hostname:=192.168.1.179

By the looks of the output it can communicate with the scanner but there is a receive error. Changing to ASCII mode produces the same error. In SOPAS ET i can see the laser data and the scanner LEDs are green. The moment i start the ROS2 node the LEDs turn red and i get the mentioned error. Here is the full output: scanner_type string sick_mrs_1xxx
min_ang double -2.3998277
max_ang double +2.3998277
intensity_resolution_16bit bool false
hostname string 192.168.0.1
port string 2112
timelimit int 5
cloud_topic string cloud
laserscan_topic string scan
frame_id str cloud
sw_pll_only_publish bool true
use_generation_timestamp bool true
min_intensity double 0.0
scandatacfg_timingflag int -1
scandatacfg_azimuth_table int 1
imu_enable bool true
imu_enable_additional_info bool True
imu_topic string imu
range_min double 0.05
range_max double 100.0
range_filter_handling int 0
ang_res double 0
scan_freq double 0
scan_layer_filter string 4 1 1 1 1
add_transform_xyz_rpy string 0,0,0,0,0,0
add_transform_check_dynamic_updates bool false
start_services bool True
message_monitoring_enabled bool True
read_timeout_millisec_default int 5000
read_timeout_millisec_startup int 120000
read_timeout_millisec_kill_node int 150000
client_authorization_pw string F4724744
lfp_meanfilter int -1
lfp_medianfilter int -1
ros_qos int -1
tf_base_frame_id string map
tf_base_lidar_xyz_rpy string 0,0,0,0,0,0
tf_publish_rate double 10.0
tick_to_timestamp_mode int 0
[INFO] [1722428352.112609501] [sick_scan_xd]: SickTransformPublisher: broadcasting TF messages parent_frame_id="map", child_frame_id="cloud", (x,y,z,roll,pitch,yaw)=(0.0,0.0,0.0,0.0,0.0,0.0), rate=10.0 [INFO] [1722428352.112937357] [sick_scan_xd]: Range filter configuration: range_min=0.05, range_max=100, range_filter_handling=0 [INFO] [1722428352.113138147] [sick_scan_xd]: Found emul_sensor overwriting default settings. Emulation:False [INFO] [1722428352.113229835] [sick_scan_xd]: Found sopas_protocol_type param overwriting default protocol: [INFO] [1722428352.113252745] [sick_scan_xd]: Binary protocol activated [INFO] [1722428352.113404279] [sick_scan_xd]: PointCloudMonitor started. [INFO] [1722428352.113442560] [sick_scan_xd]: Start initialising scanner [Ip: 192.168.1.179] [Port:2112] [INFO] [1722428352.113542220] [sick_scan_xd]: PointCloudMonitor: subscribing to topic cloud, qos=0 [INFO] [1722428352.113707145] [sick_scan_xd]: ScanLayerFilterCfg: filter_settings="4 1 1 1 1", 4 layers, layer_activation=[1,1,1,1], first_active_layer=0, last_active_layer=3 [INFO] [1722428352.114294562] [sick_scan_xd]: Publishing lidar pointcloud2 to cloud [INFO] [1722428352.114325070] [sick_scan_xd]: Publishing on topic "cloud", qos=0 [INFO] [1722428352.114914599] [sick_scan_xd]: Publishing on topic "sick_mrs_1xxx/imu", qos=0 [INFO] [1722428352.115338145] [sick_scan_xd]: Publishing on topic "sick_mrs_1xxx/encoder", qos=0 [INFO] [1722428352.115818132] [sick_scan_xd]: Publishing on topic "scan", qos=0 [INFO] [1722428352.116046985] [sick_scan_xd]: SickCloudTransform: add_transform_xyz_rpy = (0,0,0,0,0,0) [INFO] [1722428352.116075252] [sick_scan_xd]: SickCloudTransform: azimuth_offset = 0 [deg] [INFO] [1722428352.116108591] [sick_scan_xd]: SickCloudTransform: additional 3x3 rotation matrix = { (1,0,0), (0,1,0), (0,0,1) } [INFO] [1722428352.116126657] [sick_scan_xd]: SickCloudTransform: apply 3x3 rotation = false [INFO] [1722428352.116148991] [sick_scan_xd]: SickCloudTransform: additional translation = (0,0,0) [INFO] [1722428352.116166449] [sick_scan_xd]: SickCloudTransform: check_dynamic_updates = false [INFO] [1722428352.116207255] [sick_scan_xd]: sick_scan_xd: Tcp::open: connecting to 192.168.1.179:2112 ... [INFO] [1722428352.116794866] [sick_scan_xd]: sick_scan_xd Tcp::open: connected to 192.168.1.179:2112 [INFO] [1722428352.116819839] [sick_scan_xd]: SickThread TcpRecvThread started. [INFO] [1722428352.116923821] [sick_scan_xd]: Parameter setting for <active_echo: 0> [INFO] [1722428352.117039077] [sick_scan_xd]: Sending : sRN SCdevicestate CRC:<0x30> [INFO] [1722428352.120167201] [sick_scan_xd]: Receiving: sRA SCdevicestate \x00 [INFO] [1722428352.120215995] [sick_scan_xd]: checkColaDialect: lidar response in configured Cola-dialect Cola-B [INFO] [1722428352.320984944] [sick_scan_xd]: Sending : sMN SetAccessMode 0x03 0xf4 0x72 0x47 0x44 CRC:<0xb3> [INFO] [1722428352.322755390] [sick_scan_xd]: Receiving: sAN SetAccessMode \x01 [INFO] [1722428352.523369995] [sick_scan_xd]: Sending : sWN EIHstCola 0x01 CRC:<0x09> [INFO] [1722428352.524816606] [sick_scan_xd]: Receiving: sWA EIHstCola [INFO] [1722428352.725293619] [sick_scan_xd]: Sending : sMN LMCstopmeas CRC:<0x10> [INFO] [1722428352.727292671] [sick_scan_xd]: Receiving: sAN LMCstopmeas \x00 [INFO] [1722428352.927756265] [sick_scan_xd]: Sending : sRN SetActiveApplications CRC:<0x08> [INFO] [1722428352.929303814] [sick_scan_xd]: Receiving: sRA SetActiveApplications \x00\x01\x52\x41\x4e\x47\x01 [INFO] [1722428352.929545767] [sick_scan_xd]: response to "sRN SetActiveApplications": \x02\x02\x02\x02\x00\x00\x00\x21sRA SetActiveApplications \x00\x01RANG\x01\x3d [INFO] [1722428352.929666176] [sick_scan_xd]: FieldEvaluationActive = false [INFO] [1722428353.130492332] [sick_scan_xd]: Sending : sRN DeviceIdent CRC:<0x25> [INFO] [1722428353.132056453] [sick_scan_xd]: Receiving: sRA DeviceIdent \x00\x08\x4d\x52\x53\x31\x78\x78\x78\x78\x00\x08\x31\x2e\x34\x2e\x30\x2e\x3... [INFO] [1722428353.132323978] [sick_scan_xd]: Deviceinfo MRS1xxxx V1.4.0.0R found and supported by this driver. [INFO] [1722428353.333160421] [sick_scan_xd]: MRS1xxx firmware version 1.4.0 [INFO] [1722428353.333396917] [sick_scan_xd]: Sending : sWN SetActiveApplications 0x00 0x01 0x46 0x45 0x56 0x4c 0x00 CRC:<0x35> [INFO] [1722428353.334776853] [sick_scan_xd]: Receiving: sWA SetActiveApplications [INFO] [1722428353.535197212] [sick_scan_xd]: MRS1xxx firmware version 1.4.0 [INFO] [1722428353.535447464] [sick_scan_xd]: Sending : sWN SetActiveApplications 0x00 0x01 0x52 0x41 0x4e 0x47 0x01 CRC:<0x37> [INFO] [1722428353.536914101] [sick_scan_xd]: Receiving: sWA SetActiveApplications [INFO] [1722428353.737577405] [sick_scan_xd]: Sending : sRN SerialNumber CRC:<0x4c> [INFO] [1722428353.739014136] [sick_scan_xd]: Receiving: sRA SerialNumber \x00\x08\x31\x38\x34\x30\x30\x30\x30\x31 [INFO] [1722428353.939675512] [sick_scan_xd]: Sending : sRN FirmwareVersion CRC:<0x24> [INFO] [1722428353.941142554] [sick_scan_xd]: Receiving: sRA FirmwareVersion \x00\x09\x56\x20\x31\x2e\x34\x2e\x30\x2e\x30 [INFO] [1722428354.141616891] [sick_scan_xd]: Sending : sRN SCdevicestate CRC:<0x30> [INFO] [1722428354.142798374] [sick_scan_xd]: Receiving: sRA SCdevicestate \x00 [INFO] [1722428354.343329790] [sick_scan_xd]: Sending : sRN ODoprh CRC:<0x41> [INFO] [1722428354.345009562] [sick_scan_xd]: Receiving: sRA ODoprh \x00\x00\x0b\x07 [INFO] [1722428354.545965771] [sick_scan_xd]: Sending : sRN ODpwrc CRC:<0x52> [INFO] [1722428354.547628596] [sick_scan_xd]: Receiving: sRA ODpwrc \x00\x00\x03\xd0 [INFO] [1722428354.748570682] [sick_scan_xd]: Sending : sRN LocationName CRC:<0x55> [INFO] [1722428354.750288656] [sick_scan_xd]: Receiving: sRA LocationName \x00\x0b\x53\x4e\x20\x31\x38\x30\x33\x30\x30\x31\x30 [INFO] [1722428354.951215341] [sick_scan_xd]: ScanLayerFilterCfg: filter_settings=" 4 1 1 1 1", 4 layers, layer_activation=[1,1,1,1], first_active_layer=0, last_active_layer=3 [INFO] [1722428354.951463963] [sick_scan_xd]: Sending : sWN ScanLayerFilter 0x00 0x04 0x01 0x01 0x01 0x01 CRC:<0x32> [INFO] [1722428354.952904635] [sick_scan_xd]: Receiving: sFA\x00\x03 [WARN] [1722428354.953188512] [sick_scan_xd]: Error Sopas answer mismatch: Error unexpected Sopas answer for request sWN ScanLayerFilter 0x00 0x04 0x01..., received answer: "sFA\x00\x03", expected patterns: "sWA ScanLayerFilter","sAN ScanLayerFilter" [WARN] [1722428359.953888461] [sick_scan_xd]: Timeout during waiting for new datagram [WARN] [1722428359.954051081] [sick_scan_xd]: Error Sopas answer mismatch: Error unexpected Sopas answer for request sWN ScanLayerFilter 0x00 0x04 0x01..., received answer: "", expected patterns: "sWA ScanLayerFilter","sAN ScanLayerFilter" [ERROR] [1722428359.954289314] [sick_scan_xd]: Error unexpected Sopas answer for request sWN ScanLayerFilter 0x00 0x04 0x01..., giving up after 1 unexpected answers. [INFO] [1722428359.954447128] [sick_scan_xd]: Failed to init scanner Error Code: 1 Waiting for timeout... If the communication mode set in the scanner memory is different from that used by the driver, the scanner's communication mode is changed. This requires a restart of the TCP-IP connection, which can extend the start time by up to 30 seconds. There are two ways to prevent this:

  1. [Recommended] Set the communication mode with the SOPAS ET software to binary and save this setting in the scanner's EEPROM.
  2. Use the parameter "use_binary_protocol" to overwrite the default settings of the driver. [ERROR] [1722428359.954560568] [sick_scan_xd]: ## ERROR in mainGenericLaser: init failed, retrying... [INFO] [1722428359.954658692] [sick_scan_xd]: Start initialising scanner [Ip: 192.168.1.179] [Port:2112] [WARN] [1722428359.954764570] [sick_scan_xd]: Disconnecting TCP-Connection. [ERROR] [1722428359.955101558] [sick_scan_xd]: Tcp::readInputData: Read 0 bytes, connection is lost! [INFO] [1722428359.955233208] [sick_scan_xd]: SickThread TcpRecvThread finished (flags: threadShouldRun=0, endThread=0). SickScanCommon closed.
rostest commented 2 months ago

Thanks for your feedback. The sick_scan_xd driver fails to set the configured ScanLayerFilter. The lidar responds with error code 3 (Sopas_Error_VARIABLE_UNKNOWNINDEX), which means that the firmware has no ScanLayerFilter configuration.

Most likely the MRS1104C firmware version 1.4.0 does not yet support ScanLayerFilter settings. We recommend to upgrade the firmware to the latest release 2.3.0. Alternatively, you can disable ScanLayerFilter settings by <arg name="scan_layer_filter" default=""/> in the launch file.

IMN-Robotics commented 2 months ago

Thank you for the quick response. After setting the scan_layer_filter to "" it started working and i can receive data via rviz2. Thank you very much.

Regarding the firmware update: The only firmware files i found for download are SDD files but SOPAS will not let me update the scanner with those ones via the Firmware update option. Where can i find the 2.3.0 firmware?

rostest commented 2 months ago

Thank you for your quick reply. If a firmware update with SOPAS ET does not work, please contact SICK support.