Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

adding compatibility to RSI 4.x by providing a seperate ros_rsi.rsix #155

Open
wants to merge 2 commits into
base: melodic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion kuka_rsi_hw_interface/krl/KR_C4/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ The files included in this folder specifies the data transferred via RSI. Some o

Note that the `rsi/listen_address` and `rsi/listen_port` parameters of the `kuka_rsi_hw_interface` must correspond to the `IP_NUMBER`and `PORT` set in these KRL files.

##### ros_rsi.rsi.xml
##### ros_rsi.rsi.xml for RSI 3.x OR ros_rsi.rsix for RSI 4.x
Note: from KSS 8.5 the version of RSI is changed to 4.x and the format of the file is a little changed. The new file extension on RSI 4.x is .rsix. So to use this driver on KSS 8.5 and above use ros_rsi.rsix instead of ros_rsi.rsi.xml
This file may be edited with application specific joint limits in degrees.
* Edit the parameters within the RSIObject `AXISCORR` to specify joint limits such as **LowerLimA1**, **UpperLimA1** etc. Note that these limits are in reference to the start position of the robot.
* Edit the parameters within `AXISCORRMON` to specify the overall correction limitation. If this limit is exceeded in either of the joint directions, RSI is stopped. The values of **MaxA1**, **MaxA2** etc. may be large to allow free movement within the specified joint limits in `AXISCORR`.
Expand All @@ -58,6 +59,8 @@ The files **ros_rsi.rsi** and **ros_rsi.rsi.diagram** should not be edited. All
3. Log in as **Expert** or **Administrator**.
4. Copy the `ros_rsi.src` file to `KRC:\R1\Program`.
5. Copy the rest of the files to `C:\KRC\ROBOTER\Config\User\Common\SensorInterface`.
- for RSI 3.x : Copy ros_rsi.rsi.xml to the above folder
- for RSI 4.x : Copy ros_rsi.rsix to the above folder

## 3. Configure the kuka_rsi_hw_interface
The **kuka_rsi_hardware_interface** needs to be configured in order to successfully communicate with RSI. Inside `/kuka_rsi_hw_interface/test` and `/kuka_rsi_hw_interface/config` in this repository is a set of `*.yaml` files. These configuration files may be loaded into a launch-file used to start the **kuka_rsi_hardware_interface** with correct parameters, such as:
Expand Down
81 changes: 81 additions & 0 deletions kuka_rsi_hw_interface/krl/KR_C4/ros_rsi.rsix
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- Do not change! The content of this file is generated. -->
<!-- Generated with RSIVisual WorkVisual plugin. -->
<!-- RobotSensorInterface 4.0 B3083 -->
<RsiContext xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xmlns:xsd="http://www.w3.org/2001/XMLSchema" Version="0.1.0">
<RsiObjects>
<RsiObject ObjTypeId="33" ObjType="AxisCorr" ObjId="AxisCorr_1">
<Inputs>
<Input InIdx="0" OutObjId="Ethernet_1" OutIdx="0" />
<Input InIdx="1" OutObjId="Ethernet_1" OutIdx="1" />
<Input InIdx="2" OutObjId="Ethernet_1" OutIdx="2" />
<Input InIdx="3" OutObjId="Ethernet_1" OutIdx="3" />
<Input InIdx="4" OutObjId="Ethernet_1" OutIdx="4" />
<Input InIdx="5" OutObjId="Ethernet_1" OutIdx="5" />
</Inputs>
<Parameters>
<Parameter Name="LowerLimA1" ParamId="0" ParamValue="-90.0" />
<Parameter Name="LowerLimA2" ParamId="1" ParamValue="-90.0" />
<Parameter Name="LowerLimA3" ParamId="2" ParamValue="-90.0" />
<Parameter Name="LowerLimA4" ParamId="3" ParamValue="-90.0" />
<Parameter Name="LowerLimA5" ParamId="4" ParamValue="-90.0" />
<Parameter Name="LowerLimA6" ParamId="5" ParamValue="-90.0" />
<Parameter Name="UpperLimA1" ParamId="6" ParamValue="90.0" />
<Parameter Name="UpperLimA2" ParamId="7" ParamValue="90.0" />
<Parameter Name="UpperLimA3" ParamId="8" ParamValue="90.0" />
<Parameter Name="UpperLimA4" ParamId="9" ParamValue="90.0" />
<Parameter Name="UpperLimA5" ParamId="10" ParamValue="90.0" />
<Parameter Name="UpperLimA6" ParamId="11" ParamValue="90.0" />
</Parameters>
</RsiObject>
<RsiObject ObjTypeId="64" ObjType="Ethernet" ObjId="Ethernet_1">
<Parameters>
<Parameter IsRuntime="false" Name="ConfigFile" ParamId="0" ParamValue="ros_rsi_ethernet.xml" />
<Parameter Name="Timeout" ParamId="0" ParamValue="100" />
<Parameter Name="Flag" ParamId="3" ParamValue="1" />
<Parameter Name="Precision" ParamId="7" ParamValue="4" />
</Parameters>
</RsiObject>
<RsiObject ObjTypeId="82" ObjType="AxisCorrMon" ObjId="AxisCorrMon_1">
<Parameters>
<Parameter Name="MaxA1" ParamId="0" ParamValue="90.0" />
<Parameter Name="MaxA2" ParamId="1" ParamValue="90.0" />
<Parameter Name="MaxA3" ParamId="2" ParamValue="90.0" />
<Parameter Name="MaxA4" ParamId="3" ParamValue="90.0" />
<Parameter Name="MaxA5" ParamId="4" ParamValue="90.0" />
<Parameter Name="MaxA6" ParamId="5" ParamValue="90.0" />
<Parameter Name="MaxE1" ParamId="6" ParamValue="6.0" />
<Parameter Name="MaxE2" ParamId="7" ParamValue="6.0" />
<Parameter Name="MaxE3" ParamId="8" ParamValue="6.0" />
<Parameter Name="MaxE4" ParamId="9" ParamValue="6.0" />
<Parameter Name="MaxE5" ParamId="10" ParamValue="6.0" />
<Parameter Name="MaxE6" ParamId="11" ParamValue="6.0" />
</Parameters>
</RsiObject>

</RsiObjects>
<Editor>
<Comments />
<Connectors />
<FunctionBlocks />
<Groups />
<Links>
<Link From="Ethernet_1" FromPort="Out1" Points="-337.48,-160.5;-209.48,-160.5;-81.48,-160.5;-81.48,-160.5;356,-160.5;372,-160.5" To="AxisCorr_1" ToPort="CorrA1" />
<Link From="Ethernet_1" FromPort="Out2" Points="-337.48,-130.5;-217.48,-130.5;-97.48,-130.5;-97.48,-130.5;356,-130.5;372,-130.5" To="AxisCorr_1" ToPort="CorrA2" />
<Link From="Ethernet_1" FromPort="Out3" Points="-337.48,-100.5;-225.48,-100.5;-113.48,-100.5;-113.48,-100.5;356,-100.5;372,-100.5" To="AxisCorr_1" ToPort="CorrA3" />
<Link From="Ethernet_1" FromPort="Out4" Points="-337.48,-70.5;-233.48,-70.5;-129.48,-70.5;-129.48,-70.5;356,-70.5;372,-70.5" To="AxisCorr_1" ToPort="CorrA4" />
<Link From="Ethernet_1" FromPort="Out5" Points="-337.48,-40.5;-241.48,-40.5;-145.48,-40.5;-145.48,-40.5;356,-40.5;372,-40.5" To="AxisCorr_1" ToPort="CorrA5" />
<Link From="Ethernet_1" FromPort="Out6" Points="-337.48,-10.5;-249.48,-10.5;-161.48,-10.5;-161.48,-10.5;356,-10.5;372,-10.5" To="AxisCorr_1" ToPort="CorrA6" />

</Links>
<Nodes>
<Node Location="390,-180" Name="AxisCorr_1" Type="AxisCorr" />
<Node Location="-516,-180" Name="Ethernet_1" NumberOfInputs="1" NumberOfOutputs="17" Type="Ethernet" />
<Node Location="636,-174" Name="AxisCorrMon_1" Type="AxisCorrMon" />

</Nodes>
<Toolboxes>
<Toolbox Name="RSI" Version="1.4.0" />
</Toolboxes>
</Editor>
</RsiContext>
14 changes: 7 additions & 7 deletions kuka_rsi_hw_interface/krl/KR_C4/ros_rsi.src
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ DEF RSI_AxisCorr( )
; Technology, 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
Expand All @@ -42,9 +42,9 @@ DEF RSI_AxisCorr( )
; =============================================

; =============================================
;
;
; ROS INDUSTRIAL: KUKA RSI HW INTERFACE
; Realtime UDP data exchange with
; Realtime UDP data exchange with
; kuka_rsi_hw_interface
;
; =============================================
Expand All @@ -56,7 +56,7 @@ DECL INT CONTID ; ContainerID
;FOLD INI
;FOLD BASISTECH INI
GLOBAL INTERRUPT DECL 3 WHEN $STOPMESS==TRUE DO IR_STOPM ( )
INTERRUPT ON 3
INTERRUPT ON 3
BAS (#INITMOV,0 )
;ENDFOLD (BASISTECH INI)
;FOLD USER INI
Expand All @@ -68,8 +68,8 @@ DECL INT CONTID ; ContainerID
; Move to start position
PTP {A1 0, A2 -90, A3 90, A4 0, A5 90, A6 0}

; Create RSI Context
ret = RSI_CREATE("ros_rsi.rsi",CONTID,TRUE)
; Create RSI Context
ret = RSI_CREATE("ros_rsi",CONTID,TRUE)
IF (ret <> RSIOK) THEN
HALT
ENDIF
Expand All @@ -83,7 +83,7 @@ ENDIF
; Sensor guided movement
RSI_MOVECORR()

; Turn off RSI
; Turn off RSI
ret = RSI_OFF()
IF (ret <> RSIOK) THEN
HALT
Expand Down