UnderAutomation
Eine Frage?

[email protected]

Kontakt
UnderAutomation
⌘Q
Fanuc SDK documentation
Overview of TELNET interface
Documentation home

Read and decode files

FTP is a protocol that allows you to read and decode files from a Fanuc robot, such as variables, programs, diagnosis, etc.

  • Manipulate files
  • Read variables
  • Read safety status
  • Read IO State
  • Get current position
  • Try it

FTP (File Transfer Protocol) provides access to internal controller files, as well as fast parsing and decoding, including .va variable files and .dg diagnostic files.

Manipulate files

The SDK lets you send files, download files, rename, delete and more.

Here are some examples :

robot.Ftp.DirectFileHandling.DownloadFileFromController(@"C:\temp\MyPrg.tp", "md:/MyPrg.tp);
robot.Ftp.DirectFileHandling.UploadFileToController(@"C:\temp\MyPrg.tp", "md:/MyPrg.tp);
robot.Ftp.DirectFileHandling.DeleteFile("md:/MyPrg.tp");
robot.Ftp.DirectFileHandling.CreateDirectory("md:/NewDirectory");
robot.Ftp.DirectFileHandling.DeleteDirectory("md:/NewDirectory");

Read variables

Variables are read in bulk (note that TELNET also allows variables to be read one by one).

Variables are also written by TELNET, see previous chapter.

robot.Ftp.KnownVariableFiles allows access to known and commonly used variables on robots.

// Enumerates variables files
FtpListItem[] VariablesFiles = robot.Ftp.EnumerateVariableFiles();
// Get all variables declared in the controller
var allVariables = robot.Ftp.GetAllVariables();
// Get all variables declared in one specific file
var variables = robot.Ftp.GetVariablesFromFile("myFile.va");
// For known variables, you can access it directly.
// Example with $RMT_MASTER :
int RmtMaster = robot.Ftp.KnownVariableFiles.GetSystemFile().RmtMaster;
// Example with CellGrp
CartesianPositionVariable cellFrame = robot.Ftp.KnownVariableFiles.GetSysframeFile().CellGrp[0].CellFrame;
// cellFrame.X => 0.2
// cellFrame.Y => -0.1
// cellFrame.Z => 0
// cellFrame.Configuration.ArmFront => Back
// cellFrame.Configuration.WristFlip => NoFlip
Members of Ftp.FtpListItem :
public class FtpListItem {
// Gets the file permissions in the CHMOD format.
public int Chmod { get; }
// Gets the created date of the object.
public DateTime Created { get; }
// Gets the full path name to the object.
public string FullName { get; }
// Gets the last write time of the object.
public DateTime Modified { get; }
// Gets name to the object.
public string Name { get; }
// Gets the size of the object.
public long Size { get; }
// Gets the type of file system object.
public FtpFileSystemObjectType Type { get; }
}

Read safety status

SafetyStatus safetyStatus = robot.Ftp.GetSafetyStatus();
Members of Ftp.Diagnosis.SafetyStatus :
public class SafetyStatus : IFanucContent {
public SafetyStatus()
public bool BeltBroken { get; }
// External emergency stop active
public bool ExternalEStop { get; }
public bool FenceOpen { get; }
public bool HandBroken { get; }
public bool LowAirAlarm { get; }
// File name : sftysig.dg
public string Name { get; }
public bool NonTeacherEnb { get; }
public bool OverTravel { get; }
// Emergency stop active by SOP signal
public bool SOPEStop { get; }
public bool SVOFFDetect { get; }
// The deadman switch of the teach pendant is active
public bool TPDeadman { get; }
// Emergency stop active on teach peandant
public bool TPEStop { get; }
// Teach pendant is enabled
public bool TPEnable { get; }
}

Read IO State

The SDK rovides a list of IO states. Telnet KCL allows you to write or simulate their status.

IOState ioState = robot.Ftp.GetIOState();
Members of Ftp.Diagnosis.IOState :
public class IOState : IFanucContent {
public IOState()
// File name : iostate.dg
public string Name { get; }
// Status of all controller inputs and outputs
public IOStatus[] States { get; }
}
Members of Common.IOStatus :
public class IOStatus {
public IOStatus()
// Digital port ID
public int Id { get; }
// IO Name
public string Name { get; }
// Digital port type
public DigitalPorts Port { get; }
// String representation like : DIN[1]=True
public override string ToString()
// Digital port value
public bool Value { get; }
}
Members of Common.DigitalPorts :
public enum DigitalPorts {
// Digital input
DIN = 0
// Digital outputs
DOUT = 1
// Flags
FLG = 8
RI = 6
RO = 7
SI = 4
SO = 5
// User inputs
UI = 2
// User outputs
UO = 3
}

Get current position

The SDK allows you to retrieve the robot arm's current position in both joint and Cartesian form, in the world frame and in user frames, with a single function call.

CurrentPosition currentPosition = robot.Ftp.GetCurrentPosition();
Members of Ftp.Diagnosis.CurrentPosition :
public class CurrentPosition : IFanucContent {
public CurrentPosition()
// Position of each robots handled by this controller
public GroupPosition[] GroupsPosition { get; }
// File name : curpos.dg
public string Name { get; }
}
Members of Ftp.Diagnosis.GroupPosition :
public class GroupPosition {
public GroupPosition()
// Group ID
public int Id { get; }
// Joint positions : the position of each robot angles
public JointsPosition JointsPosition { get; }
// Position of each tools in each user frames
public CartesianPositionWithUserFrame[] UserFramePositions { get; }
// Position of each tools in world coordinates
public CartesianPositionWithTool[] WorldPositions { get; }
}
Members of Common.JointsPosition :
public class JointsPosition {
public JointsPosition()
// Joint 1 in degrees
public double J1 { get; set; }
// Joint 2 in degrees
public double J2 { get; set; }
// Joint 3 in degrees
public double J3 { get; set; }
// Joint 4 in degrees
public double J4 { get; set; }
// Joint 5 in degrees
public double J5 { get; set; }
// Joint 6 in degrees
public double J6 { get; set; }
// Joint 7 in degrees
public double J7 { get; set; }
// Joint 8 in degrees
public double J8 { get; set; }
// Joint 9 in degrees
public double J9 { get; set; }
public override string ToString()
// Numeric values for each joints
public double[] Values { get; }
}
Members of Common.CartesianPositionWithUserFrame :
public class CartesianPositionWithUserFrame : CartesianPositionWithTool {
public CartesianPositionWithUserFrame()
// Frame ID in the controller
public int Frame { get; }
}
Members of Common.CartesianPositionWithTool :
public class CartesianPositionWithTool : CartesianPosition {
public CartesianPositionWithTool()
// Tool ID
public int Tool { get; set; }
}
Members of Common.CartesianPositionWithTool :
public class CartesianPositionWithTool : CartesianPosition {
public CartesianPositionWithTool()
// Tool ID
public int Tool { get; set; }
}
Members of Common.CartesianPosition :
public class CartesianPosition : XYZPosition {
public CartesianPosition()
// Position configuration
public Configuration Configuration { get; }
// P rotation in degrees
public double P { get; set; }
// R rotation in degrees
public double R { get; set; }
// W rotation in degrees
public double W { get; set; }
}
Members of Common.XYZPosition :
public class XYZPosition {
public XYZPosition()
// X coordinate in meters
public double X { get; set; }
// Y coordinate in meters
public double Y { get; set; }
// Z coordinate in meters
public double Z { get; set; }
}

Try it

You can download the Windows Example to these features. It can be downloaded from the download page.

File handling


Integrieren Sie problemlos Universal Robots-, Fanuc-, Yaskawa- oder Staubli-Roboter in Ihre .NET-, Python-, LabVIEW- oder Matlab-Anwendungen

UnderAutomation
KontaktPreise • VertriebspartnerAngebot • BestellungLegal

© All rights reserved.