git commit -m "first commit for v2"

This commit is contained in:
2025-12-29 16:21:22 +07:00
commit aa3d832d5c
1807 changed files with 307078 additions and 0 deletions

View File

@@ -0,0 +1,54 @@
/*
*
* Copyright (C) 2019 Ing.-Buero Dr. Michael Lehning, Hildesheim
* Copyright (C) 2019 SICK AG, Waldkirch
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of SICK AG nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission
* * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* Authors:
* Michael Lehning <michael.lehning@lehning.de>
*
* Copyright 2019 SICK AG
* Copyright 2019 Ing.-Buero Dr. Michael Lehning
*
*/

Binary file not shown.

After

Width:  |  Height:  |  Size: 152 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 102 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 119 KiB

View File

@@ -0,0 +1,70 @@
# pcan-linux-installation
ROS support for sick line guidance sensors has been developed and tested using PEAK CAN adapter for the CAN communication.
This is a quick howto install linux driver for the pcan usb adapter.
# Installation
The following installation is recommended:
&nbsp; 1. Download PCAN-View for Linux from https://www.peak-system.com/linux/ or https://www.peak-system.com/quick/ViewLinux_amd64/pcanview-ncurses_0.8.7-0_amd64.deb and install:
```bash
sudo apt-get install libncurses5
sudo dpkg --install pcanview-ncurses_0.8.7-0_amd64.deb
```
&nbsp; 2. If you're running ROS in a virtual machine, make sure the usb-port for the PCAN-USB-adapter is connected to your VM.
&nbsp; 3. Download and unzip peak-linux-driver-8.17.0.tar.gz from https://www.peak-system.com/quick/PCAN-Linux-Driver
&nbsp; 4. Install the linux driver and required packages:
```bash
cd peak-linux-driver-8.17.0
# install required packages
sudo apt-get install can-utils
sudo apt-get install gcc-multilib
sudo apt-get install libelf-dev
sudo apt-get install libpopt-dev
sudo apt-get install tree
# build and install pcan driver
make clean
make NET=NETDEV_SUPPORT
sudo make install
# install the modules
sudo modprobe pcan
sudo modprobe can
sudo modprobe vcan
sudo modprobe slcan
# setup and configure "can0" net device
sudo ip link set can0 type can
sudo ip link set can0 up type can bitrate 125000 # configure the CAN bitrate, f.e. 125000 bit/s
# check installation
./driver/lspcan --all # should print "pcanusb32" and pcan version
tree /dev/pcan-usb # should show a pcan-usb device
ip -a link # should print some "can0: ..." messages
ip -details link show can0 # should print some details about "can0" net device
```
Example output after successfull installation of a pcan usb adapter:
```bash
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ./driver/lspcan --all
pcanusb32 CAN1 - 8MHz 125k ACTIVE - 1969 0 0
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ tree /dev/pcan-usb
/dev/pcan-usb
├── 0
│   └── can0 -> ../../pcanusb32
└── devid=5 -> ../pcanusb32
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ip -a link
3: can0: <NOARP> mtu 16 qdisc noop state DOWN mode DEFAULT group default qlen 10
link/can
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ip -details link show can0
3: can0: <NOARP> mtu 16 qdisc noop state DOWN mode DEFAULT group default qlen 10
link/can promiscuity 0
can state STOPPED restart-ms 0
bitrate 500000 sample-point 0.875
tq 125 prop-seg 6 phase-seg1 7 phase-seg2 2 sjw 1
pcan: tseg1 1..16 tseg2 1..8 sjw 1..4 brp 1..64 brp-inc 1
clock 8000000numtxqueues 1 numrxqueues 1 gso_max_size 65536 gso_max_segs 65535
```
See https://www.peak-system.com/fileadmin/media/linux/files/PCAN-Driver-Linux_UserMan_eng.pdf for further details.

View File

@@ -0,0 +1,128 @@
# Simulation and testing
sick_canopen_simu implements a software simulation of MLS and OLS devices for test purposes. This simulation generates synthetical can frames from an input xml-file,
and verifies the measurement messages published by the sick_line_guidance driver. By sending specified can frames, the complete processing chain of the ros driver can be verified
by comparing the actual measurement messages with the expected results. In addition, error messages and error handling can be tested, which otherwise can be challenging.
Please note, that sick_canopen_simu does not implement or simulate the behavior of the MLS or OLS hardware. It just sends specified can frames and checks the measurement messages
from the sick_line_guidance driver after entering the operational state. The purpose of sick_canopen_simu is driver verification and testing, not a fully functional simulation of
can devices.
## Usage
To test the sick_line_guidance driver with simulated can frames, four ros nodes have to be started:
- sick_line_guidance_ros2can_node to send ros messages of type can::Frame to the can driver, which sends the frames to the can bus,
- sick_line_guidance_can2ros_node to receive can frames and to publish them as ros messages of type can::Frame,
- sick_canopen_simu to read the simulation data from file, to convert them to can::Frame messages and to verify the resulting sick_line_guidance messages from the driver,
- sick_line_guidance_node, i.e. the sick_line_guidance driver.
Example for simulation and test of the OLS20 driver:
```bash
# Start can2ros converter
roslaunch -v sick_line_guidance sick_line_guidance_can2ros_node.launch &
sleep 5
# Start ros2can converter
roslaunch -v sick_line_guidance sick_line_guidance_ros2can_node.launch &
sleep 5
# Start OLS20 simulation
roslaunch -v --screen sick_line_guidance sick_canopen_simu.launch device:=OLS20 &
sleep 5
# Start OLS driver incl. canopen_chain_node, sick_line_guidance_node and sick_line_guidance_cloud_publisher
roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_ols20.yaml
```
The same example works for MLS, too, with slightly different arguments (`device:=MLS` and `yaml:=sick_line_guidance_mls.yaml`):
```bash
# Start can2ros converter
roslaunch -v sick_line_guidance sick_line_guidance_can2ros_node.launch &
sleep 5
# Start ros2can converter
roslaunch -v sick_line_guidance sick_line_guidance_ros2can_node.launch &
sleep 5
# Start MLS simulation
roslaunch -v --screen sick_line_guidance sick_canopen_simu.launch device:=MLS &
sleep 5
# Start MLS driver incl. canopen_chain_node, sick_line_guidance_node and sick_line_guidance_cloud_publisher
roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_mls.yaml
```
To simulate and test the OLS10 driver, just use the parameter `device:=OLS10` and `yaml:=sick_line_guidance_ols10.yaml`.
If the verification of measurement messages failed, an error message is displayed.
To run an automated unittest of both the MLS, OLS10 and OLS20 driver, script `runsimu.bash` in folder `sick_line_guidance/test/scripts` is provided:
```bash
cd catkin_ws/src/sick_line_guidance/test/scripts
./runsimu.bash
```
## Configuration
Settings and testcases for the simulation are specified in file `sick_line_guidance/test/cfg/sick_canopen_simu_cfg.xml`. To modify the current unittest
or to append further testcases, open this file in editor, save it and install the new configuration by
```bash
cd catkin_ws
catkin_make install
source ./install/setup.bash
```
Configuration file sick_canopen_simu_cfg.xml has three sections:
1. **sick_canopen_simu/SDO_config** : A lookup table for SDO response from SDO get request.
Whenever the ros driver sends a SDO request, the simulation responds with a SDO request from this table.
Example:
```bash
<SDO_config>
<sdo request="0x4018100400000000" response="0x4318100411AE2201" /> <!-- 1018sub4: Serial number -->
<sdo request="0x4018200000000000" response="0x4F18200000000000" /> <!-- 2018: OLS dev_status -->
</SDO_config>
```
The simulation will send a SDO response 4318100411AE2201 when receiving SDO request 4018100400000000 (serial number, object 1018sub4).
SDO response 4F18200000000000 will be sent after receiving a SDO request 4018200000000000 (OLS device status, object 2018).
Note: SDO responses of PDO mapped objects are modified, whenever a PDO is generated by the simulation.
2. **sick_canopen_simu/OLS20/PDO_config** : A list of sensor states transmitted by PDOs to simulate an OLS20 device.
This list specifies the measurement data transmitted by PDOs (lcp1, lcp2, lcp3, width1, width2, width3, status, barcode, barcode center, line quality and line intensities).
Each measurement is transmitted 25 times with a rate of 50 hertz (PDOs in 20 milliseconds intervall, configurable in the launch file sick_canopen_simu.launch)
before switching to the next sensor state. All measurements are repeated in an endless loop while the simulation is running.
Example:
```bash
<OLS20>
<PDO_config>
<pdo lcp1="0.000" lcp2="0.002" lcp3="0.000" width1="0.000" width2="0.012" width3="0.000" status="0x02" barcode="0x00" devstatus="0x00" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.010" lcp2="-0.020" lcp3="-0.030" width1="0.031" width2="0.032" width3="0.033" status="0xC7" barcode="0x12345678" devstatus="0x00" error="0x00" barcodecenter="0.050" linequality="7" lineintensity1="3" lineintensity2="9" lineintensity3="8" frame_id="ols_simulation_frame"/>
</PDO_config>
</OLS20>
```
The simulation will convert the specified sensor states and transmit PDO1 and PDO2 every 20 milliseconds.
3. **sick_canopen_simu/OLS10/PDO_config** : A list of sensor states transmitted by PDOs to simulate an OLS10 device.
This list is identical to OLS20, except that barcode center, line quality and line intensities are not supported by OLS10 devices and therefor have to be set to 0.
Example:
```bash
<OLS10>
<PDO_config>
<pdo lcp1="0.000" lcp2="0.002" lcp3="0.000" width1="0.000" width2="0.012" width3="0.000" status="0x02" barcode="0x00" devstatus="0x00" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.010" lcp2="-0.020" lcp3="-0.030" width1="0.031" width2="0.032" width3="0.033" status="0xC7" barcode="0x12345678" devstatus="0x00" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
</PDO_config>
</OLS10>
```
4. **sick_canopen_simu/MLS/PDO_config** : A list of sensor states transmitted by PDOs to simulate a MLS device.
This list specifies the measurement data transmitted by PDOs (lcp1, lcp2, lcp3, status and #lcp).
Each measurement is transmitted 5 times with a rate of 50 hertz (PDOs in 20 milliseconds intervall, configurable in the launch file sick_canopen_simu.launch)
before switching to the next sensor state. All measurements are repeated in an endless loop while the simulation is running.
Example:
```bash
<MLS>
<PDO_config>
<pdo lcp1="0.000" lcp2="0.002" lcp3="0.000" status="0x01" lcp="0x02" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="-0.005" lcp2="-0.006" lcp3="-0.007" status="0x41" lcp="0x57" error="0x00" frame_id="mls_simulation_frame"/>
</PDO_config>
</MLS>
```
The simulation will convert the specified sensor states and transmit PDO1 every 20 milliseconds.

View File

@@ -0,0 +1,242 @@
# sick_line_guidance configuration
The ROS drivers for MLS and OLS devices are configured by launch and yaml files. You can modify the default configuration by editing these files.
Please note, that an invalid or improper configuration may cause errors and unexpected results.
The basic configuration uses the default values for OLS and MLS devices. All changes should be tested carefully.
To start the MLS resp. OLS driver, just launch sick_line_guidance with a yaml-configuration file:
```bash
roslaunch sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_mls.yaml # start MLS driver
roslaunch sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_ols10.yaml # start OLS10 driver
roslaunch sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_ols20.yaml # start OLS20 driver
```
The launch file "sick_line_guidance.launch" configures the common driver settings, f.e. the ros nodes to start and the ros topics to be used by
sick_line_guidance. Unless special purposes, these settings do not require customization.
The 3rd argument to roslaunch provides the driver with a yaml-file: sick_line_guidance_mls.yaml for MLS resp. sick_line_guidance_ols10.yaml for OLS10
or sick_line_guidance_ols20.yaml for OLS20.
These two files contain the settings of the can devices and may require customization.
## yaml configuration for MLS
This is the default configuration for a MLS device in file mls/sick_line_guidance_mls.yaml:
```yaml
bus:
device: can0
driver_plugin: can::SocketCANInterface
master_allocator: canopen::SimpleMaster::Allocator
sync:
interval_ms: 10
overflow: 0
nodes:
node1:
id: 0x0A # CAN-Node-ID of can device, default: Node-ID 10=0x0A for OLS and MLS
eds_pkg: sick_line_guidance # package name for relative path
eds_file: SICK-MLS.eds # path to EDS/DCF file
publish: ["1001","1018sub1","1018sub4","2021sub1!","2021sub2!","2021sub3!","2021sub4!","2022!"]
# MLS: 1001 = error register, 1018sub1 = VendorID, 1018sub4 = SerialNumber, TPDO1 = 0x2021sub1 to 0x2021sub4 and 0x2022
# sick_line_guidance configuration of this node:
sick_device_family: "MLS" # can devices of OLS10, OLS20 or MLS family currently supported
sick_topic: "mls" # MLS_Measurement messages are published in topic "/mls"
sick_frame_id: "mls_measurement_frame" # MLS_Measurement messages are published frame_id "mls_measurement_frame"
# device configuration of writable parameter by dcf_overlay: "objectindex": "parametervalue"
# example: "2027": "0x01" # Object 2027 (sensorFlipped, defaultvalue 0x00) will be configured with value 0x01
# dcf_overlay:
# "2028sub1": "0x01" # UseMarkers (0 = disable marker detection, 1 = enable marker detection), UINT8, DataType=0x0005, defaultvalue=0
# "2028sub2": "0x02" # MarkerStyle (0 = disable marker detection, 1 = standard mode, 2 = extended mode), UINT8, DataType=0x0005, defaultvalue=0
# "2028sub3": "0x01" # FailSafeMode (0 = disabled, 1 = enabled), UINT8, DataType=0x0005, defaultvalue=0
# "2025": "1000" # Min.Level, UINT16, DataType=0x0006, defaultvalue=600
# "2026": "1" # Offset [mm] Nullpunkt, INT16, DataType=0x0003, defaultvalue=0
# "2027": "0x01" # sensorFlipped, UINT8, DataType=0x0005, defaultvalue=0
# "2029": "0x01" # LockTeach, UINT8, DataType=0x0005, defaultvalue=0
```
The following table describes these settings in detail:
| parameter name | default value | details |
| --- | --- | --- |
| bus / device | can0 | System name of can interface: net device driver for can hardware (f.e. pcan adapter) are installed to a net device named "can0". Check by system command "ifconfig -a" |
| bus / driver_plugin | can:: SocketCANInterface | Implementation of interface SocketCAN, currently only can::SocketCANInterface is supported. |
| bus / master_allocator | canopen:: SimpleMaster:: Allocator | Implementation of CAN master (network manager), currently only canopen::SimpleMaster::Allocator is supported. |
| sync / interval_ms | 10 | Timeinterval for can sync messages in milliseconds (CAN master will send a nmt sync message each 10 ms) |
| sync / overflow | 0 | Length of can sync message (0: sync message does not contain any data byte) |
| nodes | node1 | Name of the first can node configured. If you're running more than 1 can device (multiple MLS or OLS devices), you can configure each device by providing a named section for each node. |
| **nodes / node1 / id** | **0x0A** | **CAN-Node-ID of can device (default: Node-ID 10=0x0A for OLS and MLS). Change this id, if your MLS uses a different CAN-ID. :exclamation:** |
| nodes / node1 / eds_pkg | sick_line_guidance | Name of sick_line_guidance ros package. Required to resolve filenames and should not be modified. |
| nodes / node1 / eds_file | SICK-MLS.eds | Electronic datasheet for your MLS device |
| nodes / node1 / publish | ["1001", "1018sub1", "1018sub4", "2021sub1!", "2021sub2!", "2021sub3!", "2021sub4!", "2022!"] | List of published objects in the object dictionary of a can device. These objects are both published on ros topic <nodename>_<objectindex> and required by driver internal callbacks to handle PDO messages. Do not remove any PDO mapped objects from this list! |
| nodes / node1 / sick_device_family | "MLS" | Informs the ros driver that this can device is a MLS. Currently supported values are "OLS10", "OLS20" or "MLS". |
| nodes / node1 / sick_topic | "mls" | Name of the ros topic for publishing MLS measurement messages. If modified, the same topic must be set in file sick_line_guidance.launch for the sick_line_guidance_cloud_publisher node (param name="mls_topic_publish" type="str" value="mls"). Otherwise, measurement messges won't be transformed to PointCloud2 messsages. |
| nodes / node1 / sick_frame_id | "mls_measurement_frame" | Ros frame id of the MLS measurement messages. |
| **# nodes / node1 / dcf_overlay** | | **Configuration of device parameter. To set an object in the object dictionary of a can device to a specific value at startup, append dcf_overlay entries with "objectindex": "parametervalue". This section is intensionally left empty to use default values. See operation manual for possible settings. :exclamation:** |
Device specific settings can be configured in section "nodes/node1/dcf_overlay". Example to activate marker detection in extended mode (failsafe configuration):
```yaml
dcf_overlay:
"2028sub1": "0x01" # UseMarkers (0 = disable marker detection, 1 = enable marker detection), UINT8, DataType=0x0005, defaultvalue=0
"2028sub2": "0x02" # MarkerStyle (0 = disable marker detection, 1 = standard mode, 2 = extended mode), UINT8, DataType=0x0005, defaultvalue=0
"2028sub3": "0x01" # FailSafeMode (0 = disabled, 1 = enabled), UINT8, DataType=0x0005, defaultvalue=0
```
## yaml configuration for OLS
The configuration of an OLS device is pretty much the same to MLS, just with a different PDO mapping and a different eds-file. Therefore, the object list specified by `publish`
and by `dcf_overlay` vary and the eds-file "SICK_OLS20.eds" is used. Otherwise, the same configuration apply.
This is the default configuration for a OLS10 device in file ols/sick_line_guidance_ols10.yaml:
```yaml
bus:
device: can0
driver_plugin: can::SocketCANInterface
master_allocator: canopen::SimpleMaster::Allocator
sync:
interval_ms: 10
overflow: 0
nodes:
node1:
id: 0x0A # CAN-Node-ID of can device, default: Node-ID 10=0x0A for OLS and MLS
eds_pkg: sick_line_guidance # package name for relative path
eds_file: SICK_OLS10_CO.eds # path to EDS/DCF file
publish: ["1001","1018sub1","1018sub4","2021sub1!","2021sub2!","2021sub3!","2021sub4!","2021sub5!","2021sub6!","2021sub7!","2021sub8!"]
# OLS10: 1001 = error register, 1018sub1 = VendorID, 1018sub4 = SerialNumber, TPDOs 0x2021sub1 to 0x2021sub8
# sick_line_guidance configuration of this node:
sick_device_family: "OLS10" # can devices currently supported: "OLS10", "OLS20" or "MLS"
sick_topic: "ols" # OLS_Measurement messages are published in topic "/ols"
sick_frame_id: "ols_measurement_frame" # OLS_Measurement messages are published with frame_id "ols_measurement_frame"
# device configuration of writable parameter by dcf_overlay: "objectindex": "parametervalue"
# example: "2001sub5": "0x01" # Object 2001sub5 (sensorFlipped, defaultvalue 0x00) will be configured with value 0x01
# dcf_overlay:
# "2001sub5": "0x01" # sensorFlipped, UINT8, DataType=0x0005, defaultvalue=0
# "2002sub1": "0.015" # Typ. Width, FLOAT32, DataType=0x0008
# "2002sub2": "0.001" # Min. Width, FLOAT32, DataType=0x0008
# "2002sub3": "0.050" # Max. Width, FLOAT32, DataType=0x0008
```
This is the default configuration for a OLS20 device in file ols/sick_line_guidance_ols20.yaml:
```yaml
bus:
device: can0
driver_plugin: can::SocketCANInterface
master_allocator: canopen::SimpleMaster::Allocator
sync:
interval_ms: 10
overflow: 0
nodes:
node1:
id: 0x0A # CAN-Node-ID of can device, default: Node-ID 10=0x0A for OLS and MLS
eds_pkg: sick_line_guidance # package name for relative path
eds_file: SICK_OLS20_CO.eds # path to EDS/DCF file
publish: ["1001","1018sub1","1018sub4","2021sub1!","2021sub2!","2021sub3!","2021sub4!","2021sub5!","2021sub6!","2021sub7!","2021sub8!"]
# OLS20: 1001 = error register, 1018sub1 = VendorID, 1018sub4 = SerialNumber, TPDOs 0x2021sub1 to 0x2021sub8
# sick_line_guidance configuration of this node:
sick_device_family: "OLS20" # can devices currently supported: "OLS10", "OLS20" or "MLS"
sick_topic: "ols" # OLS_Measurement messages are published in topic "/ols"
sick_frame_id: "ols_measurement_frame" # OLS_Measurement messages are published with frame_id "ols_measurement_frame"
# device configuration of writable parameter by dcf_overlay: "objectindex": "parametervalue"
# example: "2001sub5": "0x01" # Object 2001sub5 (sensorFlipped, defaultvalue 0x00) will be configured with value 0x01
# dcf_overlay:
# "2001sub5": "0x01" # sensorFlipped, UINT8, DataType=0x0005, defaultvalue=0
# "2002sub1": "0.015" # Typ. Width, FLOAT32, DataType=0x0008
# "2002sub2": "0.001" # Min. Width, FLOAT32, DataType=0x0008
# "2002sub3": "0.050" # Max. Width, FLOAT32, DataType=0x0008
```
The following table describes these settings in detail:
| parameter name | default value | details |
| --- | --- | --- |
| bus / device | can0 | System name of can interface: net device driver for can hardware (f.e. pcan adapter) are installed to a net device named "can0". Check by system command "ifconfig -a" |
| bus / driver_plugin | can:: SocketCANInterface | Implementation of interface SocketCAN, currently only can::SocketCANInterface is supported. |
| bus / master_allocator | canopen:: SimpleMaster:: Allocator | Implementation of CAN master (network manager), currently only canopen::SimpleMaster::Allocator is supported. |
| sync / interval_ms | 10 | Timeinterval for can sync messages in milliseconds (CAN master will send a nmt sync message each 10 ms) |
| sync / overflow | 0 | Length of can sync message (0: sync message does not contain any data byte) |
| nodes | node1 | Name of the first can node configured. If you're running more than 1 can device (multiple MLS or OLS devices), you can configure each device by providing a named section for each node. |
| **nodes / node1 / id** | **0x0A** | **CAN-Node-ID of can device (default: Node-ID 10=0x0A for OLS and MLS). Change this id, if your OLS uses a different CAN-ID. :exclamation:** |
| nodes / node1 / eds_pkg | sick_line_guidance | Name of sick_line_guidance ros package. Required to resolve filenames and should not be modified. |
| nodes / node1 / eds_file | SICK_OLS20.eds | Electronic datasheet for your OLS device |
| nodes / node1 / publish | ["1001", "1018sub1", "1018sub4", "2021sub1!", "2021sub2!", "2021sub3!", "2021sub4!", "2021sub5!", "2021sub6!", "2021sub7!", "2021sub8!"] | List of published objects in the object dictionary of a can device. These objects are both published on ros topic <nodename>_<objectindex> and required by driver internal callbacks to handle PDO messages. Do not remove any PDO mapped objects from this list! |
| nodes / node1 / sick_device_family | "OLS20" | Informs the ros driver that this can device is an OLS20. Currently supported values are "OLS10", "OLS20" or "MLS". |
| nodes / node1 / sick_topic | "ols" | Name of the ros topic for publishing OLS measurement messages. If modified, the same topic must be set in file sick_line_guidance.launch for the sick_line_guidance_cloud_publisher node (param name="ols_topic_publish" type="str" value="ols"). Otherwise, measurement messges won't be transformed to PointCloud2 messsages. |
| nodes / node1 / sick_frame_id | "ols_measurement_frame" | Ros frame id of the OLS measurement messages. |
| **# nodes / node1 / dcf_overlay** | | **Configuration of device parameter. To set an object in the object dictionary of a can device to a specific value at startup, append dcf_overlay entries with "objectindex": "parametervalue". This section is intensionally left empty to use default values. See operation manual for possible settings. :exclamation:** |
Device specific settings can be configured in section "nodes/node1/dcf_overlay". Example to set object 2001sub5 (sensorFlipped):
```yaml
dcf_overlay:
"2001sub5": "0x01" # sensorFlipped, UINT8, DataType=0x0005, defaultvalue=0
```
## Summary of the yaml configuration for MLS and OLS devices
Set the CAN-ID of your device with `id: 0x0A # CAN-Node-ID of MLS (default: 0x0A)` and
configure device specific settings in section `dcf_overlay` by appending a line `"objectindex": "parametervalue"` for each parameter.
## Configuration for multiple devices
If you want to use multiple can devices (MLS or OLS) on one system, you have to append multiple nodes in your yaml-file. Each node must contain the configuration of one can device as shown above. Make sure to use different node names for each device:
```yaml
nodes:
node1:
id: ... # CAN-ID for the 1. device
node2:
id: ... # CAN-ID for the 2. device
```
If you configure different measurement topics for each can device (f.e. `sick_topic: "ols20A"` for the first OLS20 and `sick_topic: "ols20B"` for the second OLS20 device), you have to start multiple sick_line_guidance_cloud_publisher nodes, too. Otherwise, measurement messges from this device can't be transformed to PointCloud2 messsages.
Append multiple sick_line_guidance_cloud_publisher nodes in file sick_line_guidance.launch, each sick_line_guidance_cloud_publisher node configured with the corresponding
ros topic in parameter `"mls_topic_publish"` resp. `"ols_topic_publish"`.
Launchfile [sick_line_guidance_ols20_twin.launch](../launch/sick_line_guidance_ols20_twin.launch) and yaml-configuration [sick_line_guidance_ols20_twin.yaml](../ols/sick_line_guidance_ols20_twin.yaml) show an example how to run two OLS20 devices with can node ids 0x0A and 0x0B. Run the example with
```
rosrun rviz rviz &
roslaunch -v --screen sick_line_guidance sick_line_guidance_ols20_twin.launch
```
The point clouds of both OLS20 devices will be published on topic "cloudA" and "cloudB" with frame ids "olsA_frame" and "olsB_frame". Use a static_transform_publisher to setup a transform for each OLS frame to a reference coordinate system, e.g.
```
rosrun tf static_transform_publisher 0 0 0 0 0 0 olsA_frame cloud 10
rosrun tf static_transform_publisher 0 0 0 0 0 0 olsB_frame cloud 10
```
## Read and write parameter during runtime
You can read and write to the object dictionary of a can device on runtime, too, by using the ros services implemented by the canopen driver.
To read a value from the object dictionary, you can run
```bash
rosservice call /driver/get_object "{node: '<nodename>', object: '<objectindex>', cached: <true|false>}"
```
in your terminal. Example to read object 2001sub5 (sensorFlipped) from node1:
```bash
rosservice call /driver/get_object "{node: 'node1', object: '2001sub5', cached: false}"
```
This command results in a can upload command using a SDO with object 2001sub5. The SDO response will be converted and displayed if the command succeded.
To write a value to the object dictionary, you can run
```bash
rosservice call /driver/get_object "{node: '<nodename>', object: '<objectindex>', value: '<parametervalue>', cached: <true|false>}"
```
in the terminal. Example to write value 0x01 to object 2001sub5 (sensorFlipped):
```bash
rosservice call /driver/set_object "{node: 'node1', object: '2001sub5', value: '0x01', cached: false}"
```
This command results in a can upload command using a SDO with object 2001sub5.
## Configuration of CAN node id
The node id of a CAN device can be configured e.b. with [PCAN-View](https://www.peak-system.com/PCAN-View.242.0.html):<br/>
![screenshot01.png](pcan-config/screenshot01.png)<br/>
![screenshot02.png](pcan-config/screenshot02.png)<br/>
## Installation and bus termination
The following screenshot shows the installation and bus termination for two OLS devices:<br/>
![screenshot03.png](pcan-config/screenshot03.png)