The library has been developed to provide functions compatible with the Matlab environment.

The use of this library is based on the interoperability between Matlab and .NET

For more information, please refer to the official Matlab documentation: https://mathworks.com/help/matlab/using-net-libraries-in-matlab.html

## Load Library

Please download the library from the download page and put the .NET 3.5 DLL in your Matlab project folder. Make sure the DLL file is not locked (see its properties in Windows).

To ensure that your installation is ready to use the library, please ensure that `NET.isNETSupported` is true.

```matlab
if ~NET.isNETSupported
    disp('The Matlab .NET environment is not fully configured')
end
```

To load the library, please specify its path as an argument to the function `NET.addAssembly`.

Its path must be absolute, but you can also calculate it by concatenating the path of the current `pwd` folder.

Finally, it is necessary to import the namespaces of the library with `import UnderAutomation.UniversalRobots.*`

```matlab
% Load library
NET.addAssembly('C:\path\to\my\workspace\UnderAutomation.UniversalRobots.dll');

% You can also use relative path
% NET.addAssembly(fullfile(pwd, '.\UnderAutomation.UniversalRobots.dll'));

% Import library features in Matlab
import UnderAutomation.UniversalRobots.*
```

## Connect and interact with your robot

Once the library is loaded correctly, you can create instances of the objects implemented by this library, please refer to the rest of the documentation which describes them.

To react to events, you must use `addlistener()` which executes a function passed as a parameter when the event is raised.

```matlab
NET.addAssembly('C:\path\to\my\workspace\UnderAutomation.UniversalRobots.dll');
import UnderAutomation.UniversalRobots.*

% Setup your connection
param = ConnectParameters('192.168.0.1')
param.Rtde.Enable = true

% Instanciate robot
robot = UR()

% Connect to robot
robot.Connect(param)

% ...
```

## Limitations

Not all the features of .NET are available in Matlab, but this library has been developed to work around these limitations and allow you to make full use of it.

However, please ensure that the Framework 3.5 is enabled in the optional Windows features.

For more information on the limitations of Matlab :

- [System Requirements for Using MATLAB Interface to .NET](https://fr.mathworks.com/help/matlab/matlab_external/system-requirements-for-using-matlab-interface-to-net.html)
- [Limitations to Support of .NET Arrays](https://fr.mathworks.com/help/matlab/matlab_external/limitations-to-support-of-net-arrays.html)
- [Limitations to Support of .NET Methods](https://fr.mathworks.com/help/matlab/matlab_external/limitations-to-support-of-net-methods.html)
- [Limitations to Support of .NET Events](https://fr.mathworks.com/help/matlab/matlab_external/limitations-to-support-of-net-events.html)
- [Limitations to Support of .NET Delegates](https://fr.mathworks.com/help/matlab/matlab_external/limitations-to-support-of-net-delegates.html)
- [Limitations to Support of .NET Enumerations](https://fr.mathworks.com/help/matlab/matlab_external/limitations-to-net-enumerations.html)

## Examples

### Data exchange

**C# : DataExchange**
```csharp
﻿using UnderAutomation.UniversalRobots;
using UnderAutomation.UniversalRobots.Common;
using UnderAutomation.UniversalRobots.Rtde;

class DataExchange
{
  static void Main(string[] args)
  {
    // Create a new robot instance
    var robot = new UR();

    // Setup connection to th robot
    var param = new ConnectParameters();
    param.IP = "192.168.0.1";

    // Enable primary interface to get variable values
    param.PrimaryInterface.Enable = true;

    // Enable RTDE at 5Hz (500Hz possible)
    param.Rtde.Enable = true;
    param.Rtde.Frequency = 5;

    // Ask the robot for permission to write these registers
    param.Rtde.InputSetup.Add(RtdeInputData.StandardAnalogOutput0);
    param.Rtde.InputSetup.Add(RtdeInputData.InputBitRegisters, 64);

    // Ask the robot to send me this data
    param.Rtde.OutputSetup.Add(RtdeOutputData.ActualTcpPose);
    param.Rtde.OutputSetup.Add(RtdeOutputData.ActualTcpForce);

    // Connect to the robot
    robot.Connect(param);

    // Event raised when data is received
    robot.Rtde.OutputDataReceived += (o, e) =>
    {
      /**/
      // Display robot TCP pose
      var pose = robot.Rtde.OutputDataValues.ActualTcpPose;
      // pose.X, pose.Y, pose.Z, pose.Rx, ...

      // Display robot TCP force
      var force = robot.Rtde.OutputDataValues.ActualTcpForce;

      // Write data in robot controler
      var inputs = new RtdeInputValues();
      inputs.StandardAnalogOutput0 = 0.2;
      inputs.InputBitRegisters.X64 = true;
      robot.Rtde.WriteInputs(inputs);
      /**/
    };

    // Event raised when a program or installation variable change
    robot.PrimaryInterface.GlobalVariables.ValuesUpdated += (o, e) =>
    {
      /**/
      // Display all program and installation variables
      var variables = robot.PrimaryInterface.GlobalVariables.GetAll();
      string name = variables[0].Name;
      Pose value = variables[0].ToPose();
      GlobalVariableTypes type = variables[0].Type;
      /**/
    };

    // Several other events are raised by primary interface
    robot.PrimaryInterface.MasterboardDataReceived += (o, e) =>
    {
      double ai0 = e.AnalogInput0;
      bool di2 = e.DigitalInputs.Digital2;
      // ...
    };

    robot.PrimaryInterface.CartesianInfoReceived += (o, e) =>
    {
      double x = e.X;
      double tcpOffsetX = e.TCPOffsetX;
      // ...
    };

    robot.PrimaryInterface.JointDataReceived += (o, e) =>
    {
      double shoulderAngle = e.Shoulder.Position;
      JointModes elbowMode = e.Elbow.JointMode;
      double wrist3Speed = e.Wrist3.ActualSpeed;
    };
  }
}
```

**Python : DataExchange**
```python
﻿from underautomation.universal_robots.connect_parameters import ConnectParameters
from underautomation.universal_robots.rtde.rtde_input_data import RtdeInputData
from underautomation.universal_robots.rtde.rtde_input_values import RtdeInputValues
from underautomation.universal_robots.rtde.rtde_output_data import RtdeOutputData
from underautomation.universal_robots.ur import UR

# Create a robot instance
robot = UR()

# Setup connection to th robot
param = ConnectParameters("192.168.0.1")

# Enable primary interface to get variable values
param.primary_interface.enable = True

# Enable rtde at 5Hz (500Hz possible)
param.rtde.enable = True
param.rtde.frequency = 5

# Ask the robot for permission to write these registers
param.rtde.input_setup.add(RtdeInputData.StandardAnalogOutput0)
param.rtde.input_setup.add(RtdeInputData.InputBitRegisters, 64)

# Ask the robot to send me this data
param.rtde.output_setup.add(RtdeOutputData.ActualTcpPose)
param.rtde.output_setup.add(RtdeOutputData.ActualTcpForce)

# Connect to the robot
robot.connect(param)

# Function called when new RTDE data is received
def on_output_data_received(o, e):
    ##
    # Display robot TCP pose
    pose = robot.rtde.output_data_values.actual_tcp_pose
    # pose.X, pose.Y, pose.Z, pose.Rx, ...

    # Display robot TCP force
    force = robot.rtde.output_data_values.actual_tcp_force

    # Write data in robot controler
    inputs = RtdeInputValues()
    inputs.standard_analog_output0 = 0.2
    inputs.input_bit_registers.x64 = True
    robot.rtde.write_inputs(inputs)
    ##

# Event raised when data is received
robot.rtde.output_data_received(on_output_data_received)

# Function called when any program or installation variable changes in the robot
def on_value_updated(p, e):
    ##
    # Display all program and installation variables
    variables = robot.primary_interface.global_variables.get_all()
    name = variables[0].name
    value = variables[0].to_pose()
    type = variables[0].type
    ##    

# Event raised when a program or installation variable change
robot.primary_interface.global_variables.values_updated(on_value_updated)


# Function called when masterboard data is received
def on_masterboard_data_received(p, e):
    ai0 = robot.primary_interface.masterboard_data.analog_input0
    di2 = robot.primary_interface.masterboard_data.digital_inputs.digital2

# Several other events are raised by primary interface
robot.primary_interface.masterboard_data_received(on_masterboard_data_received)

# Function called when cartesian data is received
def on_cartesian_info_received(p, e):
    x = e.X
    tcpOffsetX = e.TCPOffsetX

robot.primary_interface.cartesian_info_received(on_cartesian_info_received)

# Function called when joint data is received
def on_joint_data_received(o,e):
    shoulderAngle = e.Shoulder.Position
    elbowMode = e.Elbow.JointMode
    wrist3Speed = e.Wrist3.ActualSpeed

robot.primary_interface.joint_data_received(on_joint_data_received)
```

**Matlab : DataExchange**
```matlab
if ~NET.isNETSupported
    disp('The Matlab .NET environment is not fully configured')
end

% Load library
NET.addAssembly(fullfile(pwd, '.\UnderAutomation.UniversalRobots.dll'));

% Import library features in Matlab
import UnderAutomation.UniversalRobots.*

% Create a robot instance
robot = UR();

% Setup connection to th robot
param = ConnectParameters();
param.IP = '192.168.0.56';

% Enable primary interface to get variable values
param.PrimaryInterface.Enable = true;

% Enable RTDE at 5Hz (500Hz possible)
param.Rtde.Enable = true;
param.Rtde.Frequency = 5;

% Ask the robot for permission to write these registers
param.Rtde.InputSetup.Add(Rtde.RtdeInputData.StandardAnalogOutput0);
param.Rtde.InputSetup.Add(Rtde.RtdeInputData.InputBitRegisters, 64);

% Ask the robot to send me this data
param.Rtde.OutputSetup.Add(Rtde.RtdeOutputData.ActualTcpPose)
param.Rtde.OutputSetup.Add(Rtde.RtdeOutputData.ActualTcpForce);

% Connect to the robot
robot.Connect(param);
addlistener(robot.Rtde, 'OutputDataReceived', @OnOutputDataReceived);

% Several other events are raised by primary interface
addlistener(robot.PrimaryInterface.GlobalVariables, 'ValuesUpdated', @OnValuesUpdated);
addlistener(robot.PrimaryInterface, 'JointDataReceived', @OnJointDataReceived);
addlistener(robot.PrimaryInterface, 'MasterboardDataReceived', @OnMasterboardDataReceived);
addlistener(robot.PrimaryInterface, 'CartesianInfoReceived', @OnCartesianInfoReceived);

input("Press enter to stop")
robot.Disconnect();

function OnOutputDataReceived(o, e)
    %%
    % Display robot TCP pose
    pose = robot.Rtde.OutputDataValues.ActualTcpPose;
    % pose.X, pose.Y, pose.Z, pose.Rx, ...

    % Display robot TCP force
    force = robot.Rtde.OutputDataValues.ActualTcpForce;

    % Write data in robot controler
    inputs = RtdeInputValues();
    inputs.StandardAnalogOutput0 = 0.2;
    inputs.InputBitRegisters.X64 = true;
    robot.Rtde.WriteInputs(inputs);
    %%
end

% Event raised when a program or installation variable change
function OnMasterboardDataReceived(o, e)
    ai0 = e.AnalogInput0;
    di2 = e.DigitalInputs.Digital2;
end

function OnCartesianInfoReceived(o, e)
    x = e.X;
    tcpOffsetX = e.TCPOffsetX;
end

function OnJointDataReceived(o, e)
    shoulderAngle = e.Shoulder.Position;
    elbowMode = e.Elbow.JointMode;
    wrist3Speed = e.Wrist3.ActualSpeed;
end

function OnValuesUpdated(o, e)
    %%
    % Display all program and installation variables
    variables = robot.PrimaryInterface.GlobalVariables.GetAll();
    name = variables(0).Name;
    value = variables(0).ToPose();
    type = variables(0).Type;
    %%
end
```

### Remote control

**C# : RemoteControl**
```csharp
﻿using UnderAutomation.UniversalRobots;

class RemoteControl
{
  static void Main(string[] args)
  {
    /**/
    // Create a new robot instance
    var robot = new UR();

    // Connect to the robot
    robot.Connect("192.168.0.1");

    // Power on the robot arm and release brakes
    robot.Dashboard.PowerOn(); // or robot.Rest.PowerOn(); for PolyscopeX
    robot.Dashboard.ReleaseBrake(); // or robot.Rest.ReleaseBrake(); for PolyscopeX

    // Load program file to polyscope
    robot.Dashboard.LoadProgram(
      "fast_bin_picking.urp"); // or robot.Rest.LoadProgram("fast_bin_picking.urp"); for PolyscopeX

    // Start the program
    robot.Dashboard.Play(); // or robot.Rest.Play(); for PolyscopeX

    // Get program name and state
    var state = robot.Dashboard.GetProgramState();
    Console.WriteLine($"Program name : {state.Value.Name}");
    Console.WriteLine($"Stopped, Playing or Paused ? : {state.Value.State}");

    // Display a popup on the pendant
    robot.Dashboard.ShowPopup("I just remote-controlled my robot!");
    /**/
  }
}
```

**Python : RemoteControl**
```python
﻿from underautomation.universal_robots.ur import UR

##
# Create a new robot instance
robot = UR()

# Connect to the robot
robot.connect("192.168.0.1")

# Power on the robot arm and release brakes
robot.dashboard.power_on()
robot.dashboard.release_brake()

# Load program file to polyscope
robot.dashboard.load_program("fast_bin_picking.urp")

# Start the program
robot.dashboard.play()

# Get program name and state
state = robot.dashboard.get_program_state()
program_name = state.value.name
program_state = state.value.state
 
# Display a popup on the pendant
robot.dashboard.show_popup("I just remote-controlled my robot!")
##
```

**Matlab : RemoteControl**
```matlab
% Load library
NET.addAssembly(fullfile(pwd, '.\UnderAutomation.UniversalRobots.dll'));

% Import library features in Matlab
import UnderAutomation.UniversalRobots.*

%%
% Create a robot instance
robot = UR();

% Connect to the robot
robot.Connect('192.168.0.56');

% Power on the robot arm and release brakes
robot.Dashboard.PowerOn();
robot.Dashboard.ReleaseBrake();

% Load program file to polyscope
robot.Dashboard.LoadProgram('fast_bin_picking.urp');

% Start the program
robot.Dashboard.Play();

% Get program name and state
state = robot.Dashboard.GetProgramState();
name = state.Value.Name
state = state.Value.State

% Display a popup on the pendant
robot.Dashboard.ShowPopup('I just remote-controlled my robot!');
%%
```

### Scripts

**C# : Scripts**
```csharp
﻿using UnderAutomation.UniversalRobots;
using UnderAutomation.UniversalRobots.Ssh.Tools.Sftp;

class Scripts
{
  static void Main(string[] args)
  {
    // Create a new robot instance
    var robot = new UR();

    // Setup connection to th robot
    var param = new ConnectParameters();
    param.IP = "192.168.0.1";

    // Enable primary interface to get variable values
    param.PrimaryInterface.Enable = true;

    // Enable SFTP file access
    param.Ssh.EnableSftp = true;

    // Connect to the robot
    robot.Connect(param);

    /**/
    // Ask robot to execute a movej
    robot.PrimaryInterface.Script.Send("movej([-1.5,-1.5,-2,-0.5,1.8,0], a=1.4, v=1.05, t=0, r=0)");

    // Enumerates files and folder
    SftpFile[] items = robot.Sftp.ListDirectory("/home/ur/ursim-current/programs/");

    // Download program file prg.urp to your local disk
    robot.Sftp.DownloadFile("/home/ur/ursim-current/programs/prg.urp", @"C:\temp\prg.urp");

    // Send a local file to the robot
    robot.Sftp.UploadFile(@"C:\temp\prg.urp", "/home/ur/ursim-current/programs/prg.urp");

    // Manipulate files and directories
    robot.Sftp.RenameFile("/home/ur/prg.urp", "/home/ur/prg2.urp");
    robot.Sftp.Delete("/home/ur/prg.urp");
    bool exists = robot.Sftp.Exists("/home/ur/prg.urp");
    robot.Sftp.WriteAllText("/home/ur/file.txt", "Hello robot !");
    // ...
    /**/
  }
}
```

**Python : Scripts**
```python

# Create a robot instance
from underautomation.universal_robots.connect_parameters import ConnectParameters
from underautomation.universal_robots.ur import UR


robot = UR()

# Setup connection to th robot
param = ConnectParameters("192.168.0.1")

# Enable primary interface to get variable values
param.primary_interface.enable = True

# Enable SFTP file access
param.ssh.enable_sftp = True

# Connect to the robot
robot.connect(param)

##
# Ask robot to execute a movej
robot.primary_interface.script.send("movej([-1.5,-1.5,-2,-0.5,1.8,0], a=1.4, v=1.05, t=0, r=0)")

# Enumerates files and folder
items = robot.sftp.list_directory("/home/ur/ursim-current/programs/")

# Download program file prg.urp to your local disk
robot.sftp.download_file("/home/ur/ursim-current/programs/prg.urp", "C:\\temp\\prg.urp")

# Send a local file to the robot
robot.sftp.upload_file("C:\\temp\\prg.urp", "/home/ur/ursim-current/programs/prg.urp")

# Manipulate files and directories
robot.sftp.rename_file("/home/ur/prg.urp", "/home/ur/prg2.urp")
robot.sftp.delete("/home/ur/prg.urp")
exists = robot.sftp.exists("/home/ur/prg.urp")
robot.sftp.write_all_text("/home/ur/file.txt", "Hello robot !")
# ...
##
```

**Matlab : Scripts**
```matlab
% Load library
NET.addAssembly(fullfile(pwd, '.\UnderAutomation.UniversalRobots.dll'));

% Import library features in Matlab
import UnderAutomation.UniversalRobots.*

% Create a robot instance
robot = UR();

% Setup connection to th robot
param = ConnectParameters();
param.IP = '192.168.0.56';

% Enable primary interface to get variable values
param.PrimaryInterface.Enable = true;

% Enable SFTP file access
param.Ssh.EnableSftp = true;

% Connect to the robot
robot.Connect(param);

%%
% Ask robot to execute a movej
robot.PrimaryInterface.Script.Send('movej([-1.5,-1.5,-2,-0.5,1.8,0], a=1.4, v=1.05, t=0, r=0)');

% Enumerates files and folder
items = robot.Sftp.ListDirectory('/home/ur/ursim-current/programs/');

% Download program file prg.urp to your local disk
robot.Sftp.DownloadFile('/home/ur/ursim-current/programs/prg.urp', 'C:\\temp\\prg.urp');

% Send a local file to the robot
robot.Sftp.UploadFile('C:\temp\prg.urp', '/home/ur/ursim-current/programs/prg.urp');

% Manipulate files and directories
robot.Sftp.RenameFile('/home/ur/prg.urp', '/home/ur/prg2.urp');
robot.Sftp.Delete('/home/ur/prg.urp');
exists = robot.Sftp.Exists('/home/ur/prg.urp');
robot.Sftp.WriteAllText('/home/ur/file.txt', 'Hello robot !');
% ...
%%
```

### Sockets

**C# : Sockets**
```csharp
﻿using System.Net;
using UnderAutomation.UniversalRobots;
using UnderAutomation.UniversalRobots.SocketCommunication;

class Sockets
{
  static void Main(string[] args)
  {
    // Create a new robot instance
    var robot = new UR();

    // Setup connection to th robot
    var param = new ConnectParameters();
    param.IP = "192.168.0.1";

    // Enable spcket server on port 50001
    param.SocketCommunication.Enable = true;
    param.SocketCommunication.Port = 50001;

    // Connect to the robot
    robot.Connect(param);

    /**/
    // Robot connects with URScipt function socket_open()
    robot.SocketCommunication.SocketClientConnection += (o, e) =>
    {
      // Reply to the robot
      e.Client.SocketWrite("Hello cobot <3");
    };

    // Event raised when the robot sends a message with socket_write()
    robot.SocketCommunication.SocketRequest += (o, e) =>
    {
      string robotMessage = e.Message;
    };

    // Send a message to all connected clients
    robot.SocketCommunication.SocketWrite("123456");
    /**/

    // List of all connected clients
    SocketClient[] connectedClients = robot.SocketCommunication.ConnectedClients;

    // IP address and remote port of a client
    IPEndPoint clientEndpoint = connectedClients[0].EndPoint;

    // Send a message to a specific connected robot
    connectedClients[0].SocketWrite("Hello robot [0] !");

    connectedClients[0].SocketClientDisconnection += (o, e) =>
    {
      /* Handle client disconnection */
    };
  }
}
```

**Python : Sockets**
```python
# Create a robot instance
from underautomation.universal_robots.connect_parameters import ConnectParameters
from underautomation.universal_robots.socket_communication.socket_client_connection_event_args import SocketClientConnectionEventArgs
from underautomation.universal_robots.socket_communication.socket_request_event_args import SocketRequestEventArgs
from underautomation.universal_robots.ur import UR


robot = UR()

# Setup connection to th robot
param = ConnectParameters("192.168.0.1")

# Enable spcket server on port 50001
param.socket_communication.enable = True
param.socket_communication.port = 50001

# Connect to the robot
robot.connect(param)

##
# Function called when robot connects with URScipt function socket_open()
def on_socket_client_connection(o, e : SocketClientConnectionEventArgs):
    e.client.socket_write("Hello cobot <3")

robot.socket_communication.socket_client_connection(on_socket_client_connection)

# Function called when the robot sends a message with socket_write()
def on_socket_request(o,e:SocketRequestEventArgs):
    # Get robot message
    robotMessage = e.Message

robot.socket_communication.socket_request(on_socket_request)

# Send a message to all connected clients
robot.socket_communication.socket_write("123456")
##

# List of all connected clients
connectedClients = robot.socket_communication.connected_clients

# IP address and remote port of a client
clientEndpoint = connectedClients[0].end_point

# Send a message to a specific connected robot
connectedClients[0].socket_write("Hello robot [0]")

  # Handle client disconnection
def on_socket_client_disconnection(o,e):
    pass

connectedClients[0].socket_client_disconnection(on_socket_client_disconnection)
```

**Matlab : Sockets**
```matlab
% Load library
NET.addAssembly(fullfile(pwd, '.\UnderAutomation.UniversalRobots.dll'));

% Import library features in Matlab
import UnderAutomation.UniversalRobots.*

%%
% Create a robot instance
robot = UR();

% Setup connection to th robot
param = ConnectParameters();
param.IP = '192.168.0.56';

% Enable spcket server on port 50001
param.SocketCommunication.Enable = true;
param.SocketCommunication.Port = 50001;

% Connect to the robot
robot.Connect(param)

% Robot connects with URScipt function socket_open()
addlistener(robot.SocketCommunication, 'SocketClientConnection', @OnSocketClientConnection)

% Event raised when the robot sends a message with socket_write()
addlistener(robot.SocketCommunication, 'SocketRequest', @OnSocketRequest)

% Send a message to all connected clients
robot.SocketCommunication.SocketWrite('123456')
%%

% List of all connected clients
connectedClients = robot.SocketCommunication.ConnectedClients

% IP address and remote port of a client
clientEndpoint = connectedClients(0).EndPoint

% Send a message to a specific connected robot
connectedClients(0).SocketWrite('Hello robot [0] !')

addlistener(connectedClients(0).SocketClientDisconnection, 'SocketClientDisconnection', @OnSocketClientDisconnection)

function OnSocketRequest(o, e)
    robotMessage = e.Message
end

function OnSocketClientDisconnection(o, e)
    % Handle client disconnection
end

function OnSocketClientConnection(o, e)
    % Reply to the robot
    e.Client.SocketWrite('Hello cobot <3')
end
```

### Toolbox

**C# : Toolbox**
```csharp
﻿using System.Xml.Linq;
using UnderAutomation.UniversalRobots.Common;
using UnderAutomation.UniversalRobots.Files;
using UnderAutomation.UniversalRobots.Kinematics;

class Toolbox
{
  static void Main(string[] args)
  {
    /**/
    // Create X, Y, Z, RX, RY, RZ pose
    var pose = new Pose(0.1, 0.2, -0.1, 0, 0.05, 0.1);

    // Convert cartesian pose type to RPY or rotation vector
    var rpy = pose.FromRotationVectorToRPY();
    var vectorPose = pose.FromRPYToRotationVector();

    // Get default DH parameters for UR3e robot model
    IUrDhParameters dhParameters = KinematicsUtils.GetDhParametersFromModel(RobotModelsExtended.UR3e);

    // Calculate forward kinematics for given joint angles in radians
    KinematicsResult fkResult = KinematicsUtils.ForwardKinematics(new double[] { 0, -1.57, 1.57, 0, 0, 0 }, dhParameters);

    // Convert the matrix transform to a Pose (X, Y, Z, RX, RY, RZ)
    Pose cartesianPosition = Pose.From4x4MatrixToRotationVector(fkResult.ToolTransform);

    // Calculate inverse kinematics for given cartesian pose
    var matrix = vectorPose.FromRotationVectorTo4x4Matrix();
    double[][] ikSolutions = KinematicsUtils.InverseKinematics(matrix, dhParameters);

    // Decompile program and installation files and access inner XML
    URInstallation installation = URInstallation.Load("C:\\temp\\default.installation");
    URProgram prg = URProgram.Load("C:\\temp\\prg.urp");
    XElement internalXml = prg.XML;
    /**/
  }
}
```

**Python : Toolbox**
```python
from underautomation.universal_robots.pose import Pose
from underautomation.universal_robots.ur_program import URProgram
from underautomation.universal_robots.ur_installation import URInstallation

##
# Create X, Y, Z, RX, RY, RZ pose
pose = Pose(0.1, 0.2, -0.1, 0, 0.05, 0.1)

# Convert cartesian pose type to RPY or rotation vector
rpy = pose.from_rotation_vector_to_rpy()
vectorPose = pose.from_rpy_to_rotation_vector()

# Decompile program and installation files and access inner XML
installation = URInstallation.load("C:\\temp\\default.installation")
prg = URProgram.load("C:\\temp\\prg.urp")
internalXml = prg.xml
##
```

**Matlab : Toolbox**
```matlab
% Load library
NET.addAssembly(fullfile(pwd, '.\UnderAutomation.UniversalRobots.dll'))

% Import library features in Matlab
import UnderAutomation.UniversalRobots.*

%%
% Create X, Y, Z, RX, RY, RZ pose
pose = Common.Pose(0.1, 0.2, -0.1, 0, 0.05, 0.1)

% Convert cartesian pose type to RPY or rotation vector
rpy = pose.FromRotationVectorToRPY()
vectorPose = pose.FromRPYToRotationVector()

% Decompile program and installation files and access inner XML
installation = Files.URInstallation.Load('C:\\temp\\default.installation')
prg = Files.URProgram.Load('C:\\temp\\prg.urp')
internalXml = prg.XML
%%
```