4. Communicating over cyclic protocols#
Our robots can also be controlled using the following three cyclic protocols: EtherCAT, EtherNetIP, and PROFINET. These protocols are described in Section 5, Section 6, and Section 7, respectively. While inherently different, they share the same cyclic data format and API, so we will cover all common concepts in this section.
With cyclic protocols, the robot is controlled using cyclic data fields, which are detailed in this section. PLCs use these fields to activate, configure, move, and monitor the robot. The cyclic data payload format is identical across all supported protocols.
Some TCP/IP commands are not available when using cyclic protocols, such as the command
SetNetworkOptions for changing network settings, or the commands for
creating, modifying, and deleting offline programs.
4.1. Types of cyclic protocol commands#
Cyclic data output is used to control the robot’s state, trigger actions, or send motion-related commands. Cyclic data input provides feedback from the robot such as status and joint positions.
Below, we briefly describe how our cyclic protocol API handles each type of action.
4.1.1. Status change commands#
Some fields (bits) directly control the robot’s state, such as:
PauseMotionClearMotionSimModeRecoveryModeBrakesControl
Set these bits to change the robot’s state. The robot confirms completion via the corresponding status bit in the cyclic data input (Section 4.5.1, Section 4.5.2).
Note
Do not rely on cycle count or time delay to confirm a state change. Always check the corresponding confirmation bit (Section 4.5.1, Section 4.5.2) before assuming the robot has completed the state change.
4.1.2. Triggered actions#
Some fields (bits) in the cyclic data directly trigger actions on the robot, such as:
ActivateDeactivateHomeResetErrorResumeMotion
To trigger an action, set the corresponding bit to 1, and clear it (reset it to 0) only after the action is completed. Completion is confirmed by the corresponding status bit in the cyclic data input (Section 4.5.1, Section 4.5.2).
Note
Do not rely on cycle count or time delay to confirm action completion. Always check the corresponding confirmation bit (Section 4.5.1, Section 4.5.2) before assuming the robot has completed the action.
4.3. Cyclic data format#
The robot cyclic data includes output fields for sending commands and actions to the robot, as well as input fields that report the complete robot status, position, and configuration.
Section 4.4 and Section 4.5 provide the necessary details to identify each field across all supported cyclic protocols. The binary format of the cyclic data is identical for all protocols.
Protocol-specific details are provided in Section 5, Section 6, and Section 7.
You will also find standard cyclic protocol definition files in the robot firmware package:
EtherNetIP:
Meca500_vX.X.X.X.edsPROFINET:
GSDML-V2.42-Mecademic-meca500-XXXXXXXX.xmlEtherCAT:
Meca500_EtherCAT_ESI_vX.X.X.X.xml
These files can be imported into your PLC to automatically describe the robot and populate a structure with all its cyclic fields.
4.4. Cyclic output format#
The cyclic output (sent to the robot) contains fields for sending commands and actions.
The total size of the cyclic output is 60 bytes, divided into the following sections:
Robot control: Controls the general robot state (activation, simulation mode, recovery mode, etc.);
Motion control: Controls robot motion (pausing, resuming, sending motion commands, etc.);
Motion-related commands: ID and arguments of the command to execute;
Host time: Synchronizes the robot’s time with the host time;
Brake control: Controls the robot’s brakes when deactivated;
Dynamic data configuration: Selects which dynamic data the robot reports in its cyclic input payload.
4.4.1. Robot control#
The RobotControl section in the cyclic output controls general robot states. Changes to bits in this
output trigger robot actions, depending on the conditions.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Bool |
0:0 |
1 |
1600h:1 |
Deactivates the robot (see
DeactivateRobot) when set to 1.Deactivation is confirmed by the
Activated status bit (Section 4.5.1). |
|
Bool |
0:1 |
1 |
1600h:2 |
Activates the robot (see
ActivateRobot) when set to 1, but only if the Deactivate bit is 0.Activation is confirmed by the
Activated status bit (Section 4.5.1). |
|
Bool |
0:2 |
1 |
1600h:3 |
Homes the robot (see
Home) when set to 1 (if the robot is activated but not yet homed).Homing is confirmed by the
Homed status bit (Section 4.5.1). |
|
Bool |
0:3 |
1 |
1600h:4 |
Resets the error (see
ResetError) when set to 1.The reset is confirmed when
ErrorCode becomes 0 (Section 4.5.1). |
|
Bool |
0:4 |
1 |
1600h:5 |
Enables (set to 1) or disables (set to 0) the default simulation mode type (only applies when the robot is deactivated and has no safety stop signal). See
ActivateSim.The simulation mode status is confirmed by the
SimActivated bit (Section 4.5.1). Note that the type of simulation mode (fast or normal) is not reported in cyclic protocols. Also, to change the default simulation mode type, use the TCP command SetSimModeCfg. |
|
Bool |
0:5 |
1 |
1600h:6 |
Enables (set to 1) or disables (set to 0) recovery mode (see
SetRecoveryMode).The recovery mode state is confirmed by the
RecoveryMode status bit (Section 4.5.1). |
|
Bool |
0:6 |
1 |
1600h:7 |
Disables the EtherCAT protocol when set to 1. |
(Reserved) |
0:7 |
25 |
Reserved for future use. |
4.4.2. Motion control#
The MotionControl section in the cyclic output controls robot motion. Changes to
bits in this output trigger robot actions, depending on the conditions.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
4 |
16 |
1601h:1 |
A user-defined number. Changing it triggers the command specified in
MotionCommandID to be added to the motion queue.Reception of the command is confirmed by the
MoveID status bit (Section 4.5.2).See Section 4.2 for details.
|
|
Bool |
6:0 |
1 |
1601h:2 |
Must be set to 1 for commands to be sent to the robot.
See Section 4.2 for details.
|
|
Bool |
6:1 |
1 |
1601h:3 |
Pauses robot motion without clearing commands in the queue
(
PauseMotion).Pause is confirmed by the
Paused status bit
(Section 4.5.2). |
|
Bool |
6:2 |
1 |
1601h:4 |
Clears the motion queue and pauses the robot (
ClearMotion).This action is confirmed by the
Cleared status bit
(Section 4.5.2).Once confirmed, this bit can be reset; robot motion remains paused and new commands can be
added to the motion queue (but will only execute once motion is resumed).
Note that as long as the
ClearMotion bit is set, the robot will refuse to add any commands to
the motion queue. |
|
Bool |
6:3 |
1 |
1601h:5 |
A rising edge (value changed from 0 to 1) resumes robot motion
(
ResumeMotion) if the following conditions are met:-
PauseMotion and ClearMotion are cleared;- No safety stop signals are active.
Resuming also clears resettable safety stops (such as P-Stop 2 or enabling
device released safety stop signals).
It also clears collision and work zone events.
Motion resume is confirmed when the
Paused status bit is cleared
(Section 4.5.2). |
|
Bool |
6:4 |
1 |
1601h:6 |
When set, the robot interprets float arguments (Section 4.4.3)
as the cyclic ID of variables to use as function arguments.
See Managing variables with cyclic protocols for details.
|
(Reserved) |
6:5 |
11 |
Reserved for future use. Must be 0. |
4.4.3. Motion-related commands#
The MotionCommand section in the cyclic output is used to specify the command to
execute (Table 6) and its arguments
(Table 7).
The list of valid MotionCommandID values is provided in
Table 8, along with the expected arguments for each command.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
8 |
32 |
1602h:1 |
The ID of the motion-related command to execute.
See Table 8 for command IDs and
Using motion-related commands for more information.
|
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Real |
12 |
32 |
1602h:2 |
First argument of the motion-related command, if applicable. |
|
Real |
16 |
32 |
1602h:3 |
First argument of the motion-related command, if applicable. |
|
Real |
20 |
32 |
1602h:4 |
First argument of the motion-related command, if applicable. |
|
Real |
24 |
32 |
1602h:5 |
First argument of the motion-related command, if applicable. |
|
Real |
28 |
32 |
1602h:6 |
First argument of the motion-related command, if applicable. |
|
Real |
32 |
32 |
1602h:7 |
First argument of the motion-related command, if applicable. |
ID |
Description |
|---|---|
0 |
No movement: all six arguments are ignored. |
1 |
|
2 |
|
3 |
|
4 |
|
5 |
|
6 |
|
7 |
|
8 |
|
9 |
|
10 |
|
11 |
|
12 |
|
13 |
|
14 |
|
15 |
|
16 |
|
17 |
|
18 |
Gripper action: argument 1 is 0 for |
19 |
|
20 |
|
21 |
|
22 |
|
23 |
|
24 |
|
25 |
|
26 |
|
27 |
|
28 |
|
29 |
|
30 |
|
31 |
|
32 |
|
33 |
|
34 |
|
35 |
|
36 |
|
37 |
|
38 |
|
39 |
|
40 |
|
41 |
|
42 |
|
43 |
|
44 |
|
45 |
|
46 |
|
47 |
|
48 |
|
49 |
|
50 |
|
51 |
|
60 |
|
100 |
|
150 |
|
151 |
|
152 |
|
153 |
|
154 |
|
155 |
|
156 |
|
200 |
|
1002 |
Clear robot homing, forcing drive reinitialization on the next activation,
similar to |
10,000 to 19,999 |
Set a robot variable (see Setting a variable) |
† Argument count and type match those of the related TCP/IP command. Extra arguments are ignored.
4.4.4. Host time#
The HostTime section in the cyclic output synchronizes the robot’s date/time with
the host’s (see SetRtc).
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
36 |
32 |
1610h:1 |
Current time in seconds since UNIX epoch (00:00:00 UTC, January 1, 1970).
If non-zero, the robot updates its time to this value
(same as
SetRtc).This ensures accurate timestamps in robot logs, as the robot resets its time on reboot.`
|
4.4.5. Brake control#
The BrakesControl section in the cyclic output controls the robot’s brakes when it
is deactivated.
The robot has brakes on joints 1, 2, and 3.
The brakes behave as follows:
Brakes disengage automatically when the robot is activated (it holds position when not moving);
Brakes engage automatically when the robot is deactivated (including safety signals or power off);
While deactivated, the brakes can be controlled using the fields in Table 10.
Danger
Disable brakes with caution; without brakes, all links will collapse downward. The brakes control fields will be removed in the upcoming firmware release.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Bool |
40:0 |
1 |
1611h:1 |
Must be set to 1 to allow brakes control through cyclic data.
This bit ensures that the brakes are not inadvertently disengaged if cyclic data
sent to the robot contains all zeros.
|
|
Bool |
40:1 |
1 |
1611h:2 |
If set to 1, the brakes are engaged.
If 0, the brakes are disengaged, and the robot may fall under the effects of
gravity.
This bit is ignored if the
BrakesControlAllowed bit is cleared or if the
robot is activated. |
(Reserved) |
40:2 |
30 |
Reserved for future use. Must be 0. |
4.4.6. Dynamic data configuration#
The DynamicDataConfiguration section in the cyclic output determines which dynamic
data the robot
reports in each of the 4 available dynamic-data slots in its cyclic input payload.
When a specific dynamic data type is chosen (in Table 11), the robot will return the corresponding values in Table 22, Table 23, Table 24, or Table 25.
If dynamic data type 0 (Automatic) is used, the robot cycles through available
dynamic data types, reporting a different type each cycle.
See Table 12 for a list of available dynamic data types.
Note
A delay of one or two cycles may occur before a change to the requested dynamic data type takes effect.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
44:0 |
32 |
1620h:1 |
Dynamic data type for index #0 (see Table 12). |
|
Integer |
48:0 |
32 |
1621h:1 |
Dynamic data type for index #1 (see Table 12). |
|
Integer |
52:0 |
32 |
1622h:1 |
Dynamic data type for index #2 (see Table 12). |
|
Integer |
56:0 |
32 |
1623h:1 |
Dynamic data type for index #3 (see Table 12). |
ID |
Description |
|---|---|
0 |
Automatic.The robot will automatically choose a dynamic data type and change it every
cycle, going through all of them in around-robin manner.
This is the easiest way for the host to receive all possible values
periodically.
|
1 |
Firmware version (GetFwVersion).Values: [major version, minor version, patch version, build number].
|
2 |
Product type (GetProductType).Values: [product type] where 3 = Meca500 R3, 4 = Meca500 R4, 20 = MCS500 R1.
|
3 |
Serial number (GetRobotSerial).Values: [serial number as a 32 bits float, serial number as a 32 bits unsigned integer].
Please use the integer value. The float version may not properly represent large serial numbers
and remains available only for backward compatibility.
|
4–10 |
Reserved. |
11 |
Joint limits configuration (GetJointLimitsCfg).Values: [1/0].
|
12 |
Model joint limits (GetModelJointLimits), for joints 1, 2, and 3.Values: [q1,min, q2,min, q3,min, q1,max, q2,max, q3,max], in °.
|
13 |
Model joint limits (GetModelJointLimits), for joints 4, 5, and 6.Values: [q4,min, q5,min, q6,min, q4,max, q5,max, q6,max], in °.
|
14 |
Effective joint limits (GetJointLimits), for joints 1, 2, and 3.Values: [q1,min, q2,min, q3,min, q1,max, q2,max, q3,max], in °.
|
15 |
Effective joint limits (GetJointLimits), for joints 4, 5, and 6.Values: [q4,min, q5,min, q6,min, q4,max, q5,max, q6,max], in °.
|
17 |
Work zone configuration (GetWorkZoneCfg).Values: [work zone limits severity, work zone limits detection mode].
|
18 |
Work zone limits (GetWorkZoneLimits).Values: [xmin, ymin, zmin, xmax, ymax, zmax], in mm.
|
19 |
Tool sphere (GetToolSphere).Values: [x, y, z, r], in mm.
|
20 |
Values: [shoulder −1/1/NaN, elbow −1/1/NaN, wrist −1/1/NaN, last joint turn or NaN].
NaN indicates auto-conf or auto-conf-turn.
|
21 |
Values: [blending ratio percent, velocity timeout in seconds].
|
22 |
Motion queue velocities and accelerations (GetJointVel, GetJointAcc, GetCartLinVel, GetCartAngVel, GetCartAcc, GetJointVelLimit).Values: [joint velocity, joint acceleration, Cartesian linear velocity, Cartesian angular velocity, Cartesian acceleration, joint velocity limit], in percent.
|
23 |
Values: [gripper force, gripper velocity, fingers opening corresponding to closed state, fingers opening corresponding to open state].
Arguments 1 and 2 are in percentage, while arguments 3 and 4 are in mm.
|
24 |
Torque limits configuration (GetTorqueLimitsCfg).Values: [severity, detection mode].
|
25 |
Torque limits (GetTorqueLimits).Values: [motor 1 limit, motor 2 limit, …], in percent.
|
26 |
Values: [holdThreshold, releaseThreshold, purgeDuration].
Arguments 1 and 2 are in kPa, argument 3 is in seconds.
|
27 |
|
28 |
|
29 |
Values: [move mode, severity, duration].
|
30 |
Values: [calibrationEnabled, calibrated].
|
31 |
Robot payload (GetPayload).Values: [m, cx, cy, cz], in kg or mm.
|
32 |
Target real-time joint velocity (GetRtTargetJointVel).Values: [ω1, ω2, …], in °/s.
|
33 |
Target real-time joint torque (GetRtTargetJointTorq).Values: [motor 1 torque, motor 2 torque, …], in percent.
|
34 |
Target real-time Cartesian velocity (GetRtTargetCartVel).Values: [ẋ, ẏ, ż, ωx, ωy, ωz], in mm/s or °/s.
|
36 |
Collision configuration (GetCollisionCfg).Values: [collision severity level].
|
37 |
Collision status (GetCollisionStatus).Values: [collision boolean state, group of colliding object 1, ID of colliding object 1, group of colliding object 2, ID of colliding object 2].
|
38 |
Work zone status (GetWorkZoneStatus).Values: [work zone breach Boolean state, group of object in breach, ID of object in breach].
|
40 |
Actual joint position (GetRtJointPos).Values: [q1, q2, q3, …]. Unit is °.
|
41 |
Actual end-effector pose ( GetRtCartPos).Values: [x, y, z, α, β, γ]. Units are mm or °.
|
42 |
Actual joint velocity (GetRtJointVel).Values: [ω1, ω2, …], in °/s.
|
43 |
Actual joint torque (GetRtJointTorq).Values: [joint 1 torque, joint 2 torque, …], in percent.
|
44 |
Actual Cartesian velocity (GetRtCartVel).Values: [ẋ, ẏ, ż, ωx, ωy, ωz], in mm/s or °/s.
|
45 |
Values: [shoulder −1/0/1, elbow −1/0/1, wrist −1/0/1, last joint turn].
|
46 |
Accelerometer (GetRtAccelerometer).Values: [ax, ay, az], in 1/16,000 of G.
|
52 |
External tool status (GetRtExtToolStatus).Values: [type, homing done, error state, overheated].
|
53 |
EOAT status.Values: [holding part, desired fingers opening reached, gripper closed, gripper open, gripper force, fingers opening].
In the case of the MPM500 pneumatic module:
GetRtValveState.Values: [valve 1 state, valve 2 state].
|
54 |
Time scaling (GetTimeScaling).Values: [p], in percent.
|
55 |
Not available on this robot. |
56 |
Not available on this robot. |
61 |
Configured joint limits (GetJointLimits), for joints 1, 2, and 3 (ignored if joint limits are disabled).Values: [q1,min, q2,min, q3,min, q1,max, q2,max, q3,max], in °.
|
62 |
Configured joint limits (GetJointLimits), for joints 4, 5, and 6 (ignored if joint limits are disabled).Values: [q4,min, q5,min, q6,min, q4,max, q5,max, q6,max], in °.
|
72 |
Not available on this robot. |
73 |
Not available on this robot. |
10,000 to 19,999 |
A |
Note
Each DynamicDataTypeID returns six values as defined in
Section 4.5.10. Unused values are set to 0. For example, ID 19
provides four meaningful values, and the last two are 0.
Note
No dynamic data IDs are defined for information that is already available in other cyclic data fields, such as Target joint set, Target end-effector pose, Target configuration, Target WRF, etc. See Cyclic input format for details.
4.5. Cyclic input format#
The cyclic input (received from the robot) provides the complete status, position, and configuration of the robot.
The total size of the cyclic input is 252 bytes, divided into the following sections:
Robot status: General robot state (e.g., activation, simulation mode, recovery mode, etc.);
Motion status: Robot motion status (e.g., paused state, motion queue status, and other motion-related conditions);
Target joint set: Real-time calculated joint positions (
GetRtTargetJointPos);Target end-effector pose: Real-time calculated Cartesian position (
GetRtTargetCartPos);Target configuration: Real-time calculated shoulder, elbow, wrist, and turn configuration (
GetRtTargetConfandGetRtTargetConfTurn);Target WRF: World Reference Frame used in the real-time calculated position (
GetRtWrf,GetWrf);Target TRF: Tool Reference Frame used in the real-time calculated position (
GetRtTrf,GetTrf);Robot timestamp: Precise monotonic robot timestamp associated with this cyclic data (
GetRtc);Safety status: Safety-related information (e.g., safety signals, power supply states, operating mode);
Dynamic data: Additional robot information not included in the above; contents may vary.
4.5.1. Robot status#
The RobotStatus section in the cyclic input reports the general robot state (similar to GetStatusRobot).
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Bool |
0:0 |
1 |
1A00h:2 |
True only while the robot is being activated, homed, or deactivated. |
|
Bool |
0:1 |
1 |
1A00h:3 |
Indicates whether the motors are on (powered). |
|
Bool |
0:2 |
1 |
1A00h:4 |
Indicates whether the robot is homed and ready to receive motion commands. |
|
Bool |
0:3 |
1 |
1A00h:5 |
Indicates whether the robot simulation mode is activated. |
|
Bool |
0:4 |
1 |
1A00h:6 |
Indicates whether the brakes are engaged. |
|
Bool |
0:5 |
1 |
1A00h:7 |
Indicates whether the robot recovery mode is activated. |
|
Bool |
0:6 |
1 |
1A00h:8 |
Indicates whether the emergency stop safety signal is activated.
Deprecated; use
EStop bit from SafetyStatus instead. |
|
Bool |
0:7 |
1 |
1A00h:9 |
Indicates whether the robot has detected an imminent collision ( |
|
Bool |
1:0 |
1 |
1A00h:10 |
Indicates whether the robot has detected a work zone breach ( |
|
Bool |
1:1 |
1 |
1A00h:11 |
1 if this connection with the robot only allows monitoring, not controlling. |
(Reserved) |
1:2 |
6 |
Reserved for future use. |
||
|
Integer |
2 |
16 |
1A00h:1 |
Indicates the error code (see Table 1 and Table 3) or 0, if there is no error. |
4.5.2. Motion status#
The MotionStatus section in the cyclic input reports the robot’s motion status
(similar to GetStatusRobot).
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
4 |
16 |
1A01h:1 |
Indicates the last checkpoint number reached (
GetCheckpoint).The value remains the same until another checkpoint is reached.
|
|
Integer |
6 |
16 |
1A01h:2 |
Indicates the last checkpoint number discarded (
GetCheckpointDiscarded).The value remains unchanged until another checkpoint is discarded.
|
|
Integer |
8 |
16 |
1A01h:3 |
Acknowledges the
MoveID of the last command the robot received (Motion control).For details, refer to Using motion-related commands.
|
|
Integer |
10 |
16 |
1A01h:4 |
The number of commands that can be added to the robot’s motion queue at any time (the maximum is 13,000).
If 0 (too many commands sent), subsequent commands will be ignored.
|
|
Bool |
12:0 |
1 |
1A01h:6 |
Indicates whether motion is paused.
This bit stays set (and the robot remains paused) until motion is resumed with Motion control bit
ResumeMotion. |
|
Bool |
12:1 |
1 |
1A01h:7 |
The End of Block (
EOB) bit is set when the robot is not moving and there are no motion commands left in the queue.Note that the
EOB bit may occasionally be set before all commands are completed due to network or processing delays.Therefore, don’t rely on this flag to determine when all movements have finished. Use a checkpoint instead (
SetCheckpoint). |
|
Bool |
12:2 |
1 |
1A01h:8 |
The End of Motion (
EOM) bit is set when the robot is not moving.Note that the
EOM bit may occasionally be set between two consecutive motion commands.Therefore, do not rely on this flag to determine when all movements have finished. Use a checkpoint instead (
SetCheckpoint). |
|
Bool |
12:3 |
1 |
1A01h:9 |
Indicates whether the motion queue is cleared. When set, the
robot is not moving and resuming motion will not execute any pending command.
This bit resets when new commands are added to the motion queue or when motion is resumed
(using the Motion control bit
ResumeMotion).Note that this bit remains set (and no commands can be added to the motion queue) under the
following conditions:
(1) the robot is deactivated,
(2) the cyclic bit
ClearMotion is set (Motion control),(3) the robot is in an error state,
(4) a
P-Stop safety signal is present and configured to clear motion (SetPStop2Cfg). |
|
Bool |
12:4 |
1 |
1A01h:10 |
Indicates whether the SWStop safety signal is set.
Deprecated; use the
PStop2 bit from SafetyStatus instead. |
|
Bool |
12:5 |
1 |
1A01h:11 |
Indicates whether a joint torque is exceeding the corresponding user-defined
torque limit (
SetTorqueLimits, GetTorqueLimitsStatus). |
(Reserved) |
12:6 |
10 |
Reserved for future use. |
||
|
Integer |
14 |
16 |
1A01h:5 |
ID of the offline program currently running; 0 if none (
StartProgram). |
4.5.3. Target joint set#
The TargetJointSet section in the cyclic input reports the robot’s real-time calculated joint position
(similar to GetRtTargetJointPos).
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Real |
16 |
32 |
1A02h:1 |
Real-time calculated target position for joint 1, in °.
|
|
Real |
20 |
32 |
1A02h:2 |
Real-time calculated target position for joint 2, in °.
|
|
Real |
24 |
32 |
1A02h:3 |
Real-time calculated target position for joint 3, in °.
|
|
Real |
28 |
32 |
1A02h:4 |
Real-time calculated target position for joint 4, in °.
|
|
Real |
32 |
32 |
1A02h:5 |
Real-time calculated target position for joint 5, in °.
|
|
Real |
36 |
32 |
1A02h:6 |
Real-time calculated target position for joint 6, in °.
|
4.5.4. Target end-effector pose#
The TargetEndEffectorPose section in the cyclic input reports the robot’s real-time
calculated Cartesian position of the origin of the TRF with respect to
the WRF (similar to GetRtTargetCartPos).
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Real |
40 |
32 |
1A03h:1 |
X coordinate of the origin of the TRF with respect to the WRF, in mm.
|
|
Real |
44 |
32 |
1A03h:2 |
Y coordinate of the origin of the TRF with respect to the WRF, in mm.
|
|
Real |
48 |
32 |
1A03h:3 |
Z coordinate of the origin of the TRF with respect to the WRF, in mm.
|
|
Real |
52 |
32 |
1A03h:4 |
α Euler angle representing the orientation of the TRF with respect to the WRF, in °.
|
|
Real |
56 |
32 |
1A03h:5 |
β Euler angle representing the orientation of the TRF with respect to the WRF, in °.
|
|
Real |
60 |
32 |
1A03h:6 |
γ Euler angle representing the orientation of the TRF with respect to the WRF, in °.
|
4.5.5. Target configuration#
The TargetConfiguration section in the cyclic input reports robot real-time posture
and turn configurations that correspond to the calculated joint set
(GetRtTargetConf, GetRtTargetConfTurn). For more details, see
Section 2.2.1.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
64 |
8 |
1A08h:1 |
Real-time shoulder posture configuration corresponding to the calculated joint position.
The value is typically −1 or 1 but may also be 0 when the robot is near the shoulder singularity.
See Section 2.2.1.
|
|
Integer |
65 |
8 |
1A08h:2 |
Real-time elbow posture configuration corresponding to the calculated joint position.
The value is typically −1 or 1 but may also be 0 when the robot is near the elbow singularity.
See Section 2.2.1.
|
|
Integer |
66 |
8 |
1A08h:3 |
Real-time wrist posture configuration corresponding to the calculated joint position.
The value is typically −1 or 1 but may also be 0 when the robot is near the wrist singularity.
See Section 2.2.1.
|
|
Integer |
67 |
8 |
1A08h:4 |
Real-time turn configuration for the last joint.
See Section 2.2.1.
|
4.5.6. Target WRF#
The TargetWrf section in the cyclic input reports the WRF (with respect of the BRF)
used for reporting the current end-effector pose
(Target end-effector pose), similar to the GetRtWrf and
GetWrf command.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Real |
68 |
32 |
1A09h:1 |
X coordinate of the origin of the WRF with respect to the BRF, in mm.
|
|
Real |
72 |
32 |
1A09h:2 |
Y coordinate of the origin of the WRF with respect to the BRF, in mm.
|
|
Real |
76 |
32 |
1A09h:3 |
Z coordinate of the origin of the WRF with respect to the BRF, in mm.
|
|
Real |
80 |
32 |
1A09h:4 |
α Euler angle representing the orientation of the WRF with respect to the BRF, in °.
|
|
Real |
84 |
32 |
1A09h:5 |
β Euler angle representing the orientation of the WRF with respect to the BRF, in °.
|
|
Real |
88 |
32 |
1A09h:6 |
γ Euler angle representing the orientation of the WRF with respect to the BRF, in °.
|
4.5.7. Target TRF#
The TargetTrf section in the cyclic input reports the TRF (with respect of the FRF)
used for reporting the current end-effector pose
(Target end-effector pose), similar to the GetRtTrf and
GetTrf commands.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Real |
92 |
32 |
1A0Ah:1 |
X coordinate of the origin of the TRF with respect to the FRF, in mm.
|
|
Real |
96 |
32 |
1A0Ah:2 |
Y coordinate of the origin of the TRF with respect to the FRF, in mm.
|
|
Real |
100 |
32 |
1A0Ah:3 |
Z coordinate of the origin of the TRF with respect to the FRF, in mm.
|
|
Real |
104 |
32 |
1A0Ah:4 |
α Euler angle representing the orientation of the TRF with respect to the FRF, in °.
|
|
Real |
108 |
32 |
1A0Ah:5 |
β Euler angle representing the orientation of the TRF with respect to the FRF, in °.
|
|
Real |
112 |
32 |
1A0Ah:6 |
γ Euler angle representing the orientation of the TRF with respect to the FRF, in °.
|
4.5.8. Robot timestamp#
The RobotTimestamp section in the cyclic input reports a precise, monotonic robot
timestamp associated with the cyclic data (similar to the command GetRtc).
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
116 |
32 |
1A10h:1 |
Robot’s monotonic timestamp in seconds, based on an arbitrary reference. |
|
Integer |
120 |
32 |
1A10h:2 |
Robot’s monotonic timestamp in microseconds, within the current second. |
|
Integer |
124 |
32 |
1A10h:3 |
Incremented each time the robot cycles through all available dynamic data to
report.
Applies only if at least one dynamic data slot
(Table 11) is configured with ID 0
(
Automatic). |
4.5.9. Safety status#
The SafetyStatus section in the cyclic input reports safety-related information
(safety signals, power supply input states, operating mode, etc.). See
Management of errors and safety stops.
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Bool |
128:0 |
1 |
1A11h:1 |
E-Stop safety stop signal state† |
|
Bool |
128:1 |
1 |
1A11h:2 |
Not supported on the Meca500 |
|
Bool |
128:2 |
1 |
1A11h:3 |
P-Stop 2 safety stop signal state† |
(Reserved) |
128:3 |
1 |
Reserved for future use. |
||
|
Bool |
128:4 |
1 |
1A11h:5 |
Not supported on the Meca500 |
|
Bool |
128:5 |
1 |
1A11h:6 |
Not supported on the Meca500 |
|
Bool |
128:6 |
1 |
1A11h:7 |
Not supported on the Meca500 |
|
Bool |
128:7 |
1 |
1A11h:8 |
Not supported on the Meca500 |
|
Bool |
129:0 |
1 |
1A11h:9 |
Not supported on the Meca500 |
|
Bool |
129:1 |
1 |
1A11h:10 |
Not supported on the Meca500 |
|
Bool |
129:2 |
1 |
1A11h:11 |
TCP/IP connection dropped safety stop signal state† |
|
Bool |
129:3 |
1 |
1A11h:12 |
Not supported on the Meca500 |
(Reserved) |
129:4 |
20 |
Reserved for future use. |
||
|
Bool |
132:0 |
1 |
1A11h:33 |
(Only on Meca500 R4) E-Stop safety stop signal ready to be reset (Reset button) |
|
Bool |
132:1 |
1 |
1A11h:34 |
Not supported on the Meca500 |
|
Bool |
132:2 |
1 |
1A11h:35 |
P-Stop 2 safety stop signal ready to be reset (with |
(Reserved) |
132:3 |
1 |
Reserved for future use. |
||
|
Bool |
132:4 |
1 |
1A11h:37 |
Not supported on the Meca500 |
|
Bool |
132:5 |
1 |
1A11h:38 |
Not supported on the Meca500 |
|
Bool |
132:6 |
1 |
1A11h:39 |
Not supported on the Meca500 |
|
Bool |
132:7 |
1 |
1A11h:40 |
Not supported on the Meca500 |
|
Bool |
133:0 |
1 |
1A11h:41 |
Always 0. A redundancy fault requires rebooting the robot; it cannot be reset. |
|
Bool |
133:1 |
1 |
1A11h:42 |
Not supported on the Meca500 |
|
Bool |
133:2 |
1 |
1A11h:43 |
Connection dropped safety stop signal ready to be reset (with |
|
Bool |
133:3 |
1 |
1A11h:44 |
Not supported on the Meca500 |
(Reserved) |
133:4 |
20 |
Reserved for future use. |
||
|
Integer |
136 |
8 |
1A11h:65 |
Not supported on the Meca500 |
|
Bool |
137:0 |
1 |
1A11h:66 |
(Only on Meca500 R4) If no more safety signals causing motor power to be removed are present, and the robot is ready to be reset with the Reset button |
|
Bool |
137:1 |
1 |
1A11h:67 |
Robot motors powered or not |
(Reserved) |
137:2 |
6 |
Reserved for future use |
||
|
Bool |
138:0 |
1 |
1A11h:74 |
Not supported on the Meca500 |
|
Bool |
138:1 |
1 |
1A11h:75 |
Not supported on the Meca500 |
|
Bool |
138:2 |
1 |
1A11h:76 |
Not supported on the Meca500 |
|
Bool |
138:3 |
1 |
1A11h:77 |
Not supported on the Meca500 |
|
Bool |
138:4 |
1 |
1A11h:78 |
Not supported on the Meca500 |
|
Bool |
138:5 |
1 |
1A11h:79 |
Not supported on the Meca500 |
(Reserved) |
138:6 |
10 |
Reserved for future use. |
† 1 when safety signal is present or resettable, 0 when safety signal has been successfully reset
4.5.10. Dynamic data#
The DynamicData section in the cyclic input reports additional robot information
that is not covered by other cyclic input fields.
The contents of each dynamic data slot are controlled by
Table 11. Slots can be set to a specific dynamic data
type (Table 12) or configured in Automatic mode. In
Automatic mode, the robot cycles through all available dynamic data types every
cycle, prioritizing types whose values have changed. As a result, all data changes are
generally reported within a few cycles (typically ~3–5, although it can take longer if
many data points change at once).
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
140 |
32 |
1A20h:1 |
Dynamic data type (see Table 12 for available values). |
|
Real |
144 |
32 |
1A20h:2 |
Value index 0 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
148 |
32 |
1A20h:3 |
Value index 1 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
152 |
32 |
1A20h:4 |
Value index 2 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
156 |
32 |
1A20h:5 |
Value index 3 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
160 |
32 |
1A20h:6 |
Value index 4 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
164 |
32 |
1A20h:7 |
Value index 5 (the meaning depends on the
DynamicType, see Table 12). |
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
168 |
32 |
1A21h:1 |
Dynamic data type (see Table 12 for available values). |
|
Real |
172 |
32 |
1A21h:2 |
Value index 0 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
176 |
32 |
1A21h:3 |
Value index 1 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
180 |
32 |
1A21h:4 |
Value index 2 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
184 |
32 |
1A21h:5 |
Value index 3 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
188 |
32 |
1A21h:6 |
Value index 4 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
192 |
32 |
1A21h:7 |
Value index 5 (the meaning depends on the
DynamicType, see Table 12). |
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
196 |
32 |
1A22h:1 |
Dynamic data type (see Table 12 for available values). |
|
Real |
200 |
32 |
1A22h:2 |
Value index 0 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
204 |
32 |
1A22h:3 |
Value index 1 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
208 |
32 |
1A22h:4 |
Value index 2 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
212 |
32 |
1A22h:5 |
Value index 3 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
216 |
32 |
1A22h:6 |
Value index 4 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
220 |
32 |
1A22h:7 |
Value index 5 (the meaning depends on the
DynamicType, see Table 12). |
Field |
Type |
Offset |
Size (bits) |
ECAT PDO |
Description |
|---|---|---|---|---|---|
|
Integer |
224 |
32 |
1A23h:1 |
Dynamic data type (see Table 12 for available values). |
|
Real |
228 |
32 |
1A23h:2 |
Value index 0 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
232 |
32 |
1A23h:3 |
Value index 1 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
236 |
32 |
1A23h:4 |
Value index 2 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
240 |
32 |
1A23h:5 |
Value index 3 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
244 |
32 |
1A23h:6 |
Value index 4 (the meaning depends on the
DynamicType, see Table 12). |
|
Real |
248 |
32 |
1A23h:7 |
Value index 5 (the meaning depends on the
DynamicType, see Table 12). |