UnderAutomation
Any question?

[email protected]

Contact us
UnderAutomation
⌘Q
Fanuc SDK documentation
Program management
Documentation home

Registers & variables

Read and write numeric, position, and string registers, system variables, and perform batch operations via CGTP.

  • Read a variable
  • Read and Write registers
  • Batch variables
  • Complete example
  • API reference

CGTP lets you read and write any system variable, program variable, and register (numeric, position, string) on your Fanuc robot.

Read a variable

ReadVariable returns a typed CgtpVariableValue with automatic parsing:

// Read as typed value
CgtpVariableValue var1 = robot.Cgtp.ReadVariable("$RMT_MASTER");
int intVal = var1.IntegerValue;
CgtpVariableType type = var1.Type;
// Read as raw string
string raw = robot.Cgtp.ReadVariableAsString("$MCR.$GENOVERRIDE");
// Write a variable
robot.Cgtp.WriteVariable("$RMT_MASTER", 1);
robot.Cgtp.WriteVariable("$MCR.$GENOVERRIDE", 50.0);
// Program-scoped variables (Karel)
CgtpVariableValue karelVar = robot.Cgtp.ReadVariable("my_variable", progName: "MY_KAREL");
robot.Cgtp.WriteVariable("my_variable", 42, progName: "MY_KAREL");

Supported types

The variable type is auto-detected. You can access the appropriate typed property:

TypeProperty
IntegerIntegerValue
RealRealValue
BooleanBooleanValue
StringStringValue
CartesianPositionCartesianPositionValue
JointPositionJointPositionValue
VectorVectorValue
ConfigConfigurationValue

Read and Write registers

// Numeric registers
NumericRegisterWithComment reg = robot.Cgtp.ReadNumericRegisterWithComment(1);
Console.WriteLine($"R[1] = {reg.RealValue}, Comment: {reg.Comment}");
NumericRegisterWithComment[] allRegs = robot.Cgtp.ReadNumericRegistersWithComment();
robot.Cgtp.WriteNumericRegisterAsDouble(5, 123.45);
robot.Cgtp.WriteNumericRegisterAsInteger(5, 100);
// Position registers
PositionRegisterWithComment posReg = robot.Cgtp.ReadPositionRegisterWithComment(1);
robot.Cgtp.WritePositionRegisterAsCartesian(1, new CartesianPosition(100, 200, 300, 0, 90, 0));
robot.Cgtp.WritePositionRegisterAsJoint(1, new JointsPosition { J1 = 0, J2 = 0, J3 = 0, J4 = 0, J5 = 0, J6 = 0 });
// String registers
StringRegisterWithComment[] allStr = robot.Cgtp.ReadStringRegistersWithComment();
robot.Cgtp.WriteStringRegister(1, "Hello from CGTP");

Batch variables

Read or write multiple registers and variables in a single HTTP request:

// Create a batch
var batch = new CgtpBatchVariables();
batch.AddNumericRegister(1);
batch.AddNumericRegister(2);
batch.AddStringRegister(1);
batch.AddPositionRegister(1);
batch.AddVariable("$RMT_MASTER");
batch.AddVariable("$MCR.$GENOVERRIDE");
// Read all at once
CgtpBatchReadResult result = robot.Cgtp.ReadBatchVariables(batch);
// Write batch with values
var writeBatch = new CgtpBatchVariables();
writeBatch.AddNumericRegisterAsReal(1, "Speed", 50.0);
writeBatch.AddNumericRegisterAsInteger(2, "Counter", 0);
writeBatch.AddStringRegisterWithValue(1, "Status", "Running");
robot.Cgtp.WriteBatchVariables(writeBatch);

Complete example

using UnderAutomation.Fanuc;
using UnderAutomation.Fanuc.Common;
using UnderAutomation.Fanuc.Cgtp;
using UnderAutomation.Fanuc.Cgtp.BatchVariables;
public class CgtpRegistersVariables
{
public static void Main()
{
FanucRobot robot = new FanucRobot();
ConnectionParameters parameters = new ConnectionParameters("192.168.0.1");
parameters.Cgtp.Enable = true;
robot.Connect(parameters);
/**/
// --- Read variables ---
CgtpVariableValue var = robot.Cgtp.ReadVariable("$RMT_MASTER");
int intVal = var.IntegerValue;
CgtpVariableType type = var.Type;
// Read as raw string
string raw = robot.Cgtp.ReadVariableAsString("$MCR.$GENOVERRIDE");
// Write a variable
robot.Cgtp.WriteVariable("$RMT_MASTER", 1);
robot.Cgtp.WriteVariable("$MCR.$GENOVERRIDE", 50.0);
// --- Program-scoped variables ---
CgtpVariableValue karelVar = robot.Cgtp.ReadVariable("my_variable", progName: "MY_KAREL");
robot.Cgtp.WriteVariable("my_variable", 42, progName: "MY_KAREL");
// --- Numeric registers ---
NumericRegisterWithComment reg = robot.Cgtp.ReadNumericRegisterWithComment(1);
robot.Cgtp.WriteNumericRegisterAsDouble(5, 123.45);
robot.Cgtp.WriteNumericRegisterAsInteger(5, 100);
// --- Position registers ---
PositionRegisterWithComment posReg = robot.Cgtp.ReadPositionRegisterWithComment(1);
robot.Cgtp.WritePositionRegisterAsCartesian(1, new CartesianPosition(100, 200, 300, 0, 90, 0));
robot.Cgtp.WritePositionRegisterAsJoint(1, new JointsPosition { J1 = 0, J2 = 0, J3 = 0, J4 = 0, J5 = 0, J6 = 0 });
// --- String registers ---
StringRegisterWithComment[] allStr = robot.Cgtp.ReadStringRegistersWithComment();
robot.Cgtp.WriteStringRegister(1, "Hello from CGTP");
// --- Batch read ---
var batch = new CgtpBatchVariables();
batch.AddNumericRegister(1);
batch.AddNumericRegister(2);
batch.AddStringRegister(1);
batch.AddPositionRegister(1);
batch.AddVariable("$RMT_MASTER");
CgtpBatchReadResult result = robot.Cgtp.ReadBatchVariables(batch);
// --- Batch write ---
var writeBatch = new CgtpBatchVariables();
writeBatch.AddNumericRegisterAsReal(1, "Speed", 50.0);
writeBatch.AddNumericRegisterAsInteger(2, "Counter", 0);
writeBatch.AddStringRegisterWithValue(1, "Status", "Running");
robot.Cgtp.WriteBatchVariables(writeBatch);
/**/
}
}

API reference

Members of Cgtp.CgtpVariableValue :
public class CgtpVariableValue {
// Value interpreted as a boolean (TRUE/FALSE).
public bool BooleanValue { get; }
// Value interpreted as a Cartesian position.
public CartesianPositionVariable CartesianPositionValue { get; }
// Value interpreted as a robot configuration.
public Configuration ConfigurationValue { get; }
// Value interpreted as an integer.
public int IntegerValue { get; }
// Value interpreted as a joint position.
public JointPositionVariable JointPositionValue { get; }
// Value interpreted as a double-precision floating-point number.
public double RealValue { get; }
// Maximum string length if the variable type is String
public int StringLength { get; }
// Raw string value of the variable
public string StringValue { get; }
public override string ToString()
// Data type of the variable
public CgtpVariableType Type { get; }
// Value interpreted as a 3D vector.
public VectorVariable VectorValue { get; }
}
Members of Cgtp.CgtpVariableType :
public enum CgtpVariableType {
// Boolean value (TRUE or FALSE).
Boolean = 18
// 8-bit byte value.
Byte = 24
// Cartesian position (X, Y, Z, W, P, R with configuration).
CartesianPosition = 2
// Robot configuration string.
Config = 28
// 32-bit integer value.
Integer = 16
// Joint position with up to 9 axes.
JointPose9 = 8601
// Joint position (J1..J9).
JointPosition = 9
// Numeric value that can be either integer or real.
Numeric = 38
// Full position type.
POSITION = 257
// Double-precision floating-point value.
Real = 17
// 16-bit short integer value.
Short = 23
// String value. The actual type code encodes the maximum string length.
String = 7936
// 3D vector (X, Y, Z).
Vector = 19
// XYZWPR position type.
XYZWPR = 256
// Extended XYZWPR position with additional axes.
XYZWPRExt = 262
}
Members of Cgtp.BatchVariables.CgtpBatchVariables :
public class CgtpBatchVariables : IList<ICgtpBatchVariable>, ICollection<ICgtpBatchVariable>, IEnumerable<ICgtpBatchVariable>, IEnumerable {
public CgtpBatchVariables()
public void Add(ICgtpBatchVariable item)
// Add a numeric register for reading. The value and comment will be populated after a batch read.
public CgtpNumericRegister AddNumericRegister(int index)
// Add a numeric register with an integer value and comment for writing.
public CgtpNumericRegister AddNumericRegisterAsInteger(int index, string comment, int value)
// Add a numeric register with a real (double) value and comment for writing.
public CgtpNumericRegister AddNumericRegisterAsReal(int index, string comment, double value)
// Add a position register for reading. The position data will be populated after a batch read.
public CgtpPositionRegister AddPositionRegister(int index, int group = 1)
// Add a position register with a Cartesian position for writing.
public CgtpPositionRegister AddPositionRegisterAsCartesian(int index, CartesianPosition position, int group = 1, string comment = null)
// Add a position register with a joint position for writing.
public CgtpPositionRegister AddPositionRegisterAsJoint(int index, JointsPosition position, int group = 1, string comment = null)
// Add multiple variables at once.
public void AddRange(IEnumerable<ICgtpBatchVariable> items)
// Add a string register for reading. The value and comment will be populated after a batch read.
public CgtpStringRegister AddStringRegister(int index)
// Add a string register with a value and comment for writing.
public CgtpStringRegister AddStringRegisterWithValue(int index, string comment, string value)
// Add a generic variable for reading or writing.
// For system variables, leave <code class="paramref">programName</code> null.
// Set the desired value on the returned object before performing a batch write.
public CgtpVariable AddVariable(string name, string programName = null)
public void Clear()
public bool Contains(ICgtpBatchVariable item)
public void CopyTo(ICgtpBatchVariable[] array, int arrayIndex)
public int Count { get; }
public IEnumerator<ICgtpBatchVariable> GetEnumerator()
public int IndexOf(ICgtpBatchVariable item)
public void Insert(int index, ICgtpBatchVariable item)
public bool IsReadOnly { get; }
public ICgtpBatchVariable this[int index] { get; set; }
public bool Remove(ICgtpBatchVariable item)
public void RemoveAt(int index)
}
Members of Common.NumericRegisterWithComment :
public class NumericRegisterWithComment : NumericRegister {
// Default constructor.
public NumericRegisterWithComment()
// Creates a numeric register with a real value and comment.
public NumericRegisterWithComment(double value, string comment)
// Creates a numeric register with an integer value and comment.
public NumericRegisterWithComment(int value, string comment)
// Creates a numeric register with a comment.
public NumericRegisterWithComment(string comment)
// Comment associated with this register.
public string Comment { get; set; }
public override string ToString()
}
Members of Common.PositionRegisterWithComment :
public class PositionRegisterWithComment : PositionRegister {
// Default constructor.
public PositionRegisterWithComment()
// Comment associated with this position register.
public string Comment { get; set; }
// Parses a position register with comment from its string representation.
public static PositionRegisterWithComment Parse(string value)
}

Easily integrate Universal Robots, Fanuc, Yaskawa, ABB or Staubli robots into your .NET, Python, LabVIEW or Matlab applications

UnderAutomation
Contact usLegal

© All rights reserved.