CGTP is the web server running on Fanuc robots (port 80/3080). It provides HTTP-based access to programs, variables, registers, I/O, positions, and files.

## Key features

- **Program management**: Create, delete, rename, run, pause, abort programs
- **Variables & registers**: Read/write any variable, numeric/position/string registers
- **I/O control**: Read, write, simulate, and unsimulate I/O ports
- **Position reading**: Read current Cartesian and joint positions
- **Online kinematics**: Forward and inverse kinematics on the controller
- **Batch operations**: Read/write groups of registers and variables in one request
- **Comments**: Read/write register, I/O, and user alarm descriptions
- **File access**: List and download controller files via HTTP
- **KCL commands**: Execute KCL commands over CGTP

## Quick example

**C# : Cgtp**
```csharp
using UnderAutomation.Fanuc;
using UnderAutomation.Fanuc.Common;
using UnderAutomation.Fanuc.Cgtp;

public class Cgtp
{
  public static void Main()
  {
    FanucRobot robot = new FanucRobot();

    ConnectionParameters parameters = new ConnectionParameters("192.168.0.1");
    parameters.Cgtp.Enable = true;

    robot.Connect(parameters);

    /**/
    // Read a variable
    CgtpVariableValue var = robot.Cgtp.ReadVariable("$RMT_MASTER");
    int rmtMaster = var.IntegerValue;

    // Write a variable
    robot.Cgtp.WriteVariable("$RMT_MASTER", 1);

    // Read a numeric register with comment
    NumericRegisterWithComment reg = robot.Cgtp.ReadNumericRegisterWithComment(1);

    // Read I/O
    int di1 = robot.Cgtp.ReadIo(CgtpIoPortType.DI, 1);

    // Write I/O
    robot.Cgtp.WriteIo(CgtpIoPortType.DO, 1, 1);

    // Read current Cartesian position
    CartesianPosition pos = robot.Cgtp.ReadCartesianPosition();

    // Run a program
    robot.Cgtp.RunProgram("MY_PROGRAM");
    /**/
  }
}
```

**Python : Cgtp**
```python
from underautomation.fanuc.fanuc_robot import FanucRobot
from underautomation.fanuc.connection_parameters import ConnectionParameters
from underautomation.fanuc.cgtp.cgtp_io_port_type import CgtpIoPortType

# Create a robot instance
robot = FanucRobot()

# Configure connection parameters
parameters = ConnectionParameters("192.168.0.1")
parameters.cgtp.enable = True

# Connect to the robot
robot.connect(parameters)

##
# Read a variable
var = robot.cgtp.read_variable("$RMT_MASTER")
rmt_master = var.integer_value

# Write a variable
robot.cgtp.write_variable("$RMT_MASTER", 1)

# Read a numeric register with comment
reg = robot.cgtp.read_numeric_register_with_comment(1)

# Read I/O
di1 = robot.cgtp.read_io(CgtpIoPortType.DI, 1)

# Write I/O
robot.cgtp.write_io(CgtpIoPortType.DO, 1, 1)

# Read current Cartesian position
pos = robot.cgtp.read_cartesian_position()

# Run a program
robot.cgtp.run_program("MY_PROGRAM")
##
```

## Robot options

CGTP does not require any additional options. The robot typically listens on port **80** or **3080**.

Most features require firmware **V8.30** or later. Some features (program management, position reading) require **V9.10+**.

## Firmware compatibility

| Feature | Min. firmware |
|---------|--------------|
| Variable read/write | V8.30 |
| I/O read/write/simulate | V8.30 |
| Program management | V9.10 |
| Position reading | V9.10 |
| Program execution (Run) | V9.30 |
| File listing | V9.40 |

## Connection

**C# : CgtpConnection**
```csharp
using UnderAutomation.Fanuc;
using UnderAutomation.Fanuc.Cgtp;

public class CgtpConnection
{
    static void Main()
    {
        /**/
        // Via FanucRobot
        var robot = new FanucRobot();
        var parameters = new ConnectionParameters("192.168.0.1");
        parameters.Cgtp.Enable = true;           // enabled by default
        parameters.Cgtp.Port = 80;              // default port
        parameters.Cgtp.RequestTimeoutMs = 3000; // default timeout
        robot.Connect(parameters);

        // Or standalone
        var cgtp = new CgtpClient();
        cgtp.Connect("192.168.0.1");
        /**/
    }
}
```

**Python : CgtpConnection**
```python
from underautomation.fanuc.fanuc_robot import FanucRobot
from underautomation.fanuc.connection_parameters import ConnectionParameters
from underautomation.fanuc.cgtp.cgtp_client import CgtpClient

##
# Via FanucRobot
robot = FanucRobot()
parameters = ConnectionParameters("192.168.0.1")
parameters.cgtp.enable = True           # enabled by default
parameters.cgtp.port = 80              # default port
parameters.cgtp.request_timeout_ms = 3000
robot.connect(parameters)

# Or standalone
cgtp = CgtpClient()
cgtp.connect("192.168.0.1")
##
```

## Authentication

Some robots require authentication. Pass credentials during connection:

**C# : CgtpAuth**
```csharp
using UnderAutomation.Fanuc;
using UnderAutomation.Fanuc.Cgtp;

public class CgtpAuth
{
    static void Main()
    {
        FanucRobot robot = new FanucRobot();
        var parameters = new ConnectionParameters("192.168.0.1");

        /**/
        // Via FanucRobot
        parameters.Cgtp.Login = "admin";
        parameters.Cgtp.Password = "password";
        robot.Connect(parameters);

        // Or standalone
        var cgtp = new CgtpClient();
        cgtp.Connect("192.168.0.1", login: "admin", password: "password");
        /**/
    }
}
```

**Python : CgtpAuth**
```python
from underautomation.fanuc.fanuc_robot import FanucRobot
from underautomation.fanuc.connection_parameters import ConnectionParameters
from underautomation.fanuc.cgtp.cgtp_client import CgtpClient

robot = FanucRobot()
parameters = ConnectionParameters("192.168.0.1")

##
# Via FanucRobot
parameters.cgtp.login = "admin"
parameters.cgtp.password = "password"
robot.connect(parameters)

# Or standalone
cgtp = CgtpClient()
cgtp.connect("192.168.0.1", login="admin", password="password")
##
```

## KCL over CGTP

CGTP provides an embedded KCL client accessible via `robot.Cgtp.Kcl`. This allows executing KCL commands without a Telnet connection:

**C# : CgtpKcl**
```csharp
using UnderAutomation.Fanuc;

public class CgtpKcl
{
    static void Main()
    {
        FanucRobot robot = new FanucRobot();
        robot.Connect("192.168.0.1");

        /**/
        robot.Cgtp.Kcl.SetVariable("$RMT_MASTER", 1);

        TaskInformationResult taskInfo = robot.Cgtp.Kcl.GetTaskInformation("MY_PROGRAM");

        robot.Cgtp.Kcl.AddBreakpoint("MY_PROGRAM", line: 10);
        /**/
    }
}
```

**Python : CgtpKcl**
```python
from underautomation.fanuc.fanuc_robot import FanucRobot

robot = FanucRobot()
robot.connect("192.168.0.1")

##
robot.cgtp.kcl.set_variable("$RMT_MASTER", 1)

task_info = robot.cgtp.kcl.get_task_information("MY_PROGRAM")

robot.cgtp.kcl.add_breakpoint("MY_PROGRAM", line=10)
##
```

## Next steps

- [Program management](/fanuc/documentation/cgtp-programs) : Create, run, pause, abort programs
- [Registers & variables](/fanuc/documentation/cgtp-registers-variables) : Read/write registers and variables
- [Inputs & Outputs](/fanuc/documentation/cgtp-io) : Read, write, simulate I/O
- [Position & kinematics](/fanuc/documentation/cgtp-position-kinematics) : Read position, FK/IK
- [Alarms, comments & files](/fanuc/documentation/cgtp-alarms-files) : Comments, user alarms, file listing

## API reference

**Members of Cgtp.CgtpClient**
```csharp
public class CgtpClient : CgtpClientBase {
    // Creates a new instance of the CGTP Web Server client.
    public CgtpClient()

    // Connect to the CGTP Web Server on the controller.
    public void Connect(string ip, int port = 3080, int requestTimeoutMs = 3000, string login = null, string password = null)
}
```

**Members of Cgtp.Internal.CgtpClientBase**
```csharp
public abstract class CgtpClientBase {
    protected CgtpClientBase()

    // Abort the task specified by <code class="paramref">progName</code>.
    // Set to null to abort all user tasks.
    // From firmware 9.10
    public void AbortTask(string progName = null)

    // Change the active TP program to <code class="paramref">progName</code>.
    // From firmware 9.10
    public void ChangeActiveProgram(string progName)

    // Create a new TP program on the controller.
    // From firmware 9.10
    public void CreateProgram(string progName, string owner = null, string comment = null, int defaultGroup = 0, CgtpProgramSubType subType = CgtpProgramSubType.None)

    // Delete the program <code class="paramref">progName</code> from the controller.
    // From firmware 9.10
    public void DeleteProgram(string progName)

    // Delete <code class="paramref">count</code> lines starting at <code class="paramref">lineNum</code> in program <code class="paramref">progName</code>.
    // From firmware 9.10
    public void DeleteSourceLines(string progName, int lineNum, int count = 1)

    // Disconnect from the CGTP Web Server. After calling this method, the client must be reconnected before it can be used again.
    public void Disconnect()

    // Indicates whether the client is currently connected to the CGTP Web Server.
    public bool Enabled { get; }

    // Compute the forward kinematics on the controller: convert joint angles to a Cartesian position.
    public CartesianPosition ForwardKinematics(int group, JointsPosition jointPosition, int userTool = -1, int userFrame = -1)

    // Read all comments for the specified element type.
    // For I/O types (RI, RO, DI, DO, GI, GO, AI, AO), returns the input or output comments accordingly.
    public string[] GetComments(CgtpCommentType type)

    // Download the content of a file from the controller as a string.
    // From firmware 9.10
    public string GetFileAsString(string pathName)

    // Read all I/O comments for the specified I/O type.
    public IOComments GetIoComments(CgtpCommentIoType type)

    // Check whether I/O port at <code class="paramref">index</code> of type <code class="paramref">portType</code> is simulated.
    // From firmware 8.30
    public bool GetIoSimulationStatus(CgtpIoPortType portType, int index)

    // Get the comment of program <code class="paramref">progName</code>.
    // From firmware 9.10
    public string GetProgramComment(string progName)

    // Get whether program <code class="paramref">progName</code> ignores pause requests.
    // From firmware 9.10
    public bool GetProgramIgnorePause(string progName)

    // Get the owner of program <code class="paramref">progName</code>.
    // From firmware 9.10
    public string GetProgramOwner(string progName)

    // Get the stack size of program <code class="paramref">progName</code>.
    // From firmware 9.10
    public int GetProgramStackSize(string progName)

    // Get the sub-type of program <code class="paramref">progName</code>.
    // From firmware 9.10
    public CgtpProgramSubType GetProgramSubType(string progName)

    // Get whether program <code class="paramref">progName</code> is write-protected.
    // From firmware 9.10
    public bool GetProgramWriteProtect(string progName)

    // Provides methods to download and decode files from the controller via HTTP.
    public CgtpHttpClient Http { get; }

    // Insert a source line before <code class="paramref">lineNum</code> in program <code class="paramref">progName</code>.
    // From firmware 9.10
    public void InsertSourceLine(string progName, string lineContent, int lineNum)

    // Compute the inverse kinematics on the controller: convert a Cartesian position to joint angles.
    public JointsPosition InvertKinematics(int group, CartesianPosition cartesianPosition, int userTool = -1, int userFrame = -1)

    // KCL client for executing KCL commands over CGTP.
    public CgtpKclClient Kcl { get; }

    // Controller language (default is English)
    public Languages Language { get; set; }

    // List files at the specified path on the controller.
    // From firmware 9.40
    public string[] ListFiles(string pathName = "MD:")

    // List all TP or Karel programs on the controller
    public string[] ListPrograms(CgtpProgramType type, CgtpProgramSubType subType)

    // List all TP programs on the controller, regardless of their sub-type.
    public string[] ListTpPrograms()

    // Pause program execution on the controller.
    // From firmware 9.10
    public void PauseAllPrograms()

    // Read multiple variables from the controller in a single batch operation.
    // Each variable in <code class="paramref">variables</code> will be updated with the value read from the controller.
    public CgtpBatchReadResult ReadBatchVariables(CgtpBatchVariables variables)

    // Read the current Cartesian position of motion group <code class="paramref">groupNum</code>.
    // From firmware 9.10
    public CartesianPosition ReadCartesianPosition(int groupNum = 1)

    // Read the value of I/O port at <code class="paramref">index</code> of type <code class="paramref">portType</code>.
    // From firmware 8.30
    public int ReadIo(CgtpIoPortType portType, int index)

    // Read the current joint angles of motion group <code class="paramref">groupNum</code>.
    // From firmware 9.10
    public JointsPosition ReadJointPosition(int groupNum = 1)

    // Read the numeric register (R[]) at <code class="paramref">index</code>.
    // From firmware 9.10
    public NumericRegisterWithComment ReadNumericRegisterWithComment(int index)

    // Read all numeric registers (R[]) with their comments and values.
    public NumericRegisterWithComment[] ReadNumericRegistersWithComment()

    // Read the position register (PR[]) at <code class="paramref">index</code> for motion group <code class="paramref">groupNum</code>.
    // From firmware 9.10
    public PositionRegisterWithComment ReadPositionRegisterWithComment(int index, int groupNum = 1)

    // Read all string registers (SR[]) with their comments and values.
    public StringRegisterWithComment[] ReadStringRegistersWithComment()

    // Read all user alarm definitions with their comments and severity.
    public UserAlarmDefinition[] ReadUserAlarms()

    // Read the typed value of variable <code class="paramref">varName</code> in program <code class="paramref">progName</code>.
    // From firmware 9.10
    public CgtpVariableValue ReadVariable(string varName, string progName = null)

    // Read the value of variable <code class="paramref">varName</code> in program <code class="paramref">progName</code>.
    // From firmware 9.10
    public string ReadVariableAsString(string varName, string progName = null)

    // Rename program <code class="paramref">sourceName</code> to <code class="paramref">newName</code>.
    // From firmware 9.10
    public void RenameProgram(string sourceName, string newName)

    // Replace the source line at <code class="paramref">lineNum</code> in program <code class="paramref">progName</code>.
    // From firmware 9.10
    public void ReplaceSourceLine(string progName, string lineContent, int lineNum)

    // Run the specified program starting at <code class="paramref">lineNum</code>.
    // From firmware 9.30
    public void RunProgram(string progName, int lineNum = 1)

    // Open the TP program <code class="paramref">progName</code> and move cursor to <code class="paramref">lineNum</code>.
    // From firmware 9.10
    public void SelectProgram(string progName, int lineNum = 1)

    // Set the comment of a register or I/O port identified by <code class="paramref">type</code> and <code class="paramref">index</code>.
    public void SetComment(CgtpCommentType type, int index, string comment)

    // Set the comment of program <code class="paramref">progName</code>.
    // From firmware 9.10
    public void SetProgramComment(string progName, string comment)

    // Set whether program <code class="paramref">progName</code> ignores pause requests.
    // From firmware 9.10
    public void SetProgramIgnorePause(string progName, bool ignorePause)

    // Set the owner of program <code class="paramref">progName</code>.
    // From firmware 9.10
    public void SetProgramOwner(string progName, string owner)

    // Set position at index <code class="paramref">positionIndex</code> in program <code class="paramref">progName</code> to the given <code class="paramref">position</code>.
    // Supports both joint and Cartesian representations. Only the first motion group is supported via CGTP.
    // From firmware 9.10
    public void SetProgramPosition(string progName, int positionIndex, Position position)

    // Set position at index <code class="paramref">positionIndex</code> to the current Cartesian position in program <code class="paramref">progName</code> and return the updated position.
    public CartesianPosition SetProgramPositionToCurrentCartesianPosition(string progName, int positionIndex, int groupNumber = 1)

    // Set the stack size of program <code class="paramref">progName</code>.
    // From firmware 9.10
    public void SetProgramStackSize(string progName, int stackSize)

    // Set the sub-type of program <code class="paramref">progName</code>.
    // From firmware 9.10
    public void SetProgramSubType(string progName, CgtpProgramSubType subType)

    // Set whether program <code class="paramref">progName</code> is write-protected.
    // From firmware 9.10
    public void SetProgramWriteProtect(string progName, bool writeProtect)

    // Set the severity of a user alarm.
    public void SetUserAlarmSeverity(int index, int severity)

    // Set I/O port at <code class="paramref">index</code> of type <code class="paramref">portType</code> to simulated.
    // From firmware 8.30
    public void SimulateIo(CgtpIoPortType portType, int index)

    // Remove simulation from I/O port at <code class="paramref">index</code> of type <code class="paramref">portType</code>.
    // From firmware 8.30
    public void UnsimulateIo(CgtpIoPortType portType, int index)

    // Write multiple variables to the controller in a single batch operation.
    public CgtpBatchWriteResult WriteBatchVariables(CgtpBatchVariables variables)

    // Set the value of I/O port at <code class="paramref">index</code> of type <code class="paramref">portType</code>.
    // From firmware 8.30
    public void WriteIo(CgtpIoPortType portType, int index, int value)

    // Write a real (double) value to numeric register R[<code class="paramref">index</code>].
    public void WriteNumericRegisterAsDouble(int index, double value)

    // Write an integer value to numeric register R[<code class="paramref">index</code>].
    public void WriteNumericRegisterAsInteger(int index, int value)

    // Write a cartesian position value to a position register (PR[])
    public void WritePositionRegisterAsCartesian(int index, CartesianPosition value, int groupNum = 1)

    // Write a joint position value to a position register (PR[])
    public void WritePositionRegisterAsJoint(int index, JointsPosition value, int groupNum = 1)

    // Write a string value to string register SR[<code class="paramref">index</code>].
    public void WriteStringRegister(int index, string value)

    // Write a real (double) <code class="paramref">value</code> to variable <code class="paramref">varName</code> in program <code class="paramref">progName</code>.
    // From firmware 8.30
    public void WriteVariable(string varName, double value, string progName = null)

    // Write an integer <code class="paramref">value</code> to variable <code class="paramref">varName</code> in program <code class="paramref">progName</code>.
    // From firmware 8.30
    public void WriteVariable(string varName, int value, string progName = null)

    // Write <code class="paramref">value</code> to variable <code class="paramref">varName</code> in program <code class="paramref">progName</code>.
    // From firmware 8.30
    public void WriteVariable(string varName, string value, string progName = null)
}
```