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

LMS4xxx switch from Software to Free Running #198

Closed manuelrucci7 closed 1 year ago

manuelrucci7 commented 1 year ago

I am trying to send a ros2 service call to switch the laser into Software mode without using the sopas. I was looking at the documentation

Screenshot from 2023-07-31 11-34-21

and I tried to send the following command

ros2 service call /scan3/ColaMsg sick_scan/srv/ColaMsgSrv "{request: 'sWN IOlasc 1 +500 0 0 0'}"

resulting in this error:

[WARN] [1690796155.255845658] [sick_scan]: Error Sopas answer mismatch: Error unexpected Sopas answer for request <STX><STX><STX><STX><Len=0023>sWN IOlasc 0x01 0x20 0x2b 0x05 0x0..., received answer: "sFA\x00\x0a", expected patterns: "sWA IOlasc","sAN IOlasc"

I think the issue might be related to the fact that I need to use binary code. However I tried

ros2 service call /scan3/ColaMsg sick_scan/srv/ColaMsgSrv "{request: '02 02 02 02 00 00 00 16 73 57 4E 20 49 4F 6C 61 73 63 20 01 01 F4 00 00 00 00 00 00 00 20 A5'}"

and it is not working either.

The thing that is strange is that I am using the following command without any issue, to start and stop the laser.

ros2 service call /scan3/ColaMsg sick_scan/srv/ColaMsgSrv "{request: 'LMCstartmeas}"
ros2 service call /scan3/ColaMsg sick_scan/srv/ColaMsgSrv "{request: 'LMCstandby'}"

Do u have any idea what is wrong?

This is the launch file that I am currently using.

<?xml version="1.0"?>
<!--
     **********************************************
     Launch File for LMS 4xxx scanner
     **********************************************
     Start and stop angle is given in [rad]

     Default min_angle is  -35 degree.
     Default max_angle is +35 degree.

     SOPAS angles in lidar coordinates: min_angle = 55 deg, max_angle = 125 deg, delta = 125-55 = 70 deg
     Angle offset -90 degree: (55-90 = -35 deg, 125-90 = +35 deg)
     Angle configuration in ROS coordinates: min_angle = -35 deg, max_angle = +35 deg, delta = 70 deg

     Check IP-address, if you scanner is not found after roslaunch.
-->

<!-- You can launch a LMS_4xxx-scanner on a specific ip address (e.g. 192.68.0.71) using the following example call:

     roslaunch sick_scan sick_lms_4xxx.launch hostname:=192.168.0.71

-->
<!-- Using node option required="true" will close roslaunch after node exits -->

<launch>
    <arg name="hostname" default="192.168.124.103"/>
    <arg name="cloud_topic" default="cloud"/>
    <arg name="frame_id" default="L3"/>
    <node name="sick_lms_4xxx" pkg="sick_scan" type="sick_generic_caller" respawn="false" output="screen" required="true">

        <!-- default values: -->
        <!--
          <param name="scanner_type" type="string" value="sick_tim_5xx" />
          <param name="min_ang" type="double" value="-2.35619449" />
          <param name="max_ang" type="double" value="2.35619449" />
          <param name="intensity" type="bool" value="True" />
          <param name="skip" type="int" value="0" />
          <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="scanner_type" type="string" value="sick_lms_4xxx"/>

        <!-- -20 deg Up -->
        <!--<param name="min_ang" type="double" value="-0.34906585"/>-->

        <!-- +35 deg  Buttom -->
        <!--<param name="max_ang" type="double" value="0.34906585"/>-->

        <param name="min_ang" type="double" value="-0.34906585" />
        <param name="max_ang" type="double" value="0.34906585" />

        <param name="use_binary_protocol" type="bool" value="true"/>
        <param name="range_max" type="double" value="3.5"/>
        <param name="range_min" type="double" value="0.7"/>
        <param name="intensity" type="bool" value="True"/>

        <param name="hostname" type="string" value="$(arg hostname)"/>
        <param name="cloud_topic" type="string" value="$(arg cloud_topic)"/>
        <param name="frame_id" type="str" value="$(arg frame_id)"/>
        <param name="port" type="string" value="2112"/>
        <param name="timelimit" type="int" value="5"/>
        <param name="min_intensity" type="double" value="0.0"/> <!-- Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) -->

        <param name="start_services" type="bool" value="True" />                  <!-- Start ros service for cola commands, default: true -->
        <param name="message_monitoring_enabled" type="bool" value="False" />      <!-- Enable message monitoring with reconnect+reinit in case of timeouts, default: true -->
        <param name="read_timeout_millisec_default" type="int" value="5000"/>     <!-- 5 sec read timeout in operational mode (measurement mode), default: 5000 milliseconds -->
        <param name="read_timeout_millisec_startup" type="int" value="250000"/>   <!-- 120 sec read timeout during startup (sensor may be starting up, which can take up to 120 sec.), default: 120000 milliseconds -->
        <param name="read_timeout_millisec_kill_node" type="int" value="250000"/> <!-- 150 sec pointcloud timeout, ros node will be killed if no point cloud published within the last 150 sec., default: 150000 milliseconds -->
        <param name="client_authorization_pw" type="string" value="F4724744"/>    <!-- Default password for client authorization -->

    </node>

</launch>
michael1309 commented 1 year ago

The command requires the authorization level "Authorized Client". We recommend that you first send a command to authorize this level according to the message structure in the attached screenshot.

image
michael1309 commented 1 year ago

See also https://github.com/SICKAG/sick_scan_xd/issues/160 for an example.

michael1309 commented 1 year ago

Just a note about sending a binary message like in your example:

image

Please remove all spaces between the hex values in this case.

rostest commented 1 year ago

@manuelrucci7 I am closing this issue for now. Please do not hesitate to reopen the ticket in case of further issues.