using CHAR8 = char;
using UCHAR = unsigned char;
using UINT8 = std::uint8_t;
using UINT16 = std::uint16_t;
using UINT32 = std::uint32_t;
using UINT64 = std::uint64_t;
using INT8 = std::int8_t;
using INT16 = std::int16_t;
using INT32 = std::int32_t;
using INT64 = std::int64_t;
using DOUBLE64 = std::double_t;
using FLOAT32 = std::float_t;
using CoordinateArray = std::array<DOUBLE64, max_supported_axis>;
using AxisConfigurationData = std::array<CHAR8, max_supported_axis>;
using RegisterData = UINT16;
using IOByteData = std::bitset<8>;
using IOWordData = std::bitset<16>;
Selection of control groups. Encompasses robots, bases and stations.
enum class ControlGroupId
{
R1 = 1, R2, R3, R4, R5, R6, R7, R8,
B1 = 11, B2, B3, B4, B5, B6, B7, B8,
S1 = 21, S2, S3, S4, S5, S6, S7, S8, S9, S10, S11, S12, S13, S14, S15, S16, S17, S18, S19, S20, S21, S22, S23, S24
};
The type of information to be requested from the controller by the GetSystemInfo function.
This includes robots, stations and application number.
enum class SystemInfoId
{
R1 = 11, R2, R3, R4, R5, R6, R7, R8, // Robot number
S1 = 21, S2, S3, S4, S5, S6, S7, S8, S9, S10, S11, S12, S13, S14, S15, S16, S17, S18, S19, S20, S21, S22, S23, S24, // Station number
A1 = 101, A2, A3, A4, A5, A6, A7, A8 //Application number.
};
Used to specify the type of system parameter to be retrieved by the GetSystemParameter function.
enum class SystemParameterType
{
S1CG = 0, /* S1CxG requires group number.*/
S2C = 1, /* S2C */
S3C = 2, /* S3C */
S4C = 3, /* S4C */
RS = 4, /* RS */
AP = 5, /* AxP requires group number*/
SE = 6, /* SxE requires group number*/
};
Type of alarm to retrieve. Used by the GetActiveAlarms and GetAlarmHistory functions.
enum class AlarmCategory { Major = 0, Minor = 1000, UserSystem = 2000, User = 3000, Offline = 4000 };
Activate or deactivate Hold, Servo.
enum class SignalStatus { ON = 1, OFF = 2 };
Category of I/O signal. All signal categories are readable. Writing is limited to NetworkInput.
Additionally, GeneralOutput can be written on YRC1000 or newer controllers.
enum class IOType {
GeneralInput, GeneralOutput, ExternalInput, NetworkInput, ExternalOutput, NetworkOutput,
SpecificInput, SpecificOutput, InterfacePanelInput, AuxiliaryRelay, RobotControlStatus, PsuedoInput
};
Specifies the task to reference when getting the executing job information and Job stack.
enum class InformTaskNumber {
Master, Subtask1, Subtask2, Subtask3, Subtask4, Subtask5, Subtask6,
Subtask7, Subtask8, Subtask9, Subtask10, Subtask11, Subtask12, Subtask13, Subtask14, Subtask15
};
enum class CoordinateType { Pulse = 0, BaseCoordinate = 16, RobotCoordinate = 17, ToolCoordinate = 18, UserCoordinate = 19, MasterTool = 20, Undefined = 55, JointDegrees = 56 };
enum class MoveInterpolationType { NoneSelected, MoveJoint, MoveLinear, MoveCircular };
enum class CycleMode { Step = 0, Cycle, Automatic };
Specifies whether the controller is set to Teach, Play or Remote mode.
enum class ControlMode { Teach = 0, Play, Remote };
Specifies file types for file interface operations.
enum class FileType { Job_JBI, Data_DAT, Condition_CND, Parameter_PRM, System_SYS, Ladder_LST, Log_LOG };
The location of the B axis rotation when viewed from the right side of the robot.
Front: center of the B-axis is to the right of the S-axis rotation center.
Back: center of the B-axis is to the left of the S-axis rotation center.
enum class FrontOrBack { Front, Back };
The angle of the elbow (L and U axis) when viewed by the right side. Upper is less than 180 degrees, lower is greater than 180 degrees.
enum class UpperOrLower { Uppper, Lower };
Flip: B axis is in positive direction (Theta B > = 0 degrees).
NoFlip = B axis is in negative direction (Theta B < 0 degrees).
enum class FlipOrNoFlip { Flip, NoFlip };
Specify if an angle is less than or greater than 180 degrees.
enum class AxisAngle { LessThanOrEqual180, GreaterThan180 };
Type of time to request when calling GetOperatingTime.
enum class TimeType
{
ControllerOnTime = 1,
ServoPowerOnTimeTotal = 10,
ServoPowerOnTimeRobot = 11,
ServoPowerOnTimeStation = 20,
PlayBackTimeTotal = 110,
PlayBackTimeRobot = 111,
PlayBackTimeStation = 120,
MovingTimeTotal = 210,
MovingTimeRobot = 211,
MovingTimeStation = 221,
ApplicationOperationTime = 300
};
Application ex. Arc Welding, Spot Welding, Painting, General Purpose.
On standard pendant, assignments can be found from the main menu under
[System Information]>[Controller Information] under the APPLICATION section.
enum class ApplicationNumber
{
ApplicationOne = 1,
ApplicationTwo,
ApplicationThree,
ApplicationFour,
ApplicationFive,
ApplicationSix,
ApplicationSeven,
ApplicationEight
};
The index of each axis in the CoordinateArray.
example:
CoordinateArray coordArray{};
coordArray[AxisIndex::S] = 1000;
namespace AxisIndex
{
enum PulseAxis { S = 0, L, U, R, B, T, E, W };
enum CartesianAxis { X = 0, Y, Z, Rx, Ry, Rz, Re, Rw };
};
When converting between coordinate types using the KinematicsInterface, specifies the conversion to use.
enum class KinematicConversions
{
JointAngleToCartesianPos, // Convert Joint Angles(in degrees) To Cartesian Position.
PulseToJointAngle, // Convert Pulse position To Joint Angles(in degrees).
JointAngleToPulse, // Convert Joint Angles(in degrees) To Pulse.
PulseToCartesianPos, // Convert Pulse position To Cartesian Position.
CartesianPosToJointAngle,
CartesianPosToPulse
};
Specifies how to solve inverse kinematics when converting from cartesian position. Used when calling ConvertPosition in the Kinematics interface.
enum class KinematicType
{
Default,// Calculate using parameter S2C430 value. 2:Delta, 1:Figure
Delta,// Calculate by prevAngle. If this type is selected, prevAngle must be provided.
Figure //Calculate by the figure set in the position to convert.
};
Representation of the robot's figure. Includes front/back, upper/lower, and flip/no flip in addition to the axis angles.
Axis Angles are represented as either less than or equal to 180 degrees or greater than 180 degrees.
Name | Description |
---|---|
frontOrBack | Location of B-axis rotation. See FrontOrBack. |
upperOrLower | Elbow angle. See UpperOrLower. |
flipOrNoFlip | B-axis flip. See FlipOrNoFlip. |
axisAngles | Angle of an axis. See AxisAngle. |
struct Figure
{
FrontOrBack frontOrBack{};
UpperOrLower upperOrLower{};
FlipOrNoFlip flipOrNoFlip{};
std::array<AxisAngle, max_supported_axis> axisAngles{}; // An array of entries for each axis.
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const Figure& fig);
};
Information about a position. Includes the coordinate type, figure, tool number, user coordinate number, and the position values of the axes.
Name | Description |
---|---|
coordinateType | The type of coordinate system in which the axis data is represented. See CoordinateType. |
figure | Used to represent a robot configuration when the coordinate system is cartesian. See Figure. NOTE: When adding points to the trajectory, the figure information will only be explicitly considered when S2C430 = 1. This is not recommended for most applications. |
toolNumber | The Tool File contains the TCP data for cartesian coordinates. It also contains mass properties for path and PFL calculations. |
userCoordinateNumber | 0 if the coordinate type is anything other than UserCoordinate. |
axisData | Pulse counts for coordinate type pulse, millimeters and joint angles otherwise. |
struct PositionData
{
CoordinateType coordinateType{};
Figure figure{};
UINT32 toolNumber{};
UINT32 userCoordinateNumber{};//Only used when coordinateType is UserCoordinate. otherwise it is 0.
CoordinateArray axisData{};
PositionData() = default;
PositionData(CoordinateType coordType, const Figure& fig, UINT32 toolNum, UINT32 userCoordNumber, const CoordinateArray& coordinates) :
coordinateType(coordType)
, figure(fig)
, toolNumber(toolNum)
, userCoordinateNumber(userCoordNumber)
, axisData(coordinates)
{}
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const PositionData& pos);
};
Type of position vector.
Name | Description |
---|---|
X | X axis value. |
Y | Y axis value. |
Z | Z axis value. |
struct XyzVector
{
DOUBLE64 X{};
DOUBLE64 Y{};
DOUBLE64 Z{};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const XyzVector& xyz);
};
Representation of the pose in 3D space. Includes the position and orientation. Orientation is represented as ZYX-intrinsic (roll, pitch, yaw).
https://en.wikipedia.org/wiki/Rotation_matrix
struct EulerMatrix
{
DOUBLE64 nx{};
DOUBLE64 ny{};
DOUBLE64 nz{};
DOUBLE64 ox{};
DOUBLE64 oy{};
DOUBLE64 oz{};
DOUBLE64 ax{};
DOUBLE64 ay{};
DOUBLE64 az{};
DOUBLE64 px{};
DOUBLE64 py{};
DOUBLE64 pz{};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const EulerMatrix& em);
};
Servo error data. The difference between the command position and the feedback position of each axis.
Name | Description |
---|---|
axisData | Error data for each axis. |
struct PositionErrorData
{
std::array<INT32, max_supported_axis> axisData{};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const PositionErrorData& posErr);
};
Torque data of a control group. Includes the control group ID and the axis torques. Expressed as a percentage.
Name | Description |
---|---|
controlGroupId | Control group ID of the requested data. See ControlGroupId. |
axisData | Torque value for each axis. |
struct TorqueData
{
ControlGroupId controlGroupId{ ControlGroupId::R1 };
std::array<INT32, max_supported_axis> axisData{};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const TorqueData& torque);
};
Used in TimeData structure. Represents the elapsed time in seconds, minutes and hours.
Name | Description |
---|---|
Seconds | Seconds elapsed. |
Minutes | Minutes elapsed. |
Hours | Hours elapsed. |
struct ElapsedTime
{
UINT32 Seconds{};
UINT32 Minutes{};
UINT32 Hours{};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const ElapsedTime& time);
};
Includes the start time and elapsed. Since this structure is used in GetOperatingTime, the elapsed time cooresponds to the TimeType Selected.
Name | Description |
---|---|
startTime | Start time for the requested data. |
elapsedTime | Total elapsed time period for the requested data. |
struct TimeData
{
std::time_t startTime;
ElapsedTime elapsedTime;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const TimeData& time);
};
The software version running on the controller. Also includes the model of the system
or application name requested by ReadSystemInformation.
Name | Description |
---|---|
softwareVersion | Software version of the controller. |
modelName | Model name of the system or application name if requested. |
struct SystemInfoData
{
std::string softwareVersion;
std::string modelName;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const SystemInfoData& sysInfo);
};
All of the information about the controller's state. Includes the running mode, control mode, and hold status.
Name | Description |
---|---|
cycleMode | Current cycle mode of the controller. See CycleMode |
isRunning | True if the controllers equipment is in motion. |
controlMode | Current control mode of the controller. See ControlMode |
isInHold | True if controller is in a hold status. |
isAlarming | True if controller has an active alarm. |
isErroring | True if an error is happening. |
isServoOn | True if the servo is on. |
struct ControllerStateData
{
enum class ControlMode { Teach = 0, Play, Remote };
CycleMode cycleMode;
bool isRunning;
ControlMode controlMode;
bool isInHold;
bool isAlarming;
bool isErroring;
bool isServoOn;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const ControllerStateData& state);
};
The name, line, step number, and speed override of a job. Line cooresponds to the line number of the job. Step number cooresponds to the motion step in the job.
SpeedOverride is expressed as a percentage. 100% is programmed speed. Ranges from 10% to 150%.
Name | Description |
---|---|
name | Current active job. |
line | Active line in active job. |
stepNumber | Current motion step in the active job. |
speedOverride | Speed override for the active job. |
struct JobData
{
std::string name;
UINT32 line;
UINT32 stepNumber;
DOUBLE64 speedOverride;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const JobData& job);
};
The code, subcode, alarm type, time, and name of an alarm.
Name | Description |
---|---|
code | Alarms main code. |
subcode | Alarms subcode. |
time | Time of alarm. |
name | Alarms name. |
struct AlarmData
{
UINT32 code;
UINT32 subcode;
std::string time;
std::string name;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const AlarmData& alarm);
};
A structure containing all of the active alarms on the controller. There can be four alarms at a time.
Name | Description |
---|---|
alarms | Array of active alarms. See AlarmData. |
numberOfActiveAlarms | Amount of active alarms. |
struct ActiveAlarms
{
std::array<AlarmData, max_alarms> alarms;
UINT32 numberOfActiveAlarms;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const ActiveAlarms& activeAlarms);
};
The previous n alarms of the controller. n = numberOfAlarmsFetched. Also includes any active alarms.
Name | Description |
---|---|
alarm | Array of alarms. See AlarmData. |
numberOfAlarmsFetched | Number of alarms in array. |
struct AlarmHistory
{
std::array<AlarmData, alarm_history_size> alarm{};
UINT32 numberOfAlarmsFetched{};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const AlarmHistory& alarmHistory);
};
The value and index of a byte(B) variable.
Name | Description |
---|---|
value | Value of the variable. |
variableIndex | Variables index. |
struct ByteVariableData
{
UINT8 value;
UINT16 variableIndex;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const ByteVariableData& byteVariableData);
};
The value and index of an integer(I) variable.
Name | Description |
---|---|
value | Value of the variable. |
variableIndex | Variables index. |
struct IntegerVariableData
{
INT16 value;
UINT16 variableIndex;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const IntegerVariableData& integerVariableData);
};
The value and index of an double(D) variable.
Name | Description |
---|---|
value | Value of the variable. |
variableIndex | Variables index. |
struct DoubleIntVariableData
{
INT32 value;
UINT16 variableIndex;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const DoubleIntVariableData& doubleIntVariableData);
};
The value and index of a real(R) variable.
Name | Description |
---|---|
value | Value of the variable. |
variableIndex | Variables index. |
struct RealVariableData
{
FLOAT32 value;
UINT16 variableIndex;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const RealVariableData& realVariableData);
};
The value and index of a string(S) variable. Max length is 32 characters.
Name | Description |
---|---|
stringVariableData | Value of the variable. |
variableIndex | Variables index. |
struct StringVariableData
{
std::string stringVariableData;
UINT16 variableIndex;
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const StringVariableData& stringVariableData);
};
The value and index of a robot position(P) variable.
Name | Description |
---|---|
positionData | Value of the variable. See PositionData. |
variableIndex | Variables index. |
struct RobotPositionVariableData
{
PositionData positionData;
UINT16 variableIndex;
RobotPositionVariableData() = default;
RobotPositionVariableData(const PositionData& positionData, UINT16 variableIndex) :
positionData(positionData), variableIndex(variableIndex) {};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const RobotPositionVariableData& robotPositionVariableData);
};
The values and index of a base axis position variable. If the coordinate type is pulse, the pulse counts will be in X.
Name | Description |
---|---|
positionData | Value of the variable. See PositionData. |
variableIndex | Variables index. |
struct BaseAxisPositionVariableData
{
PositionData positionData{};
UINT16 variableIndex{};
BaseAxisPositionVariableData() = default;
BaseAxisPositionVariableData(const PositionData& positionData, UINT16 variableIndex) :
positionData(positionData), variableIndex(variableIndex) {};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const
BaseAxisPositionVariableData& robotPositionVariableData);
};
The value and index of a station position variable.
Name | Description |
---|---|
positionData | Value of the variable. See PositionData. |
variableIndex | Variables index. |
struct StationPositionVariableData
{
PositionData positionData{};
UINT16 variableIndex{};
StationPositionVariableData() = default;
StationPositionVariableData(const PositionData& positionData, UINT16 variableIndex) :
positionData(positionData), variableIndex(variableIndex) {};
YMCONNECT_API friend std::ostream& operator<<(std::ostream& os, const StationPositionVariableData& stationPositionVariableData);
};
Contains the acceleration and deceleration ratios for a motion. These ratios reduce the amount of acceleration and/or deceleration that occurs during a motion. For example, if the acceleration ratio is set to 50%, the robot will accelerate at half of the programmed acceleration rate. If the deceleration ratio is set to 50%, the robot will decelerate at half of the programmed deceleration rate.
Name | Description |
---|---|
accelRatio | Acceleration ratio. Valid range is 20.00%-100.00%. |
decelRatio | Deceleration ratio. Valid range is 20.0%-100.00% |
struct MotionAccelDecel
{
//Will change the acceleration ratio of subsequent motions until changed again. Valid range is 20.00%-100.00%.
DOUBLE64 accelRatio{ DBL_MAX };
//Will change the deceleration ratio of subsequent motions until changed again. Valid range is 20.0%-100.00%
DOUBLE64 decelRatio{ DBL_MAX };
};
Name | Description |
---|---|
groupId | Group to move. See ControlGroupId. |
speed | Speed of the motion. This value is a percentage (0.00 - 100.00) for JointMotion. For LinearMotion and CircularMotion, the value is in mm/sec (0.0 - 1500.0) |
attributes | Acceleration and deceleration rate. See MotionAccelDecel |
interpolationType | Motion interpolation. Note that changing this instead of using the proper derived class can cause undefined behavior. |
accuracy | Optional accuracy for the motion target. Measured in mm. When -1 is specified, the motion planner will plot a smooth trajectory and attempt to maintain velocity by potentially rounding corners. If this rounding must be minimized due to application requirements, you can specify the maximum distance (xxx units) from the target point at which the robot is allowed to deviate. |
|position|Target position of the motion. Note that tool frame coordinate type is not supported at this time. See PositionData.|
Note that changing interpolationType instead of using the proper derived class can cause undefined behavior.
struct Motion
{
ControlGroupId groupId{};
DOUBLE64 speed{}; //Speed of the motion. This value is a percentage (0.00 - 100.00) for JointMotion. For LinearMotion and CircularMotion, the value is in mm/sec (0.0 - 1500.0)
MotionAccelDecel attributes{}; //The acceleration and deceleration ratios for the motion.
MoveInterpolationType interpolationType{ MoveInterpolationType::NoneSelected }; //The interpolation type of the motion.
INT32 accuracy{ -1 };
PositionData position{}; //The position data of the motion.
Motion() = default;
Motion(ControlGroupId groupId, const PositionData& destinationCoords, DOUBLE64 speed, INT32 accuracy = -1, const MotionAccelDecel& attributes = MotionAccelDecel())
: groupId(groupId),
speed(speed),
accuracy(accuracy),
attributes(attributes),
position(destinationCoords)
{}
};
Constructor for a linear motion target. See Motion.
LinearMotion() = default;
LinearMotion(ControlGroupId groupId, const PositionData& destinationCoords, DOUBLE64 speed, INT32 accuracy = -1, const MotionAccelDecel& attributes = MotionAccelDecel())
: Motion(groupId, destinationCoords, speed, accuracy, attributes)
{
interpolationType = MoveInterpolationType::MoveLinear;
}
};
Use this struct to create a joint motion target. See Motion.
struct JointMotion : Motion
{
JointMotion() = default;
JointMotion(ControlGroupId groupId, const PositionData& destinationCoords, DOUBLE64 speed, INT32 accuracy = -1, const MotionAccelDecel& attributes = MotionAccelDecel())
: Motion(groupId, destinationCoords, speed, accuracy, attributes)
{
interpolationType = MoveInterpolationType::MoveJoint;
}
};
Use this struct to create a Circular motion target. This motion target requires an auxillary set of coordinates. This is the passing point used to calculate the arc. See Motion.
Name | Description |
---|---|
auxCoords | Passing point of a circular motion. |
CoordinateArray auxCoords{}; // Passing point.
CircularMotion() = default;
CircularMotion(ControlGroupId groupId, const PositionData& destinationCoords, const CoordinateArray& auxCoords, DOUBLE64 speed, INT32 accuracy = -1, const MotionAccelDecel& attributes = MotionAccelDecel())
: Motion(groupId, destinationCoords, speed, accuracy, attributes),
auxCoords(auxCoords)
{
interpolationType = MoveInterpolationType::MoveCircular;
}
};