SOAP Overview
On this page :
SOAP is a communication protocol that allows you to connect to a Staubli robot controller.
This documentation describes the usage of the Staubli native SOAP protocol to interact with industrial robot controllers programmatically.
Overview
Staubli industrial robot controllers expose a SOAP-based interface to interact with third applications, like SRS (Staubli Robotics Suite) or this library.
This includes retrieving status information, controlling movement, accessing I/Os, handling applications, and managing tasks.
To use this API, you must connect to a controller over its network address and authenticate using SOAP credentials.
This SDK is compatible with CS8 and CS9 controllers, providing a unified interface for both.
Connecting to the Controller
Initialization
To begin any SOAP interaction, create a StaubliController
and configure ConnectionParameters
:
- IP Address: The robot controller's network address.
- SOAP Enable: Enables the SOAP layer.
- Port: Usually
851
. - Authentication: Username and password, typically
"default"
.
Example Usage
using UnderAutomation.Staubli;using UnderAutomation.Staubli.Common;using UnderAutomation.Staubli.Soap.Data;public class Connect{static void Main(){/**/StaubliController controller = new StaubliController();var parameters = new ConnectionParameters();parameters.PingBeforeConnect = true; // Send a ping request before connecting (Optional, default is true)parameters.Address = "192.168.0.1";parameters.Soap.Enable = true; // Enable SOAP communication (default is true)parameters.Soap.Port = SoapConnectParameters.DEFAULT_PORT; // default is 851parameters.Soap.User = "default"; // default is "default"parameters.Soap.Password = "default"; // default is "default"// Connect to the Staubli controllercontroller.Connect(parameters);bool isConnected = controller.Soap.Enabled; // Check if the SOAP connection is enabledPhysicalIo[] ios = controller.Soap.GetAllPhysicalIos(); // Example of using SOAP to get all physical I/Os/**/}}
Retrieving System Information
Robots
Use GetRobots()
to retrieve connected robot arms:
- Arm: Model name (e.g. TX2-140).
- MountType: Physical installation (Floor, Ceiling, Wall).
- Kinematic: Configuration (Anthropomorphic, SCARA, etc.).
public class Robot {public Robot()public string Arm { get; set; }public DiameterAxis3 DiameterAxis3 { get; set; }public Kinematic Kinematic { get; set; }public LengthAxis3 LengthAxis3 { get; set; }public MountType MountType { get; set; }public string Tuning { get; set; }}
Controller Parameters
Call GetControllerParameters()
to read system-level configuration:
- Returns an array of name/value pairs (e.g.,
CycleTime = 0.004s
).
public class Parameter {public Parameter()public string Key { get; set; }public string Name { get; set; }public string Value { get; set; }}
DH Parameters
Denavit-Hartenberg parameters are retrieved via GetDhParameters()
:
- Describes the robot's mechanical structure.
- Parameters include
Alpha
,Beta
,Theta
,A
,D
.
public class DhParameters {public DhParameters()public double A { get; set; }public double Alpha { get; set; }public double Beta { get; set; }public double D { get; set; }public double Theta { get; set; }}
Example Usage
using UnderAutomation.Staubli;using UnderAutomation.Staubli.Soap.Data;class GetInfos{static void Main(){StaubliController controller = new StaubliController();var parameters = new ConnectionParameters("192.168.0.1");/**/Robot[] robots = controller.Soap.GetRobots(); // Get all robots driven by the controllerforeach (var robot in robots){Console.WriteLine($"Arm: {robot.Arm}"); // i.e. TX2-140Console.WriteLine($"Mount type: {robot.MountType}"); // i.e. Floor, Ceiling, WallConsole.WriteLine($"Kinematic: {robot.Kinematic}"); // i.e. ANTHROPOMORPH6, SCARA, ...// see Robot class for more properties}// ---------------Parameter[] controllerParams = controller.Soap.GetControllerParameters(); // Get controller parametersforeach (var param in controllerParams)Console.WriteLine($"{param.Name} = {param.Value}"); // i.e. CycleTime = 0.004s// ---------------DhParameters[] dhParameters = controller.Soap.GetDhParameters(robot: 0); // Get DH parameters of the first robotforeach (var dh in dhParameters)Console.WriteLine($"{dh.Alpha} - {dh.Beta} - {dh.Theta} - {dh.A} - {dh.D}");/**/}}
Position and Joints
GetCurrentJointPosition()
: Returns only joint angles.GetCurrentCartesianJointPosition()
: Returns tool position in space (XYZ + rotation) and joint angles.
public class CartesianJointPosition {public CartesianJointPosition()// The Cartesian position of the robot end effector.public CartesianPosition CartesianPosition { get; set; }// The joint positions in radians.public double[] JointsPosition { get; set; }}
public class CartesianPosition {public CartesianPosition()public double Rx { get; set; }public double Ry { get; set; }public double Rz { get; set; }public double X { get; set; }public double Y { get; set; }public double Z { get; set; }}
Returned types include:
CartesianPosition
: X, Y, Z, Rx, Ry, Rz.JointsPosition
: Array of joint values in radians.
using UnderAutomation.Staubli;using UnderAutomation.Staubli.Soap.Data;class CurrentPosition{static void Main(){StaubliController controller = new StaubliController();var parameters = new ConnectionParameters("192.168.0.1");/**/// Get the current flange position of the first robot in world coordinatesCartesianJointPosition position = controller.Soap.GetCurrentCartesianJointPosition(robot: 0, tool: null, frame: null);double[] jointPosition1 = position.JointsPosition; // Joint position in radiansCartesianPosition cartesianPosition = position.CartesianPosition;Console.WriteLine($"X: {cartesianPosition.X}, Y: {cartesianPosition.Y}, Z: {cartesianPosition.Z}");Console.WriteLine($"Rx: {cartesianPosition.Rx}, Ry: {cartesianPosition.Ry}, Rz: {cartesianPosition.Rz}");// ---------------// Get only the current joint position of the first robotdouble[] jointPosition2 = controller.Soap.GetCurrentJointPosition(robot: 0);// ---------------// Get the joint ranges (min/max angle of each joint)controller.Soap.GetJointRange(robot: 0);/**/}}
Kinematics
Forward Kinematics
Use ForwardKinematics()
to compute end-effector position from joint angles:
- Returns a
Frame
(position/orientation matrix). - Includes
Config
, which defines the robot’s pose solution.
public interface IForwardKinematics {Config Config { get; }Frame Position { get; }}
Inverse Kinematics
Use ReverseKinematics()
to compute joint angles from a desired Frame
:
- Inputs: Desired pose, current joint state, configuration, and joint limits.
- Returns
IReverseKinematics
, including solution result and joint values.
public interface IReverseKinematics {double[] Joint { get; }ReversingResult Result { get; }}
public class Frame {// Default constructor.public Frame()// X component of the local Z-axis vector (Approach X).public double Ax { get; set; }// Y component of the local Z-axis vector (Approach Y).public double Ay { get; set; }// Z component of the local Z-axis vector (Approach Z).public double Az { get; set; }// X component of the local X-axis vector (Normal X).public double Nx { get; set; }// Y component of the local X-axis vector (Normal Y).public double Ny { get; set; }// Z component of the local X-axis vector (Normal Z).public double Nz { get; set; }// X component of the local Y-axis vector (Orientation X).public double Ox { get; set; }// Y component of the local Y-axis vector (Orientation Y).public double Oy { get; set; }// Z component of the local Y-axis vector (Orientation Z).public double Oz { get; set; }// X coordinate of the frame's origin in global space (Pose X).public double Px { get; set; }// Y coordinate of the frame's origin in global space (Pose Y).public double Py { get; set; }// Z coordinate of the frame's origin in global space (Pose Z).public double Pz { get; set; }}
public class Config {public Config()public AnthroConfig AnthroConfig { get; set; }public ScaraConfig ScaraConfig { get; set; }public VrbxConfig VrbxConfig { get; set; }}
Example Usage
using UnderAutomation.Staubli;using UnderAutomation.Staubli.Soap.Data;class Kinematics{static void Main(){StaubliController controller = new StaubliController();var parameters = new ConnectionParameters("192.168.0.1");double[] joints = controller.Soap.GetCurrentJointPosition(robot: 0);JointRange range = controller.Soap.GetJointRange(robot: 0);/**/// Get forward kinematicsIForwardKinematics fk = controller.Soap.ForwardKinematics(robot: 0, // Index of the robot (0 for the first robot)joints // double[] of joint positions in radians);// Position matrixFrame position = fk.Position;// Position configurationConfig config = fk.Config; // i.e. Righty/Lefty, Elbow Positive/Negtive, ...// -----------------// Get inverse kinematicsIReverseKinematics ik = controller.Soap.ReverseKinematics(robot: 0, // Index of the robot (0 for the first robot)joints,position,config,range);if (ik.Result == ReversingResult.Success)foreach (double joint in ik.Joint) Console.WriteLine(joint);/**/}}
Motion and Movement
Power Control
SetPower(true/false)
: Powers the robot on or off.
public enum PowerReturnCode {DisableTimeout = 3EnableTimeout = 2OnlyInRemoteMode = 4RobotNotStopped = 1Success = 0}
Motion Types
Each motion function returns an IMoveResult
, indicating success or failure.
MoveL()
: Linear Cartesian movement.MoveJC()
: Joint move to a Cartesian frame.MoveJJ()
: Move to specified joint angles.MoveC()
: Circular Cartesian movement using two frames.
public enum MotionReturnCode {MisuseError = 3NotReady = 1ParameterError = 2// Success, no error occurred.Success = 0UnexpectedError = 4}
using UnderAutomation.Staubli;using UnderAutomation.Staubli.Soap.Data;class Kinematics{static void Main(){StaubliController controller = new StaubliController();var parameters = new ConnectionParameters("192.168.0.1");double[] joints = controller.Soap.GetCurrentJointPosition(robot: 0);JointRange range = controller.Soap.GetJointRange(robot: 0);/**/// Get forward kinematicsIForwardKinematics fk = controller.Soap.ForwardKinematics(robot: 0, // Index of the robot (0 for the first robot)joints // double[] of joint positions in radians);// Position matrixFrame position = fk.Position;// Position configurationConfig config = fk.Config; // i.e. Righty/Lefty, Elbow Positive/Negtive, ...// -----------------// Get inverse kinematicsIReverseKinematics ik = controller.Soap.ReverseKinematics(robot: 0, // Index of the robot (0 for the first robot)joints,position,config,range);if (ik.Result == ReversingResult.Success)foreach (double joint in ik.Joint) Console.WriteLine(joint);/**/}}
Motion Lifecycle
StopMotion()
: Stops current motion immediately.ResetMotion()
: Resets any motion errors.RestartMotion()
: Resumes motion from a paused state.
Example Usage
using UnderAutomation.Staubli;using UnderAutomation.Staubli.Soap.Data;class Motion{static void Main(){StaubliController controller = new StaubliController();var parameters = new ConnectionParameters("192.168.0.1");double[] joints = controller.Soap.GetCurrentJointPosition(robot: 0);IForwardKinematics fk = controller.Soap.ForwardKinematics(robot: 0, joints);Frame position = fk.Position;var config = fk.Config;MotionDesc motionDesc = new MotionDesc{Config = config,Acceleration = 0.5,Deceleration = 0.5,Frequency = 100,Velocity = 0.5,TranslationVelocity = 0.1,RotationVelocity = 0.1,};position.Px += 0.1; // Move 10 cm in X directionFrame position2 = new Frame(); // fake position for circular move example/**/// Power on the controllerPowerReturnCode powerOnStatus = controller.Soap.SetPower(power: true);// Move linear to cartesian positionIMoveResult moveLResult = controller.Soap.MoveL(robot: 0,position,motionDesc);// Move joints to cartesian positionIMoveResult moveJCResult = controller.Soap.MoveJC(robot: 0,position,motionDesc);// Move joints to joint positionIMoveResult moveJResult = controller.Soap.MoveJJ(robot: 0,joints,motionDesc);// Move CircularIMoveResult moveCResult = controller.Soap.MoveC(robot: 0,position,position2,motionDesc);// Stop motionMotionReturnCode stopStatus = controller.Soap.StopMotion();// Reset motionMotionReturnCode resetStatus = controller.Soap.ResetMotion();// Restart motionMotionReturnCode restartStatus = controller.Soap.RestartMotion();/**/}}
Input/Output Management
Physical I/Os
Use GetAllPhysicalIos()
to list all hardware I/Os:
- Each
PhysicalIo
includes name, type (digital, analog, serial), lockable status, and description.
public class PhysicalIo {public PhysicalIo()// Description of the physical I/O.public string Description { get; set; }// Indicates whether the physical I/O is lockable.public bool Lockable { get; set; }// Name of the physical I/O.public string Name { get; set; }// Type of the physical I/O (e.g., din, dout, ain, serial, ...).public string TypeStr { get; set; }}
Read I/O State
Use ReadIos()
to retrieve current values:
- Includes value, lock status, and simulation status.
public class PhysicalIoState {public PhysicalIoState()public PhysicalIoAttribute Attribute { get; set; }public bool Locked { get; set; }public bool Simulated { get; set; }public PhysicalIoEnumState State { get; set; }public double Value { get; set; }}
public class PhysicalIoAttribute {public PhysicalIoAttribute()public PhysicalAioAttribute AioAttribute { get; set; }public PhysicalDioAttribute DioAttribute { get; set; }}
public class PhysicalAioAttribute {public PhysicalAioAttribute()public double CoefficientA { get; set; }public double CoefficientB { get; set; }}
public class PhysicalDioAttribute {public PhysicalDioAttribute()public bool Inverted { get; set; }}
Write I/O State
Use WriteIos()
to set values:
- Inputs: I/O names and corresponding values (typically 0 or 1 for digital).
public class PhysicalIoWriteResponse {public PhysicalIoWriteResponse()public bool Found { get; set; }public bool Success { get; set; }}
Example Usage
using UnderAutomation.Staubli;using UnderAutomation.Staubli.Soap.Data;class Ios{static void Main(){StaubliController controller = new StaubliController();var parameters = new ConnectionParameters("192.168.0.1");/**/// Get all physical I/O ports of the controllerPhysicalIo[] ios = controller.Soap.GetAllPhysicalIos();foreach (var io in ios){Console.WriteLine($"Name: {io.Name}");Console.WriteLine($"Type: {io.Description}");Console.WriteLine($"Lockable: {io.Lockable}"); // i.e. true, falseConsole.WriteLine($"Description: {io.TypeStr}"); // i.e. din, dout, ain, serial}// -----------------// Read I/Os valuePhysicalIoState[] values = controller.Soap.ReadIos(new[] { @"Socket\test", @"Serial\0", @"FastIO\fOut1", @"CpuUsage\val3" });foreach (var value in values){Console.WriteLine("Value: " + value.Value);Console.WriteLine("Locked: " + value.Locked);Console.WriteLine("Simulated: " + value.Simulated);}// -----------------// Write I/Os valuePhysicalIoWriteResponse[] response = controller.Soap.WriteIos(new[] { "my_io_1", "my_io_2" }, new double[] { 1.0, 0.0 });foreach (var res in response)Console.WriteLine($"Success: {res.Success} - Found: {res.Found}");/**/}}
Application Management
Loading Projects
LoadProject("Disk://myProject/myProject.pjx")
: Loads a project from disk.
Application Control
GetValApplications()
: Lists running and loaded VAL 3 applications.StopApplication()
: Stops the current application.StopAndUnloadAll()
: Stops and unloads all VAL 3 applications.
public class ValApplication {public ValApplication()public bool IsCrypted { get; set; }public bool IsRunning { get; set; }public bool Loaded { get; set; }public string Name { get; set; }}
Task Inspection
Use GetTasks()
to get all active tasks:
- Includes task name, creator (project path), current line number, and execution state.
Task Lifecycle
TaskKill()
: Forcefully stops a task.TaskSuspend()
: Pauses a running task.TaskResume()
: Resumes a suspended task.
Example Usage
using UnderAutomation.Staubli;using UnderAutomation.Staubli.Soap.Data;class Application{static void Main(){StaubliController controller = new StaubliController();var parameters = new ConnectionParameters("192.168.0.1");/**/// Load project from diskcontroller.Soap.LoadProject("Disk://myProject/myProject.pjx");ValApplication[] applications = controller.Soap.GetValApplications();foreach (var application in applications)Console.WriteLine($"Application: {application.Name}, Running: {application.IsRunning}");// Unload all applicationscontroller.Soap.StopAndUnloadAll();// Stop running applicationcontroller.Soap.StopApplication();// Get tasksControllerTask[] tasks = controller.Soap.GetTasks(); // Get all tasksforeach (var task in tasks){Console.WriteLine($"Task: {task.Name}");Console.WriteLine($"reated by: {task.CreatedBy}"); // i.e. Disk://myProject/myProject.pjxConsole.WriteLine($"Line: {task.ProgramLine}");Console.WriteLine($"State: {task.State}");}// Kill taskcontroller.Soap.TaskKill(tasks[0].Name, tasks[0].CreatedBy);// Suspend taskcontroller.Soap.TaskSuspend(tasks[0].Name, tasks[0].CreatedBy);// Resume taskcontroller.Soap.TaskResume(tasks[0].Name, tasks[0].CreatedBy);/**/}}
Notes on Usage
- The robot index (
robot: 0
) usually refers to the first robot connected. - Joint angles are in radians.
- Cartesian positions are in meters and radians (Rx, Ry, Rz).