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,133 @@
<?xml version="1.0" ?>
<sick_canopen_simu>
<SDO_config>
<!-- Lookup table for SDO response from SDO get request (client->server: upload request -> upload response) -->
<sdo request="0x4001100000000000" response="0x4F01100000000000" /> <!-- 1001: error register (all can devices) -->
<sdo request="0x4001200500000000" response="0x4F01200500000000" /> <!-- 2001sub5: OLS sensor flipped -->
<sdo request="0x4002200100000000" response="0x4302200100000000" /> <!-- 2002sub1: OLS Typ. Width -->
<sdo request="0x4002200200000000" response="0x4302200200000000" /> <!-- 2002sub2: OLS Min. Width -->
<sdo request="0x4002200300000000" response="0x4302200300000000" /> <!-- 2002sub3: OLS Max. Width -->
<sdo request="0x4018100100000000" response="0x4318100156000001" /> <!-- 1018sub1: Vendor Id (OLS and MLS) -->
<sdo request="0x4018100400000000" response="0x4318100411AE2201" /> <!-- 1018sub4: Serial number (OLS and MLS) -->
<!-- sdo request="0x4018200000000000" response="0x4B18200000000000"/ --> <!-- 2018: OLS10 dev_status (UINT16) -->
<sdo request="0x4018200000000000" response="0x4F18200000000000" /> <!-- 2018: OLS20 dev_status (UINT8) -->
<sdo request="0x4021200100000000" response="0x4B21200100000000" /> <!-- 2021sub1: LCP1 (OLS and MLS) -->
<sdo request="0x4021200200000000" response="0x4B21200200000000" /> <!-- 2021sub2: LCP2 (OLS and MLS) -->
<sdo request="0x4021200300000000" response="0x4B21200300000000" /> <!-- 2021sub3: LCP3 (OLS and MLS) -->
<sdo request="0x4021200400000000" response="0x4F21200400000000" /> <!-- 2021sub4: OLS: State, MLS: #LCP and marker -->
<sdo request="0x4021200500000000" response="0x4B21200500000000" /> <!-- 2021sub5: OLS Width LCP1 -->
<sdo request="0x4021200600000000" response="0x4B21200600000000" /> <!-- 2021sub6: OLS Width LCP2 -->
<sdo request="0x4021200700000000" response="0x4B21200700000000" /> <!-- 2021sub7: OLS Width LCP3 -->
<sdo request="0x4021200800000000" response="0x4F21200800000000" /> <!-- 2021sub8: OLS Barcode (UINT8) -->
<sdo request="0x4021200900000000" response="0x4321200900000000" /> <!-- 2021sub9: OLS Extended Barcode (UINT32) -->
<sdo request="0x4022200000000000" response="0x4F22200000000000" /> <!-- 2022: MLS status -->
<sdo request="0x4025200000000000" response="0x4F25200000000000" /> <!-- 2025: MLS Min.Level -->
<sdo request="0x4026200000000000" response="0x4F26200000000000" /> <!-- 2026: MLS Offset -->
<sdo request="0x4027200000000000" response="0x4F27200000000000" /> <!-- 2027: MLS sensorFlipped -->
<sdo request="0x4028200100000000" response="0x4F28200100000000" /> <!-- 2028sub1: MLS UseMarkers -->
<sdo request="0x4028200200000000" response="0x4F28200200000000" /> <!-- 2028sub2: MLS MarkerStyle -->
<sdo request="0x4028200300000000" response="0x4F28200300000000" /> <!-- 2028sub3: MLS FailSafeMode -->
<sdo request="0x4029200000000000" response="0x4F29200000000000" /> <!-- 2029: MLS LockTeach -->
<!--Lookup table for OLS20 only SDOs: objects 2021subA (barcode center point, INT16), 2021subB (quality of lines, UINT8) and 2023sub1 to 2023sub3 (intensity line 1 - 3, UINT8) -->
<sdo request="0x4021200A00000000" response="0x4B21200A00000000" /> <!-- 2021subA: OLS20 Barcode center point (INT16) -->
<sdo request="0x4021200B00000000" response="0x4F21200B00000000" /> <!-- 2021subB: OLS20 Quality of lines (UINT8) -->
<sdo request="0x4023200100000000" response="0x4F23200100000000" /> <!-- 2023sub1: OLS20 Intensity of line 1 (UINT8) -->
<sdo request="0x4023200200000000" response="0x4F23200200000000" /> <!-- 2023sub1: OLS20 Intensity of line 2 (UINT8) -->
<sdo request="0x4023200300000000" response="0x4F23200300000000" /> <!-- 2023sub1: OLS20 Intensity of line 3 (UINT8) -->
<!-- Lookup table for SDO response from SDO set request (dcf overlays, client->server: download request -> download response), -->
<!-- f.e. SDO request = 0x23022003CDCC4C3D = 0x2302200300000000 + {4 byte data}: SDO response = 0x6002200300000000 -->
<sdo request="0x2302200100000000" response="0x6002200100000000" /> <!-- 2002sub1: OLS Typ. Width -->
<sdo request="0x2302200200000000" response="0x6002200200000000" /> <!-- 2002sub2: OLS Min. Width -->
<sdo request="0x2302200300000000" response="0x6002200300000000" /> <!-- 2002sub3: OLS Max. Width -->
<sdo request="0x2B17100000000000" response="0x6017100000000000" /> <!-- 1017: OLS Producer Heartbeat Time -->
<sdo request="0x2B25200000000000" response="0x6025200000000000" /> <!-- 2025: MLS Min.Level -->
<sdo request="0x2B26200000000000" response="0x6026200000000000" /> <!-- 2026: MLS Offset -->
<sdo request="0x2F01200500000000" response="0x6001200501000000" /> <!-- 2001sub5: OLS sensor flipped -->
<sdo request="0x2F27200000000000" response="0x6027200000000000" /> <!-- 2027: MLS sensorFlipped -->
<sdo request="0x2F28200100000000" response="0x6028200100000000" /> <!-- 2028sub1: MLS UseMarkers -->
<sdo request="0x2F28200200000000" response="0x6028200200000000" /> <!-- 2028sub2: MLS MarkerStyle -->
<sdo request="0x2F28200300000000" response="0x6028200300000000" /> <!-- 2028sub3: MLS FailSafeMode -->
<sdo request="0x2F29200000000000" response="0x6029200000000000" /> <!-- 2029: MLS LockTeach -->
</SDO_config>
<OLS10>
<PDO_config>
<!-- List of PDOs to simulate OLS device -->
<!-- Status byte OLS (0x2021sub4 in object dictionary, Bit7=MSBit to Bit0=LSBit): -->
<!-- Bit7: CodeValid, Bit6: CodeFlipped, Bit5: x, Bit4: DeviceStatus, Bit3: x, Bit2: #LCPBit2, Bit1: #LCPBit1, Bit0: #LCPBit0 -->
<!-- Device status byte OLS (0x2018 in object dictionary): -->
<!-- Bit0=0: Device okay, Bit0=1: Device error -->
<!-- OLS10: barcodecenter, linequality and lineintensity1-3 always 0 -->
<pdo lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0x00" 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.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.000" lcp2="0.002" lcp3="0.003" width1="0.000" width2="0.012" width3="0.013" status="0x03" 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.001" lcp2="0.002" lcp3="0.000" width1="0.011" width2="0.012" width3="0.000" status="0x06" 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.001" lcp2="0.002" lcp3="0.003" width1="0.011" width2="0.012" width3="0.013" status="0x07" 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.001" lcp2="0.002" lcp3="0.003" width1="0.011" width2="0.012" width3="0.013" status="0x87" barcode="0x78" devstatus="0x00" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="-0.001" lcp2="-0.002" lcp3="-0.003" width1="0.021" width2="0.022" width3="0.023" status="0x87" barcode="0xEF" 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="0x87" barcode="0x100" 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="0x87" barcode="0x12345678" 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 lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0xD7" barcode="0xFFFFFFFF" devstatus="0x01" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0xD7" barcode="0xFFFFFFFF" devstatus="0xAB" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
</PDO_config>
</OLS10>
<OLS20>
<PDO_config>
<!-- List of PDOs to simulate OLS-20 device -->
<!-- Status byte OLS (0x2021sub4 in object dictionary, Bit7=MSBit to Bit0=LSBit): -->
<!-- Bit7: CodeValid, Bit6: CodeFlipped, Bit5: x, Bit4: DeviceStatus, Bit3: x, Bit2: #LCPBit2, Bit1: #LCPBit1, Bit0: #LCPBit0 -->
<!-- Device status byte OLS (0x2018 in object dictionary): -->
<!-- Bit0=0: Device okay, Bit0=1: Device error -->
<!-- OLS20: simulate barcodecenter, linequality and lineintensity1-3 (OLS10: always 0) -->
<pdo lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0x00" 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.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.000" lcp2="0.002" lcp3="0.003" width1="0.000" width2="0.012" width3="0.013" status="0x03" 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.001" lcp2="0.002" lcp3="0.000" width1="0.011" width2="0.012" width3="0.000" status="0x06" 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.001" lcp2="0.002" lcp3="0.003" width1="0.011" width2="0.012" width3="0.013" status="0x07" 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.001" lcp2="0.002" lcp3="0.003" width1="0.011" width2="0.012" width3="0.013" status="0x87" barcode="0x78" devstatus="0x00" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="-0.001" lcp2="-0.002" lcp3="-0.003" width1="0.021" width2="0.022" width3="0.023" status="0x87" barcode="0xEF" 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="0x87" barcode="0x100" 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="0x87" barcode="0x12345678" 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 lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0xD7" barcode="0xFFFFFFFF" devstatus="0x01" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0xD7" barcode="0xFFFFFFFF" devstatus="0xAB" error="0x00" barcodecenter="0.000" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0x00" 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.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="2" lineintensity1="0" lineintensity2="5" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.000" lcp2="0.002" lcp3="0.003" width1="0.000" width2="0.012" width3="0.013" status="0x03" barcode="0x00" devstatus="0x00" error="0x00" barcodecenter="0.000" linequality="6" lineintensity1="0" lineintensity2="5" lineintensity3="4" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.001" lcp2="0.002" lcp3="0.000" width1="0.011" width2="0.012" width3="0.000" status="0x06" barcode="0x00" devstatus="0x00" error="0x00" barcodecenter="0.000" linequality="3" lineintensity1="1" lineintensity2="5" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.001" lcp2="0.002" lcp3="0.003" width1="0.011" width2="0.012" width3="0.013" status="0x07" barcode="0x00" devstatus="0x00" error="0x00" barcodecenter="0.000" linequality="7" lineintensity1="1" lineintensity2="5" lineintensity3="4" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.001" lcp2="0.002" lcp3="0.003" width1="0.011" width2="0.012" width3="0.013" status="0x87" barcode="0x78" devstatus="0x00" error="0x00" barcodecenter="0.010" linequality="7" lineintensity1="1" lineintensity2="5" lineintensity3="4" frame_id="ols_simulation_frame"/>
<pdo lcp1="-0.001" lcp2="-0.002" lcp3="-0.003" width1="0.021" width2="0.022" width3="0.023" status="0x87" barcode="0xEF" devstatus="0x00" error="0x00" barcodecenter="0.010" linequality="7" lineintensity1="2" lineintensity2="9" lineintensity3="6" 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="0x87" barcode="0x100" devstatus="0x00" error="0x00" barcodecenter="0.010" linequality="7" lineintensity1="2" lineintensity2="9" lineintensity3="6" 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="0x87" barcode="0x12345678" devstatus="0x00" error="0x00" barcodecenter="0.050" linequality="7" lineintensity1="3" lineintensity2="9" lineintensity3="8" 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 lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0xD7" barcode="0xFFFFFFFF" devstatus="0x01" error="0x00" barcodecenter="0.123" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
<pdo lcp1="0.000" lcp2="0.000" lcp3="0.000" width1="0.000" width2="0.000" width3="0.000" status="0xD7" barcode="0xFFFFFFFF" devstatus="0xAB" error="0x00" barcodecenter="0.123" linequality="0" lineintensity1="0" lineintensity2="0" lineintensity3="0" frame_id="ols_simulation_frame"/>
</PDO_config>
</OLS20>
<MLS>
<PDO_config>
<!-- List of PDOs to simulate MLS device -->
<!-- status byte MLS (2022 in object dictionary, Bit7=MSBit to Bit0=LSBit): -->
<!-- Bit7: 0, Bit6: ReadingCode, Bit5: Polarity, Bit4: SensorFlipped, Bit3: LineLevBit2, Bit2: LineLevBit1, Bit1: LineLevBit0, Bit0: Linegood(1:LineGood,0:NotGood) -->
<!-- lcp byte MLS (0x2021sub4 in object dictionary, Bit7=MSBit to Bit0=LSBit): -->
<!-- Bit7: MarkerBit4, Bit6: MarkerBit3, Bit5: MarkerBit2, Bit4: MarkerBit1, Bit3: MarkerBit0, Bit2: #LCPBit2, Bit1: #LCPBit1, Bit0: #LCPBit0 -->
<pdo lcp1="0.000" lcp2="0.000" lcp3="0.000" status="0x00" lcp="0x00" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="0.000" lcp2="0.002" lcp3="0.000" status="0x01" lcp="0x02" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="0.000" lcp2="0.002" lcp3="0.003" status="0x01" lcp="0x03" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="0.001" lcp2="0.002" lcp3="0.000" status="0x01" lcp="0x06" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="0.001" lcp2="0.002" lcp3="0.003" status="0x01" lcp="0x07" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="-0.010" lcp2="0.020" lcp3="0.030" status="0x01" lcp="0x07" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="0.010" lcp2="-0.020" lcp3="0.030" status="0x01" lcp="0x07" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="0.010" lcp2="0.020" lcp3="-0.030" status="0x01" lcp="0x07" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="-0.010" lcp2="-0.020" lcp3="-0.030" status="0x01" lcp="0x07" 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 lcp1="-0.005" lcp2="-0.006" lcp3="-0.007" status="0x41" lcp="0xAF" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="-0.005" lcp2="-0.006" lcp3="-0.007" status="0x41" lcp="0xFF" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="-0.005" lcp2="-0.006" lcp3="-0.007" status="0x41" lcp="0xFF" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="-0.005" lcp2="-0.006" lcp3="-0.007" status="0x61" lcp="0xFF" error="0x00" frame_id="mls_simulation_frame"/>
<pdo lcp1="-0.005" lcp2="-0.006" lcp3="-0.007" status="0x7F" lcp="0xFF" error="0x00" frame_id="mls_simulation_frame"/>
</PDO_config>
</MLS>
</sick_canopen_simu>

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,143 @@
[FileInfo]
FileName=CiA401_minimal.eds
FileVersion=1
FileRevision=1
EDSVersion=4.0
Description=CANopenIA CiA401 Minimal Example
CreatedBy=rostest
CreationTime=11:00AM
CreationDate=13-02-2019
ModifiedBy=rostest
ModificationTime=11:00AM
ModificationDate=13-02-2019
[DeviceInfo]
VendorName=rostest
VendorNumber=0x01000056
ProductName=rostest
ProductNumber=0x00001004
RevisionNumber=1
OrderCode=-
BaudRate_10=1
BaudRate_20=1
BaudRate_50=1
BaudRate_125=1
BaudRate_250=1
BaudRate_500=1
BaudRate_800=0
BaudRate_1000=1
DynamicChannelsSupported=0
GroupMessaging=0
LSS_Supported=0
Granularity=0
SimpleBootUpSlave=1
SimpleBootUpMaster=0
NrOfRXPDO=0
NrOfTXPDO=2
CompactPDO=0x00
[Comments]
Lines=0
[DummyUsage]
Dummy0001=0
Dummy0002=0
Dummy0003=0
Dummy0004=0
Dummy0005=0
Dummy0006=0
Dummy0007=0
[MandatoryObjects]
SupportedObjects=3
1=0x1000
2=0x1001
3=0x1018
[OptionalObjects]
SupportedObjects=0
[ManufacturerObjects]
SupportedObjects=0
[1000]
ParameterName=Device Type
ObjectType=0x07
DataType=0x0007
LowLimit=
HighLimit=
AccessType=const
DefaultValue=0x000F0191
PDOMapping=0
ObjFlags=0x00
[1001]
ParameterName=Error Register
ObjectType=0x07
DataType=0x0005
LowLimit=
HighLimit=
AccessType=ro
DefaultValue=
PDOMapping=0
ObjFlags=0x00
[1018]
ParameterName=Identity Object
SubNumber=5
ObjectType=0x08
[1018sub0]
ParameterName=number of entries
ObjectType=0x07
DataType=0x0005
LowLimit=1
HighLimit=4
AccessType=const
DefaultValue=4
PDOMapping=0
ObjFlags=0x00
[1018sub1]
ParameterName=Vendor ID
ObjectType=0x07
DataType=0x0007
LowLimit=
HighLimit=
AccessType=const
DefaultValue=0x01455341
PDOMapping=0
ObjFlags=0x00
[1018sub2]
ParameterName=Product Code
ObjectType=0x07
DataType=0x0007
LowLimit=
HighLimit=
AccessType=const
DefaultValue=0xC01A0401
PDOMapping=0
ObjFlags=0x00
[1018sub3]
ParameterName=Revision number
ObjectType=0x07
DataType=0x0007
LowLimit=
HighLimit=
AccessType=ro
DefaultValue=0xFFFFFFFF
PDOMapping=0
ObjFlags=0x00
[1018sub4]
ParameterName=Serial number
ObjectType=0x07
DataType=0x0007
LowLimit=
HighLimit=
AccessType=ro
DefaultValue=0xFFFFFFFF
PDOMapping=0
ObjFlags=0x00

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,787 @@
; This EDS file was created by the CANopen Design Tool 2.3.19.0.
; port GmbH Halle/Saale Germany, http://www.port.de, mailto:service@port.de
; DefaultValues added by rostest.
[FileInfo]
FileName=OLS20.eds
FileVersion=1
FileRevision=1
EDSVersion=4.0
Description=Optical Line Guidance
CreationTime=09:08AM
CreationDate=08-15-2018
CreatedBy=herrmra
ModificationTime=10:51AM
ModificationDate=12-03-2018
ModifiedBy=rostest
[DeviceInfo]
VendorName=SICK AG
VendorNumber=0x01000056
ProductName=OLS20
ProductNumber=0x00001004
RevisionNumber=1
OrderCode=-
BaudRate_10=1
BaudRate_20=1
BaudRate_50=1
BaudRate_125=1
BaudRate_250=1
BaudRate_500=1
BaudRate_800=0
BaudRate_1000=1
DynamicChannelsSupported=0
GroupMessaging=0
LSS_Supported=1
Granularity=8
SimpleBootUpSlave=1
SimpleBootUpMaster=0
NrOfRXPDO=0
NrOfTXPDO=2
[Comments]
Lines=0
[DummyUsage]
Dummy0001=0
Dummy0002=0
Dummy0003=0
Dummy0004=0
Dummy0005=0
Dummy0006=0
Dummy0007=0
[MandatoryObjects]
SupportedObjects=3
1=0x1000
2=0x1001
3=0x1018
[OptionalObjects]
SupportedObjects=16
1=0x1005
2=0x1008
3=0x1009
4=0x100A
5=0x100C
6=0x100D
7=0x1014
8=0x1015
9=0x1016
10=0x1017
11=0x1200
12=0x1800
13=0x1801
14=0x1A00
15=0x1A01
16=0x1F80
[ManufacturerObjects]
SupportedObjects=6
1=0x2001
2=0x2002
3=0x2003
4=0x2018
5=0x2019
6=0x2021
[1000]
ParameterName=Device Type
ObjectType=0x07
DataType=0x0007
AccessType=const
DefaultValue=0x0000000
PDOMapping=0
[1001]
ParameterName=Error Register
ObjectType=0x07
DataType=0x0005
AccessType=ro
PDOMapping=0
[1005]
ParameterName=COB-ID SYNC
ObjectType=0x07
DataType=0x0007
AccessType=rw
PDOMapping=0
[1008]
ParameterName=Manufacturer Device Name
ObjectType=0x07
DataType=0x0009
AccessType=const
PDOMapping=0
[1009]
ParameterName=Manufacturer Hardware Version
ObjectType=0x07
DataType=0x0009
AccessType=const
PDOMapping=0
[100A]
ParameterName=Manufacturer Software Version
ObjectType=0x07
DataType=0x0009
AccessType=const
PDOMapping=0
[100C]
ParameterName=Guard Time
ObjectType=0x07
DataType=0x0006
AccessType=rw
PDOMapping=0
[100D]
ParameterName=Life Time Factor
ObjectType=0x07
DataType=0x0005
AccessType=rw
PDOMapping=0
[1014]
ParameterName=COB-ID EMCY
ObjectType=0x07
DataType=0x0007
AccessType=rw
PDOMapping=0
[1015]
ParameterName=Inhibit Time Emergency
ObjectType=0x07
DataType=0x0006
AccessType=rw
DefaultValue=0x0000
PDOMapping=0
[1016]
SubNumber=3
ParameterName=Heartbeat Consumer Entries
ObjectType=0x08
[1016sub0]
ParameterName=Highest sub-index supported
ObjectType=0x07
DataType=5
AccessType=const
DefaultValue=0x02
PDOMapping=0
[1016sub1]
ParameterName=Consumer Heartbeat Time 1
ObjectType=0x07
DataType=0x0007
AccessType=rw
PDOMapping=0
[1016sub2]
ParameterName=Consumer Heartbeat Time 2
ObjectType=0x07
DataType=0x0007
AccessType=rw
PDOMapping=0
[1017]
ParameterName=Producer Heartbeat Time
ObjectType=0x07
DataType=0x0006
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1018]
SubNumber=5
ParameterName=Identity Object
ObjectType=0x09
[1018sub0]
ParameterName=number of entries
ObjectType=0x07
DataType=0x0005
AccessType=const
DefaultValue=0x4
PDOMapping=0
[1018sub1]
ParameterName=Vendor Id
ObjectType=0x07
DataType=0x0007
AccessType=ro
DefaultValue=0x01000056
PDOMapping=0
[1018sub2]
ParameterName=Product Code
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[1018sub3]
ParameterName=Revision number
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[1018sub4]
ParameterName=Serial number
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[1200]
SubNumber=3
ParameterName=Server SDO Parameter 1
ObjectType=0x09
[1200sub0]
ParameterName=Highest sub-index supported
ObjectType=0x07
DataType=0x0005
AccessType=const
DefaultValue=0x02
PDOMapping=0
[1200sub1]
ParameterName=COB-ID Client -> Server
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[1200sub2]
ParameterName=COB-ID Server -> Client
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[1800]
SubNumber=6
ParameterName=Transmit PDO Communication Parameter 1
ObjectType=0x09
[1800sub0]
ParameterName=Highest sub-index supported
ObjectType=0x07
DataType=0x0005
AccessType=const
DefaultValue=0x05
PDOMapping=0
LowLimit=0x2
HighLimit=0x6
[1800sub1]
ParameterName=COB-ID
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=$NODEID+0x180
PDOMapping=0
LowLimit=0x00000001
HighLimit=0xFFFFFFFF
[1800sub2]
ParameterName=Transmission Type
ObjectType=0x07
DataType=0x0005
AccessType=rw
DefaultValue=0xFF
PDOMapping=0
LowLimit=0x0
HighLimit=0xFF
[1800sub3]
ParameterName=Inhibit Time
ObjectType=0x07
DataType=0x0006
AccessType=rw
DefaultValue=0x0
PDOMapping=0
LowLimit=0x0000
HighLimit=0xFFFF
[1800sub4]
ParameterName=Compatibility Entry
ObjectType=0x07
DataType=0x0005
AccessType=rw
DefaultValue=0x00
PDOMapping=0
LowLimit=0x00
HighLimit=0xFF
[1800sub5]
ParameterName=Event Timer
ObjectType=0x07
DataType=0x0006
AccessType=rw
DefaultValue=0x14
PDOMapping=0
LowLimit=0x0
HighLimit=0xFFFF
[1801]
SubNumber=6
ParameterName=Transmit PDO Communication Parameter 2
ObjectType=0x09
[1801sub0]
ParameterName=Highest sub-index supported
ObjectType=0x07
DataType=0x0005
AccessType=const
DefaultValue=0x05
PDOMapping=0
LowLimit=0x02
HighLimit=0x06
[1801sub1]
ParameterName=COB-ID
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=$NODEID+0x280
PDOMapping=0
LowLimit=0x00000001
HighLimit=0xFFFFFFFF
[1801sub2]
ParameterName=Transmission Type
ObjectType=0x07
DataType=0x0005
AccessType=rw
DefaultValue=0xFF
PDOMapping=0
LowLimit=0x0
HighLimit=0xFF
[1801sub3]
ParameterName=Inhibit Time
ObjectType=0x07
DataType=0x0006
AccessType=rw
DefaultValue=0x0
PDOMapping=0
LowLimit=0x0000
HighLimit=0xFFFF
[1801sub4]
ParameterName=Compatibility Entry
ObjectType=0x07
DataType=0x0005
AccessType=rw
DefaultValue=0x00
PDOMapping=0
LowLimit=0x00
HighLimit=0xFF
[1801sub5]
ParameterName=Event Timer
ObjectType=0x07
DataType=0x0006
AccessType=rw
DefaultValue=0x14
PDOMapping=0
LowLimit=0x0
HighLimit=0xFFFF
[1A00]
SubNumber=9
ParameterName=Transmit PDO Mapping Parameter 1
ObjectType=0x09
[1A00sub0]
ParameterName=Number of mapped objects
ObjectType=0x07
DataType=0x0005
AccessType=rw
DefaultValue=0x00
PDOMapping=0
LowLimit=0x00
HighLimit=0x08
[1A00sub1]
ParameterName=Mapping Entry 1
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A00sub2]
ParameterName=Mapping Entry 2
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A00sub3]
ParameterName=Mapping Entry 3
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A00sub4]
ParameterName=Mapping Entry 4
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A00sub5]
ParameterName=Mapping Entry 5
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A00sub6]
ParameterName=Mapping Entry 6
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A00sub7]
ParameterName=Mapping Entry 7
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A00sub8]
ParameterName=Mapping Entry 8
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A01]
SubNumber=9
ParameterName=Transmit PDO Mapping Parameter 2
ObjectType=0x09
[1A01sub0]
ParameterName=Number of mapped objects
ObjectType=0x07
DataType=0x0005
AccessType=rw
DefaultValue=0x00
PDOMapping=0
LowLimit=0x0
HighLimit=0x8
[1A01sub1]
ParameterName=Mapping Entry 1
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A01sub2]
ParameterName=Mapping Entry 2
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A01sub3]
ParameterName=Mapping Entry 3
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A01sub4]
ParameterName=Mapping Entry 4
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A01sub5]
ParameterName=Mapping Entry 5
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A01sub6]
ParameterName=Mapping Entry 6
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A01sub7]
ParameterName=Mapping Entry 7
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1A01sub8]
ParameterName=Mapping Entry 8
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=0x00000000
PDOMapping=0
[1F80]
ParameterName=NMT Startup
ObjectType=0x07
DataType=0x0007
AccessType=const
PDOMapping=0
LowLimit=0x0
HighLimit=0x3F
[2001]
SubNumber=6
ParameterName=Mounting parameters
ObjectType=0x09
[2001sub0]
ParameterName=numOfEntries
ObjectType=0x07
DataType=0x0005
AccessType=const
DefaultValue=0x5
PDOMapping=0
[2001sub1]
ParameterName=reserved1
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[2001sub2]
ParameterName=reserved2
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[2001sub3]
ParameterName=reserved3
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[2001sub4]
ParameterName=reserved4
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[2001sub5]
ParameterName=sensorFlipped
ObjectType=0x07
DataType=0x0005
AccessType=rw
DefaultValue=0x00
PDOMapping=0
LowLimit=0x0
HighLimit=0xFF
[2002]
SubNumber=4
ParameterName=Tape Parameters
ObjectType=0x09
[2002sub0]
ParameterName=Number of mapped objects
ObjectType=0x07
DataType=0x0005
AccessType=const
DefaultValue=0x3
PDOMapping=0
[2002sub1]
ParameterName=Typ. Width
ObjectType=0x07
DataType=0x0008
AccessType=rw
PDOMapping=0
[2002sub2]
ParameterName=Min. Width
ObjectType=0x07
DataType=0x0008
AccessType=rw
PDOMapping=0
[2002sub3]
ParameterName=Max. Width
ObjectType=0x07
DataType=0x0008
AccessType=rw
PDOMapping=0
[2003]
SubNumber=3
ParameterName=Advanced Settings
ObjectType=0x09
[2003sub0]
ParameterName=Number of mapped objects
ObjectType=0x07
DataType=0x0005
AccessType=const
DefaultValue=0x2
PDOMapping=0
[2003sub1]
ParameterName=Off Delay Track Detection
ObjectType=0x07
DataType=0x0006
AccessType=rw
DefaultValue=0x0064
PDOMapping=0
LowLimit=0x0
HighLimit=0xFFFF
[2003sub2]
ParameterName=Off Delay Code Detection
ObjectType=0x07
DataType=0x0006
AccessType=rw
DefaultValue=0x0064
PDOMapping=0
LowLimit=0x0
HighLimit=0xFFFF
[2018]
ParameterName=Device Status
ObjectType=0x07
DataType=0x0005
AccessType=ro
PDOMapping=0
[2019]
ParameterName=Order number
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
[2021]
SubNumber=10
ParameterName=Result data (LCPs)
ObjectType=0x09
[2021sub0]
ParameterName=Number of mapped objects
ObjectType=0x07
DataType=0x0005
AccessType=const
DefaultValue=0x9
PDOMapping=0
[2021sub1]
ParameterName=LCP1
ObjectType=0x07
DataType=0x0003
AccessType=ro
PDOMapping=1
LowLimit=0x8000
HighLimit=0x7FFF
[2021sub2]
ParameterName=LCP2
ObjectType=0x07
DataType=0x0003
AccessType=ro
PDOMapping=1
LowLimit=0x8000
HighLimit=0x7FFF
[2021sub3]
ParameterName=LCP3
ObjectType=0x07
DataType=0x0003
AccessType=ro
PDOMapping=1
LowLimit=0x8000
HighLimit=0x7FFF
[2021sub4]
ParameterName=Status
ObjectType=0x07
DataType=0x0005
AccessType=ro
PDOMapping=1
LowLimit=0x00
HighLimit=0xFF
[2021sub5]
ParameterName=Width LCP1
ObjectType=0x07
DataType=0x0003
AccessType=ro
PDOMapping=1
LowLimit=0x8000
HighLimit=0x7FFF
[2021sub6]
ParameterName=Width LCP2
ObjectType=0x07
DataType=0x0003
AccessType=ro
PDOMapping=1
LowLimit=0x8000
HighLimit=0x7FFF
[2021sub7]
ParameterName=Width LCP3
ObjectType=0x07
DataType=0x0003
AccessType=ro
PDOMapping=1
LowLimit=0x8000
HighLimit=0x7FFF
[2021sub8]
ParameterName=Code
ObjectType=0x07
DataType=0x0005
AccessType=ro
PDOMapping=1
LowLimit=0x0
HighLimit=0xFF
[2021sub9]
ParameterName=Extended Code
ObjectType=0x07
DataType=0x0007
AccessType=ro
PDOMapping=0
LowLimit=0x0
HighLimit=0xFFFFFFFF

View File

@@ -0,0 +1,13 @@
#!/bin/bash
pushd ../../../../
echo -e "\n# cleanup.bash: Stopping rosmaster and all rosnodes...\n# rosnode kill -a ; sleep 5 ; killall rosmaster ; sleep 5"
rosnode kill -a ; sleep 5 ; killall roslaunch ; sleep 5 ; killall rosmaster ; sleep 5
echo -e "\n# cleanup.bash: Deleting ros cache and logfiles and catkin folders ./build ./devel ./install"
rosclean purge -y
rm -rf ./build ./devel ./install
rm -rf ~/.ros/*
# rm -rf ~/.ros/log/*
catkin clean --yes --all-profiles --verbose
catkin_make clean
popd

View File

@@ -0,0 +1,16 @@
#!/bin/bash
# init ros environment
source /opt/ros/melodic/setup.bash
source ../../../../devel/setup.bash
# start edit resource-files
gedit ./run.bash ./runsimu.bash ../../../sick_line_guidance/launch/sick_canopen_simu.launch ../../../sick_line_guidance/launch/sick_line_guidance.launch ../../../sick_line_guidance/ols/sick_line_guidance_ols10.yaml ../../../sick_line_guidance/ols/sick_line_guidance_ols20.yaml ../../../sick_line_guidance/mls/sick_line_guidance_mls.yaml &
# start clion
# pushd ../../../sick_line_guidance
# ~/Public/clion-2018.3.3/bin/clion.sh &
pushd ../../../..
~/Public/clion-2018.3.3/bin/clion.sh ./src &
popd

View File

@@ -0,0 +1,21 @@
#!/bin/bash
source ../../../../install/setup.bash
printf "\033c"
# display PointCloud2 messages
rosrun rviz rviz &
# plot sensor positions
rqt_plot /ols/position[0] /ols/position[1] /ols/position[2] &
# rqt_plot /cloud &
# print some values from the object directory of the can device
rostopic list
rostopic echo -n 1 /node1_1001 & rostopic echo -n 1 /node1_1018sub1 & rostopic echo -n 1 /node1_1018sub4
rosservice call /driver/get_object node1 1001sub false
rosservice call /driver/get_object node1 1018sub1 false
rosservice call /driver/get_object node1 1018sub4 false
# print ros topics for ols and mls
rostopic echo /mls & rostopic echo /ols & rostopic echo /cloud & rostopic echo /diagnostics

View File

@@ -0,0 +1,30 @@
#!/bin/bash
# delete old logfiles
pushd ../../../..
rm -rf install/lib/sick_line_guidance/*
rm -rf install/share/sick_line_guidance/*
rm -f build/catkin_make_install.log
# make install
catkin_make install 2>&1 | tee -a build/catkin_make_install.log
source ./install/setup.bash
# lint, install by running
# sudo apt-get install python-catkin-lint
# catkin_lint -W1 src/sick_line_guidance
# print warnings and errors
echo -e "\nmake.bash finished.\n"
echo -e "catkin_make warnings:"
cat build/catkin_make_install.log | grep -i "warning:"
echo -e "\ncatkin_make errors:"
cat build/catkin_make_install.log | grep -i "error:"
# print sick_line_guidance install files, libraries, executables
echo -e "\ninstall/lib/sick_line_guidance:"
ls -al install/lib/sick_line_guidance/*
echo -e "\ninstall/share/sick_line_guidance:"
ls install/share/sick_line_guidance/*.*
popd

View File

@@ -0,0 +1,9 @@
#!/bin/bash
echo -e "makeall.bash: build and install ros sick_line_guidance driver"
sudo echo -e "makeall.bash started."
source /opt/ros/noetic/setup.bash
./cleanup.bash
./makepcan.bash
./make.bash
echo -e "makeall.bash finished."

View File

@@ -0,0 +1,41 @@
#!/bin/bash
# install packages required for peak can device driver
if [ -f ../../../../../peak_systems/pcanview-ncurses_0.8.7-0_amd64.deb ] ; then
pushd ../../../../../peak_systems
sudo apt-get install libncurses5
sudo dpkg --install pcanview-ncurses_0.8.7-0_amd64.deb
popd
fi
# build and install peak can device driver
if [ -d ../../../../../peak_systems/peak-linux-driver-8.17.0 ] ; then
pushd ../../../../../peak_systems/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
popd
fi

View File

@@ -0,0 +1,69 @@
#!/bin/bash
# set environment, clear screen and logfiles
if [ ! -d ~/.ros/log ] ; then mkdir -p ~/.ros/log ; fi
printf "\033c"
source ../../../../install/setup.bash
echo -e "\n# run.bash: Stopping rosmaster and all rosnodes...\n# rosnode kill -a ; sleep 5 ; killall rosmaster ; sleep 5"
rosnode kill -a ; sleep 5 ; killall rosmaster ; sleep 5
rm -rf ~/.ros/log/*
# initialize can net device, can0 by peak can adapter
# sudo ip link set can0 up type can bitrate 125000
NUM_BITRATE_125000=$(ip -details link show can0 | grep "bitrate 125000" | wc -l)
if [ "$NUM_BITRATE_125000" = "0" ] ; then
echo -e "# run sick_line_guidance:\n# sudo ip link set can0 up type can bitrate 125000"
sudo ip link set can0 up type can bitrate 125000
fi
echo -e "# run sick_line_guidance:\n# ip -details link show can0"
ip -details link show can0
# check can net device by sending 000#0x820A (can command reset communication to device 0x0A), should be answered by 70A#00 (boot message from device 0x0A)
# for ((n=0;n<=2;n++)) ; do
# candump -ta -n 2 can0 &
# cansend can0 000#820A
# sleep 1
# done
# Start OLS20 simulation
# ./runsimu.bash
# start can logging
# printf "\033c" ; candump -ta can0 2>&1 | tee ~/.ros/log/candump.log
candump -ta can0 2>&1 | tee ~/.ros/log/candump.log &
# get/set values from object directory with canopen_chain_node service, f.e. Object 2001sub5 (sensorFlipped, UINT8, defaultvalue: 0x01)
# rosservice call /driver/get_object "{node: 'node1', object: '2001sub5', cached: false}"
# rosservice call /driver/set_object "{node: 'node1', object: '2001sub5', value: '0x01', cached: false}"
# Start ros driver canopen_chain_node, sick_line_guidance_node and sick_line_guidance_cloud_publisher
# echo -e "\n# run sick_line_guidance:\n# roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_ols10.yaml\n"
# roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_ols10.yaml 2>&1 | tee ~/.ros/log/sick_line_guidance_ols10.log # start OLS10 driver
echo -e "\n# run sick_line_guidance:\n# roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_ols20.yaml\n"
roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_ols20.yaml 2>&1 | tee ~/.ros/log/sick_line_guidance_ols20.log # start OLS20 driver
# echo -e "\n# run sick_line_guidance:\n# roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_mls.yaml\n"
# roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=sick_line_guidance_mls.yaml 2>&1 | tee ~/.ros/log/sick_line_guidance_mls.log # start MLS driver
# read some object indices (f.e. 1001=ErrorRegister, 1018sub1=VendorID, 1018sub4=SerialNumber)
# rostopic echo -n 1 /node1_1001 & rostopic echo -n 1 /node1_1018sub1 & rostopic echo -n 1 /node1_1018sub4
# rosservice call /driver/get_object node1 1001sub false
# rosservice call /driver/get_object node1 1018sub1 false
# rosservice call /driver/get_object node1 1018sub4 false
# Check errors and warnings in ros logfiles
killall candump
grep "\[ WARN\]" ~/.ros/log/*.log ~/.ros/log/*/ros*.log ~/.ros/log/*/sick*.log >> ~/.ros/log/ros_log_warnings.txt
grep "\[ERROR\]" ~/.ros/log/*.log ~/.ros/log/*/ros*.log ~/.ros/log/*/sick*.log >> ~/.ros/log/ros_log_errors.txt
cat ~/.ros/log/ros_log_warnings.txt
cat ~/.ros/log/ros_log_errors.txt
# Zip all logfiles
mkdir ./tmp
cp -rf ~/.ros/log ./tmp
now=$(date +"%Y%m%d_%H%M%S")
tar -cvzf ./$now-ros-logfiles.tgz ./tmp/log
rm -rf ./tmp

View File

@@ -0,0 +1,112 @@
#!/bin/bash
# set environment, clear screen and logfiles
if [ ! -d ~/.ros/log ] ; then mkdir -p ~/.ros/log ; fi
printf "\033c"
source ../../../../install/setup.bash
echo -e "\n# runsimu.bash: Stopping rosmaster and all rosnodes...\n# rosnode kill -a ; sleep 5 ; killall rosmaster ; sleep 5"
rosnode kill -a ; sleep 5 ; killall roslaunch ; sleep 5 ; killall rosmaster ; sleep 5
rm -rf ~/.ros/log/*
# Initialize can net device, can0 by peak can adapter
# sudo ip link set can0 type can loopback on # loopback not supported
# sudo ip link set can0 up type can bitrate 125000 # set default bitrate 125000 bit/s
# Reset can0 net device
# sudo ip link set can0 down
# sleep 1
# sudo ip link set can0 up type can bitrate 125000
# sleep 1
# Set default bitrate 125000 bit/s
NUM_BITRATE_125000=$(ip -details link show can0 | grep "bitrate 125000" | wc -l)
if [ "$NUM_BITRATE_125000" = "0" ] ; then
echo -e "# run ols/mls simulation:\n# sudo ip link set can0 up type can bitrate 125000"
sudo ip link set can0 up type can bitrate 125000
fi
echo -e "# run ols/mls simulation:\n# ip -details link show can0"
ip -details link show can0
sleep 1
# Start can logging
# candump -ta can0 &
# candump -ta can0 2>&1 | tee ~/.ros/log/candump.log &
# Simulation with cangineberry: Upload firmware (BEDS slave) and beds-file CiA401_IO_Node3
# ./coiaupdater -p /dev/ttyS0 -f ../APPS/CANopenIA-BEDS/CgB_COIA_BEDS1.3_sec.bin # install firmware CANopen IA BEDS slave
# ./coiaupdater -p /dev/ttyS0 -d ../APPS/CANopenIA-BEDS/EDS/CiA401_IO_Node3.bin
# Simulation with cangineberry: Read/write objects 6401sub1 (LCP1), 6401sub2 (LCP2), 6401sub3 (LCP3), 6401sub4 (WidthLCP1), 6401sub5 (WidthLCP2), 6401sub6 (WidthLCP3)
# ./coia -p /dev/ttyS0 --read=0x6401,0x01
# ./coia -p /dev/ttyS0 --write=0x6401,0x01,2,0x1234
# ./coia -p /dev/ttyS0 --write=0x6401,0x01,2,0xABCD
# get/set values from object directory with canopen_chain_node service, f.e. Object 2001sub5 (sensorFlipped, UINT8, defaultvalue: 0x01)
# rosservice call /driver/get_object "{node: 'node1', object: '2001sub5', cached: false}"
# rosservice call /driver/set_object "{node: 'node1', object: '2001sub5', value: '0x01', cached: false}"
# Run simulation for OLS and MLS by yaml-file configuration
device_settings_map=( "OLS20:sick_line_guidance_ols20.yaml;120" "OLS10:sick_line_guidance_ols10.yaml;30" "MLS:sick_line_guidance_mls.yaml;30" )
for((device_cnt=0;device_cnt<=2;device_cnt++)) ; do
device=${device_settings_map[$device_cnt]%%:*}
settings_str=${device_settings_map[$device_cnt]##*:}
IFS=';' settings_list=($settings_str)
yaml_file=${settings_list[0]}
run_seconds=${settings_list[1]}
echo -e "runsimu.bash: settings for $device device: yaml_file $yaml_file, run for $run_seconds seconds."
# Start can2ros converter
# echo -e "\n# run ols/mls simulation:\n# roslaunch -v --screen sick_line_guidance sick_line_guidance_can2ros_node.launch\n"
# roslaunch -v --screen sick_line_guidance sick_line_guidance_can2ros_node.launch &
echo -e "\n# run ols/mls simulation:\n# roslaunch -v sick_line_guidance sick_line_guidance_can2ros_node.launch\n"
roslaunch -v sick_line_guidance sick_line_guidance_can2ros_node.launch &
sleep 5
# Start ros2can converter
# echo -e "\n# run ols/mls simulation:\n# roslaunch -v --screen sick_line_guidance sick_line_guidance_ros2can_node.launch\n"
# roslaunch -v --screen sick_line_guidance sick_line_guidance_ros2can_node.launch &
echo -e "\n# run ols/mls simulation:\n# roslaunch -v sick_line_guidance sick_line_guidance_ros2can_node.launch\n"
roslaunch -v sick_line_guidance sick_line_guidance_ros2can_node.launch &
sleep 5
# Start OLS20 simulation
echo -e "\n# run ols/mls simulation:\n# roslaunch -v sick_line_guidance sick_canopen_simu.launch device:=$device\n"
roslaunch -v --screen sick_line_guidance sick_canopen_simu.launch device:=$device 2>&1 | tee ~/.ros/log/sick_canopen_simu_$device.log &
# echo -e "\n# run ols/mls simulation:\n# roslaunch -v sick_line_guidance sick_canopen_simu.launch device:=$device\n"
# roslaunch -v sick_line_guidance sick_canopen_simu.launch device:=$device &
sleep 5
# check can net device by sending 000#0x820A (can command reset communication to device 0x0A), should be answered by 70A#00 (boot message from device 0x0A)
for ((n=0;n<1;n++)) ; do
candump -ta -n 2 can0 &
cansend can0 000#820A
sleep 2
done
# Start ros driver for MLS or OLS, incl. canopen_chain_node, sick_line_guidance_node and sick_line_guidance_cloud_publisher
echo -e "\n# run sick_line_guidance:\n# roslaunch -v sick_line_guidance sick_line_guidance.launch yaml:=$yaml_file\n"
roslaunch -v --screen sick_line_guidance sick_line_guidance.launch yaml:=$yaml_file 2>&1 | tee ~/.ros/log/$yaml_file.log &
# echo -e "\n# run sick_line_guidance:\n# roslaunch -v sick_line_guidance sick_line_guidance.launch yaml:=$yaml_file\n"
# roslaunch -v sick_line_guidance sick_line_guidance.launch yaml:=$yaml_file &
# Run simulation for a while
sleep $run_seconds
# Exit simulation, shutdown all ros nodes
echo -e "\n# runsimu.bash: Stopping rosmaster and all rosnodes...\n# rosnode kill -a ; sleep 5 ; killall rosmaster ; sleep 5"
rosnode kill -a ; sleep 5 ; killall rosmaster ; sleep 5
done
# Check errors and warnings in ros logfiles
killall candump
echo -e "\n#\n# OLS/MLS simulation finished.\n#\n"
grep "\[ WARN\]" ~/.ros/log/*.log ~/.ros/log/*/ros*.log ~/.ros/log/*/sick*.log >> ~/.ros/log/ros_log_warnings.txt
grep "\[ERROR\]" ~/.ros/log/*.log ~/.ros/log/*/ros*.log ~/.ros/log/*/sick*.log >> ~/.ros/log/ros_log_errors.txt
grep "MeasurementVerificationStatistic" ~/.ros/log/*.log ~/.ros/log/*/ros*.log ~/.ros/log/*/sick*.log >> ~/.ros/log/simulation_statistic.txt
echo -e "\nSimulation warnings and errors:\n"
cat ~/.ros/log/ros_log_warnings.txt
cat ~/.ros/log/ros_log_errors.txt
echo -e "\nSimulation statistic:\n"
cat ~/.ros/log/simulation_statistic.txt

View File

@@ -0,0 +1,15 @@
#!/bin/bash
if [ -f /opt/ros/noetic/setup.bash ] ; then
source /opt/ros/noetic/setup.bash
elif [ -f /opt/ros/foxy/setup.bash ] ; then
source /opt/ros/foxy/setup.bash
fi
pushd ../../../..
if [ -f ./install/setup.bash ] ; then
source ./install/setup.bash
fi
code ./sick_line_guidance_vscode.code-workspace
popd

View File

@@ -0,0 +1,30 @@
bus:
device: can0
driver_plugin: can::SocketCANInterface
master_allocator: canopen::SimpleMaster::Allocator
sync:
interval_ms: 10
overflow: 0
# heartbeat: # simple heartbeat producer (optional, not supported by OLS or MLS, do not enable heartbeats, do not configure heartbeat rate or message)
# rate: 100 # heartbeat rate (milliseconds)
# msg: "77f#05" # message to send, cansend format: heartbeat of node 127 with status 5=Started
nodes:
node1:
id: 0x03 # CAN-Node-ID of can device, default: Node-ID 10=0x0A for OLS10 and MLS (CiA401_IO_Node3: 0x03, CiA402_Stepper_Node8: 0x08)
eds_pkg: sick_line_guidance # package name for relative path
eds_file: CiA401_IO_Node3.eds # path to EDS/DCF file
publish: ["1001","1018sub1","1018sub4","6000sub1!","6000sub2!","6000sub3!","6000sub4!","6401sub1!","6401sub2!","6401sub3!","6401sub4!","6401sub5!","6401sub6!"]
# Common objects (CiA401_IO_Node3.eds, CiA402_Stepper_node8.eds, SICK_OLS20.eds, SICK-MLS-MLS.eds): 1001 = ErrorRegister, 1018sub1 = VendorID, 1018sub4 = SerialNumber
# objects SICK_OLS20.eds: 1001 = ErrorRegister, 1018sub1 = VendorID, 1018sub4 = SerialNumber, 0x2018 = DeviceStatus(0=OK), 0x2021sub1 bis 0x2021sub9 = measurementdata
# TPDOs SICK_OLS20.eds: 0x2021sub1 bis 0x2021sub8
# SICK-MLS.eds: 0x2021sub1 bis 0x2021sub4 und 0x2022 = measurementdata
# CiA401_IO_Node3.eds: TPDO mapped: 6000sub1 bis 6000sub8 (jeweils 1 byte), 6401sub1 bis 6401subC (jeweils 2 byte)
# Note: publish with "!" (f.e. publish: ["1001!"]) means reread from object directory
# (not cached, i.e. query by SDO, if no actual PDO is transmitted),
# otherwise cached (use last received SDO or PDO).
# sick_line_guidance configuration of this node:
sick_device_family: "CIA401" # can devices of OLS or MLS family currently supported (or CIA401 for testing)
sick_topic: "ols" # OLS_Measurement messages are published in topic "/ols"
sick_frame_id: "ols_measurement_frame" # OLS_Measurement messages are published frame_id "ols_measurement_frame"