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
98 stars 84 forks source link

Can't communicate with Sick Tim781 #366

Closed akashjinandra closed 3 weeks ago

akashjinandra commented 1 month ago

Hello, I'm running Ubuntu 20.04, with ROS 1 Noetic. I'm trying to talk to a Sick TIM781 sensor with firmware v5.10. I was able to ping the device, and then use SOPAS to change the communication to binary. But I still get an error saying it can't communicate and is not getting the expected answer. Here is the full readout:

ROS_MASTER_URI=http://localhost:11311

process[sick_tim_7xx-1]: started with pid [322158] [ INFO] [1721348868.706815175]: sick_generic_caller V. 3.4.0 [ INFO] [1721348868.707611033]: Program argument 1: /home/akash/hfa_ws/devel_isolated/sick_scan_xd/lib/sick_scan_xd/sick_generic_caller [ INFO] [1721348868.707640634]: Program argument 2: log:=/home/akash/.ros/log/07046054-445b-11ef-b03c-0b48c101c823/sick_tim_7xx-1.log [ INFO] [1721348868.707650405]: Program argument 3: name:=sick_tim_7xx

[ INFO] [1721348868.711701691]: 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] [1721348868.712722688]: Range filter configuration: range_min=0, range_max=100, range_filter_handling=0 [ INFO] [1721348868.714008978]: Found sopas_protocol_type param overwriting default protocol: [ INFO] [1721348868.714034421]: Binary protocol activated [ INFO] [1721348868.714935894]: PointCloudMonitor started. [ INFO] [1721348868.714955833]: Start initialising scanner [Ip: 192.168.100.121] [Port:2112] [ INFO] [1721348868.735987792]: Publishing on topic "/sick_tim_7xx/lferec", qos=10 [ INFO] [1721348868.736449774]: Publishing on topic "/sick_tim_7xx/lidoutputstate", qos=10 [ INFO] [1721348868.736812280]: Publishing on topic "/sick_tim_7xx/marker", qos=10 [ INFO] [1721348868.737306813]: SickCloudTransform: add_transform_xyz_rpy = (0,0,0,0,0,0) [ INFO] [1721348868.737315825]: SickCloudTransform: azimuth_offset = 0 [deg] [ INFO] [1721348868.737326245]: SickCloudTransform: additional 3x3 rotation matrix = { (1,0,0), (0,1,0), (0,0,1) } [ INFO] [1721348868.737333851]: SickCloudTransform: apply 3x3 rotation = false [ INFO] [1721348868.737340998]: SickCloudTransform: additional translation = (0,0,0) [ INFO] [1721348868.737348848]: SickCloudTransform: check_dynamic_updates = false [ INFO] [1721348868.737381086]: Publishing lidar pointcloud2 to cloud [ INFO] [1721348868.737501973]: Publishing on topic "/cloud", qos=10 [ INFO] [1721348868.737862893]: Publishing on topic "/sick_tim_7xx/imu", qos=10 [ INFO] [1721348868.738160463]: Publishing on topic "/sick_tim_7xx/encoder", qos=10 [ INFO] [1721348868.738476130]: Publishing on topic "/scan", qos=10 [ INFO] [1721348868.738948083]: SickCloudTransform: add_transform_xyz_rpy = (0,0,0,0,0,0) [ INFO] [1721348868.738956843]: SickCloudTransform: azimuth_offset = 0 [deg] [ INFO] [1721348868.738967528]: SickCloudTransform: additional 3x3 rotation matrix = { (1,0,0), (0,1,0), (0,0,1) } [ INFO] [1721348868.738975185]: SickCloudTransform: apply 3x3 rotation = false [ INFO] [1721348868.738982568]: SickCloudTransform: additional translation = (0,0,0) [ INFO] [1721348868.738991701]: SickCloudTransform: check_dynamic_updates = false [ INFO] [1721348868.739022377]: sick_scan_xd: Tcp::open: connecting to 192.168.100.121:2112 ... [ INFO] [1721348868.739646951]: sick_scan_xd Tcp::open: connected to 192.168.100.121:2112 [ INFO] [1721348868.739765460]: SickThread TcpRecvThread started. [ INFO] [1721348868.740680908]: Parameter setting for <active_echo: 0> [ INFO] [1721348868.742029990]: Sending : sRN SCdevicestate CRC:<0x30> [ INFO] [1721348868.743799576]: Receiving: sRA SCdevicestate \x01 [ INFO] [1721348868.743848127]: checkColaDialect: lidar response in configured Cola-dialect Cola-B [ INFO] [1721348868.944213132]: Sending : sMN SetAccessMode 0x03 0xf4 0x72 0x47 0x44 CRC:<0xb3> [ INFO] [1721348868.946663775]: Receiving: sAN SetAccessMode \x00 [ INFO] [1721348869.147025367]: Sending : sWN EIHstCola 0x01 CRC:<0x09> [ INFO] [1721348869.148836878]: Receiving: sFA\x00\x0a [ WARN] [1721348869.148933552]: Error Sopas answer mismatch: Error unexpected Sopas answer for request sWN EIHstCola 0x01 CRC:<0x09>, received answer: "sFA\x00\x0a", expected patterns: "sWA EIHstCola","sAN EIHstCola" [ WARN] [1721348874.149309369]: Timeout during waiting for new datagram [ WARN] [1721348874.149446382]: Error Sopas answer mismatch: Error unexpected Sopas answer for request sWN EIHstCola 0x01 CRC:<0x09>, received answer: "", expected patterns: "sWA EIHstCola","sAN EIHstCola" [ERROR] [1721348874.149554899]: Error unexpected Sopas answer for request sWN EIHstCola 0x01 CRC:<0x09>, giving up after 1 unexpected answers. [ INFO] [1721348874.149617679]: 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] [1721348874.149687649]: ## ERROR in mainGenericLaser: init failed, retrying... [ INFO] [1721348874.149724095]: Start initialising scanner [Ip: 192.168.100.121] [Port:2112] [ WARN] [1721348874.149760133]: Disconnecting TCP-Connection. [ERROR] [1721348874.150024228]: Tcp::readInputData: Read 0 bytes, connection is lost! [ INFO] [1721348874.150129095]: SickThread TcpRecvThread finished (flags: threadShouldRun=0, endThread=0). SickScanCommon closed.

Let me know if I can gather any more useful info.

rostest commented 1 month ago

Thanks for your feedback and logfile. The driver establishes a TCP connection to the lidar and starts the initialisation using typical SOPAS commands. The SOPAS Command "sMN SetAccessMode 0x03 0xf4 0x72 0x47 0x44" should be answered by "sAN SetAccessMode 1", but is instaead acknowledged by "sAN SetAccessMode 0". As a consequence, the following SOPAS command "sWN EIHstCola 1" for binary cola communication fails with error code 0x0A (Sopas_Error_VARIABLE_WRITE_ACCESSDENIED).

Most probably the password for the "authorized client" has been changed (default hash value is f4724744). Please change the password for "authorized client" back to the default, or reset your device to factory defaults and try again.

Tim781 logfiles with latest sick_scan_xd releases 3.4.0 and 3.5.0 and TiM781 firmware version V5.0 are attached for information.

rostest commented 1 month ago

@akashjinandra A direct calculation of the hash values is currently not available. We are clarifying further possibilities together with SICK.

akashjinandra commented 1 month ago

Hello I was able to find away to get the calculated hash value from within the SOPAS ET software. You must be logged in as service level and you can calculate the the hash. However it seems like it did not seem to use the new value. I double checked that when I put the default password for level "authorized client" is "client". I was able to recreate the correct hash that is default in the launch file, however when I put the newly generated hash it doesn't seem to work.

rostest commented 1 month ago

Thanks for new informations! Which version of SOPAS ET do you use? Can you post a screenshot? This topic may also be of interest to other users.

We will soon publish an update to support configurable hashvalues.

rostest commented 1 month ago

@akashjinandra Please use the update in branch https://github.com/SICKAG/sick_scan_xd/tree/feature/issue_update_2407xx to configure hash values for the client authorization in the launchfile.