Configuring Axes on the EtherCAT Network

ethercat_config_axis

ethercat_config_axis(axis_name, station_address, counts_per_rev, gear_ratio, feed_constant, zero_offset_count, axis_index = -1, timeout = 2.0)

Description

Configures the axis with parameters of the corresponding hardware

  • This function must be called for each axis separately

  • This function will halt the program with an error, if the value of axis_name doesn’t match an axis name provided to axis_group_add()

Parameter

Name

Type

Optional

Description

axis_name

string

N

Name of the axis. This should match an axis name provided to axis_group_add().

station_address

int

N

EtherCAT station address for the axis. The value must be greater than 0 and no larger than 65536.

counts_per_rev

int

N

Increment in encoder counts for each round the motor turns. The value must be greater than 0.

gear_ratio

float

N

Gear ratio for the axis.

feed_constant

float

N

Feed constant for the axis in radians. Usually, it’s 2*PI (PI=3.14159265359) for rotary positioners.

zero_offset_count

int

N

Encoder reading in counts when the axis is at 0 position. The joint angle = ((current encoder – offset) * feed_constant) / (counts_per_rev * gear_ratio).

axis_index

int

Y

Index for the axis in the joint positions vector. Defaults to -1, implying that it will be determined automatically from axis name.

timeout

float

Y

Timeout in seconds to wait for the operation to finish. Defaults to 2.

Return

  • none

Examples

In this example, a new axis group and axis are added and the new axis is configured to be commanded with EtherCAT

Note: replace the values for <ENCODER> and <GEAR> to match your servo setup.

global PI = acos(-1)

AXIS_TYPE = 0                  # 0:rotary, 1:linear 
VELOCITY_LIMIT = 1             # rad/s 
ACCELERATION_LIMIT = 10        # rad/s^2 
ENCODER_RESOLUTION = <ENCODER> # Specify encoder ticks per revolution of the motor
GEAR_RATIO = <GEAR>            # Specify gear after motor output
FEED_CONSTANT = 2 * PI         # change sign to change motor direction

ZERO_OFFSET = 0 
#create new axis group and axis  
axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)

# configure the axis to be controlled via ethercat
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0) 

Using the EtherCAT Master

ethercat_start

ethercat_start(timeout = 5.0)

Description

Starts the EtherCAT Master communication with the slave axes configured through calls of ethercat_config_axis() and waits for the EtherCAT Master network state to be Operational (OP).

  • This function will halt the program and display an error popup on PolyScope, if it times out, or if an error is encountered (e.g., if initialization or configuration fails during startup)

  • This function requires one axis to be defined using ethercat_config_axis(), and the MotionPlus service running which can be checked using ethercat_is_service_responsive().

Parameter

Name

Type

Optional

Description

timeout

float

Y

Timeout in seconds to wait for EtherCAT master state to be Operational (OP). Default: 5.0.

Return

none

Example

In this example, a new axis group and axis are added and the new axis is configured to be commanded with EtherCAT. The EtherCAT master is then started using the default startup wait.

# create an axis group
axis_group_add("groupA", tf, "world") 

# create a new axis
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT) 

# configure the axis to be controlled via ethercat
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0) 

# starts up ethercat master
ethercat_start() 

ethercat_stop

ethercat_stop(reset = False, timeout = 5.0)

Description

Stops the EtherCAT Master and optionally removes all the axes (EtherCAT slaves) configured via ethercat_config_axis(). This option is useful to ensure the EtherCAT network begins in a clean, unconfigured state.

  • This function will halt the program and display an error popup on PolyScope, if it times out, or if an error is encountered

  • This function can be called whether or not the EtherCAT Master has already been started

Parameter

Name

Type

Optional

Description

reset

bool

Y

Resets the axis configuration via ResetConfiguration XML-RPC method. Default: False

timeout

float

Y

Timeout in seconds to wait for EtherCAT master to finish stopping. Default: 5.0

server_port

int

Y

TCP port for the XML-RPC server. Defaults to 0, implying that the default server port will be used.

server_host

string

Y

Hostname / IP address for the XML-RPC server. Defaults to “”, implying that localhost will be used.

Return

  • none

Example

ethercat_stop(True) # make sure the ethercat master is stopped and clear the configured ethercat slaves... this makes the program start with a clean slate

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0) 

ethercat_start() # starts up ethercat
# do stuff
ethercat_stop() # stop the ethercat master only... don't clear the ethercat slaves

ethercat_set_parameter

ethercat_set_parameter(key, value, timeout = 1.0)

Description

This sets advanced/custom EtherCAT Master parameters. This function will halt the program with an error, if the EtherCAT Master is already running, or if the key or the value is invalid.

Parameter

Name

Type

Optional

Description

key

string

N

Name of EtherCAT Master parameter to set.

value

bool, int, float, or string

N

New value for the EtherCAT Master parameter. The type of this argument depends on the value of key.

timeout

float

Y

Timeout in seconds to wait for the operation to finish. Defaults to 1.

The following EtherCAT Master parameters are supported by this function:

Key

Value Type

Default Value

Description

dc_enable

bool

False

Whether EtherCAT Distributed Clock should be enabled. ** Note: DC enabled is on by default.**

Return

  • none

Example

In this example, the EtherCAT Distributed Clock is disabled

ethercat_set_parameter("dc_enable", False)

ethercat_is_master_running

ethercat_is_master_running(timeout = 2.0)

Description

Checks whether the EtherCAT Master is running

  • This function will halt the program with an error, if it times out, or if an error is encountered

  • This function requires the MotionPlus Service to be running

Parameter

Name

Type

Optional

Description

timeout

float

Y

Seconds to wait for heartbeat (Status) before failing with error. Default: 2.0

Return

bool result indicating whether the EtherCAT Master is currently running

Example

# assuming ethercat start/stop is handled on a different thread
if ethercat_is_master_running():
  # do stuff if master is running
else:
  # do stuff if master is not running
end

ethercat_begin_status_monitor

ethercat_begin_status_monitor(period = 0.1, max_missed_messages = 3, timeout = 1.0)

Description

Starts background task to periodically call

GetStatus

XML-RPC method

  • This function will halt the program, if the responses stop or are never received

  • This function will halt the program, if any response contains a non-zero error code

    • This is useful for making a URScript program identify if the MotionPlus Service has prematurely quit or encountered a runtime error

    • Note: Runtime errors are those that prevent the MotionPlus Service from functioning properly. They do not include faults from the EtherCAT slaves

  • This function will halt the program, if another monitoring task is already running

    • Only one Status Monitor task may be running at any given time

    • Call ethercat_end_status_monitor() to stop the previous task, before starting a new one

  • Monitoring will automatically start when program

Parameter

Name

Type

Optional

Description

period

float

Y

Rate (in seconds) at which to request Status messages. Default: 0.1

max_missed_messages

int

Y

Maximum number of heartbeats that may be missed consecutively before a halt is triggered. Default: 3

timeout

float

Y

Seconds to wait for response before considering it to be missed. Default: 1.0

server_port

int

Y

TCP port for the XML-RPC server. Defaults to 0, implying that the default server port will be used.

server_host

string

Y

Hostname / IP address for the XML-RPC server. Defaults to “”, implying that localhost will be used.

Return

  • none

Example

ethercat_end_status_monitor() # end status monitor
ethercat_begin_status_monitor() # restart

ethercat_end_status_monitor

ethercat_end_status_monitor()

Description

Stops any Status Monitor task started with ethercat_begin_status_monitor()

  • Monitoring will automatically end when a program completes, but this command can be used to stop monitoring at any point in the program

Parameter

  • none

Return

  • none

Example

# end default status monitor first
ethercat_end_status_monitor() 

# restart
ethercat_begin_status_monitor() 

Enabling/Disabling External Axes

ethercat_enable_axis

ethercat_enable_axis(axis_name, timeout = 10, steady_time = 0.5)

Description

Enables the EtherCAT axis specified by axis_name

  • This function requires the EtherCAT Master to be running

  • This function blocks until either the axis is enabled or the timeout expires

  • This function returns True if it succeeded and False if it timed out

  • This function will halt the program with an error, if the value of the axis_name parameter is invalid

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

timeout

float

Y

Maximum time in seconds to wait for axis to be enabled. Negative values indicate unlimited time. Default: 10

steady_time

float

Y

Time to wait after enabling axis to verify that it stays in operation enabled state. Default: 0.5

Return

bool value where True indicates the axis was enabled and False if it timed out

Example

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()

ethercat_enable_axis("axis1") # enables the axis and waits 1s to verify the axis remains enabled before continuing

ethercat_disable_axis

ethercat_disable_axis(axis_name, timeout = 10)

Description

Disables the EtherCAT axis specified by axis_name

  • This function requires the EtherCAT Master to be running

  • This function blocks until either the axis is disabled or the timeout expires

  • This function returns True if it succeeded and False if it timed out

  • This function will halt the program with an error, if the value of the axis_name parameter is invalid

Note

A call to reset_world_model() will automatically disable any enabled EtherCAT axes.

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

timeout

float

Y

Maximum time in seconds to wait for axis to be disabled. Negative values indicate unlimited time. Default: 10

Return

bool value where True indicates the axis was disabled and False if it timed out

Example

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()

ethercat_enable_axis("axis1") # enables the axis
# do stuff
ethercat_disable_axis("axis1") # disables the axis

ethercat_is_axis_enabled

ethercat_is_axis_enabled(axis_name)

Description

Checks whether the specified EtherCAT axis is enabled

  • This function requires the EtherCAT Master to be running. If the EtherCAT Master is not running, it will provide the last known status

  • This function will halt the program with an error, if the value of the axis_name parameter is invalid

  • This function requires one axis to be defined

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

Return

bool where True indicates that the axis is enabled

Example

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()

ethercat_enable_axis("axis1") # enables the axis and waits 1s to verify the axis remains enabled before continuing

enabled = ethercat_is_axis_enabled("axis1") # would be True if ethercat_enable_axis() succeeded

ethercat_is_axis_disabled

ethercat_is_axis_disabled(axis_name)

Description

Checks whether the specified EtherCAT axis is disabled

  • This function requires the EtherCAT Master to be running. If the EtherCAT Master is not running, it will provide the last known status

  • This function will halt the program with an error, if the value of the axis_name parameter is invalid

  • This function requires one axis to be defined

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

Return

bool value where True indicates the axis is disabled

Example

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()
  
ethercat_enable_axis("axis1") # enables the axis
# do stuff
ethercat_disable_axis("axis1") # disables the axis
  
disabled = ethercat_is_axis_disabled("axis1") # would be True if ethercat_disable_axis() succeeded

Handling Errors and Faults

ethercat_clear_error

ethercat_clear_error(timeout = 1.0)

Description

Clears the EtherCAT Master error

  • This function allows the user to clear the error on the EtherCAT Master using the ClearError XML-RPC method

  • This function will halt the program with a popup, if it times out, or if an error is encountered (e.g. if there is a configuration error on the EtherCAT Master)

  • If the EtherCAT Master halts on a runtime error, and the Status Monitoring is disabled, user will be unable to start the EtherCAT Master again until the error is cleared

Parameter

Name

Type

Optional

Description

timeout

float

Y

Seconds to wait for operation to finish before failing with error. Default: 1.0

Return

  • none

Example

# Status Monitor (started by `ethercat_begin_status_monitor()`) 
# has detected an EtherCAT Master runtime error and stopped the previous UR program.

ethercat_clear_error()  # Clear current error

# Proceed to reconfigure and restart EtherCAT Master.

ethercat_is_axis_in_fault_state

ethercat_is_axis_in_fault_state(axis_name)

Description

Checks whether the specified axis has reported fault on EtherCAT network

  • This function requires the EtherCAT Master to be running by calling ethercat_start()

  • However, if the EtherCAT Master is not running, it will return the last known status

  • This function will halt the program with an error, if the value of the axis_name parameter is invalid

  • This function requires one axis to be defined

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

Return

bool value where True indicates the axis has a fault

Example

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)

ethercat_start() # starts up ethercat

# query whether or not "axis1" is in fault state
isAxis1Faulted = ethercat_is_axis_in_fault_state("axis1") 

ethercat_get_axis_errors

ethercat_get_axis_errors(timeout = 1.0)

Description

Gets the axis error codes for all axes on the EtherCAT network

  • Returns a struct containing a list of drive (axis) indices and a corresponding list of error codes from those drives

  • If the EtherCAT master is not running, the return value may be invalid

Parameter

Name

Type

Optional

Description

timeout

float

Y

Seconds to wait for method result before failing with error. Default: 1.0

Return

  • struct AxisErrors type structure containing the following:

    • timestamp.sec (int) whole seconds elapsed since the UNIX epoch (1970-01-01, 00:00:00) in local time zone

    • timestamp.nsec (int) nanoseconds elapsed in addition to timestamp.sec

    • axis_count (int) number of configured axis

    • axis_indices (int[]) list of axis indices EtherCAT Master is controlling

    • axis_errors (int[]) list of current error codes for the axes listed in axis_indices

Example

# make sure the ethercat master is stopped and clear the configured ethercat slaves... 
# this makes the program start with a clean slate
ethercat_stop(True) 

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0) 

ethercat_start() # starts up ethercat
# do stuff
msg = ethercat_get_axis_errors()
textmsg(str_cat("Current error code for axis1: ", to_str(msg.axis_errors[0])))
ethercat_stop(False) # stop the ethercat master only... don't clear the ethercat slaves

ethercat_reset_axis_fault

ethercat_reset_axis_fault(axis_name, timeout = 10)

Description

Resets fault status for the axis specified by axis_name

  • This function requires the EtherCAT Master to be running

  • This function blocks until either the fault is successfully reset or the timeout expires

  • This function returns True if it succeeded and False if it timed out while trying to reset the fault

  • This function will halt the program with an error, if the value of the axis_name parameter is invalid

  • This function requires one axis to be defined

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

timeout

float

Y

Maximum time in seconds to wait for fault to be reset. Negative values indicate unlimited time. Default: 10

Return

  • bool value where True indicates the fault was successfully reset while False indicates it timed out

Example

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)
ethercat_start()
  
if ethercat_is_axis_in_fault_state("axis1"):
  ethercat_reset_axis_fault("axis1") # reset fault of "axis1" if there is any
end

Homing External Axes

ethercat_home_axis_direct

ethercat_home_axis_direct(axis_name, timeout = 10.0)

Note

This method is deprecated as of MotionPlus 1.1 and is planned for removal in MotionPlus 2.0. Please use ethercat_home_axis() instead. The equivalent call is ethercat_home_axis(axis_name, 35, 0, [], [], timeout).

Description

Performs EtherCAT home-to-current homing method on the external axis specified by axis_name.

  • This function requires the EtherCAT Master to be running for it to succeed (see ethercat_start())

  • This function requires the axis to be enabled (see ethercat_enable_axis())

  • This function returns a boolean flag indicating whether the function exited due to timeout.

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

home_offset

int

N

Moves the homed zero position by the given offset (given in [encoder counts]). ** Note:** This parameter is not supported and is ignored by the Mitsubishi J4 drive.

timeout

float

Y

Seconds to wait for method result before failing with error. Default: 10.0

Return

  • bool value where True indicates the axis was homed and False if it timed out

Example

ethercat_stop(True) # make sure the ethercat master is stopped and clear the configured ethercat slaves... this makes the program start with a clean slate

axis_group_add("groupA", tf, "world")
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)

ethercat_start() # starts up ethercat
# do stuff
positions = axis_group_get_target_positions("groupA")
textmsg(str_cat("Axis 1 position: ", to_str(positions[0])))

ethercat_home_axis_direct("axis1", 0)

positions = axis_group_get_target_positions("groupA")
textmsg(str_cat("Axis 1 position: ", to_str(positions[0]))) # axis has been homed and position is now 0.0

ethercat_stop(False) # stop the ethercat master only... don't clear the ethercat slaves

ethercat_home_axis

ethercat_home_axis(axis_name, homing_method, home_offset, homing_velocities, homing_accelerations, timeout = 10.0)

Description

Performs homing on the the external axis specified by axis_name using the specified EtherCAT CoE CiA402 homing method.

  • This function requires the EtherCAT Master to be running for it to succeed (see ethercat_start())

  • This function requires the axis to be enabled (see ethercat_enable_axis())

  • This function returns a boolean flag indicating whether the function exited due to timeout.

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

homing_method

int

N

The EtherCAT CoE CiA402 homing method to use. Valid values are between -128 and 127 inclusive. The supported values vary between servo manufacturers. See servo manufacturer’s documentation for supported methods (refer to EtherCAT CoE CiA 402 object: 0x6098).
Commonly supported methods include:

  • 1: Move the axis in the negative(-) direction until the negative(-) limit switch is triggered, then move the axis in the positive(+) direction and home the axis to the next index pulse
  • 2: Move the axis in the positive(+) direction until the positive(+) limit switch is triggered, then move the axis in the negative(-) direction and home the axis to the next index pulse
  • 35: Home the axis to the current position without moving (typically identical behavior to method 37)
  • 37: Home the axis to the current position without moving (typically identical behavior to method 35)

home_offset

int

N

Moves the homed zero position by the given offset (given in [encoder counts]). Note: This parameter is not supported and is ignored by the Mitsubishi J4 drive.

homing_velocities

int[]

N

An integer array (max size 6) containing the velocity(ies) to use while homing (given in [encoder counts/s]). Typically [switch_search_speed, zero_search_speed]. Enter [] to use existing values stored in the servo. Note: This parameter is not supported and is ignored by the Mitsubishi J4 drive.

homing_accelerations

int[]

N

An integer array (max size 6) containing the acceleration(s) to use while homing (given in [encoder counts/s^2]). Typically [homing_acceleration]. Enter [] to use existing values stored in the servo. Note: This parameter is not supported and is ignored by the Mitsubishi J4 drive.

timeout

float

Y

Seconds to wait for method result before failing with error. Default: 10.0.

Note

The homing operation, executed by the servo drive, ignores any speed slider (speed scaling) setting on the TP.

Warning

Behavior and support varies by servo manufacturer. See manufacturer documentation for supported values of homing_method (refer to EtherCAT CoE CiA 402 object: 0x6098). For example, the Mitsubishi J4 drive does not support and ignores the values passed in the home_offset, homing_velocities, and homing_accelerations parameters.

Return

  • bool value where True indicates the axis was homed and False if it timed out

Example

ethercat_stop(True) # make sure the ethercat master is stopped and clear the configured ethercat slaves... this makes the program start with a clean slate
 
axis_group_add("groupA", tf, "world") # create an axis group
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], 0, 1, 10) # create a new axis
ethercat_config_axis("axis1", 1, 4194304, 120.460000, 6.280000, 0) # configure the axis to be controlled via ethercat
 
ethercat_start() # starts up ethercat
# do stuff
positions = axis_group_get_target_positions("groupA")
textmsg(str_cat("Axis 1 position: ", to_str(positions[0])))
 
# home the axis against the encoder index nearest to the positive limit switch
# use the servo-provided velocity and acceleration values
ethercat_home_axis("axis1", 2, 0, [], [])
 
# alternatively, set home to the current position
# ethercat_home_axis("axis1", 35, 0, [], [])
 
positions = axis_group_get_target_positions("groupA")
textmsg(str_cat("Axis 1 position: ", to_str(positions[0]))) # axis has been homed and position is now 0.0
 
ethercat_stop(False) # stop the ethercat master only... don't clear the ethercat slaves

Get External Axis Positions

ethercat_get_axis_positions

ethercat_get_axis_positions(timeout = 1.0)

Description

Gets the last known axis positions for all axes on the EtherCAT network

  • This function returns a struct with a timestamp, axis indices, target axis positions, actual axis positions, target axis position encoder counts and actual axis position encoder counts

  • This function requires the EtherCAT Master to be running for the returned data to be valid

  • This function will halt the program with an error, if the EtherCAT Master is not running

Parameter

Name

Type

Optional

Description

timeout

float

Y

Seconds to wait for method result before failing with error. Default: 1.0

Return

  • struct structure containing the following:

    • timestamp.sec (int) whole seconds elapsed since the UNIX epoch (1970-01-01, 00:00:00) in local time zone

    • timestamp.nsec (int) nanoseconds elapsed in addition to timestamp.sec

    • axis_count (int) number of configured axis

    • axis_indices (int[]) list of axis indices EtherCAT Master is controlling

    • target_positions (float[]) list of target positions in metric units for the axes listed in axis_indices

    • actual_positions (float[]) list of current actual positions in metric units for the axes listed in axis_indices

    • target_position_counts (int[]) list of target positions in encoder counts for the axes listed in axis_indices

    • actual_position_counts (int[]) list of actual positions in encoder counts for the axes listed in axis_indices

Example

ethercat_stop(True) # make sure the ethercat master is stopped and clear the configured ethercat slaves... this makes the program start with a clean slate

axis_group_add("groupA", tf, "world") 
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], AXIS_TYPE, VELOCITY_LIMIT, ACCELERATION_LIMIT)
ethercat_config_axis("axis1", 1, ENCODER_RESOLUTION, GEAR_RATIO, FEED_CONSTANT, 0)

ethercat_start()
# do stuff
positions = ethercat_get_axis_positions()
textmsg(str_cat("Current actual encoder counts for axis1: ", to_str(positions.actual_position_counts[0])))
ethercat_stop(False) # stop the ethercat master only... don't clear the ethercat slaves

Getting MotionPlus Service Information

ethercat_is_service_responsive

ethercat_is_service_responsive(timeout = 0.5)

Description

Checks if the MotionPlus Service is responsive. This function returns True if the MotionPlus Service responds to a GetStatus XML-RPC call within the provided timeout

Parameter

Name

Type

Optional

Description

timeout

float

Y

Seconds to wait for method result before failing with error. Default: 0.5

Return

bool where True indicates the MotionPlus Service is responsive

Example

ret = ethercat_is_service_responsive() # would be True, if the service is responsive

Reading and Writing Services Data Objects (SDO)

ethercat_write_axis_sdo

ethercat_write_axis_sdo(axis_name, sdo_index, sdo_subindex, type, value, timeout 

Description

Writes SDO to the EtherCAT axis specified by axis_name

  • This function requires the EtherCAT Master to be running

  • This function blocks until either the SDO is written or the timeout expires

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

sdo_index

int

N

The EtherCAT index of the SDO to write. Will be converted to unsigned 16 bit (0x0000-0xFFFF).

sdo_subindex

int

N

The EtherCAT subindex of the SDO to write. Will be converted to unsigned 8 bit (0x00-0xFF).

type

string

N

The type of the SDO to write. Valid types are {“U8”, “U16”, “U32”, “I8”, “I16”, “I32”, and “STR”}.

value

int, or string

N

The value of the SDO to write. For type “U8”, “U16”, and “U32”, hexidecimal strings starting with “0x” are also supported.

timeout

float

Y

Maximum time in seconds to wait for SDO write to finish. Negative values indicate unlimited time. Default: 1.0

Return

  • none

Example

axis_group_add("groupA", tf, "world") # create an axis group
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], 0, 1, 10) # create a new axis
ethercat_config_axis("axis1", 1, 4194304, 120.460000, 6.280000, 0) # configure the axis to be controlled via ethercat
 
ethercat_start() # starts up ethercat
 
ethercat_write_axis_sdo("axis1", to_num("0x6060"), 0, "I8", 8) # SDO writes 8 to Modes of Operation (0x6060:0)

ethercat_read_axis_sdo

ethercat_read_axis_sdo(axis_name, sdo_index, sdo_subindex, type, timeout = 1.0)

Description

Reads SDO from the EtherCAT axis specified by axis_name

  • This function requires the EtherCAT Master to be running

  • This function blocks until either the SDO is read or the timeout expires

Parameter

Name

Type

Optional

Description

axis_name

string

N

The name of the axis. This should match an axis name created by calling axis_group_add_axis().

sdo_index

int

N

The EtherCAT index of the SDO to read. Will be converted to unsigned 16 bit (0x0000-0xFFFF).

sdo_subindex

int

N

The EtherCAT subindex of the SDO to read. Will be converted to unsigned 8 bit (0x00-0xFF).

type

string

N

The type of the SDO to read. Valid types are {“U8”, “U16”, “U32”, “I8”, “I16”, “I32”, and “STR”}.

timeout

float

Y

Maximum time in seconds to wait for SDO write to finish. Negative values indicate unlimited time. Default: 1.0

Return

  • *float* or string value of the SDO. Returns a string if the type of the SDO is “STR”, otherwise returns a float

Example

axis_group_add("groupA", tf, "world") # create an axis group
axis_group_add_axis("groupA", "axis1", "", p[0,0,0,0,0,0], 0, 1, 10) # create a new axis
ethercat_config_axis("axis1", 1, 4194304, 120.460000, 6.280000, 0) # configure the axis to be controlled via ethercat
 
ethercat_start() # starts up ethercat
 
device_name = ethercat_read_axis_sdo("axis1", to_num("0x1008"), 0, "STR") # SDO reads Device Name 

Miscellaneous Utility Functions

time_sec()

Description: returns the current execution time of the UR Controller in seconds

Parameter: none

Return

float current execution time in seconds

Example

cur_time = time_sec()
textmsg(str_cat("Current time in seconds: ", to_str(cur_time)))