From f24c52be4155612f6d861348b5eacf1114a789a2 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 26 Apr 2023 18:47:49 -0500 Subject: [PATCH 001/121] lcec: Add `ethercat.conf.xml` PDO entry `scale`+`offset` attributes --- hw_device_mgr/lcec/config.py | 10 +++++++++- hw_device_mgr/lcec/tests/ethercat.conf.xml | 4 ++-- 2 files changed, 11 insertions(+), 3 deletions(-) diff --git a/hw_device_mgr/lcec/config.py b/hw_device_mgr/lcec/config.py index 41ed4cee..c13353ad 100644 --- a/hw_device_mgr/lcec/config.py +++ b/hw_device_mgr/lcec/config.py @@ -87,7 +87,10 @@ def gen_ethercat_xml(cls, bus_configs=dict()): sm_xml.append(pdo_xml) for entry in sm_data["pdo_mapping"]["entries"]: sdo = dev.sdo(entry["index"]) - dt = sdo.data_type + if "scale" in entry: + dt = cls.data_type_class.float + else: + dt = sdo.data_type pdo_entry_xml = etree.Element( "pdoEntry", idx=str(sdo.index), @@ -98,6 +101,11 @@ def gen_ethercat_xml(cls, bus_configs=dict()): if "name" in entry: pdo_entry_xml.set("halPin", entry["name"]) pdo_entry_xml.set("halType", dt.hal_type_str()[4:]) + if "scale" in entry: + pdo_entry_xml.set("scale", str(entry["scale"])) + if "offset" in entry: + pdo_entry_xml.set("offset", str(entry["offset"])) + else: # complexEntry pdo_entry_xml.set("halType", "complex") diff --git a/hw_device_mgr/lcec/tests/ethercat.conf.xml b/hw_device_mgr/lcec/tests/ethercat.conf.xml index 268b1db1..f819a170 100644 --- a/hw_device_mgr/lcec/tests/ethercat.conf.xml +++ b/hw_device_mgr/lcec/tests/ethercat.conf.xml @@ -42,7 +42,7 @@ - + @@ -117,7 +117,7 @@ - + From c173a78500ef469220dbc4aaab631a3f5346a975 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 08:53:52 -0500 Subject: [PATCH 002/121] async_task_queue.py: Run formatters & fix pydocstyle issues --- hw_device_mgr/async_task_queue.py | 25 +++++++++++++++---------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/hw_device_mgr/async_task_queue.py b/hw_device_mgr/async_task_queue.py index 5ee8877f..8627a0ac 100644 --- a/hw_device_mgr/async_task_queue.py +++ b/hw_device_mgr/async_task_queue.py @@ -2,13 +2,14 @@ import queue from functools import cached_property, lru_cache + class AsyncTaskQueue: """ Generic class to process commands in an asynchronous queue. - Multiple instances may `enqueue` commands for a singleton worker instance - processing those in a thread with the `process_queue` command (implemented - in subclasses). + Multiple instances may `enqueue` commands for a singleton worker + instance processing those in a thread with the `process_queue` + command (implemented in subclasses). """ # Class-level dict of singleton queues @@ -51,8 +52,8 @@ def _work(self): """ Worker thread loop callback. - Pop commands off command queue and pass to `process_cmd` method. Repeat - untill `join` method is called. + Pop commands off command queue and pass to `process_cmd` method. + Repeat untill `join` method is called. """ while True: cmd_version, cmd = self.cmd_queue.get() @@ -66,8 +67,9 @@ def start(cls): """ Create new worker instance and start worker thread. - This may be called from multiple instances enqueuing commands, but will - only ever create a single worker instance running a single thread. + This may be called from multiple instances enqueuing commands, + but will only ever create a single worker instance running a + single thread. """ if hasattr(cls, "_worker_instance"): assert type(cls._worker_instance) is cls # Subclass sanity @@ -125,13 +127,16 @@ def all_cmds_complete(self): """ Return `True` if all commands enqueued by this instance were processed. - This may return `True` for one instance while returning `False` for - another instance with commands still waiting to be processed. + This may return `True` for one instance while returning `False` + for another instance with commands still waiting to be + processed. """ return self.progress_version >= self.cmd_version def join(self): - """Block until all queued items are processed and join worker thread.""" + """ + Block until all queued items are processed and join worker thread. + """ self.cmd_queue.join() # Wait for worker to drain cmd queue & join self.all_cmds_complete() # Drain progress queue self.progress_queue.join() # & join From 05916b0c493ec631af6476fea9cdb7b95c28b14e Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 08:55:15 -0500 Subject: [PATCH 003/121] base class: Run formatters --- hw_device_mgr/device.py | 13 +++++++++---- hw_device_mgr/interface.py | 4 +++- hw_device_mgr/latency/halsampler_decode.py | 1 - hw_device_mgr/logging/__init__.py | 1 + hw_device_mgr/tests/test_data_types.py | 1 - hw_device_mgr/tests/test_device.py | 4 +--- 6 files changed, 14 insertions(+), 10 deletions(-) diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 354bc852..b976bca0 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -18,14 +18,20 @@ class Device(LoggingMixin, abc.ABC): feedback_in_data_types = dict() feedback_out_data_types = dict( - goal_reached="bit", goal_reason="str", fault="bit", fault_desc="str", + goal_reached="bit", + goal_reason="str", + fault="bit", + fault_desc="str", ) command_in_data_types = dict() command_out_data_types = dict() feedback_in_defaults = dict() feedback_out_defaults = dict( - goal_reached=True, goal_reason="Reached", fault=False, fault_desc="", + goal_reached=True, + goal_reason="Reached", + fault=False, + fault_desc="", ) command_in_defaults = dict() command_out_defaults = dict() @@ -170,7 +176,7 @@ def check_and_set_timeout(self): return False def set_timeout(self, timeout_seconds): - """Set timeout for `timeout_seconds` in the future""" + """Set timeout for `timeout_seconds` in the future.""" self._timeout = time.time() + timeout_seconds def set_command(self, **kwargs) -> Interface: @@ -375,7 +381,6 @@ def dot_color(cls): class SimDevice(Device): - sim_feedback_data_types = dict() sim_feedback_defaults = dict() diff --git a/hw_device_mgr/interface.py b/hw_device_mgr/interface.py index 9c9a490e..894a5bc2 100644 --- a/hw_device_mgr/interface.py +++ b/hw_device_mgr/interface.py @@ -22,7 +22,9 @@ def add_attribute(self, attr, default, data_type): def set_types(self, **values): """Set data types for values if a type is defined for that value.""" for key, val in list(values.items()): - assert key in self.data_types, f"No key '{key}' in '{self.name}' interface" + assert ( + key in self.data_types + ), f"No key '{key}' in '{self.name}' interface" values[key] = self.data_types[key](val) return values diff --git a/hw_device_mgr/latency/halsampler_decode.py b/hw_device_mgr/latency/halsampler_decode.py index cb135c6a..f69d4f3a 100755 --- a/hw_device_mgr/latency/halsampler_decode.py +++ b/hw_device_mgr/latency/halsampler_decode.py @@ -9,7 +9,6 @@ class HalSamplerDecoder: - logger = logging.getLogger(__name__) sampler_pin_re = re.compile( diff --git a/hw_device_mgr/logging/__init__.py b/hw_device_mgr/logging/__init__.py index cee8aa0f..78d37e48 100644 --- a/hw_device_mgr/logging/__init__.py +++ b/hw_device_mgr/logging/__init__.py @@ -40,6 +40,7 @@ def __getattr__(self, name): def getLogger(cls, name): return cls(name) + class LoggingMixin: """Mixin class that provides a `logger` attribute.""" diff --git a/hw_device_mgr/tests/test_data_types.py b/hw_device_mgr/tests/test_data_types.py index bf367b95..93fd7268 100644 --- a/hw_device_mgr/tests/test_data_types.py +++ b/hw_device_mgr/tests/test_data_types.py @@ -2,7 +2,6 @@ class TestDataType(BaseTestClass): - # All shared types in the base `DataType` class all_shared_types = { "bit", diff --git a/hw_device_mgr/tests/test_device.py b/hw_device_mgr/tests/test_device.py index 9c05fd17..f6a2d7a2 100644 --- a/hw_device_mgr/tests/test_device.py +++ b/hw_device_mgr/tests/test_device.py @@ -2,7 +2,6 @@ from .base_test_class import BaseTestClass from ..device import Device import subprocess -import time from pprint import pformat @@ -196,7 +195,6 @@ def do_test(expected): fb_set(True, False) assert not obj.check_and_set_timeout() - ######################################### # Test read()/update()/write() integration # @@ -252,7 +250,7 @@ def setup_test(self, test_case): # Nested dictionaries of { interface : { attr : { model_id, ... } } }: # model_id must have interface attribute; for other models, missing OK self.missing_not_ok = { - i:dict() for i in self.device_class.interface_names + i: dict() for i in self.device_class.interface_names } self.read_update_write_conv_test_data() From 3f59f2414966d7237dfc835411411e0eb5c5b20c Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 08:57:28 -0500 Subject: [PATCH 004/121] cia_301: Run formatters & fix pyflake errors --- hw_device_mgr/cia_301/async_params.py | 3 ++- hw_device_mgr/cia_301/config.py | 2 +- hw_device_mgr/cia_301/device.py | 13 +++---------- hw_device_mgr/cia_301/tests/test_config.py | 2 +- hw_device_mgr/cia_301/tests/test_data_types.py | 1 - hw_device_mgr/cia_301/tests/test_device.py | 2 +- 6 files changed, 8 insertions(+), 15 deletions(-) diff --git a/hw_device_mgr/cia_301/async_params.py b/hw_device_mgr/cia_301/async_params.py index 185dd6ef..d291de66 100644 --- a/hw_device_mgr/cia_301/async_params.py +++ b/hw_device_mgr/cia_301/async_params.py @@ -1,5 +1,6 @@ from ..async_task_queue import AsyncTaskQueue + class AsyncParamsQueue(AsyncTaskQueue): """Process device configuration commands in an asynchronous queue.""" @@ -11,5 +12,5 @@ def process_cmd(self, cmd_raw): def download(self, config, values, **cmd_kwargs): """Enqueue one param config 'download' command.""" for sdo, val in values.items(): - cmd = (config, 'download', (sdo, val), cmd_kwargs) + cmd = (config, "download", (sdo, val), cmd_kwargs) super().enqueue(cmd) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index f045107c..ee7870cc 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -78,7 +78,7 @@ def command(cls): def __str__(self): cname = self.__class__.__name__ - return f"{cname}:{self.model_id}@{self.address}".replace(" ","") + return f"{cname}:{self.model_id}@{self.address}".replace(" ", "") def __repr__(self): return f"<{self}>" diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index c84ccb76..19a5687d 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -1,5 +1,4 @@ from ..device import Device, SimDevice -from ..interface import Interface from .config import CiA301Config, CiA301SimConfig from .data_types import CiA301DataType from functools import cached_property, lru_cache @@ -108,10 +107,9 @@ def get_feedback(self): # Param init: download param values asynchronously after coming online if ( - self.feedback_in.changed("online") or - not self.config.initialize_params() + self.feedback_in.changed("online") + or not self.config.initialize_params() ): - restart = self.feedback_in.changed("online") self.config.initialize_params(restart=True) goal_reached = False goal_reasons.append("updating device params") @@ -139,7 +137,7 @@ def get_feedback(self): fb_out.update( goal_reached=goal_reached, goal_reason=goal_reason, - param_state=param_state + param_state=param_state, ) if goal_reached and fb_out.changed("param_state"): self.logger.info("Device param init complete") @@ -147,11 +145,6 @@ def get_feedback(self): self.logger.info(f"Goal not reached: {goal_reason}") return fb_out - def set_command(self, **kwargs) -> Interface: - cmd_out = super().set_command(**kwargs) - fb_out = self.interface("feedback_out") - return cmd_out - @classmethod def munge_sdo_data(cls, sdo_data): # Turn per-model name SDO data from YAML into per-model_id SDO data diff --git a/hw_device_mgr/cia_301/tests/test_config.py b/hw_device_mgr/cia_301/tests/test_config.py index 4b4a86ce..bdf564c0 100644 --- a/hw_device_mgr/cia_301/tests/test_config.py +++ b/hw_device_mgr/cia_301/tests/test_config.py @@ -80,7 +80,7 @@ def test_initialize_params(self, obj, sdo_data, sim_device_data): # Spin while we wait on the worker timeout, incr = 1, 0.01 - for i in range(int(timeout/incr)): + for i in range(int(timeout / incr)): if obj.initialize_params(): break time.sleep(incr) diff --git a/hw_device_mgr/cia_301/tests/test_data_types.py b/hw_device_mgr/cia_301/tests/test_data_types.py index 72f10c46..ed2b7b19 100644 --- a/hw_device_mgr/cia_301/tests/test_data_types.py +++ b/hw_device_mgr/cia_301/tests/test_data_types.py @@ -3,7 +3,6 @@ class TestCiA301DataType(BaseCiA301TestClass, _TestDataType): - defined_shared_types = { "bit", "int8", diff --git a/hw_device_mgr/cia_301/tests/test_device.py b/hw_device_mgr/cia_301/tests/test_device.py index cba2f6af..141f793b 100644 --- a/hw_device_mgr/cia_301/tests/test_device.py +++ b/hw_device_mgr/cia_301/tests/test_device.py @@ -33,7 +33,7 @@ def get_feedback_and_check(self): return # Spin while we wait on the worker timeout, incr = 1, 0.01 - for i in range(int(timeout/incr)): + for i in range(int(timeout / incr)): if self.obj.config.initialize_params(): break time.sleep(incr) From 0cc5b1081100cb77521fa939959e0915c9b1c26a Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 08:58:39 -0500 Subject: [PATCH 005/121] cia_402: Run formatters & fix pyflake errors --- hw_device_mgr/cia_402/device.py | 54 +++++++++++-------- .../cia_402/tests/base_test_class.py | 1 - hw_device_mgr/cia_402/tests/test_device.py | 41 +++++++------- 3 files changed, 53 insertions(+), 43 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index d0105b34..80b603b4 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -4,7 +4,7 @@ CiA301SimDevice, ) from ..errors.device import ErrorDevice, ErrorSimDevice -from functools import cached_property, lru_cache +from functools import lru_cache class CiA402Device(CiA301Device, ErrorDevice): @@ -141,7 +141,10 @@ def get_feedback_hm(self, sw): if self.feedback_out.get("state") != "OPERATION ENABLED": fault_desc = "Home request while drive not enabled" self.feedback_out.update( - home_success=False, home_error=True, fault=True, fault_desc=fault_desc + home_success=False, + home_error=True, + fault=True, + fault_desc=fault_desc, ) return False, fault_desc @@ -168,7 +171,10 @@ def get_feedback_pp(self, sw): if self.feedback_out.get("state") != "OPERATION ENABLED": reason = "Move request while drive not enabled" self.feedback_out.update( - move_success=False, move_error=True, fault=True, fault_desc=reason + move_success=False, + move_error=True, + fault=True, + fault_desc=reason, ) return False, reason @@ -187,7 +193,7 @@ def get_feedback_sto(self): if not self.feedback_in.get("sto"): # STO inactive (low) if self.feedback_in.changed("sto"): # Log once - self.logger.info(f"STO input inactive") + self.logger.info("STO input inactive") return True, None # STO active (high) @@ -205,7 +211,7 @@ def get_feedback_sto(self): else: # No ENABLE_OPERATION command; log (warning, once) and return if self.feedback_in.changed("sto"): - self.logger.warning(f"STO input active") + self.logger.warning("STO input active") return True, None @property @@ -261,16 +267,19 @@ def get_feedback(self): state_cmd = self.command_in.get("state") sw = fb_in.get("status_word") goal_reasons.append(f"state {state} != {state_cmd}") - if (state_cmd in ("SWITCHED ON", "OPERATION ENABLED") - and not self.test_sw_bit(sw, "VOLTAGE_ENABLED")): + if state_cmd in ( + "SWITCHED ON", + "OPERATION ENABLED", + ) and not self.test_sw_bit(sw, "VOLTAGE_ENABLED"): fault = True fault_desc = "Enable command while no voltage at motor" goal_reasons.append(fault_desc) # Raise fault if device unexpectedly goes offline - if ( - self.command_in.get("state") == "OPERATION ENABLED" and - not self.test_sw_bit(sw, "READY_TO_SWITCH_ON") + if self.command_in.get( + "state" + ) == "OPERATION ENABLED" and not self.test_sw_bit( + sw, "READY_TO_SWITCH_ON" ): fault = True fault_desc = "Enabled drive unexpectedly disabled" @@ -363,7 +372,7 @@ def sw_to_str(cls, sw): flags = [ k for k, v in cls.sw_bits.items() - if not sw_mask & (1< Date: Thu, 27 Apr 2023 08:58:51 -0500 Subject: [PATCH 006/121] errors: Run formatters --- hw_device_mgr/errors/device.py | 10 +++------- hw_device_mgr/errors/tests/base_test_class.py | 1 - 2 files changed, 3 insertions(+), 8 deletions(-) diff --git a/hw_device_mgr/errors/device.py b/hw_device_mgr/errors/device.py index debb1362..9670c776 100644 --- a/hw_device_mgr/errors/device.py +++ b/hw_device_mgr/errors/device.py @@ -20,12 +20,8 @@ class ErrorDevice(Device, ConfigIO): feedback_in_data_types = dict(error_code="uint32") feedback_in_defaults = dict(error_code=0) - feedback_out_defaults = dict( - error_code=0, description="No error" - ) - feedback_out_data_types = dict( - error_code="uint32", description="str" - ) + feedback_out_defaults = dict(error_code=0, description="No error") + feedback_out_data_types = dict(error_code="uint32", description="str") no_error = feedback_out_defaults @@ -51,7 +47,7 @@ def error_descriptions(cls): keys = set(cls.no_error.keys()) keys.discard("error_code") for err_code_str, err_data_raw in err_yaml.items(): - err_data = { k:err_data_raw[k] for k in keys } + err_data = {k: err_data_raw[k] for k in keys} errs[int(err_code_str, 0)] = err_data return errs diff --git a/hw_device_mgr/errors/tests/base_test_class.py b/hw_device_mgr/errors/tests/base_test_class.py index 89f95799..50713310 100644 --- a/hw_device_mgr/errors/tests/base_test_class.py +++ b/hw_device_mgr/errors/tests/base_test_class.py @@ -8,6 +8,5 @@ class ErrorBaseTestClass(BaseTestClass): - device_class = BogusErrorDevice device_model_classes = BogusErrorV1Servo, BogusErrorV2Servo, BogusErrorV1IO From bf3c46d2a58f088ae52e2db51cfb31ec1dc7b4b8 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 08:59:20 -0500 Subject: [PATCH 007/121] ethercat: Run formatters & fix pyflake errors --- hw_device_mgr/ethercat/command.py | 1 - hw_device_mgr/ethercat/tests/base_test_class.py | 1 - hw_device_mgr/ethercat/tests/test_device.py | 1 - 3 files changed, 3 deletions(-) diff --git a/hw_device_mgr/ethercat/command.py b/hw_device_mgr/ethercat/command.py index c53844b7..f3ef2726 100644 --- a/hw_device_mgr/ethercat/command.py +++ b/hw_device_mgr/ethercat/command.py @@ -3,7 +3,6 @@ CiA301SimCommand, CiA301CommandException, ) -from .data_types import EtherCATDataType class EtherCATCommandException(CiA301CommandException): diff --git a/hw_device_mgr/ethercat/tests/base_test_class.py b/hw_device_mgr/ethercat/tests/base_test_class.py index 8fa05b86..4a67be6e 100644 --- a/hw_device_mgr/ethercat/tests/base_test_class.py +++ b/hw_device_mgr/ethercat/tests/base_test_class.py @@ -14,7 +14,6 @@ class BaseEtherCATTestClass(BaseCiA402TestClass): - # Classes under test in this module data_type_class = EtherCATDataType sdo_class = EtherCATSDO diff --git a/hw_device_mgr/ethercat/tests/test_device.py b/hw_device_mgr/ethercat/tests/test_device.py index 3692bfee..8061409b 100644 --- a/hw_device_mgr/ethercat/tests/test_device.py +++ b/hw_device_mgr/ethercat/tests/test_device.py @@ -3,7 +3,6 @@ class TestEtherCATDevice(BaseEtherCATTestClass, _TestCiA402Device): - expected_mro = [ "RelocatableESIDevice", "EtherCATSimDevice", From ff7cf843efba25b99afec65dc9e001a0086d863b Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 08:59:33 -0500 Subject: [PATCH 008/121] hal: Run formatters --- hw_device_mgr/hal/tests/base_test_class.py | 1 - hw_device_mgr/hal/tests/mock_hal.py | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/hw_device_mgr/hal/tests/base_test_class.py b/hw_device_mgr/hal/tests/base_test_class.py index 957a20d7..8aaa97d9 100644 --- a/hw_device_mgr/hal/tests/base_test_class.py +++ b/hw_device_mgr/hal/tests/base_test_class.py @@ -11,7 +11,6 @@ class BaseHALTestClass(BaseCiA402TestClass): - # Classes under test in this module data_type_class = HALDataType device_class = BogusHALDevice diff --git a/hw_device_mgr/hal/tests/mock_hal.py b/hw_device_mgr/hal/tests/mock_hal.py index dc1be1ac..d53982e7 100644 --- a/hw_device_mgr/hal/tests/mock_hal.py +++ b/hw_device_mgr/hal/tests/mock_hal.py @@ -21,7 +21,7 @@ def _set_storage(self, storage): self.storage[self.pname] = 0 def format_val(self, val): - """Format value for printing by fixture""" + """Format value for printing by fixture.""" if self.ptype in (HALMixin.HAL_U32, getattr(HALMixin, "HAL_U64", None)): return f"{val}/0x{val:X}" else: From 24ff02c94f5882157297c1a09da12dd56f894dd9 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 08:59:46 -0500 Subject: [PATCH 009/121] devices: Run formatters --- hw_device_mgr/devices/inovance_sv660.py | 2 +- hw_device_mgr/devices/tests/base_test_class.py | 1 - hw_device_mgr/devices/tests/test_devices.py | 8 ++++++-- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/hw_device_mgr/devices/inovance_sv660.py b/hw_device_mgr/devices/inovance_sv660.py index ab4c0ddb..bb7fdb6d 100644 --- a/hw_device_mgr/devices/inovance_sv660.py +++ b/hw_device_mgr/devices/inovance_sv660.py @@ -58,8 +58,8 @@ def get_feedback(self): fb_out.update(home_found=True) return fb_out -class SimInovanceSV660(InovanceSV660, CiA402SimDevice): +class SimInovanceSV660(InovanceSV660, CiA402SimDevice): def set_sim_feedback(self): # Simulate home_found feedback sfb = super().set_sim_feedback() diff --git a/hw_device_mgr/devices/tests/base_test_class.py b/hw_device_mgr/devices/tests/base_test_class.py index 76fb4ceb..7d4a269a 100644 --- a/hw_device_mgr/devices/tests/base_test_class.py +++ b/hw_device_mgr/devices/tests/base_test_class.py @@ -10,7 +10,6 @@ class BaseDevicesTestClass(BaseEtherCATTestClass): - device_class = DevicesForTest # device_class = DevicesForTest device_model_classes = ( diff --git a/hw_device_mgr/devices/tests/test_devices.py b/hw_device_mgr/devices/tests/test_devices.py index de5c5611..c88a1f19 100644 --- a/hw_device_mgr/devices/tests/test_devices.py +++ b/hw_device_mgr/devices/tests/test_devices.py @@ -1,8 +1,12 @@ from .base_test_class import BaseDevicesTestClass -from ...ethercat.tests.test_device import TestEtherCATDevice as _TestEtherCATDevice +from ...ethercat.tests.test_device import ( + TestEtherCATDevice as _TestEtherCATDevice, +) class TestDevices(BaseDevicesTestClass, _TestEtherCATDevice): expected_mro = [ - c for c in _TestEtherCATDevice.expected_mro if c != "RelocatableESIDevice" + c + for c in _TestEtherCATDevice.expected_mro + if c != "RelocatableESIDevice" ] From bd2021b7f2d784696d8f728e44d8baace651b271 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 09:00:00 -0500 Subject: [PATCH 010/121] lcec: Run formatters --- hw_device_mgr/lcec/tests/base_test_class.py | 1 - hw_device_mgr/lcec/tests/test_config.py | 1 - hw_device_mgr/lcec/tests/test_data_types.py | 1 - hw_device_mgr/lcec/tests/test_device.py | 1 - 4 files changed, 4 deletions(-) diff --git a/hw_device_mgr/lcec/tests/base_test_class.py b/hw_device_mgr/lcec/tests/base_test_class.py index 39169461..f8153e2e 100644 --- a/hw_device_mgr/lcec/tests/base_test_class.py +++ b/hw_device_mgr/lcec/tests/base_test_class.py @@ -15,7 +15,6 @@ class BaseLCECTestClass(BaseEtherCATTestClass, BaseHALTestClass): - # Classes under test in this module data_type_class = LCECDataType sdo_class = LCECSDO diff --git a/hw_device_mgr/lcec/tests/test_config.py b/hw_device_mgr/lcec/tests/test_config.py index 13f8f310..2e81135e 100644 --- a/hw_device_mgr/lcec/tests/test_config.py +++ b/hw_device_mgr/lcec/tests/test_config.py @@ -6,7 +6,6 @@ class TestLCECConfig(BaseLCECTestClass, _TestEtherCATConfig): - halcomp_name = "lcec_config" ethercat_conf_xml_package = "hw_device_mgr.lcec.tests" ethercat_conf_xml_resource = "ethercat.conf.xml" diff --git a/hw_device_mgr/lcec/tests/test_data_types.py b/hw_device_mgr/lcec/tests/test_data_types.py index b05e6357..5aab20e8 100644 --- a/hw_device_mgr/lcec/tests/test_data_types.py +++ b/hw_device_mgr/lcec/tests/test_data_types.py @@ -8,7 +8,6 @@ class TestLCECDataType( BaseLCECTestClass, _TestEtherCATDataType, _TestHALDataType ): - defined_shared_types = { "bit", "int8", diff --git a/hw_device_mgr/lcec/tests/test_device.py b/hw_device_mgr/lcec/tests/test_device.py index 09c15e8a..4b72470a 100644 --- a/hw_device_mgr/lcec/tests/test_device.py +++ b/hw_device_mgr/lcec/tests/test_device.py @@ -9,7 +9,6 @@ class TestLCECDevice(BaseLCECTestClass, _TestEtherCATDevice, _TestHALDevice): - expected_mro = [ "LCECSimDevice", "LCECDevice", From d3b46535a9c3c79e3fc4822c58dc08fbafe5bce2 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 09:00:54 -0500 Subject: [PATCH 011/121] mgr: Run formatters & fix pyflake errors --- hw_device_mgr/mgr/mgr.py | 32 ++++++++++++----------------- hw_device_mgr/mgr/tests/test_mgr.py | 7 +++---- 2 files changed, 16 insertions(+), 23 deletions(-) diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 5322742d..9b66a304 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -1,4 +1,3 @@ -from ..logging import LoggingMixin from ..device import Device, SimDevice from ..cia_402.device import CiA402Device, CiA402SimDevice @@ -64,7 +63,7 @@ def __init__(self): # mgr_config and device_config are YAML loaded by __main__ and passed in def init(self, /, mgr_config, device_config, **kwargs): """Initialize Manager instance.""" - self.logger.info(f"New device manager instance starting") + self.logger.info("New device manager instance starting") self.mgr_config = mgr_config # Pass device config to Config class assert device_config, "Empty device configuration" @@ -129,7 +128,8 @@ def scan_devices(cls, **kwargs): # - goal_reached/goal_reason used by mgr feedback_out={ # These are sim only, not needed in debug output - "position_cmd", "position_fb", + "position_cmd", + "position_fb", }, # - Don't expose device `state` cmd, controlled by manager command_in={"state"}, @@ -436,7 +436,7 @@ def get_device_feedback(self, dev): return dev.get_feedback() def merge_device_descriptions(self, descriptions): - """Merge descriptions into a single string with deduplication""" + """Merge descriptions into a single string with deduplication.""" # descriptions is hash of device:description; invert to hash of # description:[str(device), ...] rev_descriptions = dict() @@ -512,8 +512,9 @@ def get_feedback(self): # Drives enabled or not enabled = ( - cmd_out.get("state") == self.STATE_START and - goal_reached and not fault + cmd_out.get("state") == self.STATE_START + and goal_reached + and not fault ) # Update feedback out, log, return @@ -528,9 +529,7 @@ def get_feedback(self): if mgr_fb_out.get("goal_reached"): self.logger.debug("Manager reached goal state") else: - self.logger.debug( - f"Waiting: {mgr_fb_out.get('goal_reason')}" - ) + self.logger.debug(f"Waiting: {mgr_fb_out.get('goal_reason')}") return mgr_fb_out def set_command(self, **cmd_in_kwargs): @@ -556,19 +555,15 @@ def set_command(self, **cmd_in_kwargs): else: new_state_cmd = False - # Check for new faults - new_device_faults = self.query_devices(fault=True, changed=True) - # Special cases where 'fault' or incoming command update overrides # current command: if cmd_in.get("state_cmd") not in self.cmd_int_to_name_map: msg = f"Invalid state command, '{cmd_in.get('state_cmd')}'" self.logger.error(msg) cmd_out.update(state=self.STATE_FAULT, state_log=msg) - elif ( - old_cmd_out.get("state") != self.STATE_FAULT and - self.feedback_out.get("fault") - ): + elif old_cmd_out.get( + "state" + ) != self.STATE_FAULT and self.feedback_out.get("fault"): # Fault feedback not from device faults (e.g. timeout) if self.feedback_out.changed("fault"): self.logger.warning( @@ -578,7 +573,7 @@ def set_command(self, **cmd_in_kwargs): self.logger.warning("Ignoring new state command") cmd_out.update( state=self.STATE_FAULT, - state_log=f"Manager fault", + state_log="Manager fault", ) elif new_state_cmd: # state_set went high; latch state_cmd from kwargs @@ -592,7 +587,7 @@ def set_command(self, **cmd_in_kwargs): # Received new command to stop/start/fault. Try it # by triggering the FSM event; a Canceled exception means # it can't be done, so ignore it. - cmd_int = cmd_out.get('state') + cmd_int = cmd_out.get("state") cmd_str = self.state_str self.logger.debug(f"New state command: {cmd_str} ({cmd_int})") event = f"{cmd_str}_command" @@ -694,5 +689,4 @@ def __str__(self): class SimHWDeviceMgr(HWDeviceMgr, SimDevice): - device_base_class = CiA402SimDevice diff --git a/hw_device_mgr/mgr/tests/test_mgr.py b/hw_device_mgr/mgr/tests/test_mgr.py index 2b3c1039..0b913d7d 100644 --- a/hw_device_mgr/mgr/tests/test_mgr.py +++ b/hw_device_mgr/mgr/tests/test_mgr.py @@ -43,7 +43,7 @@ def drive_addr_to_index_map(self): def string_format_kwargs(self): """YAML string `format()` keyword args.""" items = enumerate(str(d) for d in self.obj.devices) - drive_strs=[item[1] for item in items] + drive_strs = [item[1] for item in items] return dict( drives=drive_strs, drives3plus=",".join(drive_strs[3:]), @@ -250,8 +250,7 @@ def setup_test(self, test_case): # Add SV660N feedback_out home_found exception mno = self.missing_not_ok["feedback_out"] for i in range(7): - attr = f"d.{i}.home_found" - mno_home_found = mno.setdefault(attr, set()) # Empty set signified OK + mno.setdefault(f"d.{i}.home_found", set()) # Empty set signifies OK def get_feedback_and_check(self): super().get_feedback_and_check() @@ -265,7 +264,7 @@ def get_feedback_and_check(self): continue # Spin while we wait on the worker timeout, incr = 1, 0.01 - for i in range(int(timeout/incr)): + for i in range(int(timeout / incr)): if dev.config.initialize_params(): break time.sleep(incr) From c641e5f2d31897e088e8d78c2595f7939e07a357 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 09:01:03 -0500 Subject: [PATCH 012/121] mgr_ros: Run formatters --- hw_device_mgr/mgr_ros/tests/test_mgr.py | 1 - 1 file changed, 1 deletion(-) diff --git a/hw_device_mgr/mgr_ros/tests/test_mgr.py b/hw_device_mgr/mgr_ros/tests/test_mgr.py index 8addfa3b..a120f243 100644 --- a/hw_device_mgr/mgr_ros/tests/test_mgr.py +++ b/hw_device_mgr/mgr_ros/tests/test_mgr.py @@ -5,7 +5,6 @@ class TestROSHWDeviceMgr(BaseROSMgrTestClass, _TestHWDeviceMgr): - expected_mro = [ "ROSHWDeviceMgrTestCategory", "ROSSimHWDeviceMgr", From f8b7dd510bff8af4f04b22bbfd5d62806402d865 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 27 Apr 2023 09:01:10 -0500 Subject: [PATCH 013/121] mgr_ros_hal: Run formatters --- hw_device_mgr/mgr_ros_hal/tests/test_mgr.py | 1 - 1 file changed, 1 deletion(-) diff --git a/hw_device_mgr/mgr_ros_hal/tests/test_mgr.py b/hw_device_mgr/mgr_ros_hal/tests/test_mgr.py index 70d6cdaf..d60a3323 100644 --- a/hw_device_mgr/mgr_ros_hal/tests/test_mgr.py +++ b/hw_device_mgr/mgr_ros_hal/tests/test_mgr.py @@ -6,7 +6,6 @@ class TestROSHWDeviceMgr( BaseROSHALMgrTestClass, _TestHALHWDeviceMgr, _TestROSHWDeviceMgr ): - expected_mro = [ "ROSHWDeviceMgrTestCategory", "ROSHALSimHWDeviceMgr", From 88db2317e5c6ffa5904c864ada90317a5913f70f Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 19 Apr 2023 16:14:58 -0500 Subject: [PATCH 014/121] cia_301: Fix param update logic Fix issue where drive param updates cycle indefinitely with console log spamming --- hw_device_mgr/cia_301/device.py | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 19a5687d..a4e0e4cd 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -106,16 +106,15 @@ def get_feedback(self): goal_reached, goal_reasons = True, list() # Param init: download param values asynchronously after coming online - if ( - self.feedback_in.changed("online") - or not self.config.initialize_params() - ): + if self.feedback_in.changed("online"): self.config.initialize_params(restart=True) goal_reached = False goal_reasons.append("updating device params") param_state = self.PARAM_STATE_UPDATING - else: + elif self.config.initialize_params(): param_state = self.PARAM_STATE_COMPLETE + else: + param_state = self.PARAM_STATE_UPDATING # Update operational status if not self.feedback_in.get("oper"): From 2cc6198f702876959245b6b18621226a493f28fa Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 26 Feb 2024 18:18:08 -0600 Subject: [PATCH 015/121] hw_device_mgr: Tweak Inovance SV660 sim drive inheritance --- hw_device_mgr/devices/inovance_sv660.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/hw_device_mgr/devices/inovance_sv660.py b/hw_device_mgr/devices/inovance_sv660.py index bb7fdb6d..664a9818 100644 --- a/hw_device_mgr/devices/inovance_sv660.py +++ b/hw_device_mgr/devices/inovance_sv660.py @@ -1,4 +1,4 @@ -from ..ethercat.device import EtherCATDevice +from ..ethercat.device import EtherCATDevice, EtherCATSimDevice from ..ethercat.config import EtherCATConfig from ..cia_402.device import CiA402Device, CiA402SimDevice from ..errors.device import ErrorDevice @@ -59,7 +59,7 @@ def get_feedback(self): return fb_out -class SimInovanceSV660(InovanceSV660, CiA402SimDevice): +class SimInovanceSV660(InovanceSV660, EtherCATSimDevice, CiA402SimDevice): def set_sim_feedback(self): # Simulate home_found feedback sfb = super().set_sim_feedback() From b4dd2762463d7283ed29f3214914233959d23da5 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 26 Feb 2024 12:42:37 -0600 Subject: [PATCH 016/121] Split out `test_read_update_write` tests into separate modules The `test_read_update_write` test can be reused with different inputs to test many different cases. Split it out so it can be subclassed and run alone without dragging in the rest of the device tests. --- hw_device_mgr/cia_301/tests/test_device.py | 31 --- .../tests/test_device_read_update_write.py | 37 +++ hw_device_mgr/cia_402/tests/test_device.py | 114 -------- .../tests/test_device_read_update_write.py | 128 +++++++++ .../tests/test_device_read_update_write.py | 8 + hw_device_mgr/hal/tests/test_device.py | 53 ---- .../tests/test_device_read_update_write.py | 68 +++++ .../tests/test_device_read_update_write.py | 18 ++ hw_device_mgr/mgr/tests/test_mgr.py | 220 --------------- .../mgr/tests/test_mgr_read_update_write.py | 237 ++++++++++++++++ hw_device_mgr/mgr_hal/tests/test_mgr.py | 50 ---- .../tests/test_mgr_read_update_write.py | 63 +++++ .../tests/test_mgr_read_update_write.py | 19 ++ .../tests/test_mgr_read_update_write.py | 13 + hw_device_mgr/tests/base_test_class.py | 9 - hw_device_mgr/tests/test_device.py | 252 +---------------- .../tests/test_device_read_update_write.py | 254 ++++++++++++++++++ 17 files changed, 854 insertions(+), 720 deletions(-) create mode 100644 hw_device_mgr/cia_301/tests/test_device_read_update_write.py create mode 100644 hw_device_mgr/cia_402/tests/test_device_read_update_write.py create mode 100644 hw_device_mgr/ethercat/tests/test_device_read_update_write.py create mode 100644 hw_device_mgr/hal/tests/test_device_read_update_write.py create mode 100644 hw_device_mgr/lcec/tests/test_device_read_update_write.py create mode 100644 hw_device_mgr/mgr/tests/test_mgr_read_update_write.py create mode 100644 hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py create mode 100644 hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py create mode 100644 hw_device_mgr/mgr_ros_hal/tests/test_mgr_read_update_write.py create mode 100644 hw_device_mgr/tests/test_device_read_update_write.py diff --git a/hw_device_mgr/cia_301/tests/test_device.py b/hw_device_mgr/cia_301/tests/test_device.py index 141f793b..792e68b0 100644 --- a/hw_device_mgr/cia_301/tests/test_device.py +++ b/hw_device_mgr/cia_301/tests/test_device.py @@ -1,7 +1,5 @@ from .base_test_class import BaseCiA301TestClass from ...tests.test_device import TestDevice as _TestDevice -import pytest -import time class TestCiA301Device(BaseCiA301TestClass, _TestDevice): @@ -10,32 +8,3 @@ class TestCiA301Device(BaseCiA301TestClass, _TestDevice): "CiA301Device", *_TestDevice.expected_mro, ] - - # CiA NMT init online & operational status test cases - read_update_write_package = "hw_device_mgr.cia_301.tests" - - @pytest.fixture - def obj(self, device_cls, sim_device_data): - self.obj = self.device_model_cls(address=sim_device_data["address"]) - self.obj.init() - yield self.obj - - def get_feedback_and_check(self): - super().get_feedback_and_check() - # Asynch param download causes a race condition. When - # feedback_out.param_state == PARAM_STATE_UPDATING, wait for the - # param download to complete before the next cycle - if not hasattr(self.device_class, "PARAM_STATE_UPDATING"): - # mgr class needs to skip the below - return - updating = self.device_class.PARAM_STATE_UPDATING - if self.test_data["feedback_out"].get("param_state", None) != updating: - return - # Spin while we wait on the worker - timeout, incr = 1, 0.01 - for i in range(int(timeout / incr)): - if self.obj.config.initialize_params(): - break - time.sleep(incr) - else: - print("initialize_params() never returned True!") diff --git a/hw_device_mgr/cia_301/tests/test_device_read_update_write.py b/hw_device_mgr/cia_301/tests/test_device_read_update_write.py new file mode 100644 index 00000000..befa7bfe --- /dev/null +++ b/hw_device_mgr/cia_301/tests/test_device_read_update_write.py @@ -0,0 +1,37 @@ +from .base_test_class import BaseCiA301TestClass +from ...tests.test_device_read_update_write import ( + TestDeviceRUW as _TestDeviceRUW, +) +import pytest +import time + + +class TestCiA301DeviceRUW(BaseCiA301TestClass, _TestDeviceRUW): + # CiA NMT init online & operational status test cases + read_update_write_package = "hw_device_mgr.cia_301.tests" + + @pytest.fixture + def obj(self, device_cls, sim_device_data): + self.obj = self.device_model_cls(address=sim_device_data["address"]) + self.obj.init() + yield self.obj + + def get_feedback_and_check(self): + super().get_feedback_and_check() + # Asynch param download causes a race condition. When + # feedback_out.param_state == PARAM_STATE_UPDATING, wait for the + # param download to complete before the next cycle + if not hasattr(self.device_class, "PARAM_STATE_UPDATING"): + # mgr class needs to skip the below + return + updating = self.device_class.PARAM_STATE_UPDATING + if self.test_data["feedback_out"].get("param_state", None) != updating: + return + # Spin while we wait on the worker + timeout, incr = 1, 0.01 + for i in range(int(timeout / incr)): + if self.obj.config.initialize_params(): + break + time.sleep(incr) + else: + print("initialize_params() never returned True!") diff --git a/hw_device_mgr/cia_402/tests/test_device.py b/hw_device_mgr/cia_402/tests/test_device.py index 0245c968..1a7021ae 100644 --- a/hw_device_mgr/cia_402/tests/test_device.py +++ b/hw_device_mgr/cia_402/tests/test_device.py @@ -48,117 +48,3 @@ def test_sw_to_str(self, cia402_cls): actual = cia402_cls.sw_to_str(sw) print(f"actual: {actual}") assert actual == expected - - def read_update_write_conv_test_data(self): - if not self.is_402_device: - return - uint16 = self.device_class.data_type_class.uint16 - for data in (self.test_data, self.ovr_data): - for intf, intf_data in data.items(): - # Format status_word, control_word for readability, e.g. 0x000F - for key in ("status_word", "control_word"): - if key in intf_data: - intf_data[key] = uint16(intf_data[key]) - - def setup_test(self, test_case): - super().setup_test(test_case) - # Add SV660N feedback_out home_found exception - mno = self.missing_not_ok["feedback_out"] - mno_home_found = mno.setdefault("home_found", set()) - mno_home_found.add((0x00100000, 0x000C010D)) - - def test_read_update_write(self, obj): - if hasattr(obj, "MODE_CSP"): - # CiA 402 device - self.read_update_write_package = self.read_update_write_402_package - self.read_update_write_yaml = self.read_update_write_402_yaml - self.is_402_device = True - else: - self.is_402_device = False - super().test_read_update_write(obj) - - def test_hm_timeout(self, obj, mock_time): - # Only applies to CiA402 devices - if not hasattr(obj, "MODE_CSP"): - return - self.is_402_device = True - - # Read test case YAML - self.read_update_write_package = self.read_update_write_402_package - self.read_update_write_yaml = "hm_timeout.cases.yaml" - test_cases = self.load_test_cases() - - # Timeouts for test - start_time = 10000 - self.now = start_time - obj.feedback_in.update(oper=True, online=True) # Normal timeout cond. - initial_timeout = obj.goal_reached_timeout - assert obj.home_timeout > initial_timeout # Sanity - - # Test case 0: from CSP enabled, command HM mode - self.read_update_write_loop(test_cases[0]) - assert obj.command_out.get("control_mode") == obj.MODE_HM - - # Test case 1: HOMING_START command to drive - self.read_update_write_loop(test_cases[1]) - assert obj.command_out.get("control_word") == 0x001F # HOMING_START - assert not obj.feedback_out.get("fault") # No timeout - - # Test case 2: Homing in progress (no time increment)) - self.read_update_write_loop(test_cases[2]) - assert not obj.feedback_out.get("fault") # No timeout - - # Test case 2: Homing in progress (small time increment) - self.now = start_time + initial_timeout + 1 - self.read_update_write_loop(test_cases[2]) - assert not obj.feedback_out.get("fault") # No timeout - - # Test case 3: Homing timeout exceeded - self.now = start_time + obj.home_timeout + 1 - self.read_update_write_loop(test_cases[3]) - assert obj.feedback_out.get("fault") # Timeout - - def test_pp_timeout(self, obj, mock_time): - # Only applies to CiA402 devices - if not hasattr(obj, "MODE_CSP"): - return - self.is_402_device = True - - # Read test case YAML - self.read_update_write_package = self.read_update_write_402_package - self.read_update_write_yaml = "pp_timeout.cases.yaml" - test_cases = self.load_test_cases() - - # Timeouts for test - start_time = 10000 - self.now = start_time - obj.feedback_in.update(oper=True, online=True) # Normal timeout cond. - initial_timeout = obj.goal_reached_timeout - assert obj.move_timeout > initial_timeout + 1 # Sanity - - # Test case 0: Command PP move - self.read_update_write_loop(test_cases[0]) - assert obj.command_out.get("control_mode") == obj.MODE_PP - - # Test case 1: NEW_SETPOINT command to drive - self.read_update_write_loop(test_cases[1]) - assert not obj.feedback_out.get("fault") # No timeout - - # Test case 2: SETPOINT_ACKNOWLEDGE feedback (no time increment) - self.read_update_write_loop(test_cases[2]) - assert not obj.feedback_out.get("fault") # No timeout - - # Test case 3: Move in progress (small time increment) - self.now = start_time + initial_timeout + 1 - self.read_update_write_loop(test_cases[3]) - assert not obj.feedback_out.get("fault") # No timeout - - # Test case 3: Move in progress (small time increment) - self.now = start_time + initial_timeout + 1 - self.read_update_write_loop(test_cases[3]) - assert not obj.feedback_out.get("fault") # No timeout - - # Test case 4: Move timeout exceeded - self.now = start_time + obj.move_timeout + 1 - self.read_update_write_loop(test_cases[4]) - assert obj.feedback_out.get("fault") # Timeout diff --git a/hw_device_mgr/cia_402/tests/test_device_read_update_write.py b/hw_device_mgr/cia_402/tests/test_device_read_update_write.py new file mode 100644 index 00000000..cfe32904 --- /dev/null +++ b/hw_device_mgr/cia_402/tests/test_device_read_update_write.py @@ -0,0 +1,128 @@ +from .base_test_class import BaseCiA402TestClass +from ...cia_301.tests.test_device_read_update_write import ( + TestCiA301DeviceRUW as _TestCiA301DeviceRUW, +) + + +class TestCiA402DeviceRUW(_TestCiA301DeviceRUW, BaseCiA402TestClass): + def read_update_write_conv_test_data(self): + if not self.is_402_device: + return + uint16 = self.device_class.data_type_class.uint16 + for data in (self.test_data, self.ovr_data): + for intf, intf_data in data.items(): + # Format status_word, control_word for readability, e.g. 0x000F + for key in ("status_word", "control_word"): + if key in intf_data: + intf_data[key] = uint16(intf_data[key]) + + def setup_test(self, test_case): + super().setup_test(test_case) + # Add SV660N feedback_out home_found exception + mno = self.missing_not_ok["feedback_out"] + mno_home_found = mno.setdefault("home_found", set()) + mno_home_found.add((0x00100000, 0x000C010D)) + + def test_read_update_write(self, obj): + if hasattr(obj, "MODE_CSP"): + # CiA 402 device + self.read_update_write_package = self.read_update_write_402_package + self.read_update_write_yaml = self.read_update_write_402_yaml + self.is_402_device = True + else: + self.is_402_device = False + super().test_read_update_write(obj) + + +class TestCiA402DeviceRUWHMTimeout(TestCiA402DeviceRUW): + def test_read_update_write(self, obj, mock_time): + # Test HM mode homing operation timeout + # + # Only applies to CiA402 devices + if not hasattr(obj, "MODE_CSP"): + return + self.is_402_device = True + + # Read test case YAML + self.read_update_write_package = self.read_update_write_402_package + self.read_update_write_yaml = "hm_timeout.cases.yaml" + test_cases = self.load_test_cases() + + # Timeouts for test + start_time = 10000 + self.now = start_time + obj.feedback_in.update(oper=True, online=True) # Normal timeout cond. + initial_timeout = obj.goal_reached_timeout + assert obj.home_timeout > initial_timeout # Sanity + + # Test case 0: from CSP enabled, command HM mode + self.read_update_write_loop(test_cases[0]) + assert obj.command_out.get("control_mode") == obj.MODE_HM + + # Test case 1: HOMING_START command to drive + self.read_update_write_loop(test_cases[1]) + assert obj.command_out.get("control_word") == 0x001F # HOMING_START + assert not obj.feedback_out.get("fault") # No timeout + + # Test case 2: Homing in progress (no time increment)) + self.read_update_write_loop(test_cases[2]) + assert not obj.feedback_out.get("fault") # No timeout + + # Test case 2: Homing in progress (small time increment) + self.now = start_time + initial_timeout + 1 + self.read_update_write_loop(test_cases[2]) + assert not obj.feedback_out.get("fault") # No timeout + + # Test case 3: Homing timeout exceeded + self.now = start_time + obj.home_timeout + 1 + self.read_update_write_loop(test_cases[3]) + assert obj.feedback_out.get("fault") # Timeout + + +class TestCiA402DeviceRUWPPTimeout(TestCiA402DeviceRUW): + def test_read_update_write(self, obj, mock_time): + # Test PP mode move timeout + # + # Only applies to CiA402 devices + if not hasattr(obj, "MODE_CSP"): + return + self.is_402_device = True + + # Read test case YAML + self.read_update_write_package = self.read_update_write_402_package + self.read_update_write_yaml = "pp_timeout.cases.yaml" + test_cases = self.load_test_cases() + + # Timeouts for test + start_time = 10000 + self.now = start_time + obj.feedback_in.update(oper=True, online=True) # Normal timeout cond. + initial_timeout = obj.goal_reached_timeout + assert obj.move_timeout > initial_timeout + 1 # Sanity + + # Test case 0: Command PP move + self.read_update_write_loop(test_cases[0]) + assert obj.command_out.get("control_mode") == obj.MODE_PP + + # Test case 1: NEW_SETPOINT command to drive + self.read_update_write_loop(test_cases[1]) + assert not obj.feedback_out.get("fault") # No timeout + + # Test case 2: SETPOINT_ACKNOWLEDGE feedback (no time increment) + self.read_update_write_loop(test_cases[2]) + assert not obj.feedback_out.get("fault") # No timeout + + # Test case 3: Move in progress (small time increment) + self.now = start_time + initial_timeout + 1 + self.read_update_write_loop(test_cases[3]) + assert not obj.feedback_out.get("fault") # No timeout + + # Test case 3: Move in progress (small time increment) + self.now = start_time + initial_timeout + 1 + self.read_update_write_loop(test_cases[3]) + assert not obj.feedback_out.get("fault") # No timeout + + # Test case 4: Move timeout exceeded + self.now = start_time + obj.move_timeout + 1 + self.read_update_write_loop(test_cases[4]) + assert obj.feedback_out.get("fault") # Timeout diff --git a/hw_device_mgr/ethercat/tests/test_device_read_update_write.py b/hw_device_mgr/ethercat/tests/test_device_read_update_write.py new file mode 100644 index 00000000..0630cb22 --- /dev/null +++ b/hw_device_mgr/ethercat/tests/test_device_read_update_write.py @@ -0,0 +1,8 @@ +from ...cia_402.tests.test_device_read_update_write import ( + TestCiA402DeviceRUW as _TestCiA402DeviceRUW, +) +from .base_test_class import BaseEtherCATTestClass + + +class TestEtherCATDeviceRUW(BaseEtherCATTestClass, _TestCiA402DeviceRUW): + pass diff --git a/hw_device_mgr/hal/tests/test_device.py b/hw_device_mgr/hal/tests/test_device.py index bee85663..06661e64 100644 --- a/hw_device_mgr/hal/tests/test_device.py +++ b/hw_device_mgr/hal/tests/test_device.py @@ -41,56 +41,3 @@ def test_init(self, obj): continue names.add(name) assert names == set(obj.pins[intf_name].keys()) - - ######################################### - # Test read()/update()/write() integration - # - - def override_interface_param(self, interface, ovr_data): - intf = self.obj.interface(interface) - intf.update(**ovr_data) - if interface not in self.obj.pin_interfaces: - return - dt_names = self.obj.merge_dict_attrs(f"{interface}_data_types") - for key, val in ovr_data.items(): - dt = dt_names.get(key, None) - if dt is not None: - val = self.obj.data_type_class.by_shared_name(dt)(val) - pname = self.obj.pin_name(interface, key) - self.set_pin(pname, val) - - def copy_sim_feedback(self, obj=None): - if obj is None: - obj = self.obj - print(f"\n*** Copy HAL pin values sim_feedback -> feedback_in {obj}") - for name in obj.sim_feedback.get(): - sfbpname = obj.pin_name("sim_feedback", name) - fbpname = obj.pin_name("feedback_in", name) - sfb_val = self.get_pin(sfbpname) - self.set_pin(fbpname, sfb_val) - fb_val = self.get_pin(fbpname) - assert sfb_val == fb_val - print(f"*** Finished sim_feedback HAL pin copy {obj}") - - def pre_read_actions(self): - self.copy_sim_feedback() - - def check_halpin_values(self, iface, obj=None): - if obj is None: - obj = self.obj - print(f"\n*** Checking {obj} {iface} halpin values") - pins = obj.pins[iface] - for name, iface_val in obj.interface(iface).get().items(): - if name not in pins: - print(f" {name}: no HAL pin") - continue - pname = obj.pin_name(iface, name) - pin_val = self.get_pin(pname) - print(f" {pname}={pin_val}, {name}={iface_val}") - assert pin_val == iface_val - - def post_write_actions(self): - obj = self.obj - for iface, pins in obj.pins.items(): - if obj.pin_interfaces[iface][0] == obj.HAL_OUT: - self.check_halpin_values(iface, obj) diff --git a/hw_device_mgr/hal/tests/test_device_read_update_write.py b/hw_device_mgr/hal/tests/test_device_read_update_write.py new file mode 100644 index 00000000..a1c9a706 --- /dev/null +++ b/hw_device_mgr/hal/tests/test_device_read_update_write.py @@ -0,0 +1,68 @@ +import pytest +from .base_test_class import BaseHALTestClass +from ...cia_402.tests.test_device_read_update_write import ( + TestCiA402DeviceRUW as _TestCiA402DeviceRUW, +) + + +class TestHALDeviceRUW(BaseHALTestClass, _TestCiA402DeviceRUW): + halcomp_name = "hal_device" + + @pytest.fixture + def obj(self, sim_device_data, mock_halcomp, device_cls): + self.obj = self.device_model_cls(address=sim_device_data["address"]) + self.obj.init(comp=mock_halcomp) + yield self.obj + + ######################################### + # Test read()/update()/write() integration + # + + def override_interface_param(self, interface, ovr_data): + intf = self.obj.interface(interface) + intf.update(**ovr_data) + if interface not in self.obj.pin_interfaces: + return + dt_names = self.obj.merge_dict_attrs(f"{interface}_data_types") + for key, val in ovr_data.items(): + dt = dt_names.get(key, None) + if dt is not None: + val = self.obj.data_type_class.by_shared_name(dt)(val) + pname = self.obj.pin_name(interface, key) + self.set_pin(pname, val) + + def copy_sim_feedback(self, obj=None): + if obj is None: + obj = self.obj + print(f"\n*** Copy HAL pin values sim_feedback -> feedback_in {obj}") + for name in obj.sim_feedback.get(): + sfbpname = obj.pin_name("sim_feedback", name) + fbpname = obj.pin_name("feedback_in", name) + sfb_val = self.get_pin(sfbpname) + self.set_pin(fbpname, sfb_val) + fb_val = self.get_pin(fbpname) + assert sfb_val == fb_val + print(f"*** Finished sim_feedback HAL pin copy {obj}") + + def pre_read_actions(self): + self.copy_sim_feedback() + + def check_halpin_values(self, iface, obj=None): + if obj is None: + obj = self.obj + print(f"\n*** Checking {obj} {iface} halpin values") + pins = obj.pins[iface] + for name, iface_val in obj.interface(iface).get().items(): + if name not in pins: + print(f" {name}: no HAL pin") + continue + pname = obj.pin_name(iface, name) + pin_val = self.get_pin(pname) + print(f" {pname}={pin_val}, {name}={iface_val}") + assert pin_val == iface_val + + def post_write_actions(self): + obj = self.obj + for iface, pins in obj.pins.items(): + if obj.pin_interfaces[iface][0] == obj.HAL_OUT: + self.check_halpin_values(iface, obj) diff --git a/hw_device_mgr/lcec/tests/test_device_read_update_write.py b/hw_device_mgr/lcec/tests/test_device_read_update_write.py new file mode 100644 index 00000000..a5225cb1 --- /dev/null +++ b/hw_device_mgr/lcec/tests/test_device_read_update_write.py @@ -0,0 +1,18 @@ +import pytest +from ...ethercat.tests.test_device_read_update_write import ( + TestEtherCATDeviceRUW as _TestEtherCATDeviceRUW, +) +from ...hal.tests.test_device_read_update_write import ( + TestHALDeviceRUW as _TestHALDeviceRUW, +) +from .base_test_class import BaseLCECTestClass + + +class TestLCECDeviceRUW( + BaseLCECTestClass, _TestEtherCATDeviceRUW, _TestHALDeviceRUW +): + @pytest.fixture + def obj(self, sim_device_data, mock_halcomp, device_cls): + self.obj = self.device_model_cls(address=sim_device_data["address"]) + self.obj.init(comp=mock_halcomp) + yield self.obj diff --git a/hw_device_mgr/mgr/tests/test_mgr.py b/hw_device_mgr/mgr/tests/test_mgr.py index 0b913d7d..3b1cb300 100644 --- a/hw_device_mgr/mgr/tests/test_mgr.py +++ b/hw_device_mgr/mgr/tests/test_mgr.py @@ -1,9 +1,6 @@ from .base_test_class import BaseMgrTestClass from ...tests.test_device import TestDevice as _TestDevice -import re import pytest -import time -from functools import lru_cache, cached_property class TestHWDeviceMgr(BaseMgrTestClass, _TestDevice): @@ -25,58 +22,6 @@ def obj(self, mgr_config, device_config, all_device_data): ) yield self.obj - test_case_key_re = re.compile(r"^d\.([x0-9])\.(.*)$") - drive_interface_key_re = re.compile(r"^d([0-9])\.([0-9]+)\.([0-9]+)\.(.*)$") - - @cached_property - def drive_addr_to_index_map(self): - """Map drive address (& all aliases) to `mgr.devices` list index.""" - config_class = self.device_base_class.config_class - index_map = dict() - for i, d in enumerate(self.obj.devices): - index_map[d.address] = i - for addr in config_class.address_variants(d.address): - index_map[addr] = i - return index_map - - @cached_property - def string_format_kwargs(self): - """YAML string `format()` keyword args.""" - items = enumerate(str(d) for d in self.obj.devices) - drive_strs = [item[1] for item in items] - return dict( - drives=drive_strs, - drives3plus=",".join(drive_strs[3:]), - all_drives=",".join(drive_strs), - ) - - @lru_cache - def obj_interface_to_test_case_kv(self, interface_key, interface_val): - # Translate interface values `Foo {address[6]} bar` to - # `Foo (0, 1, 0) bar` - val = interface_val - if isinstance(val, str): - val = val.format(**self.string_format_kwargs) - - # Extract drive address `(0, 16, 0)` from key `d0.16.0.control_mode` - m = self.drive_interface_key_re.match(interface_key) - if m is None: - return interface_key, val # Doesn't match fmt. `d.6.control_mode` - address = tuple(map(int, m.groups()[:-1])) # (0, 16, 0) - # Get device test case index - index = self.drive_addr_to_index_map[address] # 6 - - # Translate test object interface key `d0.16.0.control_mode` to test - # case key `d.6.control_mode` - key = f"d.{index}.{m.groups()[-1]}" # "d.6.control_mode" - - return key, val - - def obj_interface_to_test_case(self, data): - return dict( - self.obj_interface_to_test_case_kv(k, v) for k, v in data.items() - ) - def test_state_values(self, obj): values = dict() print(f"cmd_name_to_int_map: {obj.cmd_name_to_int_map}") @@ -105,168 +50,3 @@ def test_category_registry(self): # tests break, even though there's nothing wrong with the mgr class. # Fixing it isn't useful, so skip it instead. pass - - def read_update_write_conv_test_data(self): - uint16 = self.device_class.data_type_class.uint16 - for data in (self.test_data, self.ovr_data): - for intf, intf_data in data.items(): - for key in intf_data.keys(): - # Test drive keys - match = self.test_case_key_re.match(key) - if not match: - continue # Only testing drive keys - if match.group(2) in ("status_word", "control_word"): - # Format status_word, control_word for - # readability, e.g. 0x000F - intf_data[key] = uint16(intf_data[key]) - - def munge_test_case_data(self, test_case, dst, suffix=""): - # Expand d.x.foo -> d.1.foo, etc.; don't clobber - # specific case - for intf in self.device_class.interface_names: - values = test_case.get(intf + suffix, dict()) - intf_dst = dst.setdefault(intf, dict()) - for key, val in values.items(): - match = self.test_case_key_re.match(key) - if not match: - intf_dst[key] = val - continue # Regular attribute, not d.x.foo - d_ix, d_key = match.groups() - if d_ix == "x": - for i, dev in enumerate(self.obj.devices): - dev_key = f"d.{i}.{d_key}" - if dev_key not in values: - intf_dst[dev_key] = val - else: - d_ix = int(d_ix) - dev_key = f"d.{d_ix}.{d_key}" - intf_dst[dev_key] = val - - def munge_interface_data(self, interface): - # Translate test case key `d.6.control_mode` to object interface key - # `d0.16.control_mode` - data_raw = super().munge_interface_data(interface) - data = dict() - for key, val in data_raw.items(): - m = self.test_case_key_re.match(key) - if m is None: - # Doesn't match fmt. `d.6.control_mode` - data[key] = val - else: - index, key = m.groups() # ("6", "control_mode") - dev = self.obj.devices[int(index)] - pfx = self.obj.dev_prefix(dev, suffix=dev.slug_separator) - dev_key = f"{pfx}{key}" # "d0.16.control_mode" - data[dev_key] = val - - return data - - def override_interface_param(self, interface, ovr_data): - for key, val in ovr_data.items(): - match = self.test_case_key_re.match(key) - if match: - index, key = match.groups() - intf = self.obj.devices[int(index)].interface(interface) - intf.update(**{key: val}) - else: - super().override_interface_param(interface, {key: val}) - - def check_interface_values(self, interface, indent=4): - if interface in {"feedback_out", "command_in"}: - # Higher level interfaces to application - return self.check_interface_values_higher(interface, indent=indent) - else: - # Lower level interfaces close to hardware interface - return self.check_interface_values_lower(interface, indent=indent) - - def check_interface_values_higher(self, interface, indent=4): - # Check feedback_in, command_out, sim interfaces - expected_raw = self.test_data[interface] - expected = self.obj_interface_to_test_case(expected_raw) - actual_raw = self.obj.interface(interface).get() - actual = self.obj_interface_to_test_case(actual_raw) - # self.print_dict(actual, f"Actual {interface}", indent=2) - if super().check_data_values(interface, expected, actual, indent): - return True - else: - print(f"FAILURE at {self.test_desc}") - return False - - def split_drive_data(self, data): - # The manager is a device, and each of obj.devices is a - # device. The test cases are crammed together with device - # keys prefixed with `d.x.`, meaning it applies to all - # drives, or prefixed with `d.0.`, meaning it applies to - # the first drive, or prefixed with nothing, meaning it - # applies to the manager. - mgr_data = data.copy() - device_data = list([dict() for d in self.obj.devices]) - for drive_key, val in list(mgr_data.items()): - match = self.test_case_key_re.match(drive_key) - if not match: - continue # Not a drive_key - val = mgr_data.pop(drive_key) - index, key = match.groups() - device_data[int(index)][key] = val - return mgr_data, device_data - - def check_interface_values_lower(self, interface, indent=4): - # Check feedback_in, command_out, sim interfaces - - # Prepare expected data - expected = self.test_data[interface] - mgr_expected, device_expected = self.split_drive_data(expected) - for k, v in mgr_expected.items(): - if isinstance(v, str): - mgr_expected[k] = v.format(**self.string_format_kwargs) - # self.print_dict(mgr_expected, f"Expected {interface}", indent=2) - # for i, d in enumerate(device_expected): - # self.print_dict(d, f"drive_{i}", indent=4) - - # Check actual against expected data - passing = True - # - Mgr - actual_raw = self.obj.interface(interface).get() - actual = self.obj_interface_to_test_case(actual_raw) - # self.print_dict(actual, f"Actual {interface}", indent=2) - passing &= self.check_data_values( - interface, mgr_expected, actual, indent=indent - ) - - # - Devices - for i, device in enumerate(self.obj.devices): - actual = device.interface(interface).get() - # self.print_dict(actual, f"drive_{i}", indent=4) - passing &= self.check_data_values( - "", device_expected[i], actual, indent=indent, prefix=f"d.{i}." - ) - - if not passing: - print(f"FAILURE at {self.test_desc}") - return passing - - def setup_test(self, test_case): - super().setup_test(test_case) - # Add SV660N feedback_out home_found exception - mno = self.missing_not_ok["feedback_out"] - for i in range(7): - mno.setdefault(f"d.{i}.home_found", set()) # Empty set signifies OK - - def get_feedback_and_check(self): - super().get_feedback_and_check() - # Asynch param download causes a race condition. When - # feedback_out.param_state == PARAM_STATE_UPDATING, wait for the - # param download to complete before the next cycle - updating = self.device_base_class.PARAM_STATE_UPDATING - test_data = self.test_data["feedback_out"] - for i, dev in enumerate(self.obj.devices): - if test_data.get(f"d.{i}.param_state", None) != updating: - continue - # Spin while we wait on the worker - timeout, incr = 1, 0.01 - for i in range(int(timeout / incr)): - if dev.config.initialize_params(): - break - time.sleep(incr) - else: - print(f"{dev}.initialize_params() never returned True!") diff --git a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py new file mode 100644 index 00000000..e64a66ec --- /dev/null +++ b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py @@ -0,0 +1,237 @@ +from .base_test_class import BaseMgrTestClass +from ...tests.test_device_read_update_write import ( + TestDeviceRUW as _TestDeviceRUW, +) +import re +import pytest +import time +from functools import lru_cache, cached_property + + +class TestHWDeviceMgrRUW(BaseMgrTestClass, _TestDeviceRUW): + @pytest.fixture + def obj(self, mgr_config, device_config, all_device_data): + self.obj = self.device_class() + self.obj.init( + mgr_config=mgr_config, + device_config=device_config, + sim_device_data=all_device_data.values(), + ) + yield self.obj + + test_case_key_re = re.compile(r"^d\.([x0-9])\.(.*)$") + drive_interface_key_re = re.compile(r"^d([0-9])\.([0-9]+)\.([0-9]+)\.(.*)$") + + @cached_property + def drive_addr_to_index_map(self): + """Map drive address (& all aliases) to `mgr.devices` list index.""" + config_class = self.device_base_class.config_class + index_map = dict() + for i, d in enumerate(self.obj.devices): + index_map[d.address] = i + for addr in config_class.address_variants(d.address): + index_map[addr] = i + return index_map + + @cached_property + def string_format_kwargs(self): + """YAML string `format()` keyword args.""" + items = enumerate(str(d) for d in self.obj.devices) + drive_strs = [item[1] for item in items] + return dict( + drives=drive_strs, + drives3plus=",".join(drive_strs[3:]), + all_drives=",".join(drive_strs), + ) + + @lru_cache + def obj_interface_to_test_case_kv(self, interface_key, interface_val): + # Translate interface values `Foo {address[6]} bar` to + # `Foo (0, 1, 0) bar` + val = interface_val + if isinstance(val, str): + val = val.format(**self.string_format_kwargs) + + # Extract drive address `(0, 16, 0)` from key `d0.16.0.control_mode` + m = self.drive_interface_key_re.match(interface_key) + if m is None: + return interface_key, val # Doesn't match fmt. `d.6.control_mode` + address = tuple(map(int, m.groups()[:-1])) # (0, 16, 0) + # Get device test case index + index = self.drive_addr_to_index_map[address] # 6 + + # Translate test object interface key `d0.16.0.control_mode` to test + # case key `d.6.control_mode` + key = f"d.{index}.{m.groups()[-1]}" # "d.6.control_mode" + + return key, val + + def obj_interface_to_test_case(self, data): + return dict( + self.obj_interface_to_test_case_kv(k, v) for k, v in data.items() + ) + + def read_update_write_conv_test_data(self): + uint16 = self.device_class.data_type_class.uint16 + for data in (self.test_data, self.ovr_data): + for intf, intf_data in data.items(): + for key in intf_data.keys(): + # Test drive keys + match = self.test_case_key_re.match(key) + if not match: + continue # Only testing drive keys + if match.group(2) in ("status_word", "control_word"): + # Format status_word, control_word for + # readability, e.g. 0x000F + intf_data[key] = uint16(intf_data[key]) + + def munge_test_case_data(self, test_case, dst, suffix=""): + # Expand d.x.foo -> d.1.foo, etc.; don't clobber + # specific case + for intf in self.device_class.interface_names: + values = test_case.get(intf + suffix, dict()) + intf_dst = dst.setdefault(intf, dict()) + for key, val in values.items(): + match = self.test_case_key_re.match(key) + if not match: + intf_dst[key] = val + continue # Regular attribute, not d.x.foo + d_ix, d_key = match.groups() + if d_ix == "x": + for i, dev in enumerate(self.obj.devices): + dev_key = f"d.{i}.{d_key}" + if dev_key not in values: + intf_dst[dev_key] = val + else: + d_ix = int(d_ix) + dev_key = f"d.{d_ix}.{d_key}" + intf_dst[dev_key] = val + + def munge_interface_data(self, interface): + # Translate test case key `d.6.control_mode` to object interface key + # `d0.16.control_mode` + data_raw = super().munge_interface_data(interface) + data = dict() + for key, val in data_raw.items(): + m = self.test_case_key_re.match(key) + if m is None: + # Doesn't match fmt. `d.6.control_mode` + data[key] = val + else: + index, key = m.groups() # ("6", "control_mode") + dev = self.obj.devices[int(index)] + pfx = self.obj.dev_prefix(dev, suffix=dev.slug_separator) + dev_key = f"{pfx}{key}" # "d0.16.control_mode" + data[dev_key] = val + + return data + + def override_interface_param(self, interface, ovr_data): + for key, val in ovr_data.items(): + match = self.test_case_key_re.match(key) + if match: + index, key = match.groups() + intf = self.obj.devices[int(index)].interface(interface) + intf.update(**{key: val}) + else: + super().override_interface_param(interface, {key: val}) + + def check_interface_values(self, interface, indent=4): + if interface in {"feedback_out", "command_in"}: + # Higher level interfaces to application + return self.check_interface_values_higher(interface, indent=indent) + else: + # Lower level interfaces close to hardware interface + return self.check_interface_values_lower(interface, indent=indent) + + def check_interface_values_higher(self, interface, indent=4): + # Check feedback_in, command_out, sim interfaces + expected_raw = self.test_data[interface] + expected = self.obj_interface_to_test_case(expected_raw) + actual_raw = self.obj.interface(interface).get() + actual = self.obj_interface_to_test_case(actual_raw) + # self.print_dict(actual, f"Actual {interface}", indent=2) + if super().check_data_values(interface, expected, actual, indent): + return True + else: + print(f"FAILURE at {self.test_desc}") + return False + + def split_drive_data(self, data): + # The manager is a device, and each of obj.devices is a + # device. The test cases are crammed together with device + # keys prefixed with `d.x.`, meaning it applies to all + # drives, or prefixed with `d.0.`, meaning it applies to + # the first drive, or prefixed with nothing, meaning it + # applies to the manager. + mgr_data = data.copy() + device_data = list([dict() for d in self.obj.devices]) + for drive_key, val in list(mgr_data.items()): + match = self.test_case_key_re.match(drive_key) + if not match: + continue # Not a drive_key + val = mgr_data.pop(drive_key) + index, key = match.groups() + device_data[int(index)][key] = val + return mgr_data, device_data + + def check_interface_values_lower(self, interface, indent=4): + # Check feedback_in, command_out, sim interfaces + + # Prepare expected data + expected = self.test_data[interface] + mgr_expected, device_expected = self.split_drive_data(expected) + for k, v in mgr_expected.items(): + if isinstance(v, str): + mgr_expected[k] = v.format(**self.string_format_kwargs) + # self.print_dict(mgr_expected, f"Expected {interface}", indent=2) + # for i, d in enumerate(device_expected): + # self.print_dict(d, f"drive_{i}", indent=4) + + # Check actual against expected data + passing = True + # - Mgr + actual_raw = self.obj.interface(interface).get() + actual = self.obj_interface_to_test_case(actual_raw) + # self.print_dict(actual, f"Actual {interface}", indent=2) + passing &= self.check_data_values( + interface, mgr_expected, actual, indent=indent + ) + + # - Devices + for i, device in enumerate(self.obj.devices): + actual = device.interface(interface).get() + # self.print_dict(actual, f"drive_{i}", indent=4) + passing &= self.check_data_values( + "", device_expected[i], actual, indent=indent, prefix=f"d.{i}." + ) + + if not passing: + print(f"FAILURE at {self.test_desc}") + return passing + + def setup_test(self, test_case): + super().setup_test(test_case) + # Add SV660N feedback_out home_found exception + mno = self.missing_not_ok["feedback_out"] + for i in range(7): + mno.setdefault(f"d.{i}.home_found", set()) # Empty set signifies OK + + def get_feedback_and_check(self): + super().get_feedback_and_check() + # Asynch param download causes a race condition. When + # feedback_out.param_state == PARAM_STATE_UPDATING, wait for the + # param download to complete before the next cycle + updating = self.device_base_class.PARAM_STATE_UPDATING + test_data = self.test_data["feedback_out"] + for i, dev in enumerate(self.obj.devices): + if test_data.get(f"d.{i}.param_state", None) != updating: + continue + # Spin while we wait on the worker + timeout, incr = 1, 0.01 + for i in range(int(timeout / incr)): + if dev.config.initialize_params(): + break + time.sleep(incr) + else: + print(f"{dev}.initialize_params() never returned True!") diff --git a/hw_device_mgr/mgr_hal/tests/test_mgr.py b/hw_device_mgr/mgr_hal/tests/test_mgr.py index 42fa5f57..4fb21767 100644 --- a/hw_device_mgr/mgr_hal/tests/test_mgr.py +++ b/hw_device_mgr/mgr_hal/tests/test_mgr.py @@ -15,53 +15,3 @@ class TestHALHWDeviceMgr(BaseHALMgrTestClass, _TestHWDeviceMgr, _TestHALDevice): *_TestHWDeviceMgr.expected_mro[2:], # HWDeviceMgr...ABC _TestHALDevice.expected_mro[-1], # HalMixin (skip CiA301, etc.) ] - - def override_interface_param(self, interface, ovr_data): - for key, val in ovr_data.items(): - match = self.test_case_key_re.match(key) - if match: - index, key = match.groups() - dev = self.obj.devices[int(index)] - pname = dev.pin_name(interface, key) - self.set_pin(pname, val) - else: - super().override_interface_param(interface, key, val) - - def copy_sim_feedback(self): - super().copy_sim_feedback() - for dev in self.obj.devices: - super().copy_sim_feedback(obj=dev) - - def post_read_actions(self, obj=None): - if obj is None: - obj = self.obj - super().post_read_actions() - for dev in obj.devices: - self.post_read_actions(dev) - - print(f" feedback_in pin values: {obj}") - for name in obj.pins["feedback_in"]: - pname = obj.pin_name("feedback_in", name) - val = self.get_pin(pname) - print(f" {pname} = {val}") - assert val == obj.feedback_in.get(name) - print() - - def munge_interface_data(self, interface): - # `HALDevice.set_command()` takes no arguments, and reads from HAL pins - # instead. - data = super().munge_interface_data(interface) - if interface != "command_in": - return data # Do the usual thing for other interfaces - # For `command_in`, write HAL pins - print(" (Setting command_in HAL pins)") - for key, val in data.items(): - self.set_pin(key, val) - return dict() - - def post_write_actions(self): - super().post_write_actions() - for dev in self.obj.devices: - for iface in dev.pins: - if dev.pin_interfaces[iface][0] == dev.HAL_OUT: - self.check_halpin_values(iface, dev) diff --git a/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py new file mode 100644 index 00000000..410e27a7 --- /dev/null +++ b/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py @@ -0,0 +1,63 @@ +from .base_test_class import BaseHALMgrTestClass +from ...mgr.tests.test_mgr_read_update_write import ( + TestHWDeviceMgrRUW as _TestHWDeviceMgrRUW, +) +from ...hal.tests.test_device_read_update_write import ( + TestHALDeviceRUW as _TestHALDeviceRUW, +) + + +class TestHALHWDeviceMgrRUW( + BaseHALMgrTestClass, _TestHWDeviceMgrRUW, _TestHALDeviceRUW +): + halcomp_name = "hal_mgr" + + def override_interface_param(self, interface, ovr_data): + for key, val in ovr_data.items(): + match = self.test_case_key_re.match(key) + if match: + index, key = match.groups() + dev = self.obj.devices[int(index)] + pname = dev.pin_name(interface, key) + self.set_pin(pname, val) + else: + super().override_interface_param(interface, key, val) + + def copy_sim_feedback(self): + super().copy_sim_feedback() + for dev in self.obj.devices: + super().copy_sim_feedback(obj=dev) + + def post_read_actions(self, obj=None): + if obj is None: + obj = self.obj + super().post_read_actions() + for dev in obj.devices: + self.post_read_actions(dev) + + print(f" feedback_in pin values: {obj}") + for name in obj.pins["feedback_in"]: + pname = obj.pin_name("feedback_in", name) + val = self.get_pin(pname) + print(f" {pname} = {val}") + assert val == obj.feedback_in.get(name) + print() + + def munge_interface_data(self, interface): + # `HALDevice.set_command()` takes no arguments, and reads from HAL pins + # instead. + data = super().munge_interface_data(interface) + if interface != "command_in": + return data # Do the usual thing for other interfaces + # For `command_in`, write HAL pins + print(" (Setting command_in HAL pins)") + for key, val in data.items(): + self.set_pin(key, val) + return dict() + + def post_write_actions(self): + super().post_write_actions() + for dev in self.obj.devices: + for iface in dev.pins: + if dev.pin_interfaces[iface][0] == dev.HAL_OUT: + self.check_halpin_values(iface, dev) diff --git a/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py new file mode 100644 index 00000000..7563b791 --- /dev/null +++ b/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py @@ -0,0 +1,19 @@ +from .base_test_class import BaseROSMgrTestClass +from ...mgr.tests.test_mgr_read_update_write import ( + TestHWDeviceMgrRUW as _TestHWDeviceMgrRUW, +) +import pytest + + +class TestROSHWDeviceMgrRUW(BaseROSMgrTestClass, _TestHWDeviceMgrRUW): + rclpy_patches = [ + "hw_device_mgr.mgr_ros.mgr.rclpy", + ] + + @pytest.fixture + def obj(self, category_cls): + # init_sim() and init_devices() signatures changed, so can't + # use parent test class obj fixture + self.obj = self.device_class() + self.obj.init(argv=list()) + yield self.obj diff --git a/hw_device_mgr/mgr_ros_hal/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr_ros_hal/tests/test_mgr_read_update_write.py new file mode 100644 index 00000000..43fb24d6 --- /dev/null +++ b/hw_device_mgr/mgr_ros_hal/tests/test_mgr_read_update_write.py @@ -0,0 +1,13 @@ +from .base_test_class import BaseROSHALMgrTestClass +from ...mgr_ros.tests.test_mgr_read_update_write import ( + TestROSHWDeviceMgrRUW as _TestROSHWDeviceMgrRUW, +) +from ...mgr_hal.tests.test_mgr_read_update_write import ( + TestHALHWDeviceMgrRUW as _TestHALHWDeviceMgrRUW, +) + + +class TestROSHWDeviceMgrRUW( + BaseROSHALMgrTestClass, _TestHALHWDeviceMgrRUW, _TestROSHWDeviceMgrRUW +): + pass diff --git a/hw_device_mgr/tests/base_test_class.py b/hw_device_mgr/tests/base_test_class.py index f3dd1636..98d3e341 100644 --- a/hw_device_mgr/tests/base_test_class.py +++ b/hw_device_mgr/tests/base_test_class.py @@ -1,5 +1,4 @@ import pytest -from pprint import pformat from ..config_io import ConfigIO from .bogus_devices.data_types import BogusDataType from .bogus_devices.device import ( @@ -234,11 +233,3 @@ def pytest_generate_tests(self, metafunc): # Parametrize it if names: metafunc.parametrize(names, vals, ids=ids, scope="class") - - def test_fixture(self, device_cls, sim_device_data, category_cls): - print("device_cls:", device_cls) - print("sim_device_data:\n", pformat(sim_device_data)) - assert sim_device_data["device_cls"] is device_cls - assert hasattr(device_cls, "name") - assert device_cls in self.device_model_classes - assert issubclass(device_cls, category_cls) diff --git a/hw_device_mgr/tests/test_device.py b/hw_device_mgr/tests/test_device.py index f6a2d7a2..6c14a595 100644 --- a/hw_device_mgr/tests/test_device.py +++ b/hw_device_mgr/tests/test_device.py @@ -14,6 +14,15 @@ class TestDevice(BaseTestClass): "ABC", ] + def test_fixture(self, device_cls, sim_device_data, category_cls): + # Fixture sanity check + print("device_cls:", device_cls) + print("sim_device_data:\n", pformat(sim_device_data)) + assert sim_device_data["device_cls"] is device_cls + assert hasattr(device_cls, "name") + assert device_cls in self.device_model_classes + assert issubclass(device_cls, category_cls) + # # Class tests # @@ -194,246 +203,3 @@ def do_test(expected): self.now += 1000 fb_set(True, False) assert not obj.check_and_set_timeout() - - ######################################### - # Test read()/update()/write() integration - # - # Run object through test cases defined in external .yaml file: - # - Optionally set goal and/or override feedback - # - Check expected feedback & command, in & out - - # Configuration - # - YAML test cases package resource - read_update_write_package = None # Skip tests if None - read_update_write_yaml = "read_update_write.cases.yaml" - # - Translate feedback/command test input params from values - # human-readable in .yaml to values matching actual params - read_update_write_translate_feedback_in = dict() - read_update_write_translate_feedback_out = dict() - read_update_write_translate_command_in = dict() - read_update_write_translate_command_out = dict() - read_update_write_translate_sim_feedback = dict() - - def read_update_write_conv_test_data(self): - # Subclasses may massage data - pass - - # - # Setup - # - - # Print intro and merge test case updates - def setup_test(self, test_case): - self.test_desc = test_case["desc"] - print() - print("*" * 80) - print(" ", test_case["desc"]) - print("*" * 80) - print(f"obj: {self.obj}") - # Throw separator into pytest log output - self.obj.logger.info(f"Step -> {self.test_desc}") - - # Expected feedback/command in/out data: Update values from - # last iteration - # - self.test_data = getattr(self, "test_data", dict()) - self.munge_test_case_data(test_case, self.test_data) - - # Override feedback/command/sim_feedback data - # - # Unlike check data, override data isn't carried over from - # previous iterations - # - self.ovr_data = dict() - self.munge_test_case_data(test_case, self.ovr_data, suffix="_set") - - # Nested dictionaries of { interface : { attr : { model_id, ... } } }: - # model_id must have interface attribute; for other models, missing OK - self.missing_not_ok = { - i: dict() for i in self.device_class.interface_names - } - - self.read_update_write_conv_test_data() - # self.print_dict(self.test_data, "Test data") - # self.print_dict(self.ovr_data, "Override data") - - def munge_test_case_data(self, test_case, dst, suffix=""): - for intf in self.device_class.interface_names: - values = test_case.get(intf + suffix, dict()) - dst.setdefault(intf, dict()).update(values) - - # - # Read, get_feedback, set_command, write - # - def read_and_check(self): - print("\n*** Overriding sim_feedback") - self.override_data("sim_feedback") - print("\n*** Running object read() and checking feedback") - self.pre_read_actions() - self.obj.read() - self.post_read_actions() - assert self.check_interface_values("feedback_in") - - def pre_read_actions(self): - """Provide hook for inserting actions before `read()`.""" - pass - - def post_read_actions(self): - """Provide hook for inserting actions after `read()`.""" - pass - - def get_feedback_and_check(self): - print("\n*** Overriding feedback_in") - self.override_data("feedback_in") - print("\n*** Overriding command_in") - self.override_data("command_in") - # self.print_dict(self.test_data, "Test data (after override)") - print("\n*** Running object get_feedback()") - self.obj.get_feedback() - # self.print_dict( - # self.obj.interface("feedback_out").get(), "feedback_out", indent=2 - # ) - assert self.check_interface_values("feedback_out") - - def munge_interface_data(self, interface): - # Do any test data manipulation before sending to interface; subclasses - # may override - return self.test_data[interface] - - def set_command_and_check(self): - print("\n*** Running object set_command()") - self.obj.set_command(**self.munge_interface_data("command_in")) - assert self.check_interface_values("command_in") - assert self.check_interface_values("command_out") - print("\n*** Overriding command_out") - self.override_data("command_out") - # self.print_dict(self.test_data, "Test data (after override)") - - def write_and_check(self): - print("\n*** Running object write() and checking sim_feedback") - self.obj.write() - assert self.check_interface_values("sim_feedback") - self.post_write_actions() - - def post_write_actions(self): - """Provide hook for inserting actions after `write()`.""" - pass - - # - # Utilities - # - - def override_interface_param(self, interface, ovr_data): - intf = self.obj.interface(interface) - intf.update(**ovr_data) - - def override_data(self, interface): - ovr_data = self.ovr_data.get(interface, dict()) - if not ovr_data: - print(f" {interface}: {{}} (no overrides)") - return - self.override_interface_param(interface, ovr_data) - self.print_dict(ovr_data, interface, indent=2) - # self.print_dict(intf_data, interface, indent=2) - - def print_dict(self, d, name, indent=0, prefix=""): - # Print in format that can be pasted right back into .yaml file - if isinstance(d, dict): - if name: - print(f"{' ' * indent}{name}:") - for k, v in d.items(): - if isinstance(v, dict): - if v: - self.print_dict(v, k, indent=indent + 2) - else: - print(f"{' ' * (indent + 2)}{prefix}{k}: {{}}") - else: - print(f"{' ' * (indent + 2)}{prefix}{k}: {v}") - else: - if d is None: - d = "null" - print(f"{' ' * indent}{prefix}{name}: {d}") - - def check_interface_values(self, interface, indent=4): - # Prepare expected data - expected = self.test_data[interface] - # self.print_dict(expected, f"Expected {interface}", indent=2) - - # Prepare actual data - actual = self.obj.interface(interface).get() - # self.print_dict(actual, "Actual", indent=2) - - # Check actual against expected data - passing = self.check_data_values( - interface, expected, actual, indent=indent - ) - if not passing: - print(f"FAILURE at {self.test_desc}") - return passing - - def check_data_values( - self, interface, expected, actual, indent=4, prefix="" - ): - # Destructive operations ahead - actual, expected = actual.copy(), expected.copy() - passing = True - MISSING = dict() # Sentinel object - mno = self.missing_not_ok.get(interface, dict()) - model_id = getattr(self.obj, "model_id", None) - mno_dfl = set([model_id]) # By default, missing params not OK - if interface: - print(f" {interface}:") - for param in list(expected.keys()): - expected_val = expected.pop(param) - actual_val = actual.pop(param, MISSING) - missing_not_ok = model_id in mno.get(param, mno_dfl) - # Print debug info - if actual_val is MISSING: - msg = "MISSING" if missing_not_ok else "(missing; ok)" - print(f'{" "*indent}{prefix}{param}: {msg}') - elif isinstance(expected_val, dict): - if actual_val: - self.print_dict(actual_val, prefix + param, indent=indent) - else: - print(f'{" "*indent}{prefix}{param}: {{}}') - else: - self.print_dict(actual_val, param, indent=indent, prefix=prefix) - # Check param actual vs expected - if actual_val != expected_val and missing_not_ok: - print(f" ****MISMATCH**** expected: {expected_val}") - passing = False - # Check expected data is comprehensive, all params checked - self.check_untested_params(actual) - - return passing - - def check_untested_params(self, params): - if params: - print(f" ****ERROR**** Params not checked: {params}") - raise KeyError(f"Params not checked: {params}") - - def load_test_cases(self): - rsrc = (self.read_update_write_package, self.read_update_write_yaml) - rsrc_str = self.resource_path(*rsrc) - test_cases = self.load_yaml_resource(*rsrc) - assert test_cases, f"Empty YAML from package resource {rsrc_str}" - print(f"Read test cases from package resource {rsrc_str}") - return test_cases - - # - # Main function - # - - def read_update_write_loop(self, test_case): - self.setup_test(test_case) - self.read_and_check() - self.get_feedback_and_check() - self.set_command_and_check() - self.write_and_check() - - def test_read_update_write(self, obj): - if self.read_update_write_package is None: - return # No test cases defined for this class - test_cases = self.load_test_cases() - for test_case in test_cases: - self.read_update_write_loop(test_case) diff --git a/hw_device_mgr/tests/test_device_read_update_write.py b/hw_device_mgr/tests/test_device_read_update_write.py new file mode 100644 index 00000000..2f100e25 --- /dev/null +++ b/hw_device_mgr/tests/test_device_read_update_write.py @@ -0,0 +1,254 @@ +import pytest +from .base_test_class import BaseTestClass + + +class TestDeviceRUW(BaseTestClass): + @pytest.fixture + def obj(self, device_cls, sim_device_data): + assert device_cls.name + self.obj = device_cls(address=sim_device_data["address"]) + self.obj.init() + yield self.obj + + ######################################### + # Test read()/update()/write() integration + # + # Run object through test cases defined in external .yaml file: + # - Optionally set goal and/or override feedback + # - Check expected feedback & command, in & out + + # Configuration + # - YAML test cases package resource + read_update_write_package = None # Skip tests if None + read_update_write_yaml = "read_update_write.cases.yaml" + # - Translate feedback/command test input params from values + # human-readable in .yaml to values matching actual params + read_update_write_translate_feedback_in = dict() + read_update_write_translate_feedback_out = dict() + read_update_write_translate_command_in = dict() + read_update_write_translate_command_out = dict() + read_update_write_translate_sim_feedback = dict() + + def read_update_write_conv_test_data(self): + # Subclasses may massage data + pass + + # + # Setup + # + + # Print intro and merge test case updates + def setup_test(self, test_case): + self.test_desc = test_case["desc"] + print() + print("*" * 80) + print(" ", test_case["desc"]) + print("*" * 80) + print(f"obj: {self.obj}") + # Throw separator into pytest log output + self.obj.logger.info(f"Step -> {self.test_desc}") + + # Expected feedback/command in/out data: Update values from + # last iteration + # + self.test_data = getattr(self, "test_data", dict()) + self.munge_test_case_data(test_case, self.test_data) + + # Override feedback/command/sim_feedback data + # + # Unlike check data, override data isn't carried over from + # previous iterations + # + self.ovr_data = dict() + self.munge_test_case_data(test_case, self.ovr_data, suffix="_set") + + # Nested dictionaries of { interface : { attr : { model_id, ... } } }: + # model_id must have interface attribute; for other models, missing OK + self.missing_not_ok = { + i: dict() for i in self.device_class.interface_names + } + + self.read_update_write_conv_test_data() + # self.print_dict(self.test_data, "Test data") + # self.print_dict(self.ovr_data, "Override data") + + def munge_test_case_data(self, test_case, dst, suffix=""): + for intf in self.device_class.interface_names: + values = test_case.get(intf + suffix, dict()) + dst.setdefault(intf, dict()).update(values) + + # + # Read, get_feedback, set_command, write + # + def read_and_check(self): + print("\n*** Overriding sim_feedback") + self.override_data("sim_feedback") + print("\n*** Running object read() and checking feedback") + self.pre_read_actions() + self.obj.read() + self.post_read_actions() + assert self.check_interface_values("feedback_in") + + def pre_read_actions(self): + """Provide hook for inserting actions before `read()`.""" + pass + + def post_read_actions(self): + """Provide hook for inserting actions after `read()`.""" + pass + + def get_feedback_and_check(self): + print("\n*** Overriding feedback_in") + self.override_data("feedback_in") + print("\n*** Overriding command_in") + self.override_data("command_in") + # self.print_dict(self.test_data, "Test data (after override)") + print("\n*** Running object get_feedback()") + self.obj.get_feedback() + # self.print_dict( + # self.obj.interface("feedback_out").get(), "feedback_out", indent=2 + # ) + assert self.check_interface_values("feedback_out") + + def munge_interface_data(self, interface): + # Do any test data manipulation before sending to interface; subclasses + # may override + return self.test_data[interface] + + def set_command_and_check(self): + print("\n*** Running object set_command()") + self.obj.set_command(**self.munge_interface_data("command_in")) + assert self.check_interface_values("command_in") + assert self.check_interface_values("command_out") + print("\n*** Overriding command_out") + self.override_data("command_out") + # self.print_dict(self.test_data, "Test data (after override)") + + def write_and_check(self): + print("\n*** Running object write() and checking sim_feedback") + self.obj.write() + assert self.check_interface_values("sim_feedback") + self.post_write_actions() + + def post_write_actions(self): + """Provide hook for inserting actions after `write()`.""" + pass + + # + # Utilities + # + + def override_interface_param(self, interface, ovr_data): + intf = self.obj.interface(interface) + intf.update(**ovr_data) + + def override_data(self, interface): + ovr_data = self.ovr_data.get(interface, dict()) + if not ovr_data: + print(f" {interface}: {{}} (no overrides)") + return + self.override_interface_param(interface, ovr_data) + self.print_dict(ovr_data, interface, indent=2) + # self.print_dict(intf_data, interface, indent=2) + + def print_dict(self, d, name, indent=0, prefix=""): + # Print in format that can be pasted right back into .yaml file + if isinstance(d, dict): + if name: + print(f"{' ' * indent}{name}:") + for k, v in d.items(): + if isinstance(v, dict): + if v: + self.print_dict(v, k, indent=indent + 2) + else: + print(f"{' ' * (indent + 2)}{prefix}{k}: {{}}") + else: + print(f"{' ' * (indent + 2)}{prefix}{k}: {v}") + else: + if d is None: + d = "null" + print(f"{' ' * indent}{prefix}{name}: {d}") + + def check_interface_values(self, interface, indent=4): + # Prepare expected data + expected = self.test_data[interface] + # self.print_dict(expected, f"Expected {interface}", indent=2) + + # Prepare actual data + actual = self.obj.interface(interface).get() + # self.print_dict(actual, "Actual", indent=2) + + # Check actual against expected data + passing = self.check_data_values( + interface, expected, actual, indent=indent + ) + if not passing: + print(f"FAILURE at {self.test_desc}") + return passing + + def check_data_values( + self, interface, expected, actual, indent=4, prefix="" + ): + # Destructive operations ahead + actual, expected = actual.copy(), expected.copy() + passing = True + MISSING = dict() # Sentinel object + mno = self.missing_not_ok.get(interface, dict()) + model_id = getattr(self.obj, "model_id", None) + mno_dfl = set([model_id]) # By default, missing params not OK + if interface: + print(f" {interface}:") + for param in list(expected.keys()): + expected_val = expected.pop(param) + actual_val = actual.pop(param, MISSING) + missing_not_ok = model_id in mno.get(param, mno_dfl) + # Print debug info + if actual_val is MISSING: + msg = "MISSING" if missing_not_ok else "(missing; ok)" + print(f'{" "*indent}{prefix}{param}: {msg}') + elif isinstance(expected_val, dict): + if actual_val: + self.print_dict(actual_val, prefix + param, indent=indent) + else: + print(f'{" "*indent}{prefix}{param}: {{}}') + else: + self.print_dict(actual_val, param, indent=indent, prefix=prefix) + # Check param actual vs expected + if actual_val != expected_val and missing_not_ok: + print(f" ****MISMATCH**** expected: {expected_val}") + passing = False + # Check expected data is comprehensive, all params checked + self.check_untested_params(actual) + + return passing + + def check_untested_params(self, params): + if params: + print(f" ****ERROR**** Params not checked: {params}") + raise KeyError(f"Params not checked: {params}") + + def load_test_cases(self): + rsrc = (self.read_update_write_package, self.read_update_write_yaml) + rsrc_str = self.resource_path(*rsrc) + test_cases = self.load_yaml_resource(*rsrc) + assert test_cases, f"Empty YAML from package resource {rsrc_str}" + print(f"Read test cases from package resource {rsrc_str}") + return test_cases + + # + # Main function + # + + def read_update_write_loop(self, test_case): + self.setup_test(test_case) + self.read_and_check() + self.get_feedback_and_check() + self.set_command_and_check() + self.write_and_check() + + def test_read_update_write(self, obj): + if self.read_update_write_package is None: + return # No test cases defined for this class + test_cases = self.load_test_cases() + for test_case in test_cases: + self.read_update_write_loop(test_case) From a8a45174fbf348e826ad1362ee5ac59bc0205ea7 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 26 Feb 2024 18:29:57 -0600 Subject: [PATCH 017/121] Enable read_update_write tests to stabilize after one update This paves the way for running many tests over just one update. --- .../mgr/tests/test_mgr_read_update_write.py | 14 ++++++++++++++ .../mgr_hal/tests/test_mgr_read_update_write.py | 2 +- .../tests/test_device_read_update_write.py | 17 ++++++++++++++--- 3 files changed, 29 insertions(+), 4 deletions(-) diff --git a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py index e64a66ec..5a89d24f 100644 --- a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py +++ b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py @@ -217,6 +217,20 @@ def setup_test(self, test_case): for i in range(7): mno.setdefault(f"d.{i}.home_found", set()) # Empty set signifies OK + def set_override_data(self, test_case): + start_state = test_case.pop("mgr_state", None) + if start_state: + self.set_mgr_state = f"{start_state}_complete" + cmd_out_state = self.obj.cmd_name_to_int_map[start_state] + self.obj.command_out.update(state=cmd_out_state) + super().set_override_data(test_case) + + def set_command_and_check(self): + if getattr(self, "set_mgr_state", None): + print(f"\n*** Overriding mgr state: {self.set_mgr_state}") + self.obj.state = self.set_mgr_state + super().set_command_and_check() + def get_feedback_and_check(self): super().get_feedback_and_check() # Asynch param download causes a race condition. When diff --git a/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py index 410e27a7..e4dfd5d6 100644 --- a/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py +++ b/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py @@ -21,7 +21,7 @@ def override_interface_param(self, interface, ovr_data): pname = dev.pin_name(interface, key) self.set_pin(pname, val) else: - super().override_interface_param(interface, key, val) + super().override_interface_param(interface, {key: val}) def copy_sim_feedback(self): super().copy_sim_feedback() diff --git a/hw_device_mgr/tests/test_device_read_update_write.py b/hw_device_mgr/tests/test_device_read_update_write.py index 2f100e25..835445b6 100644 --- a/hw_device_mgr/tests/test_device_read_update_write.py +++ b/hw_device_mgr/tests/test_device_read_update_write.py @@ -54,13 +54,12 @@ def setup_test(self, test_case): self.test_data = getattr(self, "test_data", dict()) self.munge_test_case_data(test_case, self.test_data) - # Override feedback/command/sim_feedback data + # Override feedback/command/sim_feedback data & mgr state # # Unlike check data, override data isn't carried over from # previous iterations # - self.ovr_data = dict() - self.munge_test_case_data(test_case, self.ovr_data, suffix="_set") + self.set_override_data(test_case) # Nested dictionaries of { interface : { attr : { model_id, ... } } }: # model_id must have interface attribute; for other models, missing OK @@ -72,6 +71,10 @@ def setup_test(self, test_case): # self.print_dict(self.test_data, "Test data") # self.print_dict(self.ovr_data, "Override data") + def set_override_data(self, test_case): + self.ovr_data = dict() # Clear overrides from previous round + self.munge_test_case_data(test_case, self.ovr_data, suffix="_set") + def munge_test_case_data(self, test_case, dst, suffix=""): for intf in self.device_class.interface_names: values = test_case.get(intf + suffix, dict()) @@ -116,6 +119,8 @@ def munge_interface_data(self, interface): return self.test_data[interface] def set_command_and_check(self): + print("\n*** Overriding feedback_out") + self.override_data("feedback_out") print("\n*** Running object set_command()") self.obj.set_command(**self.munge_interface_data("command_in")) assert self.check_interface_values("command_in") @@ -250,5 +255,11 @@ def test_read_update_write(self, obj): if self.read_update_write_package is None: return # No test cases defined for this class test_cases = self.load_test_cases() + # Start by overriding feedback_out and command_out + print("\n*** Overriding feedback_out and command_out") + self.set_override_data(test_cases[0]) + self.override_data("feedback_out") + self.override_data("command_out") + # Now loop over cases for test_case in test_cases: self.read_update_write_loop(test_case) From bcd57133927a198553101ac9afb237d3a8d69172 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 28 Feb 2024 17:59:28 -0600 Subject: [PATCH 018/121] Update test_read_update_write fixtures to set initial device state The first cycle of the `test_read_update_write()` loop will completely reset all device interfaces. Interfaces are set twice so that the object doesn't see any change from the previous update cycle. Top-level device mgr objects may have their state machine forced to any desired state. --- .../tests/test_device_read_update_write.py | 4 ++- hw_device_mgr/mgr/tests/base_test_class.py | 5 +++ hw_device_mgr/mgr/tests/test_mgr.py | 4 ++- .../mgr/tests/test_mgr_read_update_write.py | 21 ++++++++--- .../tests/test_mgr_read_update_write.py | 6 ++-- .../tests/test_device_read_update_write.py | 36 ++++++++++++------- 6 files changed, 54 insertions(+), 22 deletions(-) diff --git a/hw_device_mgr/hal/tests/test_device_read_update_write.py b/hw_device_mgr/hal/tests/test_device_read_update_write.py index a1c9a706..dac627b9 100644 --- a/hw_device_mgr/hal/tests/test_device_read_update_write.py +++ b/hw_device_mgr/hal/tests/test_device_read_update_write.py @@ -18,9 +18,11 @@ def obj(self, sim_device_data, mock_halcomp, device_cls): # Test read()/update()/write() integration # - def override_interface_param(self, interface, ovr_data): + def override_interface_param(self, interface, ovr_data, double=False): intf = self.obj.interface(interface) intf.update(**ovr_data) + if double: + intf.set(**intf.values) if interface not in self.obj.pin_interfaces: return dt_names = self.obj.merge_dict_attrs(f"{interface}_data_types") diff --git a/hw_device_mgr/mgr/tests/base_test_class.py b/hw_device_mgr/mgr/tests/base_test_class.py index a679b7db..3cb73a3a 100644 --- a/hw_device_mgr/mgr/tests/base_test_class.py +++ b/hw_device_mgr/mgr/tests/base_test_class.py @@ -64,3 +64,8 @@ def category_cls(self, category_extra_fixtures): """Fixture for Device class category.""" self.init_sim() yield self.device_base_class + + @pytest.fixture + def extra_obj_fixtures(self): + # Subclasses may add extra fixtures to the obj() fixture + pass diff --git a/hw_device_mgr/mgr/tests/test_mgr.py b/hw_device_mgr/mgr/tests/test_mgr.py index 3b1cb300..46309540 100644 --- a/hw_device_mgr/mgr/tests/test_mgr.py +++ b/hw_device_mgr/mgr/tests/test_mgr.py @@ -13,7 +13,9 @@ class TestHWDeviceMgr(BaseMgrTestClass, _TestDevice): ] @pytest.fixture - def obj(self, mgr_config, device_config, all_device_data): + def obj( + self, mgr_config, device_config, all_device_data, extra_obj_fixtures + ): self.obj = self.device_class() self.obj.init( mgr_config=mgr_config, diff --git a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py index 5a89d24f..e2fa472f 100644 --- a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py +++ b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py @@ -10,7 +10,9 @@ class TestHWDeviceMgrRUW(BaseMgrTestClass, _TestDeviceRUW): @pytest.fixture - def obj(self, mgr_config, device_config, all_device_data): + def obj( + self, mgr_config, device_config, all_device_data, extra_obj_fixtures + ): self.obj = self.device_class() self.obj.init( mgr_config=mgr_config, @@ -126,15 +128,22 @@ def munge_interface_data(self, interface): return data - def override_interface_param(self, interface, ovr_data): + def override_interface_param(self, interface, ovr_data, double=False): + interfaces = set([self.obj.interface(interface)]) for key, val in ovr_data.items(): match = self.test_case_key_re.match(key) if match: index, key = match.groups() intf = self.obj.devices[int(index)].interface(interface) intf.update(**{key: val}) + interfaces.add(intf) else: super().override_interface_param(interface, {key: val}) + if double: + # Call intf.set() with same values to simulate nothing changed since + # last update + for intf in interfaces: + intf.set(**intf.values) def check_interface_values(self, interface, indent=4): if interface in {"feedback_out", "command_in"}: @@ -217,13 +226,15 @@ def setup_test(self, test_case): for i in range(7): mno.setdefault(f"d.{i}.home_found", set()) # Empty set signifies OK - def set_override_data(self, test_case): - start_state = test_case.pop("mgr_state", None) + def set_initial_state(self, initial_state): + super().set_initial_state(initial_state) + # Force initial mgr state to a `mgr_state` key, if it exists + start_state = initial_state.pop("mgr_state", None) if start_state: + print(f"\n*** Forcing initial mgr state = {start_state}") self.set_mgr_state = f"{start_state}_complete" cmd_out_state = self.obj.cmd_name_to_int_map[start_state] self.obj.command_out.update(state=cmd_out_state) - super().set_override_data(test_case) def set_command_and_check(self): if getattr(self, "set_mgr_state", None): diff --git a/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py index e4dfd5d6..1ce1888e 100644 --- a/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py +++ b/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py @@ -12,7 +12,7 @@ class TestHALHWDeviceMgrRUW( ): halcomp_name = "hal_mgr" - def override_interface_param(self, interface, ovr_data): + def override_interface_param(self, interface, ovr_data, double=False): for key, val in ovr_data.items(): match = self.test_case_key_re.match(key) if match: @@ -21,7 +21,9 @@ def override_interface_param(self, interface, ovr_data): pname = dev.pin_name(interface, key) self.set_pin(pname, val) else: - super().override_interface_param(interface, {key: val}) + super().override_interface_param( + interface, {key: val}, double=double + ) def copy_sim_feedback(self): super().copy_sim_feedback() diff --git a/hw_device_mgr/tests/test_device_read_update_write.py b/hw_device_mgr/tests/test_device_read_update_write.py index 835445b6..9039fd43 100644 --- a/hw_device_mgr/tests/test_device_read_update_write.py +++ b/hw_device_mgr/tests/test_device_read_update_write.py @@ -84,7 +84,6 @@ def munge_test_case_data(self, test_case, dst, suffix=""): # Read, get_feedback, set_command, write # def read_and_check(self): - print("\n*** Overriding sim_feedback") self.override_data("sim_feedback") print("\n*** Running object read() and checking feedback") self.pre_read_actions() @@ -101,9 +100,7 @@ def post_read_actions(self): pass def get_feedback_and_check(self): - print("\n*** Overriding feedback_in") self.override_data("feedback_in") - print("\n*** Overriding command_in") self.override_data("command_in") # self.print_dict(self.test_data, "Test data (after override)") print("\n*** Running object get_feedback()") @@ -119,13 +116,11 @@ def munge_interface_data(self, interface): return self.test_data[interface] def set_command_and_check(self): - print("\n*** Overriding feedback_out") self.override_data("feedback_out") print("\n*** Running object set_command()") self.obj.set_command(**self.munge_interface_data("command_in")) assert self.check_interface_values("command_in") assert self.check_interface_values("command_out") - print("\n*** Overriding command_out") self.override_data("command_out") # self.print_dict(self.test_data, "Test data (after override)") @@ -143,16 +138,22 @@ def post_write_actions(self): # Utilities # - def override_interface_param(self, interface, ovr_data): + def override_interface_param(self, interface, ovr_data, double=False): intf = self.obj.interface(interface) intf.update(**ovr_data) + if double: + # Apply overrides again to look like nothing changed since last + # update cycle + intf.set(**intf.values) - def override_data(self, interface): + def override_data(self, interface, double=False): ovr_data = self.ovr_data.get(interface, dict()) if not ovr_data: print(f" {interface}: {{}} (no overrides)") return - self.override_interface_param(interface, ovr_data) + double_str = " (overwriting last update)" if double else "" + print(f"\n*** Overriding {interface}{double_str}") + self.override_interface_param(interface, ovr_data, double=double) self.print_dict(ovr_data, interface, indent=2) # self.print_dict(intf_data, interface, indent=2) @@ -244,6 +245,18 @@ def load_test_cases(self): # Main function # + def set_initial_state(self, initial_state): + # Apply initial overrides *twice* so that nothing seems to have changed + # on the last update cycle + # Start by overriding feedback_out and command_out + print("\n*** Forcing all interfaces") + self.setup_test(initial_state) + self.override_data("feedback_in", double=True) + self.override_data("feedback_out", double=True) + self.override_data("command_in", double=True) + self.override_data("command_out", double=True) + self.override_data("sim_feedback", double=True) + def read_update_write_loop(self, test_case): self.setup_test(test_case) self.read_and_check() @@ -252,14 +265,11 @@ def read_update_write_loop(self, test_case): self.write_and_check() def test_read_update_write(self, obj): + self.obj = obj if self.read_update_write_package is None: return # No test cases defined for this class test_cases = self.load_test_cases() - # Start by overriding feedback_out and command_out - print("\n*** Overriding feedback_out and command_out") - self.set_override_data(test_cases[0]) - self.override_data("feedback_out") - self.override_data("command_out") + self.set_initial_state(test_cases[0]) # Now loop over cases for test_case in test_cases: self.read_update_write_loop(test_case) From 5f5393ca054de998554e480f88816cd584acf035 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 27 Feb 2024 20:44:44 -0600 Subject: [PATCH 019/121] Improve logging Log names now show up as device name@address; for example, in `hw_device_mgr/devices/tests/devices.py`, a log name could be `SV660_ECAT_test@(0,5,10)`. Its config object logger would be `SV660_ECAT_test_cfg@(0,5,10)`. --- hw_device_mgr/cia_301/config.py | 16 ++++++++++++++-- hw_device_mgr/cia_301/device.py | 1 + hw_device_mgr/device.py | 3 ++- hw_device_mgr/logging/__init__.py | 6 ++++-- 4 files changed, 21 insertions(+), 5 deletions(-) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index ee7870cc..2a031208 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -25,8 +25,9 @@ class CiA301Config(LoggingMixin): in order to read/write dictionary objects from/to devices. """ + @cached_property def logging_name(self): - return __name__ + return f"{self.name}@{str(self.address).replace(' ','')}" data_type_class = CiA301DataType command_class = CiA301Command @@ -40,10 +41,15 @@ def logging_name(self): _model_dcs = dict() def __init__( - self, address=None, model_id=None, skip_optional_config_values=True + self, + address=None, + model_id=None, + name=None, + skip_optional_config_values=True, ): self.address = self.canon_address(address) self.model_id = self.format_model_id(model_id) + self.name = name or str(self.model_id) self.params_queue = AsyncParamsQueue() self.skip_optional_config_values = skip_optional_config_values @@ -76,6 +82,11 @@ def command(cls): cls._command_objs[cls.__name__] = cls.command_class() return cls._command_objs[cls.__name__] + def set_name(self, name): + self.name = name + if "logging_name" in self.__dict__: + del self.logging_name # clear cached property + def __str__(self): cname = self.__class__.__name__ return f"{cname}:{self.model_id}@{self.address}".replace(" ", "") @@ -172,6 +183,7 @@ def download( ): # Get SDO object sdo = self.sdo(sdo) + val = sdo.data_type(val) msg = f"(was {old})" if old is not None else "" if val == old: return # SDO value already correct diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index a4e0e4cd..81a8df21 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -55,6 +55,7 @@ def __init__( model_id=self.model_id, skip_optional_config_values=skip_optional_config_values, ) + config.set_name(f"{self.name}_cfg") self.config = config super().__init__(address=address, **kwargs) diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index b976bca0..54b6a2df 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -55,8 +55,9 @@ def __init__(self, address=None): self.address = self.canon_address(address) self._timeout = None + @cached_property def logging_name(self): - return f"{self.category}.{self}" + return self.__str__() def init(self): """ diff --git a/hw_device_mgr/logging/__init__.py b/hw_device_mgr/logging/__init__.py index 78d37e48..92dba988 100644 --- a/hw_device_mgr/logging/__init__.py +++ b/hw_device_mgr/logging/__init__.py @@ -1,5 +1,5 @@ import logging -from functools import cached_property +from functools import cached_property, lru_cache class Logging: @@ -28,6 +28,7 @@ def setLevel(self, level): def getLevel(self): return self._logger.getEffectiveLevel() + @lru_cache def __getattr__(self, name): if name in self._level_map: return getattr(self._logger, self._level_map[name]) @@ -46,9 +47,10 @@ class LoggingMixin: logging_class = Logging + @cached_property def logging_name(self): return str(self) @cached_property def logger(self): - return self.logging_class.getLogger(self.logging_name()) + return self.logging_class.getLogger(self.logging_name) From 0d8ffe9757764b718ed2b6491b35ee3d72e79188 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 28 Feb 2024 13:18:01 -0600 Subject: [PATCH 020/121] Update pre-commit hooks and run formatters --- .pre-commit-config.yaml | 8 ++++---- hw_device_mgr/async_task_queue.py | 4 +--- hw_device_mgr/ethercat/device.py | 8 ++++---- 3 files changed, 9 insertions(+), 11 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 80304cfd..dd070924 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,6 +1,6 @@ repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.1.0 + rev: v4.5.0 hooks: - id: check-ast - id: fix-byte-order-marker @@ -25,18 +25,18 @@ repos: types: [python] - repo: https://github.com/myint/docformatter - rev: v1.4 + rev: v1.7.5 hooks: - id: docformatter args: [--pre-summary-newline, --in-place] - repo: https://github.com/pycqa/flake8 - rev: 4.0.1 + rev: 7.0.0 hooks: - id: flake8 - repo: https://github.com/pycqa/pydocstyle - rev: 6.1.1 + rev: 6.3.0 hooks: - id: pydocstyle args: diff --git a/hw_device_mgr/async_task_queue.py b/hw_device_mgr/async_task_queue.py index 8627a0ac..47d6b453 100644 --- a/hw_device_mgr/async_task_queue.py +++ b/hw_device_mgr/async_task_queue.py @@ -134,9 +134,7 @@ def all_cmds_complete(self): return self.progress_version >= self.cmd_version def join(self): - """ - Block until all queued items are processed and join worker thread. - """ + """Block until queue processed and join worker thread.""" self.cmd_queue.join() # Wait for worker to drain cmd queue & join self.all_cmds_complete() # Drain progress queue self.progress_queue.join() # & join diff --git a/hw_device_mgr/ethercat/device.py b/hw_device_mgr/ethercat/device.py index 52a0f6c1..68092ed0 100644 --- a/hw_device_mgr/ethercat/device.py +++ b/hw_device_mgr/ethercat/device.py @@ -10,11 +10,11 @@ class EtherCATDevice(CiA301Device, abc.ABC): """ Abstract class representing an EtherCAT CoE device. - Device instances are addressed by `(master, alias, position)`. For no - alias, use 0; with alias, use position 0. + Device instances are addressed by `(master, alias, position)`. For + no alias, use 0; with alias, use position 0. - Device model subclasses have matching XML description and other features - specific to that model. + Device model subclasses have matching XML description and other + features specific to that model. """ # Resource names for locating device description XML and error files From c7f5da37159b6e609456d0e4234e276880883d3a Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 28 Feb 2024 13:38:13 -0600 Subject: [PATCH 021/121] Fix tests after pytest version update Classmethods beginning with `test_` are now considered test cases. --- hw_device_mgr/cia_301/tests/base_test_class.py | 6 +++--- hw_device_mgr/tests/base_test_class.py | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/hw_device_mgr/cia_301/tests/base_test_class.py b/hw_device_mgr/cia_301/tests/base_test_class.py index e7dd36db..0c220c3c 100644 --- a/hw_device_mgr/cia_301/tests/base_test_class.py +++ b/hw_device_mgr/cia_301/tests/base_test_class.py @@ -84,7 +84,7 @@ def munge_device_config(cls, device_config): if "test_category" not in conf: # No monkey-patching needed new_device_config.append(conf) continue - device_cls = cls.test_category_class(conf["test_category"]) + device_cls = cls.get_test_category_class(conf["test_category"]) assert device_cls new_device_config.append(conf) model_id = device_cls.device_model_id() @@ -222,7 +222,7 @@ def sdo_data(self, _sdo_data, device_cls): def munge_sdo_data(cls, sdo_data, conv_sdos=False): new_sdo_data = dict() for test_category, old_sdos in sdo_data.items(): - device_cls = cls.test_category_class(test_category) + device_cls = cls.get_test_category_class(test_category) assert device_cls sdos = new_sdo_data[device_cls.device_model_id()] = dict() for ix, sdo in old_sdos.items(): @@ -308,7 +308,7 @@ def load_dcs_data(cls): def munge_dcs_data(cls, dcs_data): new_dcs_data = dict() for test_category, dcs in dcs_data.items(): - device_cls = cls.test_category_class(test_category) + device_cls = cls.get_test_category_class(test_category) assert device_cls new_dcs_data[device_cls.device_model_id()] = dcs assert new_dcs_data diff --git a/hw_device_mgr/tests/base_test_class.py b/hw_device_mgr/tests/base_test_class.py index 98d3e341..a8b4bd01 100644 --- a/hw_device_mgr/tests/base_test_class.py +++ b/hw_device_mgr/tests/base_test_class.py @@ -63,7 +63,7 @@ def munge_sim_device_data(cls, sim_device_data): for dev in sim_device_data: # Fill in missing device data based on `test_category` key if "test_category" in dev: - device_cls = cls.test_category_class(dev["test_category"]) + device_cls = cls.get_test_category_class(dev["test_category"]) assert device_cls assert device_cls.name # Set model_id key @@ -85,7 +85,7 @@ def munge_sim_device_data(cls, sim_device_data): return new_sim_device_data @classmethod - def test_category_class(cls, test_category): + def get_test_category_class(cls, test_category): for dmc in cls.device_model_classes: assert dmc.name if dmc.test_category == test_category: @@ -205,7 +205,7 @@ def pytest_generate_tests(self, metafunc): for dev in dev_data: # Fill in `device_cls` key with actual class if "test_category" in dev: - device_cls = self.test_category_class(dev["test_category"]) + device_cls = self.get_test_category_class(dev["test_category"]) else: device_cls = self.sim_device_data_device_cls(dev) assert device_cls is not None From 549c0ea61495c0194849ae9189d82ec4e9f2f65f Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 11 Mar 2024 15:05:43 -0500 Subject: [PATCH 022/121] cia_402: Expose drive setpoint ack from drive --- hw_device_mgr/cia_402/device.py | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 80b603b4..6ba82287 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -107,6 +107,7 @@ def control_mode_str(cls, mode): transition="int8", home_success="bit", home_error="bit", + move_setpoint_ack="bit", move_success="bit", move_error="bit", ) @@ -116,6 +117,7 @@ def control_mode_str(cls, mode): transition=-1, home_success=False, home_error=False, + move_setpoint_ack=False, move_success=False, move_error=False, ) @@ -166,11 +168,14 @@ def get_feedback_hm(self, sw): def get_feedback_pp(self, sw): # Control mode is PP if not self.command_in.get("move_request"): - self.feedback_out.update(move_success=False, move_error=False) + self.feedback_out.update( + move_setpoint_ack=False, move_success=False, move_error=False + ) return True, None if self.feedback_out.get("state") != "OPERATION ENABLED": reason = "Move request while drive not enabled" self.feedback_out.update( + move_setpoint_ack=False, move_success=False, move_error=True, fault=True, @@ -178,14 +183,17 @@ def get_feedback_pp(self, sw): ) return False, reason - success, error, reason = False, False, None + success, reason = False, None + sp_ack = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") if self.test_sw_bit(sw, "TARGET_REACHED"): # done bit set success = True else: reason = "move not complete" - self.feedback_out.update(move_success=success, move_error=error) + self.feedback_out.update( + move_success=success, move_error=False, move_setpoint_ack=sp_ack + ) return success, reason def get_feedback_sto(self): From 3887b5feb696139cd127ac028175a4e9dbeb098e Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 11 Mar 2024 15:06:34 -0500 Subject: [PATCH 023/121] cia_402: No-op improve HM and PP control_word flag interface Have `hm_request_cw_flags()` and `pp_request_cw_flags()` return a `dict` with updated flags. This is nice for consistency, easy to understand, and easy to override if needed. --- hw_device_mgr/cia_402/device.py | 27 ++++++++++++--------------- 1 file changed, 12 insertions(+), 15 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 6ba82287..ff6fca31 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -507,7 +507,7 @@ def set_command(self, **kwargs): self._get_next_control_word(cmd_out) return cmd_out - def _check_hm_request(self): + def hm_request_cw_flags(self): # Check for home request home_request = False if self.command_in.get("home_request"): @@ -518,9 +518,9 @@ def _check_hm_request(self): home_request = True elif self.command_in.changed("home_request"): # home_request cleared self.logger.info("Homing operation complete") - return home_request + return dict(OPERATION_MODE_SPECIFIC_1=home_request) - def _check_pp_request(self): + def pp_request_cw_flags(self): # Check for move request move_request = False relative_target = False @@ -541,7 +541,10 @@ def _check_pp_request(self): move_request = prev_nsp and not setpoint_ack if self.command_in.changed("move_request"): # move_request cleared self.logger.info("Move operation request cleared") - return move_request, relative_target + return dict( + OPERATION_MODE_SPECIFIC_1=move_request, + OPERATION_MODE_SPECIFIC_3=relative_target, + ) @classmethod @lru_cache @@ -569,23 +572,17 @@ def _get_next_control_word(self, cmd_out): # Add flags and return next_cm = cmd_out.get("control_mode") + cw_flags = dict(OPERATION_MODE_SPECIFIC_3=False) operation_mode_specific_3 = False # operation mode specific 3 sets the target to relative position # when in PP mode if next_cm == self.MODE_HM: - operation_mode_specific_1 = self._check_hm_request() + cw_flags.update(self.hm_request_cw_flags()) elif next_cm == self.MODE_PP: - ( - operation_mode_specific_1, - operation_mode_specific_3, - ) = self._check_pp_request() + cw_flags.update(self.pp_request_cw_flags()) else: - operation_mode_specific_1 = False - next_cw = self._add_control_word_flags( - control_word, - OPERATION_MODE_SPECIFIC_1=operation_mode_specific_1, - OPERATION_MODE_SPECIFIC_3=operation_mode_specific_3, - ) + cw_flags.update(OPERATION_MODE_SPECIFIC_1=False) + next_cw = self._add_control_word_flags(control_word, **cw_flags) cmd_out.update(control_word=next_cw) if cmd_out.changed("control_word"): cw_str = self.cw_to_str(next_cw) From a67454a17c74f55dd54c81c1261b652e3a83a764 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 11 Mar 2024 18:59:04 -0500 Subject: [PATCH 024/121] Enable devices to request mgr fast track the next update cycle Introduce separate update rates, the usual update rate (default 10Hz) for normal operation, and a fast track update rate (default 100Hz) for when fast track is requested. --- hw_device_mgr/device.py | 12 ++++++++---- hw_device_mgr/mgr/mgr.py | 16 +++++++++++----- 2 files changed, 19 insertions(+), 9 deletions(-) diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 54b6a2df..0e149ab0 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -24,7 +24,9 @@ class Device(LoggingMixin, abc.ABC): fault_desc="str", ) command_in_data_types = dict() - command_out_data_types = dict() + command_out_data_types = dict( + fasttrack="bit", + ) feedback_in_defaults = dict() feedback_out_defaults = dict( @@ -34,7 +36,9 @@ class Device(LoggingMixin, abc.ABC): fault_desc="", ) command_in_defaults = dict() - command_out_defaults = dict() + command_out_defaults = dict( + fasttrack=False, + ) interface_names = { "feedback_in", @@ -183,7 +187,7 @@ def set_timeout(self, timeout_seconds): def set_command(self, **kwargs) -> Interface: """Process `command_in` and return `command_out` interface.""" self._interfaces["command_in"].set(**kwargs) - self._interfaces["command_out"].set() # Set defaults + self._interfaces["command_out"].set(fasttrack=False) # Set defaults return self._interfaces["command_out"] def write(self): @@ -452,5 +456,5 @@ def set_sim_feedback(self): def write(self): """Write `command_out` to hardware interface.""" - super().write() self.set_sim_feedback() + super().write() diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 9b66a304..101162e9 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -348,7 +348,9 @@ def fsm_finalize_command(self, e): def run_loop(self): """Program main loop.""" - update_period = 1.0 / self.mgr_config.get("update_rate", 10.0) + conf = self.mgr_config + update_period = 1.0 / conf.get("update_rate", 10.0) + update_period_ft = 1.0 / conf.get("update_rate_fast_track", 100.0) self.fast_track = False self.shutdown = False while not self.shutdown: @@ -364,11 +366,13 @@ def run_loop(self): state=self.STATE_FAULT, state_log="Unexpected exception" ) if self.fast_track: - # This update included a state transition; skip - # the `sleep()` before the next update + # This update included a state transition or device requests + # fast track self.fast_track = False - continue - time.sleep(update_period) + cycle_update_period = update_period_ft + else: + cycle_update_period = update_period + time.sleep(cycle_update_period) def run(self): """Program main.""" @@ -667,6 +671,8 @@ def set_drive_command(self): dev.set_command( state=self.command_out.get("drive_state"), ) + if dev.command_out.get("fasttrack"): + self.fast_track = True def query_devices(self, changed=False, **kwargs): res = list() From 394d41127a560318c9ed705d08e5f7a7fc19d2f3 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 11 Mar 2024 19:00:11 -0500 Subject: [PATCH 025/121] cia_402: Fast track the next update cycle on PP move request --- hw_device_mgr/cia_402/device.py | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index ff6fca31..e408e26b 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -525,12 +525,10 @@ def pp_request_cw_flags(self): move_request = False relative_target = False if self.command_in.get("move_request"): - if self.command_in.changed("move_request"): + if self.command_in.changed("move_request"): # Rising edge self.logger.info("Move operation requested") move_request = True - if self.command_in.get("relative_target"): - self.logger.info("Target position is relative") - relative_target = True + self.command_out.update(fasttrack=True) else: # Clear move request unless setpoint ack not set after previous new # set point @@ -541,6 +539,10 @@ def pp_request_cw_flags(self): move_request = prev_nsp and not setpoint_ack if self.command_in.changed("move_request"): # move_request cleared self.logger.info("Move operation request cleared") + if move_request: + if self.command_in.get("relative_target"): + self.logger.info("Target position is relative") + relative_target = True return dict( OPERATION_MODE_SPECIFIC_1=move_request, OPERATION_MODE_SPECIFIC_3=relative_target, @@ -786,9 +788,12 @@ def set_sim_feedback_pp(self, cw, sw): # OPERATION_MODE_SPECIFIC_1 is SETPOINT_ACKNOWLEDGE fb if self.test_cw_bit(cw, "OPERATION_MODE_SPECIFIC_1"): # If cw NEW_SETPOINT is set, then set sw SETPOINT_ACKNOWLEDGE + self.logger.info("sim SETPOINT_ACKNOWLEDGE set") return dict(OPERATION_MODE_SPECIFIC_1=True) elif self.target_reached(sw, cw): # Target reached when target position reached + if not self.test_sw_bit(sw, "TARGET_REACHED"): + self.logger.info("sim TARGET_REACHED set") return dict(TARGET_REACHED=True) else: return dict() From 0493cda5a5260a662912929f9ca12f023b801a9a Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 11 Mar 2024 21:52:21 -0500 Subject: [PATCH 026/121] cia_402: Fast track update when PP move request is active --- hw_device_mgr/cia_402/device.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index e408e26b..c7c86db1 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -528,7 +528,8 @@ def pp_request_cw_flags(self): if self.command_in.changed("move_request"): # Rising edge self.logger.info("Move operation requested") move_request = True - self.command_out.update(fasttrack=True) + # Fast track as long as move_request in effect + self.command_out.update(fasttrack=True) else: # Clear move request unless setpoint ack not set after previous new # set point From 025b25b2162db64827b8f7a3675ebbbe311bc37e Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 13 Mar 2024 12:55:37 -0500 Subject: [PATCH 027/121] lcec: Add `LCECConfig.gen_ethercat_xml(devs=devs)` arg Allow passing an explicit list `devs` of bus scan results to `gen_ethercat_xml()`; the method will use that instead of running `bus_scan()` itself. --- hw_device_mgr/lcec/config.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/hw_device_mgr/lcec/config.py b/hw_device_mgr/lcec/config.py index c13353ad..574cb077 100644 --- a/hw_device_mgr/lcec/config.py +++ b/hw_device_mgr/lcec/config.py @@ -15,7 +15,7 @@ class LCECConfig(EtherCATConfig): command_class = LCECCommand @classmethod - def gen_ethercat_xml(cls, bus_configs=dict()): + def gen_ethercat_xml(cls, bus_configs=dict(), devs=None): """ Generate the `ethercat.xml` config file for lcec. @@ -25,8 +25,9 @@ def gen_ethercat_xml(cls, bus_configs=dict()): # Convert bus_configs keys to ints (YAML wants str type) for key in list(bus_configs): bus_configs[str(key)] = bus_configs.pop(key) - # Scan bus once - devs = cls.scan_bus() + if devs is None: + # Scan bus once + devs = cls.scan_bus() # Set up XML top level elements: [...] xml = etree.Element("masters") masters = dict() From 1c3207c222f31d2108fc5a9d4f5df3e492a619b3 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 13 Mar 2024 20:28:02 -0500 Subject: [PATCH 028/121] fixup! Enable devices to request mgr fast track the next update cycle --- hw_device_mgr/cia_301/tests/read_update_write.cases.yaml | 2 ++ hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml | 1 + hw_device_mgr/cia_402/tests/read_update_write.cases.yaml | 1 + hw_device_mgr/mgr/tests/read_update_write.cases.yaml | 2 ++ 4 files changed, 6 insertions(+) diff --git a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml index 4d30d037..987e3edf 100644 --- a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml @@ -14,6 +14,8 @@ fault: False fault_desc: "" param_state: 0 # Unknown + command_out: + fasttrack: False sim_feedback: online: True oper: False diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index af7ccc74..20bd57c2 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -51,6 +51,7 @@ command_out: control_word: 0x000F control_mode: 6 + fasttrack: False sim_feedback: online: True oper: True diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index 9ea68fa9..b6a462fe 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -54,6 +54,7 @@ # CiA 402 control_word: 0x0000 control_mode: 8 # MODE_CSP + fasttrack: False sim_feedback: # CiA 301 online: True diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index 0c803b53..c3a3fce5 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -66,10 +66,12 @@ command_complete: False drive_state: SWITCH ON DISABLED reset: False + fasttrack: False # Drives # - CiA 402 d.x.control_word: 0x0000 # SWITCH ON DISABLED d.x.control_mode: 8 # MODE_CSP + d.x.fasttrack: False sim_feedback: # Drives # - CiA 301 From a105cc914a7f16c100fbeda9759aa93766032e7c Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 13 Mar 2024 20:28:54 -0500 Subject: [PATCH 029/121] cia_402: Fix tests for PP move fasttrack --- hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml | 1 + hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml | 4 ++++ hw_device_mgr/cia_402/tests/read_update_write.cases.yaml | 8 ++++++++ hw_device_mgr/mgr/tests/read_update_write.cases.yaml | 1 + 4 files changed, 14 insertions(+) diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index 20bd57c2..97222e0e 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -36,6 +36,7 @@ goal_reason: Reached move_success: False move_error: False + move_setpoint_ack: False position_cmd: 0.0 position_fb: 0.0 sto: False diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index aebc3bbb..28baade9 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -38,6 +38,7 @@ goal_reason: Reached move_success: False move_error: False + move_setpoint_ack: False position_cmd: 0.0 position_fb: 15.0 sto: False @@ -53,6 +54,7 @@ command_out: control_word: 0x001F # Bit 4 NEW_SETPOINT set control_mode: 1 # MODE_PP + fasttrack: True sim_feedback: online: True oper: True @@ -81,6 +83,7 @@ status_word: 0x1037 # Bit 12 SETPOINT_ACKNOWLEDGE set feedback_out: status_word: 0x1037 # Bit 12 SETPOINT_ACKNOWLEDGE set + move_setpoint_ack: True sim_feedback: status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED @@ -92,6 +95,7 @@ status_word: 0x0037 # Bit 12 SETPOINT_ACKNOWLEDGE cleared feedback_out: status_word: 0x0037 # Bit 12 SETPOINT_ACKNOWLEDGE cleared + move_setpoint_ack: False sim_feedback: status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index b6a462fe..c7ca2c1b 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -35,6 +35,7 @@ goal_reason: Offline move_success: False move_error: False + move_setpoint_ack: False position_cmd: 0 position_fb: 0 # STO @@ -687,6 +688,7 @@ move_request: True command_out: control_word: 0x001F # Bit 4 NEW_SETPOINT set + fasttrack: True - desc: "PP move: Wait for move (1)" sim_feedback_set: position_fb: 15.0 # Move not complete @@ -705,6 +707,7 @@ status_word: 0x1037 # Bit 12 SETPOINT_ACKNOWLEDGE set feedback_out: status_word: 0x1037 # Bit 12 SETPOINT_ACKNOWLEDGE set + move_setpoint_ack: True sim_feedback: status_word: 0x0037 # Bit 12 SETPOINT_ACKNOWLEDGE clear - desc: "PP move: Wait for move (3)" @@ -716,6 +719,7 @@ feedback_out: status_word: 0x0037 # Bit 12 SETPOINT_ACKNOWLEDGE clear position_fb: 10.0 # Move not complete + move_setpoint_ack: False - desc: "PP move: Wait for move (4)" sim_feedback_set: position_fb: 5.0 # Move not complete @@ -744,6 +748,8 @@ command_in: # Controller cancels move setpoint command move_request: False + command_out: + fasttrack: False - desc: "PP move: Hold state" feedback_out: move_success: False @@ -763,6 +769,7 @@ move_request: True command_out: control_word: 0x001F # Bit 4 NEW_SETPOINT set + fasttrack: True sim_feedback: status_word: 0x0037 # Bit 10 TARGET_REACHED clear - desc: "PP move FAULT: Hold state; wait" @@ -830,6 +837,7 @@ move_request: False command_out: control_word: 0x0006 # READY TO SWITCH ON + fasttrack: False sim_feedback: status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED - desc: "PP move FAULT: Command SWITCH ON DISABLED" diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index c3a3fce5..40828338 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -44,6 +44,7 @@ d.x.goal_reason: Offline d.x.move_success: False d.x.move_error: False + d.x.move_setpoint_ack: False # - STO d.x.sto: False # - errors From f2c5cb4bf29fa024ee40a4354964d53ac7b0a3c3 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 21 Mar 2024 16:49:40 -0500 Subject: [PATCH 030/121] cia_301: In sim command, add optional sleep time in seconds Simulate command execution by setting a period to sleep. --- hw_device_mgr/cia_301/command.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/hw_device_mgr/cia_301/command.py b/hw_device_mgr/cia_301/command.py index 180c8eb3..534bc99b 100644 --- a/hw_device_mgr/cia_301/command.py +++ b/hw_device_mgr/cia_301/command.py @@ -1,6 +1,7 @@ import abc from .data_types import CiA301DataType from ..logging import Logging +import time __all__ = ("CiA301Command", "CiA301CommandException") @@ -56,6 +57,9 @@ def decode_address(cls, address): class CiA301SimCommand(CiA301Command): """Simulated CiA 301 device.""" + # Sleep this long (s) to simulate command execution + cmd_exec_time = None # None = don't sleep + # Per-category sim device definitions from sim_devices.yaml: # [category] = {sdo data dict} sim_device_data = dict() @@ -64,6 +68,11 @@ class CiA301SimCommand(CiA301Command): # Per-device param value storage: [address][ix, subix] = value sim_sdo_values = dict() + def sim_sleep(self): + self.logger.debug("(command running)") + if self.cmd_exec_time: + time.sleep(self.cmd_exec_time) + @classmethod def init_sim(cls, sim_device_data=None, sdo_data=None): # Save & index device data @@ -101,6 +110,7 @@ def sdo_str_to_ix(cls, sdo_str): def scan_bus(self, bus=0): res = list() for dd in self.sim_device_data.values(): + self.sim_sleep() if dd["address"][0] != bus: continue res.append([dd["address"], dd["model_id"]]) @@ -110,6 +120,7 @@ def upload(self, address=None, index=None, subindex=0, datatype=None): sdo = self.sim_sdo_data[address][index, subindex] val = self.sim_sdo_values[address][index, subindex] assert datatype is sdo.data_type + self.sim_sleep() return val or 0 def download( @@ -123,4 +134,5 @@ def download( sdo = self.sim_sdo_data[address][index, subindex] assert datatype is sdo.data_type value = datatype(value) + self.sim_sleep() self.sim_sdo_values[address][index, subindex] = value From 132543c3623409e426535ca26afe396dff3e78f3 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 25 Mar 2024 12:34:12 -0500 Subject: [PATCH 031/121] cia_301: Improve param logging; simplify download() method Log all `upload()` calls at `DEBUG` prio, and make `download()` command log initial `upload()` calls. Get rid of special, now obsolete, `download()` logging `msg`. Remove unused `download(old=foo)` arg. Log `scan_bus()` calls. Because that's a class method, add a `get_logger()` method to the `LoggingMixin` class. --- hw_device_mgr/cia_301/command.py | 7 +++---- hw_device_mgr/cia_301/config.py | 24 ++++++------------------ 2 files changed, 9 insertions(+), 22 deletions(-) diff --git a/hw_device_mgr/cia_301/command.py b/hw_device_mgr/cia_301/command.py index 534bc99b..94de971e 100644 --- a/hw_device_mgr/cia_301/command.py +++ b/hw_device_mgr/cia_301/command.py @@ -69,7 +69,6 @@ class CiA301SimCommand(CiA301Command): sim_sdo_values = dict() def sim_sleep(self): - self.logger.debug("(command running)") if self.cmd_exec_time: time.sleep(self.cmd_exec_time) @@ -108,9 +107,9 @@ def sdo_str_to_ix(cls, sdo_str): return (idx, subidx) def scan_bus(self, bus=0): + self.sim_sleep() res = list() for dd in self.sim_device_data.values(): - self.sim_sleep() if dd["address"][0] != bus: continue res.append([dd["address"], dd["model_id"]]) @@ -118,10 +117,10 @@ def scan_bus(self, bus=0): def upload(self, address=None, index=None, subindex=0, datatype=None): sdo = self.sim_sdo_data[address][index, subindex] - val = self.sim_sdo_values[address][index, subindex] + val = self.sim_sdo_values[address][index, subindex] or datatype(0) assert datatype is sdo.data_type self.sim_sleep() - return val or 0 + return val def download( self, diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index 2a031208..b35cc499 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -175,34 +175,21 @@ def upload(self, sdo, **kwargs): **kwargs, ) res = sdo.data_type(res_raw) - self.logger.debug(f"upload SDO {sdo} = {res}") + self.logger.debug(f"Param upload SDO {sdo} = {res}") return res - def download( - self, sdo, val, dry_run=False, force=False, old=None, **kwargs - ): + def download(self, sdo, val, dry_run=False, force=False, **kwargs): # Get SDO object sdo = self.sdo(sdo) val = sdo.data_type(val) - msg = f"(was {old})" if old is not None else "" - if val == old: - return # SDO value already correct if not force: # Check before setting value to avoid unnecessary NVRAM writes - res_raw = self.command().upload( - address=self.address, - index=sdo.index, - subindex=sdo.subindex, - datatype=sdo.data_type, - **kwargs, - ) - if sdo.data_type(res_raw) == val: + if self.upload(sdo, **kwargs) == val: return # SDO value already correct - msg = f"(was {sdo.data_type(res_raw)})" if dry_run: - self.logger.info(f"Dry run: download {val} to {sdo} {msg}") + self.logger.info(f"Dry run: Param download {val} = {sdo}") return - self.logger.info(f"Param download {sdo} = {val} {msg}") + self.logger.info(f"Param download {sdo} = {val}") self.command().download( address=self.address, index=sdo.index, @@ -406,6 +393,7 @@ def scan_bus(cls, bus=0, skip_optional_config_values=True, **kwargs): **kwargs, ) res.append(config) + config.logger.info("Drive config created from bus scan") return res From 078409b352ac6becf5efac1a6d4f787b91cc7d3d Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 21 Mar 2024 16:50:59 -0500 Subject: [PATCH 032/121] mgr: Allow fault to preempt init state When the top-level mgr is in init state, it cannot be preempted by other states. Normally, when a device enters fault state, that triggers the top-level mgr to enter fault state. However, when the drive is in fault state during the top-level mgr init, the mgr will get stuck there, since devices never reach their goal states. Fix this by allowing fault state to preempt init. --- hw_device_mgr/mgr/mgr.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 101162e9..da858b3f 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -300,10 +300,17 @@ def fsm_check_devices_online(self, e, state): def fsm_check_command(self, e): state_cmd_str = self.fsm_command_from_event(e) state_cmd = self.cmd_name_to_int_map[state_cmd_str] - if ( + if state_cmd == self.STATE_FAULT: + # Allow only fault commands to preempt init + self.logger.debug(f"Received fault command: {e.msg}") + self.command_out.update( + state=state_cmd, state_log=e.msg, command_complete=False + ) + return True + elif ( e.src.startswith("init") and e.src != "init_complete" ) and state_cmd != self.STATE_INIT: - # Don't preempt init (fault) + # Don't preempt init msg = f"Ignoring {state_cmd_str} command in init state {e.src}" self.command_out.update(state=self.STATE_INIT, state_log=msg) if self.command_out.changed("state"): From 0d6845615e66178ca310953488a38cc980db1f6f Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 21 Mar 2024 16:58:35 -0500 Subject: [PATCH 033/121] mgr: Only require devices be online to exit init state When the top-level mgr is in init state, it cannot be preempted by other states. Normally, when a device enters fault state, that triggers the top-level mgr to enter fault state. However, when the drive is in fault state during the top-level mgr init, the mgr will get stuck there, since devices never reach their goal states. --- hw_device_mgr/mgr/mgr.py | 17 ++++------------- 1 file changed, 4 insertions(+), 13 deletions(-) diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index da858b3f..4ba1739a 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -180,9 +180,7 @@ def on_enter_init_1(self, e): self.logger.info("Waiting for devices to come online before init") def on_before_init_complete(self, e): - if self.fsm_check_devices_online(e, "INIT"): - return False - return self.fsm_check_drive_goal_state(e) + return not self.fsm_check_devices_offline(e, "INIT") def on_enter_init_complete(self, e): self.fsm_finalize_command(e) @@ -294,23 +292,16 @@ def goal_reached_timeout(self): def fsm_command_from_event(cls, e): return e.dst.split("_")[0] - def fsm_check_devices_online(self, e, state): + def fsm_check_devices_offline(self, e, state): return self.query_devices(oper=False) def fsm_check_command(self, e): state_cmd_str = self.fsm_command_from_event(e) state_cmd = self.cmd_name_to_int_map[state_cmd_str] - if state_cmd == self.STATE_FAULT: - # Allow only fault commands to preempt init - self.logger.debug(f"Received fault command: {e.msg}") - self.command_out.update( - state=state_cmd, state_log=e.msg, command_complete=False - ) - return True - elif ( + if ( e.src.startswith("init") and e.src != "init_complete" ) and state_cmd != self.STATE_INIT: - # Don't preempt init + # Don't preempt init (fault) msg = f"Ignoring {state_cmd_str} command in init state {e.src}" self.command_out.update(state=self.STATE_INIT, state_log=msg) if self.command_out.changed("state"): From 32f4ce64b48a702191d2c361431e225d1625092f Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 21 Mar 2024 17:05:58 -0500 Subject: [PATCH 034/121] mgr: Allow top-level mgr to leave init state at any time --- hw_device_mgr/mgr/mgr.py | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 4ba1739a..db718209 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -298,16 +298,7 @@ def fsm_check_devices_offline(self, e, state): def fsm_check_command(self, e): state_cmd_str = self.fsm_command_from_event(e) state_cmd = self.cmd_name_to_int_map[state_cmd_str] - if ( - e.src.startswith("init") and e.src != "init_complete" - ) and state_cmd != self.STATE_INIT: - # Don't preempt init (fault) - msg = f"Ignoring {state_cmd_str} command in init state {e.src}" - self.command_out.update(state=self.STATE_INIT, state_log=msg) - if self.command_out.changed("state"): - self.logger.warning(msg) - return False - elif e.src != f"{state_cmd_str}_command" and e.src.startswith( + if e.src != f"{state_cmd_str}_command" and e.src.startswith( state_cmd_str ): # Already running From 1b3e47f9f5d1aff5efab600b584724ae0a1f1717 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 26 Mar 2024 15:40:49 -0500 Subject: [PATCH 035/121] Add `reset_fault` to `command_in` interface On rising edge of `reset_fault`, a device subclass should attempt to clear any fault status active at its level. In `cia_301`, attempt to rerun param init if that has failed. The top-level mgr will set this bit prior to entering stop and start states. This isn't yet integrated at all levels. --- .../cia_402/tests/hm_timeout.cases.yaml | 1 + .../cia_402/tests/pp_timeout.cases.yaml | 1 + .../tests/read_update_write.cases.yaml | 1 + hw_device_mgr/device.py | 19 ++++++++++++++----- hw_device_mgr/mgr/mgr.py | 18 +++++++++++++++--- 5 files changed, 32 insertions(+), 8 deletions(-) diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index 97222e0e..e63dae9e 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -46,6 +46,7 @@ command_in: state: OPERATION ENABLED control_mode: 8 + reset_fault: False home_request: True move_request: False relative_target: False diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index 28baade9..7c20bb4c 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -48,6 +48,7 @@ command_in: state: OPERATION ENABLED control_mode: 1 # MODE_PP + reset_fault: False home_request: False move_request: True relative_target: False diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index c7ca2c1b..bdf6b8a3 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -51,6 +51,7 @@ home_request: False move_request: False relative_target: False + reset_fault: False command_out: # CiA 402 control_word: 0x0000 diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 0e149ab0..8ee9e283 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -23,7 +23,9 @@ class Device(LoggingMixin, abc.ABC): fault="bit", fault_desc="str", ) - command_in_data_types = dict() + command_in_data_types = dict( + reset_fault="bit", + ) command_out_data_types = dict( fasttrack="bit", ) @@ -35,7 +37,9 @@ class Device(LoggingMixin, abc.ABC): fault=False, fault_desc="", ) - command_in_defaults = dict() + command_in_defaults = dict( + reset_fault=False, + ) command_out_defaults = dict( fasttrack=False, ) @@ -186,9 +190,14 @@ def set_timeout(self, timeout_seconds): def set_command(self, **kwargs) -> Interface: """Process `command_in` and return `command_out` interface.""" - self._interfaces["command_in"].set(**kwargs) - self._interfaces["command_out"].set(fasttrack=False) # Set defaults - return self._interfaces["command_out"] + cmd_in = self._interfaces["command_in"] + cmd_out = self._interfaces["command_out"] + cmd_in.set(**kwargs) + cmd_out.set() + if cmd_in.get("reset_fault"): + if cmd_in.rising_edge("reset_fault"): + self.logger.info("Reset fault command") + return cmd_out def write(self): """Write `command_out` to hardware interface.""" diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index db718209..e53b4509 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -44,6 +44,7 @@ def device_model_id(cls): command_complete=False, reset=0, drive_state="SWITCH ON DISABLED", + reset_fault_cmd=False, ) command_out_data_types = dict( state="uint8", @@ -51,6 +52,7 @@ def device_model_id(cls): command_complete="bit", reset="bit", drive_state="str", + reset_fault_cmd="bit", ) #################################################### @@ -131,8 +133,8 @@ def scan_devices(cls, **kwargs): "position_cmd", "position_fb", }, - # - Don't expose device `state` cmd, controlled by manager - command_in={"state"}, + # - Don't expose device `state` or `reset_fault`, controlled by manager + command_in={"state", "reset_fault"}, ) @lru_cache @@ -215,6 +217,7 @@ def on_before_start_command(self, e): return self.fsm_check_command(e) def on_enter_start_1(self, e): + self.fsm_reset_faults(e) self.fsm_set_drive_state_cmd(e, "SWITCHED ON") def on_before_start_2(self, e): @@ -240,7 +243,8 @@ def on_before_stop_command(self, e): return self.fsm_check_command(e) def on_enter_stop_1(self, e): - return self.fsm_set_drive_state_cmd(e, "SWITCH ON DISABLED") + self.fsm_reset_faults(e) + self.fsm_set_drive_state_cmd(e, "SWITCH ON DISABLED") def on_before_stop_complete(self, e): return self.fsm_check_drive_goal_state(e) @@ -320,6 +324,11 @@ def fsm_check_drive_goal_state(self, e): # Otherwise, cancel event return False + def fsm_reset_faults(self, e): + cmd_name = self.fsm_command_from_event(e) + self.logger.info(f"{cmd_name} command: Commanding drives reset faults") + self.command_out.update(reset_fault_cmd=True) + def fsm_set_drive_state_cmd(self, e, state): cmd_name = self.fsm_command_from_event(e) self.logger.info( @@ -643,6 +652,7 @@ def init_sim_devices(cls, /, sim_device_data=None, **kwargs): def set_drive_command(self): mgr_vals = self.command_in.get() skip = self.device_translated_interfaces.get("command_in", set()) + reset = self.command_out.get("reset_fault_cmd") for dev in self.devices: if "command_in" in self.device_translated_interfaces: # Copy mgr command_out to matching device command_in @@ -650,6 +660,7 @@ def set_drive_command(self): prefix = self.dev_prefix(dev, suffix=dev.slug_separator) dev.set_command( state=self.command_out.get("drive_state"), + reset_fault=reset, **{ k: mgr_vals[f"{prefix}{k}"] for k in dev_command_in.keys() @@ -659,6 +670,7 @@ def set_drive_command(self): else: dev.set_command( state=self.command_out.get("drive_state"), + reset_fault=reset, ) if dev.command_out.get("fasttrack"): self.fast_track = True From 97f0b38b2ca369780cf3098ffd4a4afccd9d4c3b Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 25 Mar 2024 17:36:46 -0500 Subject: [PATCH 036/121] cia_301: Rework param updates Each device now has its own individual command queue. The command queue is no longer limited to writing params, but can run any arbitrary callback with any arbitrary parameters. Errors updating parameters now cause device faults. When an error is acknowledged, it can be cleared, the command queue flushed, and param init restarted. A logic error is fixed where goal state is reported reached before param init is complete. This paves the way towards queuing up parameter commands and being able to reset devices. --- hw_device_mgr/async_task_queue.py | 203 +++++++++++---------- hw_device_mgr/cia_301/async_params.py | 16 -- hw_device_mgr/cia_301/config.py | 60 +++--- hw_device_mgr/cia_301/device.py | 32 +++- hw_device_mgr/cia_301/tests/test_config.py | 4 +- 5 files changed, 168 insertions(+), 147 deletions(-) delete mode 100644 hw_device_mgr/cia_301/async_params.py diff --git a/hw_device_mgr/async_task_queue.py b/hw_device_mgr/async_task_queue.py index 47d6b453..86bb54bc 100644 --- a/hw_device_mgr/async_task_queue.py +++ b/hw_device_mgr/async_task_queue.py @@ -7,59 +7,29 @@ class AsyncTaskQueue: """ Generic class to process commands in an asynchronous queue. - Multiple instances may `enqueue` commands for a singleton worker - instance processing those in a thread with the `process_queue` - command (implemented in subclasses). + Multiple instances with separate queues `enqueue` commands. A single worker + thread rotates among queues, pulling off the next command and executing it. """ - # Class-level dict of singleton queues - queues = dict() + # Idle wait time + idle_wait = 0.1 # s - @classmethod - @lru_cache - def _get_queue(cls, name): - return cls.queues.setdefault(name, queue.Queue()) - - @cached_property - def cmd_queue(self): - """Property returning the command queue singleton instance.""" - return self._get_queue("cmd") + # Class-level singleton queue data + _queue_names = list() + _cmd_queues = dict() + _errors = dict() + _queue_stop = dict() - @cached_property - def progress_queue(self): - """Property returning the progress queue singleton instance.""" - return self._get_queue("progress") + _queues = list() - def __init__(self): - self.cmd_version = 0 - - # - # Worker-related methods # - # There should only ever be a single worker thread running, even if many - # AsyncTaskQueue instances are enqueuing commands. + # Class methods: worker thread is managed by the class itself # - def process_cmd(self, cmd): - """ - Process one command from command queue. - - Main worker function to be implemented in subclasses. - """ - pass - - def _work(self): - """ - Worker thread loop callback. - - Pop commands off command queue and pass to `process_cmd` method. - Repeat untill `join` method is called. - """ - while True: - cmd_version, cmd = self.cmd_queue.get() - self.process_cmd(cmd) - self.progress_queue.put(cmd_version) - self.cmd_queue.task_done() + @classmethod + @lru_cache + def lock(cls): + return threading.Lock() @classmethod @lru_cache # Only needs to run once per class @@ -71,70 +41,101 @@ def start(cls): but will only ever create a single worker instance running a single thread. """ - if hasattr(cls, "_worker_instance"): - assert type(cls._worker_instance) is cls # Subclass sanity - return # Already started - cls._worker_instance = cls() - cls._worker_instance._start() + assert not hasattr(cls, "_thread") # Sanity + cls._thread = threading.Thread(target=cls._work, daemon=True) + cls._stop = threading.Event() + cls._have_data = threading.Event() + cls._have_error = threading.Event() + cls._thread.start() + + @classmethod + def _work(cls): + """ + Worker thread loop callback. - @lru_cache # Only needs to run once per worker instance - def _start(self): - # Start the new thread from the worker instance - threading.Thread(target=self._work, daemon=True).start() + Pop commands off command queue and executes method with args. + Repeat untill `join` method is called. + """ + while not cls._stop.is_set(): + cls._have_data.wait() + for cmd_queue in cls._queues: + cmd_queue.churn() + with cls.lock(): # Synchronize queue check & have_data clear + if all(i.empty for i in cls._queues): + cls._have_data.clear() # All cmd queues empty + + @classmethod + def join(cls): + """Block until queue processed and join worker thread.""" + assert hasattr(cls, "_thread") + # Unblock worker thread & signal to stop + with cls.lock(): # Synchronize stop & have_data set + cls._stop.set() + cls._have_data.set() + for stop in cls._queue_stop.values(): + stop.set() + # Join queue + for cmd_queue in cls._queues: + cmd_queue.join_queue() + # Join worker thread + cls._thread.join() # - # Command-side-related methods + # Instance methods: Named instances # - # Multiple instances may exist, but must all be running in the same - # (probably main) thread. - @classmethod - def _bump_cmd_version(cls): - # Bump the global (class-level) command version and return it - if not hasattr(cls, "_cmd_version"): - cls._cmd_version = 0 - cls._cmd_version += 1 - return cls._cmd_version - - def enqueue(self, cmd): - """Enqueue one command.""" - # Automatically start thread - self.start() - # Set local command version to incremented global version - ver = self.cmd_version = self._bump_cmd_version() - self.cmd_queue.put((ver, cmd)) - - @classmethod - def _get_progress_version(cls): - if not hasattr(cls, "_progress_version"): - cls._progress_version = 0 - # Process the progress queue - progress = cls._get_queue("progress") + def __init__(self, name): + self.name = name + self.queue = queue.Queue() + self.error = None + self.stop = threading.Event() + self._queues.append(self) + + def churn(self): + """Pop command off queue and execute it.""" + if self.queue.empty(): + return + if self.stop.is_set(): + return + method, args, kwargs = self.queue.get() try: - while True: - cls._progress_version = progress.get(block=False) - progress.task_done() - except queue.Empty: - pass - return cls._progress_version + method(*args, **kwargs) + except Exception as e: + # Put exception in errors & stop queue + with self.lock(): + self.stop.set() + self.error = (e, method, args, kwargs) + self._have_error.set() + self.queue.task_done() @property - def progress_version(self): - """Return version of most recent processed command.""" - return self._get_progress_version() + def empty(self): + return self.queue.empty() - def all_cmds_complete(self): - """ - Return `True` if all commands enqueued by this instance were processed. + def join_queue(self): + """Flush and stop queue""" + self.flush_queue_and_clear_error() + self.queue.join() - This may return `True` for one instance while returning `False` - for another instance with commands still waiting to be - processed. - """ - return self.progress_version >= self.cmd_version + def enqueue(self, method, *args, **kwargs): + """Enqueue one command.""" + self.start() # Automatically start class thread worker + with self.lock(): # Synchronize queue put and have_data set + assert not self.stop.is_set() + self.queue.put((method, args, kwargs)) + self._have_data.set() - def join(self): - """Block until queue processed and join worker thread.""" - self.cmd_queue.join() # Wait for worker to drain cmd queue & join - self.all_cmds_complete() # Drain progress queue - self.progress_queue.join() # & join + @property + def started(self): + return hasattr(self, "_thread") + + def flush_queue_and_clear_error(self): + with self.lock(): + self.stop.set() # No queue processing while flushing + while not self.queue.empty(): + self.queue.get() + self.queue.task_done() + self.error = None + if self.started and not any(i.error for i in self._queues): + self._have_error.clear() + self.stop.clear() diff --git a/hw_device_mgr/cia_301/async_params.py b/hw_device_mgr/cia_301/async_params.py deleted file mode 100644 index d291de66..00000000 --- a/hw_device_mgr/cia_301/async_params.py +++ /dev/null @@ -1,16 +0,0 @@ -from ..async_task_queue import AsyncTaskQueue - - -class AsyncParamsQueue(AsyncTaskQueue): - """Process device configuration commands in an asynchronous queue.""" - - def process_cmd(self, cmd_raw): - """Execute one config command in worker.""" - config, cmd, args, kwargs = cmd_raw - return getattr(config, cmd)(*args, **kwargs) - - def download(self, config, values, **cmd_kwargs): - """Enqueue one param config 'download' command.""" - for sdo, val in values.items(): - cmd = (config, "download", (sdo, val), cmd_kwargs) - super().enqueue(cmd) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index b35cc499..adcc63c5 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -1,7 +1,7 @@ from .data_types import CiA301DataType from .command import CiA301Command, CiA301SimCommand, CiA301CommandException from .sdo import CiA301SDO -from .async_params import AsyncParamsQueue +from ..async_task_queue import AsyncTaskQueue from ..logging import LoggingMixin from functools import cached_property @@ -50,7 +50,7 @@ def __init__( self.address = self.canon_address(address) self.model_id = self.format_model_id(model_id) self.name = name or str(self.model_id) - self.params_queue = AsyncParamsQueue() + self.params_queue = AsyncTaskQueue(self.name) self.skip_optional_config_values = skip_optional_config_values @classmethod @@ -348,33 +348,45 @@ def set_device_params_nv(self, nv=True, dry_run=False): """ pass - def initialize_params(self, restart=False, dry_run=False): + def flush_command_queue(self): + """Flush the param init queue and clear any errors.""" + self.params_queue.flush_queue_and_clear_error() + + def enqueue_command(self, method, *args, **kwargs): + """Enqueue a command onto the param init queue.""" + self.params_queue.enqueue(method, *args, **kwargs) + + def initialize_params(self, dry_run=False): """ Asynchronously initialize device params. - The first time this method is called, or if the `restart` arg is set, it - will enqueue device params to be downloaded to the device in a worker - thread. This and following calls (without `restart` set) will return - `False` until device params have finished downloading, and then will - return `True`. + Clear any previous errors and flush any existing queue, then + enqueue device params to be downloaded to the device in a worker thread. - When an offline device comes online, this function should be run (with - `restart=True` the first time if device was previously offline) in a - cycle until it returns `True` to ensure the device parameters are - completely configured. + When an offline device comes online, or to clear param init errors, run + this function, then watch `param_init_in_progress` until it finishes, + and finally assert `param_init_error()` return `None` to ensure all + device parameters are completely configured. """ - if restart: - # Params haven't been queued up, or need requeuing - num_params = len(self.config["param_values"]) - self.logger.info(f"Queueing {num_params} param updates") - self.params_queue.download( - self, self.config["param_values"], dry_run=dry_run - ) - return False - else: - # Params enqueued; waiting on param processing complete - complete = self.params_queue.all_cmds_complete() - return complete + params = self.config["param_values"] + self.logger.info(f"Queueing {len(params)} param updates") + self.flush_command_queue() + for sdo, val in params.items(): + self.enqueue_command(self.download, sdo, val, dry_run=dry_run) + + @property + def param_init_in_progress(self): + """Return `False` if params still queued for init.""" + return not self.params_queue.empty + + @property + def param_init_error(self): + """Return param init error status. + + If no error, returns `None`. + Otherwise, returns a tuple of `(exception, method, args, kwargs)` + """ + return self.params_queue.error # # Scan bus device config factory diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 81a8df21..dfbd472e 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -21,6 +21,7 @@ class CiA301Device(Device): PARAM_STATE_UNKNOWN = 0 # Uninitialized and unchecked before init PARAM_STATE_UPDATING = 1 # Currently being checked & updated PARAM_STATE_COMPLETE = 2 # Params checked and updated + PARAM_STATE_ERROR = 3 # Error in param init feedback_in_data_types = dict(online="bit", oper="bit") feedback_in_defaults = dict(online=False, oper=False) @@ -107,15 +108,27 @@ def get_feedback(self): goal_reached, goal_reasons = True, list() # Param init: download param values asynchronously after coming online - if self.feedback_in.changed("online"): - self.config.initialize_params(restart=True) + old_ps = fb_out.get_old("param_state") + p_init_err = self.config.param_init_error + if p_init_err: + try: + errstr = "{1}({2}, {3}): {0}".format(p_init_err) + except: + errstr = str(p_init_err) + fb_out.update(fault=True, fault_desc=f"param init failed: {errstr}") + param_state = self.PARAM_STATE_ERROR + elif self.config.param_init_in_progress: goal_reached = False goal_reasons.append("updating device params") param_state = self.PARAM_STATE_UPDATING - elif self.config.initialize_params(): + elif old_ps in (self.PARAM_STATE_UPDATING, self.PARAM_STATE_COMPLETE): + # Previously complete, or previously updating but currently not param_state = self.PARAM_STATE_COMPLETE else: - param_state = self.PARAM_STATE_UPDATING + # Catch all, esp. after entering online state + param_state = self.PARAM_STATE_UNKNOWN + goal_reached = False + goal_reasons.append("device params unset") # Update operational status if not self.feedback_in.get("oper"): @@ -145,6 +158,17 @@ def get_feedback(self): self.logger.info(f"Goal not reached: {goal_reason}") return fb_out + def set_command(self, **kwargs): + cmd_out = super().set_command(**kwargs) + cmd_in = self._interfaces["command_in"] + if self.feedback_in.rising_edge("online"): + self.logger.info("Initializing params after coming online") + self.config.initialize_params() + elif cmd_in.rising_edge("reset_fault") and self.config.param_init_error: + self.logger.info("Re-initializing params after fault") + self.config.initialize_params() + return cmd_out + @classmethod def munge_sdo_data(cls, sdo_data): # Turn per-model name SDO data from YAML into per-model_id SDO data diff --git a/hw_device_mgr/cia_301/tests/test_config.py b/hw_device_mgr/cia_301/tests/test_config.py index bdf564c0..567143c4 100644 --- a/hw_device_mgr/cia_301/tests/test_config.py +++ b/hw_device_mgr/cia_301/tests/test_config.py @@ -72,7 +72,7 @@ def test_initialize_params(self, obj, sdo_data, sim_device_data): # Sanity checks pq = obj.params_queue - assert pq.all_cmds_complete() + assert pq.empty # Start param init print("Starting param init") @@ -88,7 +88,7 @@ def test_initialize_params(self, obj, sdo_data, sim_device_data): print("initialize_params() never returned True!") print(f"Spun {i} cycles to init params") assert obj.initialize_params() - assert pq.all_cmds_complete() + assert pq.empty for sdo_ix, val in obj.config["param_values"].items(): assert obj.upload(sdo_ix) == val From 91bdb0e6da6a3f8ee87d5c6ad95a26ba879e37fb Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 26 Mar 2024 15:38:29 -0500 Subject: [PATCH 037/121] cia_402: Don't overwrite lower layer status The `cia_301` devices can be writing params even while the CiA 402 state is undergoing management. Don't overwrite states like `fault` or `goal_reached`. --- hw_device_mgr/cia_402/device.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index c7c86db1..02943853 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -235,16 +235,17 @@ def get_feedback(self): fb_out = super().get_feedback() fb_in = self.feedback_in - # If device not operational, set default "START" state + # Set default "START" state in these cases: if not fb_out.get("oper"): - fb_out.update(**self.feedback_out_defaults) + # Device not yet operational return fb_out - # Goal reached, fault var defaults - goal_reached = True - goal_reasons = list() - fault = False - fault_desc = "" + # Don't clobber lower layer's feedback, but continue managing CiA 402 + # states even while param init continues + goal_reached = fb_out.get("goal_reached") + goal_reasons = list() if goal_reached else [fb_out.get("goal_reason")] + fault = fb_out.get("fault") + fault_desc = fb_out.get("fault_desc") # Status word, control mode from fb in sw = fb_in.get("status_word") @@ -500,8 +501,7 @@ def sw_to_str(cls, sw): def set_command(self, **kwargs): cmd_out = super().set_command(**kwargs) - if not self.feedback_in.get("oper"): - cmd_out.update(**self.command_out_defaults) + if not self.feedback_out.get("oper"): return cmd_out self._get_next_control_mode(cmd_out) self._get_next_control_word(cmd_out) From db9bab2579f26f97a5d3e63f96d5c7f634999184 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 26 Mar 2024 17:11:16 -0500 Subject: [PATCH 038/121] Fix goal state logging Device subclasses can't directly log their own reasons for goals reached because higher levels may update them. Instead, pull that out into a new `log_goal_reached()` method, executed after `get_feedback()`. --- hw_device_mgr/cia_301/device.py | 4 +--- hw_device_mgr/cia_402/device.py | 4 ---- hw_device_mgr/device.py | 11 +++++++++++ hw_device_mgr/interface.py | 4 ++-- hw_device_mgr/mgr/mgr.py | 15 ++++++++------- 5 files changed, 22 insertions(+), 16 deletions(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index dfbd472e..b6daa426 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -152,10 +152,8 @@ def get_feedback(self): goal_reason=goal_reason, param_state=param_state, ) - if goal_reached and fb_out.changed("param_state"): + if fb_out.rising_edge("param_state", self.PARAM_STATE_COMPLETE): self.logger.info("Device param init complete") - if not goal_reached and fb_out.changed("goal_reason"): - self.logger.info(f"Goal not reached: {goal_reason}") return fb_out def set_command(self, **kwargs): diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 02943853..4f46946b 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -361,10 +361,6 @@ def get_feedback(self): if not goal_reached: goal_reason = "; ".join(goal_reasons) fb_out.update(goal_reached=False, goal_reason=goal_reason) - if fb_out.changed("goal_reason"): - self.logger.info(f"Goal not reached: {goal_reason}") - elif fb_out.changed("goal_reached"): # Goal just now reached - self.logger.info("Goal reached") return fb_out @classmethod diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 8ee9e283..465b7a07 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -157,6 +157,17 @@ def get_feedback(self) -> Interface: fb_out.update(fault=True, fault_desc=timeout) return fb_out + def log_goal_reached(self): + """Log whether goal is reached and if not, why; don't spam.""" + fb_out = self._interfaces["feedback_out"] + if not fb_out.changed("goal_reason"): + return + reason = fb_out.get("goal_reason") + if fb_out.get("goal_reached"): + self.logger.info(f"Goal reached: {reason}") + else: + self.logger.info(f"Goal not reached: {reason}") + def check_and_set_timeout(self): """Set fault if feedback_out goal_reached is False for too long.""" # This is still data from previous cycle diff --git a/hw_device_mgr/interface.py b/hw_device_mgr/interface.py index 894a5bc2..cda89f90 100644 --- a/hw_device_mgr/interface.py +++ b/hw_device_mgr/interface.py @@ -53,8 +53,8 @@ def changed(self, key, return_vals=False): val_old = self.values_old[key] return (val, val_old) if return_vals else val != val_old - def rising_edge(self, key): - return self.values[key] and not self.values_old[key] + def rising_edge(self, key, val=True): + return self.values[key] == val and self.values_old[key] != val def __str__(self): res = f"Interface {self.name} (" diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index e53b4509..933bf04f 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -399,6 +399,7 @@ def read_update_write(self): try: self.read() self.get_feedback() + self.log_goal_reached() self.set_command() self.write() except KeyboardInterrupt as e: @@ -460,7 +461,7 @@ def get_feedback(self): fault = mgr_fb_out.get("fault") fault_desc = mgr_fb_out.get("fault_desc") goal_reached = True - goal_reason = "" + goal_reason = "Reached" cmd_out = self.interface("command_out") # Get device feedback @@ -519,7 +520,7 @@ def get_feedback(self): and not fault ) - # Update feedback out, log, return + # Update feedback out, return mgr_fb_out.update( fault=fault, fault_desc=fault_desc, @@ -527,13 +528,13 @@ def get_feedback(self): goal_reason=goal_reason, enabled=enabled, ) - if mgr_fb_out.changed("goal_reason"): - if mgr_fb_out.get("goal_reached"): - self.logger.debug("Manager reached goal state") - else: - self.logger.debug(f"Waiting: {mgr_fb_out.get('goal_reason')}") return mgr_fb_out + def log_goal_reached(self): + for dev in self.devices: + dev.log_goal_reached() + super().log_goal_reached() + def set_command(self, **cmd_in_kwargs): """Set command for top-level manager and for drives.""" # Initialize command out interface with previous values; this could From 58eca80e23ea37207cc88ea50091025b6f06816b Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 26 Mar 2024 17:13:19 -0500 Subject: [PATCH 039/121] Remove random bits of unneeded code Base device class contains unused methods. HAL device class has old debug logs that should have been removed. --- hw_device_mgr/device.py | 9 --------- hw_device_mgr/hal/device.py | 9 --------- 2 files changed, 18 deletions(-) diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 465b7a07..0f0d9291 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -134,15 +134,6 @@ def __getattr__(self, name): raise AttributeError(f"'{cname}' object has no attribute '{name}'") return self._interfaces[name] - def set_interface(self, what, **kwargs): - self._interfaces[what].set(**kwargs) - - def update_interface(self, what, **kwargs): - self._interfaces[what].update(**kwargs) - - def interface_changed(self, what, key, return_vals=False): - return self._interfaces[what].changed(key, return_vals=return_vals) - def read(self): """Read `feedback_in` from hardware interface.""" self._interfaces["feedback_in"].set() diff --git a/hw_device_mgr/hal/device.py b/hw_device_mgr/hal/device.py index 7ae34b68..42aa9237 100644 --- a/hw_device_mgr/hal/device.py +++ b/hw_device_mgr/hal/device.py @@ -76,15 +76,6 @@ def read(self): pins = self.pins["feedback_in"] vals = {p: pins[p].get() for p in pins.keys()} self.interface("feedback_in").update(**vals) - if not getattr(self, "read_once", False): - self.read_once = True - self.logger.debug( - f"HAL pins read for feedback_in: {list(pins.keys())}" - ) - self.logger.debug( - " Interface keys: " - f"{list(self.interface('feedback_in').keys())}" - ) def write(self): # Write to output pins From d9de222b0f9dd2e898409a3b3def9df623b43513 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 26 Mar 2024 17:17:16 -0500 Subject: [PATCH 040/121] mgr: Fix transitions out of init state Restore old code preventing init from exiting early. Init must now complete before transitioning to e.g. fault state. Init is now considered complete when all devices have reach goal state or are in fault state. After init is complete, if any devices are in fault state, then transition to fault state; otherwise, transition to stop. --- hw_device_mgr/cia_402/device.py | 5 +++- hw_device_mgr/mgr/mgr.py | 45 ++++++++++++++++++++++++--------- 2 files changed, 37 insertions(+), 13 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 4f46946b..11048d1e 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -359,8 +359,9 @@ def get_feedback(self): self.logger.info(f"status_word: {self.sw_to_str(sw)}") if not goal_reached: + goal_reached = fault # If fault active, nothing to do, goal reached goal_reason = "; ".join(goal_reasons) - fb_out.update(goal_reached=False, goal_reason=goal_reason) + fb_out.update(goal_reached=goal_reached, goal_reason=goal_reason) return fb_out @classmethod @@ -725,6 +726,8 @@ def _get_next_control_mode(self, cmd_out): if cmd_out.changed("control_mode"): cm_str = self.control_mode_str(next_cm) self.logger.info(f"control_mode: {cm_str}") + old_cm_str = cmd_out.get_old("control_mode") + self.logger.info(f"control_mode was: {old_cm_str}") class CiA402SimDevice(CiA402Device, CiA301SimDevice, ErrorSimDevice): diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 933bf04f..0b7eaa25 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -182,16 +182,28 @@ def on_enter_init_1(self, e): self.logger.info("Waiting for devices to come online before init") def on_before_init_complete(self, e): - return not self.fsm_check_devices_offline(e, "INIT") + if self.fsm_check_devices_offline(e, "INIT"): + return False # All devices must be online to complete init + elif self.query_devices(goal_reached=False): + return False # Some devices still initializing + else: + return True # All devices initialized def on_enter_init_complete(self, e): self.fsm_finalize_command(e) - # Automatically return to SWITCH ON DISABLED after init - self.logger.info("Devices all online; commanding stop state") - self.command_out.update( - state=self.STATE_STOP, - state_log="Automatic 'stop' command at init complete", - ) + # If any devices in fault state, command fault state + if self.query_devices(fault=True): + self.logger.warning("Commanding fault state") + self.command_out.update( + state=self.STATE_FAULT, + state_log="Automatic 'fault' command at init complete", + ) + else: # Automatically return to SWITCH ON DISABLED after init + self.logger.info("Devices all online; commanding stop state") + self.command_out.update( + state=self.STATE_STOP, + state_log="Automatic 'stop' command at init complete", + ) # # Fault command @@ -302,7 +314,16 @@ def fsm_check_devices_offline(self, e, state): def fsm_check_command(self, e): state_cmd_str = self.fsm_command_from_event(e) state_cmd = self.cmd_name_to_int_map[state_cmd_str] - if e.src != f"{state_cmd_str}_command" and e.src.startswith( + if ( + e.src.startswith("init") and e.src != "init_complete" + ) and state_cmd != self.STATE_INIT: + # Don't preempt init (fault) + msg = f"Ignoring {state_cmd_str} command in init state {e.src}" + self.command_out.update(state=self.STATE_INIT, state_log=msg) + if self.command_out.changed("state"): + self.logger.warning(msg) + return False + elif e.src != f"{state_cmd_str}_command" and e.src.startswith( state_cmd_str ): # Already running @@ -596,15 +617,15 @@ def set_command(self, **cmd_in_kwargs): event = f"{cmd_str}_command" try: self.trigger(event, msg=cmd_out.get("state_log")) + self.logger.debug(f"Triggered event {event} from state cmd") except Canceled as e: self.logger.warning(f"Unable to honor {event} command: {e}") elif self.automatic_next_event() is not None: # Attempt automatic transition to next state try: - self.trigger( - self.automatic_next_event(), - msg=f"Automatic transition from {self.state} state", - ) + event = self.automatic_next_event() + msg = f"Automatic transition to {event} from {self.state} state" + self.trigger(event, msg=msg) except Canceled: # `on_before_{event}()` method returned `False`, # causing `fysom.Canceled` exception From d395b9ebb8f613f5e1de7e3fc263bc2961cfc703 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 26 Mar 2024 18:38:57 -0500 Subject: [PATCH 041/121] Inovance SV660: Clear battery encoder errors on reset On reset, clear battery encoder errors and reboot the drive. This goes through the parameter interface because the operations can be enqueued on device's async task queue, which will ensure the commands are run after any other param updates, etc. --- hw_device_mgr/devices/inovance_sv660.py | 30 +++++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/hw_device_mgr/devices/inovance_sv660.py b/hw_device_mgr/devices/inovance_sv660.py index 664a9818..96de82d0 100644 --- a/hw_device_mgr/devices/inovance_sv660.py +++ b/hw_device_mgr/devices/inovance_sv660.py @@ -2,6 +2,7 @@ from ..ethercat.config import EtherCATConfig from ..cia_402.device import CiA402Device, CiA402SimDevice from ..errors.device import ErrorDevice +import time class InovanceSV660Config(EtherCATConfig): @@ -30,6 +31,26 @@ def set_device_params_nv(self, nv=True, dry_run=False): f"Params already {'non' if nv else ''}volatile mode" ) + def clear_fault(self): + err_code = self.upload("203Fh") + self.logger.info(f"Resetting device fault; code: {err_code}") + time.sleep(0.5) # This may or may not be needed + self.download("200D-02h", 1) + time.sleep(0.5) # This may or may not be needed + err_code = self.upload("203Fh") + self.logger.info(f" After fault reset, code: {err_code}") + + def soft_reset(self): + self.logger.info("Performing soft reset on drive") + time.sleep(0.5) # This may or may not be needed + self.download("200D-01h", 1) + time.sleep(2.0) # Give the drive time to react + + def reset_error_and_restart(self): + self.logger.info(f"Queueing fault reset and rebooting drive") + self.enqueue_command(self.clear_fault) + self.enqueue_command(self.soft_reset) + class InovanceSV660(EtherCATDevice, CiA402Device, ErrorDevice): """Inovance SV660 servo drives.""" @@ -58,6 +79,15 @@ def get_feedback(self): fb_out.update(home_found=True) return fb_out + def set_command(self, **kwargs): + cmd_out = super().set_command(**kwargs) + cmd_in = self._interfaces["command_in"] + fb_in = self._interfaces["feedback_in"] + if cmd_in.rising_edge("reset_fault"): + if fb_in.get("error_code") == 0x07310731: + self.config.reset_error_and_restart() + return cmd_out + class SimInovanceSV660(InovanceSV660, EtherCATSimDevice, CiA402SimDevice): def set_sim_feedback(self): From c0200282e0eed39cb6c5ab04446cfffaad0143b5 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 26 Mar 2024 18:47:18 -0500 Subject: [PATCH 042/121] cia_301: Increase goal timeout when writing params --- hw_device_mgr/cia_301/device.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index b6daa426..d0ffe991 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -41,7 +41,11 @@ def canon_address(cls, address): @property def goal_reached_timeout(self): """Increase goal_reached timeout before reaching oper state.""" - return 10 if self.feedback_in.get("oper") else 30 + if not self.feedback_in.get("oper"): + return 30 + if self.feedback_out.get("param_state") != self.PARAM_STATE_COMPLETE: + return 30 + return 10 def __init__( self, address=None, skip_optional_config_values=True, **kwargs From 7b1be09552b5458a6a54805f9430c0b8e88ef3e8 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 3 Apr 2024 15:50:47 -0500 Subject: [PATCH 043/121] Add device class `init_class()` method The `ethercat.device` module sim device was initializing SDOs from ESI in `init_sim()`. That needs to be done for non-sim devices, too. To make init a little less confusing and verbose, add `init_class()` methods to both base `hw_device_mgr.device.Device` class and `hw_device_mgr.cia_301.config.CiA301Config` class. --- hw_device_mgr/cia_301/config.py | 8 +++++- hw_device_mgr/cia_301/device.py | 19 +++++++++----- hw_device_mgr/device.py | 8 +++++- hw_device_mgr/ethercat/device.py | 21 +++++++--------- hw_device_mgr/mgr/mgr.py | 25 ++++--------------- hw_device_mgr/mgr/tests/test_mgr.py | 6 +---- .../mgr/tests/test_mgr_read_update_write.py | 6 +---- hw_device_mgr/mgr_ros/tests/test_mgr.py | 3 +-- .../tests/test_mgr_read_update_write.py | 3 +-- hw_device_mgr/tests/base_test_class.py | 2 +- 10 files changed, 46 insertions(+), 55 deletions(-) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index adcc63c5..08def225 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -408,6 +408,11 @@ def scan_bus(cls, bus=0, skip_optional_config_values=True, **kwargs): config.logger.info("Drive config created from bus scan") return res + @classmethod + def init_class(cls): + """Initialize the config class""" + pass + class CiA301SimConfig(CiA301Config): """Configuration for simulated devices with simulated command.""" @@ -415,7 +420,8 @@ class CiA301SimConfig(CiA301Config): command_class = CiA301SimCommand @classmethod - def init_sim(cls, *, sim_device_data): + def init_class(cls, *, sim_device_data, **kwargs): + super().init_class(**kwargs) assert sim_device_data sdo_data = dict() for address, data in sim_device_data.items(): diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index d0ffe991..47df024c 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -235,6 +235,12 @@ def scan_devices(cls, bus=0, **kwargs): devices.append(dev) return devices + @classmethod + def init_class(cls, *, sdo_data, dcs_data, **kwargs): + super().init_class(**kwargs) + cls.add_device_sdos(sdo_data) + cls.add_device_dcs(dcs_data) + class CiA301SimDevice(CiA301Device, SimDevice): """Simulated CAN device.""" @@ -281,12 +287,13 @@ def sim_device_data_class(cls, sim_device_data): return model @classmethod - def init_sim(cls, *, sim_device_data, sdo_data, dcs_data): - super().init_sim(sim_device_data=sim_device_data) - sim_device_data = cls._sim_device_data[cls.category] - cls.add_device_sdos(sdo_data) - cls.add_device_dcs(dcs_data) - cls.config_class.init_sim(sim_device_data=sim_device_data) + def init_class(cls, **kwargs): + super().init_class(**kwargs) + config_kwargs = dict() + if issubclass(cls.config_class, CiA301SimConfig): + sim_device_data = cls._sim_device_data[cls.category] + config_kwargs = dict(sim_device_data=sim_device_data) + cls.config_class.init_class(**config_kwargs) def set_sim_feedback(self, **kwargs): # Automatically step through to online/oper diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 0f0d9291..b873b500 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -307,6 +307,11 @@ def get_model_by_name(cls, name): assert name in model_registry, f"{name} not in {model_registry}" return model_registry[name] + @classmethod + def init_class(cls): + """Initialize device classes""" + pass + ######################################## # Device identifier registry and instance factory @@ -419,7 +424,7 @@ def sim_device_data_address(cls, sim_device_data): return cls.canon_address(sim_device_data["address"]) @classmethod - def init_sim(cls, /, sim_device_data): + def init_class(cls, *, sim_device_data, **kwargs): """ Create sim device objects for tests. @@ -441,6 +446,7 @@ def init_sim(cls, /, sim_device_data): cls_sim_data[address] = {**dev, **updates} assert cls_sim_data + super().init_class(**kwargs) @classmethod def scan_devices(cls, **kwargs): diff --git a/hw_device_mgr/ethercat/device.py b/hw_device_mgr/ethercat/device.py index 68092ed0..6ca95eb0 100644 --- a/hw_device_mgr/ethercat/device.py +++ b/hw_device_mgr/ethercat/device.py @@ -105,22 +105,19 @@ def add_device_dcs_from_esi(cls, LcId="1033"): dcs_data = cls.read_device_dcs_from_esi(LcId=LcId) cls.add_device_dcs(dcs_data) - -class EtherCATSimDevice(EtherCATDevice, CiA301SimDevice): - config_class = EtherCATSimConfig - - def __init__(self, **kwargs): - super().__init__(**kwargs) - @classmethod - def init_sim(cls, LcId="1033", **kwargs): + def init_class(cls, LcId="1033", **kwargs): """ - Configure device, config, command for sim EtherCAT devices. + Configure device, config, command for EtherCAT devices. - Like parent `CiA301SimDevice.init_sim()`, but parse SDO data - from EtherCAT ESI description file and pass with sim device data + Like parent `CiA301Device.init_class()`, but parse SDO data + from EtherCAT ESI description file and pass with other kwargs to parent class's method. """ sdo_data = cls.read_device_sdos_from_esi(LcId=LcId) dcs_data = cls.read_device_dcs_from_esi(LcId=LcId) - super().init_sim(sdo_data=sdo_data, dcs_data=dcs_data, **kwargs) + super().init_class(sdo_data=sdo_data, dcs_data=dcs_data, **kwargs) + + +class EtherCATSimDevice(EtherCATDevice, CiA301SimDevice): + config_class = EtherCATSimConfig diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 0b7eaa25..0f16faa1 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -78,13 +78,15 @@ def init(self, /, mgr_config, device_config, **kwargs): self.logger.info("Device manager initialization complete") @classmethod - def init_sim(cls, **kwargs): - cls.device_base_class.init_sim(**kwargs) + def init_class(cls, sim_device_data=None, kwargs=dict()): + # Initialize device classes, incl. any sim discovery data + if sim_device_data: + kwargs.update(sim_device_data=sim_device_data) + cls.device_base_class.init_class(**kwargs) def init_devices( self, /, - sim_device_data=None, device_init_kwargs=dict(), device_scan_kwargs=dict(), ): @@ -97,9 +99,6 @@ def init_devices( """ self.logger.info("Initializing devices") - # Initialize sim device discovery data, if any - self.init_sim_devices(sim_device_data=sim_device_data) - # Scan and init devices self.devices = self.scan_devices(**device_scan_kwargs) for dev in self.devices: @@ -657,20 +656,6 @@ def automatic_next_event(self): #################################################### # Drive helpers - @classmethod - def init_sim_devices(cls, /, sim_device_data=None, **kwargs): - """ - Run `init_sim()` on devices. - - For configurations that include sim devices (even when the - device manager itself isn't running in sim mode). - """ - if sim_device_data is None: - return # No sim devices to configure - cls.device_base_class.init_sim( - sim_device_data=sim_device_data, **kwargs - ) - def set_drive_command(self): mgr_vals = self.command_in.get() skip = self.device_translated_interfaces.get("command_in", set()) diff --git a/hw_device_mgr/mgr/tests/test_mgr.py b/hw_device_mgr/mgr/tests/test_mgr.py index 46309540..18945017 100644 --- a/hw_device_mgr/mgr/tests/test_mgr.py +++ b/hw_device_mgr/mgr/tests/test_mgr.py @@ -17,11 +17,7 @@ def obj( self, mgr_config, device_config, all_device_data, extra_obj_fixtures ): self.obj = self.device_class() - self.obj.init( - mgr_config=mgr_config, - device_config=device_config, - sim_device_data=all_device_data.values(), - ) + self.obj.init(mgr_config=mgr_config, device_config=device_config) yield self.obj def test_state_values(self, obj): diff --git a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py index e2fa472f..195efa78 100644 --- a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py +++ b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py @@ -14,11 +14,7 @@ def obj( self, mgr_config, device_config, all_device_data, extra_obj_fixtures ): self.obj = self.device_class() - self.obj.init( - mgr_config=mgr_config, - device_config=device_config, - sim_device_data=all_device_data.values(), - ) + self.obj.init(mgr_config=mgr_config, device_config=device_config) yield self.obj test_case_key_re = re.compile(r"^d\.([x0-9])\.(.*)$") diff --git a/hw_device_mgr/mgr_ros/tests/test_mgr.py b/hw_device_mgr/mgr_ros/tests/test_mgr.py index a120f243..aa22db0a 100644 --- a/hw_device_mgr/mgr_ros/tests/test_mgr.py +++ b/hw_device_mgr/mgr_ros/tests/test_mgr.py @@ -18,8 +18,7 @@ class TestROSHWDeviceMgr(BaseROSMgrTestClass, _TestHWDeviceMgr): @pytest.fixture def obj(self, category_cls): - # init_sim() and init_devices() signatures changed, so can't - # use parent test class obj fixture + # init() signature changed, so can't use parent test class obj fixture self.obj = self.device_class() self.obj.init(argv=list()) yield self.obj diff --git a/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py index 7563b791..dfed80be 100644 --- a/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py +++ b/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py @@ -12,8 +12,7 @@ class TestROSHWDeviceMgrRUW(BaseROSMgrTestClass, _TestHWDeviceMgrRUW): @pytest.fixture def obj(self, category_cls): - # init_sim() and init_devices() signatures changed, so can't - # use parent test class obj fixture + # init() signature changed, so can't use parent test class obj fixture self.obj = self.device_class() self.obj.init(argv=list()) yield self.obj diff --git a/hw_device_mgr/tests/base_test_class.py b/hw_device_mgr/tests/base_test_class.py index a8b4bd01..703c91a2 100644 --- a/hw_device_mgr/tests/base_test_class.py +++ b/hw_device_mgr/tests/base_test_class.py @@ -37,7 +37,7 @@ class BaseTestClass(ConfigIO): def init_sim(cls, **kwargs): kwargs["sim_device_data"] = cls.init_sim_device_data() cls.device_class.clear_devices() - cls.device_class.init_sim(**kwargs) + cls.device_class.init_class(**kwargs) @classmethod def init_sim_device_data(cls): From 190ad1f1ce216be5810078154af74c859bc82d7a Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 3 Apr 2024 17:54:09 -0500 Subject: [PATCH 044/121] Fix tests after cia_301 param update rework In the `read_update_write` tests, disable param init so that param init state is predictable (and fast). --- hw_device_mgr/cia_301/config.py | 4 ++ hw_device_mgr/cia_301/device.py | 7 ++- .../tests/read_update_write.cases.yaml | 16 +++---- hw_device_mgr/cia_301/tests/test_config.py | 14 ++++-- .../tests/test_device_read_update_write.py | 1 + .../cia_402/tests/hm_timeout.cases.yaml | 1 + .../cia_402/tests/pp_timeout.cases.yaml | 1 + .../tests/read_update_write.cases.yaml | 18 +++----- .../tests/test_device_read_update_write.py | 1 + .../tests/test_device_read_update_write.py | 1 + .../mgr/tests/read_update_write.cases.yaml | 44 +++++++++---------- .../mgr/tests/test_mgr_read_update_write.py | 2 + 12 files changed, 63 insertions(+), 47 deletions(-) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index 08def225..931fa79c 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -33,6 +33,7 @@ def logging_name(self): command_class = CiA301Command sdo_class = CiA301SDO + init_params = True # If False, don't update params init_params_nv = True # Mapping of model_id to a dict of (index, subindex) to SDO object @@ -369,6 +370,9 @@ def initialize_params(self, dry_run=False): device parameters are completely configured. """ params = self.config["param_values"] + if not self.init_params: + self.logger.info(f"*NOT* queueing {len(params)} param updates") + return self.logger.info(f"Queueing {len(params)} param updates") self.flush_command_queue() for sdo, val in params.items(): diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 47df024c..d9804053 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -43,7 +43,8 @@ def goal_reached_timeout(self): """Increase goal_reached timeout before reaching oper state.""" if not self.feedback_in.get("oper"): return 30 - if self.feedback_out.get("param_state") != self.PARAM_STATE_COMPLETE: + p_state = self.feedback_out.get("param_state") + if self.config.init_params and p_state != self.PARAM_STATE_COMPLETE: return 30 return 10 @@ -114,7 +115,9 @@ def get_feedback(self): # Param init: download param values asynchronously after coming online old_ps = fb_out.get_old("param_state") p_init_err = self.config.param_init_error - if p_init_err: + if not self.config.init_params: + param_state = self.PARAM_STATE_COMPLETE + elif p_init_err: try: errstr = "{1}({2}, {3}): {0}".format(p_init_err) except: diff --git a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml index 987e3edf..6df0c947 100644 --- a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml @@ -13,7 +13,9 @@ goal_reason: Offline fault: False fault_desc: "" - param_state: 0 # Unknown + param_state: 0x00 # PARAM_STATE_UNKNOWN + command_in: + reset_fault: False command_out: fasttrack: False sim_feedback: @@ -24,8 +26,8 @@ online: True feedback_out: online: True - goal_reason: Not operational, updating device params - param_state: 1 # Updating + goal_reason: Not operational + param_state: 0x02 # PARAM_STATE_COMPLETE sim_feedback: oper: True - desc: "NMT Pre-operational -> Operational" @@ -35,7 +37,6 @@ oper: True goal_reached: True goal_reason: Reached - param_state: 2 # Complete - desc: "NMT Operational; hold state x1" - desc: "NMT Operational; hold state x2" # @@ -77,11 +78,11 @@ feedback_out: online: False oper: False + param_state: 0x00 # PARAM_STATE_UNKNOWN goal_reached: False goal_reason: Offline fault: True fault_desc: Drive went offline/non-operational - param_state: 0x00 # Unknown sim_feedback: oper: False - desc: "NMC offline after online; hold state" @@ -95,9 +96,9 @@ feedback_out: online: True oper: False + param_state: 0x02 # PARAM_STATE_COMPLETE goal_reached: False - goal_reason: Not operational, updating device params - param_state: 0x01 # Updating + goal_reason: Not operational fault: True fault_desc: Drive went offline/non-operational sim_feedback: @@ -109,7 +110,6 @@ oper: True goal_reached: True goal_reason: Reached - param_state: 0x02 # Complete fault: False fault_desc: "" - desc: "NMC offline after online; hold state" diff --git a/hw_device_mgr/cia_301/tests/test_config.py b/hw_device_mgr/cia_301/tests/test_config.py index 567143c4..c3c38492 100644 --- a/hw_device_mgr/cia_301/tests/test_config.py +++ b/hw_device_mgr/cia_301/tests/test_config.py @@ -75,19 +75,25 @@ def test_initialize_params(self, obj, sdo_data, sim_device_data): assert pq.empty # Start param init + obj.command().cmd_exec_time = 0.05 # Simulate up/download time print("Starting param init") - assert obj.initialize_params(restart=True) is False + obj.initialize_params() + if obj.config["param_values"]: + assert obj.param_init_in_progress + obj.command().cmd_exec_time = None # Speed up test # Spin while we wait on the worker timeout, incr = 1, 0.01 for i in range(int(timeout / incr)): - if obj.initialize_params(): + assert not obj.param_init_error + if not obj.param_init_in_progress: break time.sleep(incr) else: - print("initialize_params() never returned True!") + print("param_init_in_progress never returned True!") print(f"Spun {i} cycles to init params") - assert obj.initialize_params() + assert not obj.param_init_in_progress + assert not obj.param_init_error assert pq.empty for sdo_ix, val in obj.config["param_values"].items(): diff --git a/hw_device_mgr/cia_301/tests/test_device_read_update_write.py b/hw_device_mgr/cia_301/tests/test_device_read_update_write.py index befa7bfe..317703ee 100644 --- a/hw_device_mgr/cia_301/tests/test_device_read_update_write.py +++ b/hw_device_mgr/cia_301/tests/test_device_read_update_write.py @@ -13,6 +13,7 @@ class TestCiA301DeviceRUW(BaseCiA301TestClass, _TestDeviceRUW): @pytest.fixture def obj(self, device_cls, sim_device_data): self.obj = self.device_model_cls(address=sim_device_data["address"]) + self.obj.config.init_params = False self.obj.init() yield self.obj diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index e63dae9e..58e2e85b 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -90,6 +90,7 @@ # Timeout treated as fault fault: True fault_desc: "Timeout (15s): homing not complete" + goal_reached: True command_in: state: FAULT home_request: False diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index 7c20bb4c..f1e2ef70 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -108,6 +108,7 @@ # Timeout treated as fault fault: True fault_desc: "Timeout (15s): move not complete" + goal_reached: True command_in: state: FAULT home_request: False diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index bdf6b8a3..ae64c7da 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -77,8 +77,8 @@ feedback_out: # CiA 301 online: True - param_state: 0x01 # Updating - goal_reason: Not operational, updating device params + param_state: 0x02 # PARAM_STATE_COMPLETE + goal_reason: Not operational sim_feedback: # CiA 301 oper: True @@ -185,7 +185,6 @@ transition: 13 # (Any)->FAULT REACTION ACTIVE fault: True fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF - goal_reached: False goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; 0xDEADBEEF Unknown error code 0xDEADBEEF error_code: 0xDEADBEEF # Bogus error code description: Unknown error code 0xDEADBEEF @@ -231,6 +230,7 @@ status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED state: READY TO SWITCH ON transition: 2 + goal_reached: False goal_reason: state READY TO SWITCH ON != OPERATION ENABLED fault: False fault_desc: "" @@ -256,6 +256,7 @@ transition: 13 # (Any)->FAULT REACTION ACTIVE fault: True fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF + goal_reached: True goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; 0xDEADBEEF Unknown error code 0xDEADBEEF error_code: 0xDEADBEEF description: Unknown error code 0xDEADBEEF @@ -281,7 +282,6 @@ error_code: 0xDEADBEEF # Bogus error code feedback_out: transition: -1 - goal_reached: True goal_reason: Reached - desc: "Hold fault: Hold state x2" sim_feedback_set: @@ -318,7 +318,6 @@ - desc: "Disable: Hold state x1" feedback_out: transition: -1 - goal_reached: True goal_reason: Reached - desc: "Disable: Hold state x2" @@ -400,8 +399,6 @@ status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED state: OPERATION ENABLED transition: 4 - goal_reached: True - goal_reason: Reached - desc: "Enable multi: Hold OPERATION ENABLED x1" feedback_out: transition: -1 @@ -427,7 +424,6 @@ status_word: 0x0017 state: QUICK STOP ACTIVE transition: 11 - goal_reached: False goal_reason: state QUICK STOP ACTIVE != FAULT; FAULT command from controller (was OPERATION ENABLED) fault: True fault_desc: FAULT command from controller (was OPERATION ENABLED) @@ -442,7 +438,6 @@ status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED state: SWITCH ON DISABLED transition: 12 - goal_reached: True goal_reason: Reached - desc: "Disable disabled: Hold SWITCH ON DISABLED x1" feedback_out: @@ -476,7 +471,6 @@ # With no voltage, drive refuses to leave SWITCH ON DISABLED # state: SWITCH ON DISABLED transition: -1 - goal_reached: False goal_reason: state SWITCH ON DISABLED != SWITCHED ON; Enable command while no voltage at motor # fault: True # (Already was True) fault_desc: Enable command while no voltage at motor @@ -499,6 +493,7 @@ status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED feedback_out: status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED + goal_reached: False goal_reason: state SWITCH ON DISABLED != SWITCHED ON fault: False fault_desc: "" @@ -511,7 +506,6 @@ status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED state: READY TO SWITCH ON transition: 2 - goal_reached: False goal_reason: state READY TO SWITCH ON != SWITCHED ON command_out: control_word: 0x0007 # SWITCHED ON @@ -798,6 +792,7 @@ status_word: 0x001F # FAULT REACTION ACTIVE - Bit 12 SETPOINT_ACK clear state: FAULT REACTION ACTIVE transition: 13 # (Any)->FAULT REACTION ACTIVE + goal_reached: True goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; Move request while drive not enabled; Fault (no error code) move_error: True fault: True @@ -848,6 +843,7 @@ status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED state: READY TO SWITCH ON transition: 2 # SWITCH ON DISABLED->READY TO SWITCH ON + goal_reached: False goal_reason: state READY TO SWITCH ON != OPERATION ENABLED move_error: False fault: False diff --git a/hw_device_mgr/hal/tests/test_device_read_update_write.py b/hw_device_mgr/hal/tests/test_device_read_update_write.py index dac627b9..9409ab92 100644 --- a/hw_device_mgr/hal/tests/test_device_read_update_write.py +++ b/hw_device_mgr/hal/tests/test_device_read_update_write.py @@ -11,6 +11,7 @@ class TestHALDeviceRUW(BaseHALTestClass, _TestCiA402DeviceRUW): @pytest.fixture def obj(self, sim_device_data, mock_halcomp, device_cls): self.obj = self.device_model_cls(address=sim_device_data["address"]) + self.obj.config.init_params = False self.obj.init(comp=mock_halcomp) yield self.obj diff --git a/hw_device_mgr/lcec/tests/test_device_read_update_write.py b/hw_device_mgr/lcec/tests/test_device_read_update_write.py index a5225cb1..6da13646 100644 --- a/hw_device_mgr/lcec/tests/test_device_read_update_write.py +++ b/hw_device_mgr/lcec/tests/test_device_read_update_write.py @@ -14,5 +14,6 @@ class TestLCECDeviceRUW( @pytest.fixture def obj(self, sim_device_data, mock_halcomp, device_cls): self.obj = self.device_model_cls(address=sim_device_data["address"]) + self.obj.config.init_params = False self.obj.init(comp=mock_halcomp) yield self.obj diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index 40828338..5adfe82e 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -54,6 +54,7 @@ # Mgr state_cmd: 0 # init state_set: 0 # don't latch in state_cmd + reset_fault: False # Drives # - CiA 402 d.x.control_mode: 8 # MODE_CSP @@ -63,10 +64,11 @@ command_out: # Mgr state: 0 # init - state_log: "Automatic transition from init_command state" + state_log: Automatic transition to init_command from init_command state command_complete: False drive_state: SWITCH ON DISABLED reset: False + reset_fault_cmd: False fasttrack: False # Drives # - CiA 402 @@ -96,12 +98,13 @@ d.x.status_word: 0x0000 # START feedback_out: # Mgr - goal_reason: Not operational, updating device params ({all_drives}) + goal_reason: Not operational ({all_drives}) + # Drives # - CiA 301 d.x.online: True - d.x.goal_reason: Not operational, updating device params - d.x.param_state: 0x01 # Updating + d.x.goal_reason: Not operational + d.x.param_state: 0x02 # PARAM_STATE_COMPLETE # - CiA 402 d.x.status_word: 0x0000 # START sim_feedback: @@ -154,10 +157,11 @@ - desc: "Init: Automatic 'stop' command" feedback_out: goal_reached: True - goal_reason: "" + goal_reason: Reached d.x.transition: -1 # No transition command_out: - state_log: "Automatic transition from init_complete state" + state_log: Automatic transition to stop_command from init_complete state + reset_fault_cmd: True command_complete: 0 - desc: "Init: Complete" feedback_out: @@ -168,7 +172,7 @@ - desc: "Init: Hold state 1" feedback_out: goal_reached: True - goal_reason: "" + goal_reason: Reached - desc: "Init: Hold state 2" # @@ -242,7 +246,7 @@ feedback_out: enabled: True goal_reached: True - goal_reason: "" + goal_reason: Reached d.x.transition: -1 # No transition - desc: "Enable: Hold state OPERATION ENABLED x2" @@ -261,7 +265,6 @@ d.1.error_code: 0xDEADBEEF feedback_out: enabled: False - goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[1]}) fault: True fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[1]}) d.1.status_word: 0x001F # FAULT REACTION ACTIVE + VOLTAGE_ENABLED @@ -271,7 +274,6 @@ d.1.fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF d.1.error_code: 0xDEADBEEF d.1.description: Unknown error code 0xDEADBEEF - d.1.goal_reached: False d.1.goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; 0xDEADBEEF Unknown error code 0xDEADBEEF command_in: state_cmd: 4 # fault @@ -293,14 +295,13 @@ d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED feedback_out: goal_reached: False - goal_reason: state QUICK STOP ACTIVE != FAULT; FAULT command from controller (was OPERATION ENABLED) ({drives[0]},{drives[2]},{drives3plus}) + goal_reason: Waiting on device manager internal transitions fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[1]}) # drive_1 holds state d.1.fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED d.1.state: FAULT d.1.transition: 14 - d.1.goal_reached: True d.1.goal_reason: Reached # ...while other drives enter QUICK STOP ACTIVE d.x.fault: True @@ -308,7 +309,6 @@ d.x.status_word: 0x0017 # QUICK STOP + VOLTAGE_ENABLED d.x.state: QUICK STOP ACTIVE d.x.transition: 11 - d.x.goal_reached: False d.x.goal_reason: state QUICK STOP ACTIVE != FAULT; FAULT command from controller (was OPERATION ENABLED) command_out: state_log: Manager fault @@ -328,7 +328,7 @@ d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED feedback_out: goal_reached: True - goal_reason: "" + goal_reason: Reached d.1.transition: -1 d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED d.1.state: FAULT @@ -437,7 +437,7 @@ feedback_out: fault: True fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[2]}) - goal_reason: state FAULT REACTION ACTIVE != SWITCHED ON; 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[2]}) + goal_reason: Waiting on device manager internal transitions d.2.status_word: 0x001F # FAULT REACTION ACTIVE + VOLTAGE_ENABLED d.2.state: FAULT REACTION ACTIVE d.2.transition: 13 @@ -445,7 +445,6 @@ d.2.fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF d.2.error_code: 0xDEADBEEF d.2.description: Unknown error code 0xDEADBEEF - d.2.goal_reached: False d.2.goal_reason: state FAULT REACTION ACTIVE != SWITCHED ON; 0xDEADBEEF Unknown error code 0xDEADBEEF d.1.status_word: 0x0033 # SWITCHED ON + VOLTAGE_ENABLED d.1.state: SWITCHED ON @@ -500,7 +499,7 @@ d.2.error_code: 0xDEADBEEF # Bogus error code feedback_out: goal_reached: True - goal_reason: "" + goal_reason: Reached d.x.transition: -1 # No transition - desc: "Hold fault: Hold state x2" sim_feedback_set: @@ -550,7 +549,7 @@ - desc: "Disable: Hold state x1" feedback_out: goal_reached: True - goal_reason: "" + goal_reason: Reached d.x.transition: -1 # No transition d.x.goal_reached: True d.x.goal_reason: Reached @@ -683,7 +682,7 @@ d.0.status_word: 0x1037 # OPERATION ENABLED + HOMING_ATTAINED d.1.status_word: 0x1037 # OPERATION ENABLED + HOMING_ATTAINED feedback_out: - goal_reason: "" + goal_reason: Reached d.0.status_word: 0x1037 # OPERATION ENABLED + HOMING_ATTAINED d.1.status_word: 0x1037 # OPERATION ENABLED + HOMING_ATTAINED d.0.home_success: True @@ -752,7 +751,7 @@ - desc: "Home: Hold SWITCH ON DISABLED x1" feedback_out: goal_reached: True - goal_reason: "" + goal_reason: Reached d.x.transition: -1 # No transition - desc: "Home: Hold SWITCH ON DISABLED x2" @@ -787,7 +786,7 @@ d.2.status_word: 0x0040 # SWITCH ON DISABLED - VOLTAGE_ENABLED feedback_out: goal_reached: False - goal_reason: state READY TO SWITCH ON != SWITCHED ON ({drives[0]},{drives[1]},{drives3plus}); state SWITCH ON DISABLED != SWITCHED ON; Enable command while no voltage at motor ({drives[2]}) + goal_reason: state READY TO SWITCH ON != SWITCHED ON ({drives[0]},{drives[1]},{drives3plus}) fault: True fault_desc: Enable command while no voltage at motor ({drives[2]}) d.2.fault: True @@ -799,6 +798,7 @@ d.x.transition: 2 d.2.transition: -1 d.x.goal_reached: False + d.2.goal_reached: True d.x.goal_reason: state READY TO SWITCH ON != SWITCHED ON d.2.goal_reason: state SWITCH ON DISABLED != SWITCHED ON; Enable command while no voltage at motor command_in: @@ -835,7 +835,7 @@ d.2.status_word: 0x0040 # SWITCH ON DISABLED - VOLTAGE_ENABLED feedback_out: goal_reached: True - goal_reason: "" + goal_reason: Reached d.x.transition: -1 - desc: "No voltage: Motor voltage restored; all drives disabled" feedback_in: diff --git a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py index 195efa78..815378a8 100644 --- a/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py +++ b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py @@ -15,6 +15,8 @@ def obj( ): self.obj = self.device_class() self.obj.init(mgr_config=mgr_config, device_config=device_config) + for d in self.obj.devices: + d.config.init_params = False yield self.obj test_case_key_re = re.compile(r"^d\.([x0-9])\.(.*)$") From 0437edcc216147e2e131f94d156d2ffb61d7416b Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 8 Apr 2024 17:30:38 -0500 Subject: [PATCH 045/121] cia_301: Fix param init Setting sim param update time to zero causes sim param init to complete instantly, so `self.config.param_init_in_progress` is never true. This results in an eventual timeout. The problem is the param init state is never bumped from `PARAM_STATE_UNKNOWN`. This commit bumps the state when `self.config.initialize_params()` executes. To keep device state all in interfaces, and to preserve `set_command()` not writing to `feedback_*` interfaces, the extra `command_out` interface `init_params` register tells `get_feedback()` that param init has been commanded so param init state can be bumped. --- hw_device_mgr/cia_301/device.py | 18 +++++++++++++++++- .../cia_301/tests/read_update_write.cases.yaml | 9 +++++++++ .../cia_402/tests/hm_timeout.cases.yaml | 1 + .../cia_402/tests/pp_timeout.cases.yaml | 1 + .../cia_402/tests/read_update_write.cases.yaml | 5 +++++ .../mgr/tests/read_update_write.cases.yaml | 5 +++++ 6 files changed, 38 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index d9804053..9ef77644 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -128,6 +128,10 @@ def get_feedback(self): goal_reached = False goal_reasons.append("updating device params") param_state = self.PARAM_STATE_UPDATING + elif self.command_out.get("init_params"): + goal_reached = False + goal_reasons.append("updating device params") + param_state = self.PARAM_STATE_UPDATING elif old_ps in (self.PARAM_STATE_UPDATING, self.PARAM_STATE_COMPLETE): # Previously complete, or previously updating but currently not param_state = self.PARAM_STATE_COMPLETE @@ -163,15 +167,27 @@ def get_feedback(self): self.logger.info("Device param init complete") return fb_out + command_out_data_types = dict( + init_params="bit", + ) + + command_out_defaults = dict( + init_params=False, + ) + def set_command(self, **kwargs): cmd_out = super().set_command(**kwargs) cmd_in = self._interfaces["command_in"] + init_params_cmd = False if self.feedback_in.rising_edge("online"): self.logger.info("Initializing params after coming online") - self.config.initialize_params() + init_params_cmd = True elif cmd_in.rising_edge("reset_fault") and self.config.param_init_error: self.logger.info("Re-initializing params after fault") + init_params_cmd = True + if init_params_cmd: self.config.initialize_params() + cmd_out.update(init_params=True) return cmd_out @classmethod diff --git a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml index 6df0c947..ff7012db 100644 --- a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml @@ -17,6 +17,7 @@ command_in: reset_fault: False command_out: + init_params: False fasttrack: False sim_feedback: online: True @@ -28,6 +29,8 @@ online: True goal_reason: Not operational param_state: 0x02 # PARAM_STATE_COMPLETE + command_out: + init_params: True sim_feedback: oper: True - desc: "NMT Pre-operational -> Operational" @@ -37,6 +40,8 @@ oper: True goal_reached: True goal_reason: Reached + command_out: + init_params: False - desc: "NMT Operational; hold state x1" - desc: "NMT Operational; hold state x2" # @@ -101,6 +106,8 @@ goal_reason: Not operational fault: True fault_desc: Drive went offline/non-operational + command_out: + init_params: True sim_feedback: oper: True - desc: "NMC offline after online; resume operational" @@ -112,4 +119,6 @@ goal_reason: Reached fault: False fault_desc: "" + command_out: + init_params: False - desc: "NMC offline after online; hold state" diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index 58e2e85b..f9914292 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -53,6 +53,7 @@ command_out: control_word: 0x000F control_mode: 6 + init_params: False fasttrack: False sim_feedback: online: True diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index f1e2ef70..86eba058 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -55,6 +55,7 @@ command_out: control_word: 0x001F # Bit 4 NEW_SETPOINT set control_mode: 1 # MODE_PP + init_params: False fasttrack: True sim_feedback: online: True diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index ae64c7da..67b6be1b 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -56,6 +56,7 @@ # CiA 402 control_word: 0x0000 control_mode: 8 # MODE_CSP + init_params: False fasttrack: False sim_feedback: # CiA 301 @@ -79,6 +80,8 @@ online: True param_state: 0x02 # PARAM_STATE_COMPLETE goal_reason: Not operational + command_out: + init_params: True sim_feedback: # CiA 301 oper: True @@ -99,6 +102,8 @@ state: 'NOT READY TO SWITCH ON' transition: 0 goal_reason: control_mode MODE_NA != MODE_CSP; state NOT READY TO SWITCH ON != SWITCH ON DISABLED + command_out: + init_params: False sim_feedback: # CiA 402 status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index 5adfe82e..71a602d9 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -74,6 +74,7 @@ # - CiA 402 d.x.control_word: 0x0000 # SWITCH ON DISABLED d.x.control_mode: 8 # MODE_CSP + d.x.init_params: False d.x.fasttrack: False sim_feedback: # Drives @@ -107,6 +108,8 @@ d.x.param_state: 0x02 # PARAM_STATE_COMPLETE # - CiA 402 d.x.status_word: 0x0000 # START + command_out: + d.x.init_params: True sim_feedback: # Drives # - CiA 301 @@ -132,6 +135,8 @@ d.x.status_word: 0x0010 # VOLTAGE_ENABLED d.x.transition: 0 d.x.goal_reason: control_mode MODE_NA != MODE_CSP; state NOT READY TO SWITCH ON != SWITCH ON DISABLED + command_out: + d.x.init_params: False sim_feedback: # - CiA 402 d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED From 5305987301cad593302919ccf474939040a1c441 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 9 Apr 2024 15:58:16 -0500 Subject: [PATCH 046/121] cia_402: Track status word following error bit Add a `following_error` feedback output tied to status word `OPERATION_MODE_SPECIFIC_2` bit 13, which represents following error in `PP` and `CSP` modes (and homing error in `HM` mode, but that has a separate feedback output). The `move_error` feedback output was never connected to anything meaningful: in `get_feedback_pp`, it only set this output when `move_request` active but drive not `OPERATION ENABLED`, but the device mgr would indicate this anyway by triggering a fault. The output is now removed. --- hw_device_mgr/cia_402/device.py | 20 +++++++++++-------- .../cia_402/tests/hm_timeout.cases.yaml | 2 +- .../cia_402/tests/pp_timeout.cases.yaml | 2 +- .../tests/read_update_write.cases.yaml | 5 +---- .../mgr/tests/read_update_write.cases.yaml | 2 +- 5 files changed, 16 insertions(+), 15 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 11048d1e..cc8a4cb1 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -25,6 +25,9 @@ class CiA402Device(CiA301Device, ErrorDevice): Feedback parameters: - `home_success`: Drive completed homing successfully - `home_error`: Drive reports homing error + - `move_setpoint_ack`: Drive acknowledges PP-mode `move_request` + - `move_success`: Drive reports PP-mode move succeeded + - `following_error`: Drive reports following error in various modes """ data_types = CiA301DataType @@ -81,7 +84,7 @@ def control_mode_str(cls, mode): TARGET_REACHED=10, INTERNAL_LIMIT_ACTIVE=11, OPERATION_MODE_SPECIFIC_1=12, # HM=HOMING_ATTAINED, PP=SETPOINT_ACK - OPERATION_MODE_SPECIFIC_2=13, # HM=HOMING_ERROR; others=FOLLOWING_ERROR + OPERATION_MODE_SPECIFIC_2=13, # HM=HOMING_ERROR; PP/CSP=FOLLOWING_ERROR MANUFACTURER_SPECIFIC_2=14, MANUFACTURER_SPECIFIC_3=15, ) @@ -109,7 +112,7 @@ def control_mode_str(cls, mode): home_error="bit", move_setpoint_ack="bit", move_success="bit", - move_error="bit", + following_error="bit", ) feedback_out_defaults = dict( **feedback_in_defaults, @@ -119,7 +122,7 @@ def control_mode_str(cls, mode): home_error=False, move_setpoint_ack=False, move_success=False, - move_error=False, + following_error=False, ) log_status_word_changes = True @@ -169,7 +172,7 @@ def get_feedback_pp(self, sw): # Control mode is PP if not self.command_in.get("move_request"): self.feedback_out.update( - move_setpoint_ack=False, move_success=False, move_error=False + move_setpoint_ack=False, move_success=False ) return True, None if self.feedback_out.get("state") != "OPERATION ENABLED": @@ -177,7 +180,6 @@ def get_feedback_pp(self, sw): self.feedback_out.update( move_setpoint_ack=False, move_success=False, - move_error=True, fault=True, fault_desc=reason, ) @@ -191,9 +193,7 @@ def get_feedback_pp(self, sw): else: reason = "move not complete" - self.feedback_out.update( - move_success=success, move_error=False, move_setpoint_ack=sp_ack - ) + self.feedback_out.update(move_success=success, move_setpoint_ack=sp_ack) return success, reason def get_feedback_sto(self): @@ -284,6 +284,10 @@ def get_feedback(self): fault_desc = "Enable command while no voltage at motor" goal_reasons.append(fault_desc) + # Handle `FOLLOWING_ERROR` active + ferror = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_2") + fb_out.update(following_error=ferror) + # Raise fault if device unexpectedly goes offline if self.command_in.get( "state" diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index f9914292..5d4cac7c 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -35,7 +35,7 @@ goal_reached: True goal_reason: Reached move_success: False - move_error: False + following_error: False move_setpoint_ack: False position_cmd: 0.0 position_fb: 0.0 diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index 86eba058..89e45c81 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -37,7 +37,7 @@ goal_reached: True goal_reason: Reached move_success: False - move_error: False + following_error: False move_setpoint_ack: False position_cmd: 0.0 position_fb: 15.0 diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index 67b6be1b..fdd938de 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -34,7 +34,7 @@ goal_reached: False goal_reason: Offline move_success: False - move_error: False + following_error: False move_setpoint_ack: False position_cmd: 0 position_fb: 0 @@ -799,7 +799,6 @@ transition: 13 # (Any)->FAULT REACTION ACTIVE goal_reached: True goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; Move request while drive not enabled; Fault (no error code) - move_error: True fault: True fault_desc: Fault (no error code) command_out: @@ -816,7 +815,6 @@ state: FAULT transition: 14 # FAULT REACTION ACTIVE->FAULT goal_reason: state FAULT != OPERATION ENABLED; Enabled drive unexpectedly disabled; Move request while drive not enabled; Fault (no error code) - move_error: True command_out: control_word: 0x0080 # Clear fault sim_feedback: @@ -850,7 +848,6 @@ transition: 2 # SWITCH ON DISABLED->READY TO SWITCH ON goal_reached: False goal_reason: state READY TO SWITCH ON != OPERATION ENABLED - move_error: False fault: False fault_desc: "" command_in: diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index 71a602d9..f74f1ff3 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -43,8 +43,8 @@ d.x.goal_reached: False d.x.goal_reason: Offline d.x.move_success: False - d.x.move_error: False d.x.move_setpoint_ack: False + d.x.following_error: False # - STO d.x.sto: False # - errors From 5fdc477fed3996e71ed608f4bcb243c9e093fed2 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 10 Apr 2024 15:34:21 -0500 Subject: [PATCH 047/121] setup.py: Only build `multilatency` HAL comp for ROS 2 --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup.py b/setup.py index a1854e50..da9cafca 100644 --- a/setup.py +++ b/setup.py @@ -45,7 +45,7 @@ class CustomInstall(install): def run(self): """Run halcompile on `multilatency.comp`.""" - if os.environ.get("ROS_VERSION", None) != "1": + if os.environ.get("ROS_VERSION", None) == "2": # ROS1 builds comp from CMakeFile comp_src = "hw_device_mgr/latency/multilatency.comp" subprocess.check_call( From 76755d3ebf4535b056d6d34663dd45cf6760d294 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 16 Apr 2024 15:34:52 -0500 Subject: [PATCH 048/121] cia_402: Stay in QUICK STOP ACTIVE after fault command After a FAULT command from the mgr, an enabled drive transitions to QUICK STOP ACTIVE, but then transitions to SWITCH ON DISABLED at the next update. Instead, the drive should remain in QUICK STOP ACTIVE until a stop or start command (or drive may be set up to automatically transition on its own). --- hw_device_mgr/cia_402/device.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index cc8a4cb1..28827e3f 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -478,9 +478,9 @@ def sw_to_str(cls, sw): # Drives in FAULT state remain in that state "FAULT REACTION ACTIVE": ["FAULT", 14], "FAULT": ["FAULT", -1], # End state - # Drives in OPERATION ENABLED quick stop & disable + # Drives in OPERATION ENABLED quick stop & stay there "OPERATION ENABLED": ["QUICK STOP ACTIVE", 11], - "QUICK STOP ACTIVE": ["SWITCH ON DISABLED", 12], + "QUICK STOP ACTIVE": ["QUICK STOP ACTIVE", -1], # Drives in all other states transition to SWITCH ON DISABLED "START": ["NOT READY TO SWITCH ON", 0], "NOT READY TO SWITCH ON": ["SWITCH ON DISABLED", 1], From 3fd687e63005645d95668019d63c029351d92e49 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 7 May 2024 17:16:42 -0500 Subject: [PATCH 049/121] cia_402: Fix tests after QUICK STOP ACTIVE change --- hw_device_mgr/cia_402/device.py | 2 +- hw_device_mgr/cia_402/tests/read_update_write.cases.yaml | 9 +++------ hw_device_mgr/mgr/tests/read_update_write.cases.yaml | 8 +++----- 3 files changed, 7 insertions(+), 12 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 28827e3f..b80a1ffa 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -602,7 +602,7 @@ def _get_next_control_word(self, cmd_out): "READY TO SWITCH ON": 0x0006, "SWITCHED ON": 0x0007, "OPERATION ENABLED": 0x000F, - "QUICK STOP ACTIVE": None, + "QUICK STOP ACTIVE": 0x0002, "FAULT REACTION ACTIVE": None, "FAULT": 0x0000, # Anything but 0x0080 will hold state } diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index fdd938de..2ec8c163 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -429,11 +429,8 @@ status_word: 0x0017 state: QUICK STOP ACTIVE transition: 11 - goal_reason: state QUICK STOP ACTIVE != FAULT; FAULT command from controller (was OPERATION ENABLED) fault: True fault_desc: FAULT command from controller (was OPERATION ENABLED) - command_out: - control_word: 0x0000 sim_feedback: status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - desc: "Disable enabled: Command disable; 402 state machine transition 12" @@ -442,11 +439,11 @@ feedback_out: status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED state: SWITCH ON DISABLED - transition: 12 + transition: -1 goal_reason: Reached + command_out: + control_word: 0x0000 - desc: "Disable disabled: Hold SWITCH ON DISABLED x1" - feedback_out: - transition: -1 - desc: "Disable disabled: Hold SWITCH ON DISABLED x2" # diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index f74f1ff3..fac448c9 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -314,14 +314,11 @@ d.x.status_word: 0x0017 # QUICK STOP + VOLTAGE_ENABLED d.x.state: QUICK STOP ACTIVE d.x.transition: 11 - d.x.goal_reason: state QUICK STOP ACTIVE != FAULT; FAULT command from controller (was OPERATION ENABLED) command_out: state_log: Manager fault # Manager does NOT all drives in FAULT state, but in STATE_FAULT # that's not necessary; drives will continue working towards their goals command_complete: True - # Manager commands TRANSITION_12 to SWITCH ON DISABLED - d.x.control_word: 0x0000 # SWITCH ON DISABLED sim_feedback: d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED @@ -334,14 +331,15 @@ feedback_out: goal_reached: True goal_reason: Reached - d.1.transition: -1 d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED d.1.state: FAULT d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED d.x.state: SWITCH ON DISABLED - d.x.transition: 12 + d.x.transition: -1 d.x.goal_reached: True d.x.goal_reason: Reached + command_out: + d.x.control_word: 0x0000 # SWITCH ON DISABLED - desc: "Sim fault: Hold fault command x1" sim_feedback_set: d.1.error_code: 0xDEADBEEF # Bogus error code From 5fe7bd3abcefd4af9dad8eaec28763ef5ddf7f3a Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 8 May 2024 12:38:15 -0500 Subject: [PATCH 050/121] devices: Fix swapped test class categories --- hw_device_mgr/devices/tests/devices.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/hw_device_mgr/devices/tests/devices.py b/hw_device_mgr/devices/tests/devices.py index 60ae2ce6..5f17309a 100644 --- a/hw_device_mgr/devices/tests/devices.py +++ b/hw_device_mgr/devices/tests/devices.py @@ -24,7 +24,7 @@ class ElmoGold520ForTest(DevicesForTest, ElmoGold520, CiA402SimDevice): class InovanceIS620NForTest(DevicesForTest, InovanceIS620N, CiA402SimDevice): name = "IS620N_ECAT_test" - test_category = "inovance_sv660n_test" + test_category = "inovance_is620n_test" class InovanceSV660NForTest(DevicesForTest, InovanceSV660, CiA402SimDevice): @@ -32,7 +32,7 @@ class InovanceSV660NForTest(DevicesForTest, InovanceSV660, CiA402SimDevice): # exception in the read_update_write.cases.yaml for the simulated status # word bit 15 "home found" name = "SV660_ECAT_test" - test_category = "inovance_is620n_test" + test_category = "inovance_sv660n_test" class EVEXCREForTest(DevicesForTest, EVEXCRE, CiA402SimDevice): From 41d1c29dbd30b12d5572ce4b1ddffacbadcbe774 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 8 May 2024 13:06:57 -0500 Subject: [PATCH 051/121] base device class: Allow controlled overriding interfaces --- hw_device_mgr/device.py | 21 +++++++++++++------ .../tests/test_device_read_update_write.py | 2 +- 2 files changed, 16 insertions(+), 7 deletions(-) diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index b873b500..5581c5f2 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -44,6 +44,11 @@ class Device(LoggingMixin, abc.ABC): fasttrack=False, ) + feedback_in_overlap = set() + feedback_out_overlap = set() + command_in_overlap = set() + command_out_overlap = set() + interface_names = { "feedback_in", "feedback_out", @@ -82,18 +87,21 @@ def exit(self): pass @classmethod - def merge_dict_attrs(cls, attr): + def merge_dict_attrs(cls, name, attr_suff): """ Merge `dict` attributes across class hierarchy. Scan through class and parent classes for `attr`, a `dict`, and return merged `dict`. """ + attr = f"{name}_{attr_suff}" + overlap_allowed = getattr(cls, f"{name}_overlap") res = dict() - for c in cls.__mro__: + for c in reversed(cls.__mro__): c_attr = c.__dict__.get(attr, dict()) - # Overlap not allowed - assert not (set(res.keys()) & set(c_attr.keys())) + # Overlap strictly controlled + overlap = set(res.keys()) & set(c_attr.keys()) + assert not (overlap - overlap_allowed) res.update(c_attr) return res @@ -116,11 +124,11 @@ def init_interfaces(self): intfs = self._interfaces = dict() dt_name2cls = self.data_type_class.by_shared_name for name in self.interface_names: - defaults = self.merge_dict_attrs(f"{name}_defaults") + defaults = self.merge_dict_attrs(name, "defaults") for k, v in defaults.items(): if isinstance(v, dict): defaults[k] = v.copy() - dt_names = self.merge_dict_attrs(f"{name}_data_types") + dt_names = self.merge_dict_attrs(name, "data_types") data_types = {k: dt_name2cls(v) for k, v in dt_names.items()} intfs[name] = self.interface_class(name, defaults, data_types) @@ -404,6 +412,7 @@ def dot_color(cls): class SimDevice(Device): sim_feedback_data_types = dict() sim_feedback_defaults = dict() + sim_feedback_overlap = set() interface_names = { "feedback_in", diff --git a/hw_device_mgr/hal/tests/test_device_read_update_write.py b/hw_device_mgr/hal/tests/test_device_read_update_write.py index 9409ab92..594c0ea9 100644 --- a/hw_device_mgr/hal/tests/test_device_read_update_write.py +++ b/hw_device_mgr/hal/tests/test_device_read_update_write.py @@ -26,7 +26,7 @@ def override_interface_param(self, interface, ovr_data, double=False): intf.set(**intf.values) if interface not in self.obj.pin_interfaces: return - dt_names = self.obj.merge_dict_attrs(f"{interface}_data_types") + dt_names = self.obj.merge_dict_attrs(interface, "data_types") for key, val in ovr_data.items(): dt = dt_names.get(key, None) if dt is not None: From 5a26a29ad2b7e20fe58bc4c10ba6af52c0d08906 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 8 May 2024 13:12:06 -0500 Subject: [PATCH 052/121] devices: Re-add `test_read_update_write()` test --- .../devices/tests/test_device_read_update_write.py | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 hw_device_mgr/devices/tests/test_device_read_update_write.py diff --git a/hw_device_mgr/devices/tests/test_device_read_update_write.py b/hw_device_mgr/devices/tests/test_device_read_update_write.py new file mode 100644 index 00000000..dbb6021b --- /dev/null +++ b/hw_device_mgr/devices/tests/test_device_read_update_write.py @@ -0,0 +1,8 @@ +from .base_test_class import BaseDevicesTestClass +from ...ethercat.tests.test_device_read_update_write import ( + TestEtherCATDeviceRUW as _TestEtherCATDeviceRUW, +) + + +class TestDevicesRUW(BaseDevicesTestClass, _TestEtherCATDeviceRUW): + pass From 259abdf3352f8fa164b715e3151861c6f1cfbdd0 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 7 May 2024 17:29:26 -0500 Subject: [PATCH 053/121] devices: Ignore Inovance SV660 error code least significant word The SV660 32-bit error code is actually two separate words, set separately. The most significant word is the "manufacturer internal fault code", which contains more information; the least significant word is the "manufacturer external fault code", which contains less information. The two words are occasionally out of synch, producing codes like `0x07300941` that can't be directly looked up in YAML tables. Fix this by using only the "internal" portion of `error_code`. This affects the `feedback_out` interface `error_code` data type and string representation. --- .../devices/device_err/inovance_sv660n.yaml | 222 +++++++++--------- hw_device_mgr/devices/inovance_sv660.py | 14 ++ .../tests/test_device_read_update_write.py | 26 +- hw_device_mgr/devices/tests/test_devices.py | 7 + hw_device_mgr/errors/device.py | 9 +- .../tests/test_device_read_update_write.py | 4 +- 6 files changed, 165 insertions(+), 117 deletions(-) diff --git a/hw_device_mgr/devices/device_err/inovance_sv660n.yaml b/hw_device_mgr/devices/device_err/inovance_sv660n.yaml index 48009824..7384f3f3 100644 --- a/hw_device_mgr/devices/device_err/inovance_sv660n.yaml +++ b/hw_device_mgr/devices/device_err/inovance_sv660n.yaml @@ -2,14 +2,14 @@ # "Communication Faults and Warning Codes" # # Parameter 603Fh shows the basic error code, but the -# manufacturer-specific SV660N parameter 2008-2Eh "Inner error code" -# shows an extended error value. The manual's table 9.2 shows +# manufacturer-specific SV660N parameter 203Fh "Manufacturer fault +# code" shows an extended error value. The manual's table 10.2 shows # e.g. "fault" E101, with "display" broken down into E101.0 and E101.1 # with different "name" and occasional differences in "fault range" # column ("type" and "resettable or not" columns appear not to # change). # -# key: "Auxiliary Code" column +# key: "Auxiliary Code" column most significant word # display: "Display" column; code displayed on drive LED panel # description: "Name" column # type: "Type" column; indicates severity, with 1 most severe @@ -19,449 +19,449 @@ # # List of fault codes # -'0x01010101': +'0x0101': display: E101.0 description: System parameter error type: 1 resettable: false -'0x11010101': +'0x1101': display: E101.1 description: 2000h/2001h parameter error type: 1 resettable: false -'0x01020102': +'0x0102': display: E102.0 description: FPGA communication initialization error type: 1 resettable: false -'0x81020102': +'0x8102': display: E102.8 description: Software version mismatch type: 1 resettable: false -'0x11040104': +'0x1104': display: E104.1 description: MCU operation timeout type: 1 resettable: false -'0x21040104': +'0x2104': display: E104.2 description: Current loop operation timeout type: 1 resettable: false -'0x41040104': +'0x4104': display: E104.4 description: MCU reference update timeout type: 1 resettable: false -'0x01080108': +'0x0108': display: E108.0 description: Parameter write error type: 1 resettable: true -'0x11080108': +'0x1108': display: E108.1 description: Parameter read error type: 1 resettable: true -'0x21080108': +'0x2108': display: E108.2 description: Invalid check on data written in EEPROM type: 1 resettable: true -'0x31080108': +'0x3108': display: E108.3 description: Invalid check on data read in EEPROM type: 1 resettable: true -'0x01200120': +'0x0120': display: E120.0 description: Unknown encoder type type: 1 resettable: false -'0x11200120': +'0x1120': display: E120.1 description: Unknown motor model type: 1 resettable: false -'0x21200120': +'0x2120': display: E120.2 description: Unknown drive model type: 1 resettable: false -'0x51200120': +'0x5120': display: E120.5 description: Motor current and drive current mismatch type: 1 resettable: false -'0x61200120': +'0x6120': display: E120.6 description: FPGA and motor model mismatch type: 1 resettable: false -'0x01220122': +'0x0122': display: E122.0 description: Multi-turn absolute encoder setting error type: 2 resettable: true -'0x11220122': +'0x1122': display: E122.1 description: Different DIs allocated with the same function type: 2 resettable: true -'0x31220122': +'0x3122': display: E122.3 description: Upper limit invalid type: 2 resettable: true -'0x01360136': +'0x0136': display: E136.0 description: Encoder parameter error type: 1 resettable: false -'0x11360136': +'0x1136': display: E136.1 description: Encoder communication error type: 1 resettable: false -'0x01400140': +'0x0140': display: E140.0 description: Encryption chip check error type: 1 resettable: false -'0x11400140': +'0x1140': display: E140.1 description: Encryption chip check failure type: 1 resettable: false -'0x01500150': +'0x0150': display: E150.0 description: STO signal input protection activated type: 1 resettable: true -'0x11500150': +'0x1150': display: E150.1 description: STO signal input error type: 1 resettable: true -'0x21500150': +'0x2150': display: E150.2 description: Abnormal voltage detected type: 1 resettable: true -'0x31500150': +'0x3150': display: E150.3 description: STO upstream optocoupler detection failure type: 1 resettable: true -'0x41500150': +'0x4150': display: E150.4 description: PWM Buffer detection failure type: 1 resettable: true -'0x02010201': +'0x0201': display: E201.0 description: Phase-P overcurrent type: 1 resettable: false -'0x12010201': +'0x1201': display: E201.1 description: Phase-U overcurrent type: 1 resettable: false -'0x22010201': +'0x2201': display: E201.2 description: Phase-V overcurrent type: 1 resettable: false -'0x42010201': +'0x4201': display: E201.4 description: Phase-N overcurrent type: 1 resettable: false -'0x02080208': +'0x0208': display: E208.0 description: MCU position reference updated frequently type: 1 resettable: true -'0x22080208': +'0x2208': display: E208.2 description: Encoder communication timeout type: 1 resettable: true -'0x32080208': +'0x3208': display: E208.3 description: Current sampling fault type: 1 resettable: true -'0x42080208': +'0x4208': display: E208.4 description: FPGA current loop operation timeout type: 1 resettable: true -'0x02100210': +'0x0210': display: E210.0 description: Output shorted to ground type: 1 resettable: false -'0x02340234': +'0x0234': display: E234.0 description: Runaway protection type: 1 resettable: false -'0x04000400': +'0x0400': display: E400.0 description: Main circuit overvoltage type: 1 resettable: true -'0x04100410': +'0x0410': display: E410.0 description: Main circuit undervoltage type: 1 resettable: true -'0x04200420': +'0x0420': display: E420.0 description: Phase loss fault type: 2 resettable: true -'0x04300430': +'0x0430': display: E430.0 description: Control circuit undervoltage type: 2 resettable: true -'0x05000500': +'0x0500': display: E500.0 description: Motor overspeed type: 1 resettable: true -'0x15000500': +'0x1500': display: E500.1 description: Speed feedback overflow type: 1 resettable: true -'0x25000500': +'0x2500': display: E500.2 description: FPGA position feedback pulse overspeed type: 1 resettable: true -'0x06020602': +'0x0602': display: E602.0 description: Angle auto-tuning error type: 1 resettable: true -'0x26020602': +'0x2602': display: E602.2 description: Wrong UVW phase sequence detected during angle auto-tuning type: 1 resettable: true -'0x06050605': +'0x0605': display: E605.0 description: Speed upon S-ON too high type: 1 resettable: true -'0x06200620': +'0x0620': display: E620.0 description: Motor overload type: 1 resettable: true -'0x06300630': +'0x0630': display: E630.0 description: Motor stall type: 1 resettable: true -'0x06400640': +'0x0640': display: E640.0 description: IGBT over-temperature type: 1 resettable: true -'0x16400640': +'0x1640': display: E640.1 description: Flywheel diode over-temperature type: 1 resettable: true -'0x06500650': +'0x0650': display: E650.0 description: Heatsink over-temperature type: 1 resettable: true -'0x06600660': +'0x0660': display: E660.0 description: Air-cooled motor over-temperature type: 1 resettable: true -'0x06610661': +'0x0661': display: E661.0 description: Auto-tuned gain values too low type: 2 resettable: true -'0x07310731': +'0x0731': display: E731.0 description: Encoder battery failure type: 2 resettable: true -'0x07330733': +'0x0733': display: E733.0 description: Encoder multi-turn counting error type: 2 resettable: true -'0x07350735': +'0x0735': display: E735.0 description: Encoder multi-turn counting overflow type: 2 resettable: true -'0x27400740': +'0x2740': display: E740.2 description: Absolute encoder error type: 1 resettable: false -'0x37400740': +'0x3740': display: E740.3 description: Absolute encoder single-turn calculation error type: 1 resettable: false -'0x67400740': +'0x6740': display: E740.6 description: Encoder write error type: 1 resettable: false -'0x07550755': +'0x0755': display: E755.0 description: Nikon encoder communication failure type: 1 resettable: false -'0x07600760': +'0x0760': display: E760.0 description: Encoder over-temperature type: 2 resettable: true -'0x07650765': +'0x0765': display: E765.0 description: Nikon encoder beyond the limit type: 1 resettable: false -'0x0B000B00': +'0x0B00': display: EB00.0 description: Position deviation too large type: 2 resettable: true -'0x1B000B00': +'0x1B00': display: EB00.1 description: Position deviation overflow type: 2 resettable: true # (Note: out of numerical order in manual) -'0x0A330A33': +'0x0A33': display: EA33.0 description: Encoder read/write check error type: 1 resettable: false -'0x1B010B01': +'0x1B01': display: EB01.1 description: Position reference increment too large for once type: 2 resettable: true -'0x2B010B01': +'0x2B01': display: EB01.2 description: Position reference increment too large continuously type: 2 resettable: true -'0x3B010B01': +'0x3B01': display: EB01.3 description: Reference overflow type: 2 resettable: true -'0x4B010B01': +'0x4B01': display: EB01.4 description: Target position beyond upper/lower limit type: 2 resettable: true -'0x0E090E09': +'0x0E09': display: EE09.0 description: Software position limit setting error type: 2 resettable: true -'0x1E090E09': +'0x1E09': display: EE09.1 description: Home setting error type: 2 resettable: true -'0x2E090E09': +'0x2E09': display: EE09.2 description: Gear ratio beyond the limit type: 2 resettable: true -'0x3E090E09': +'0x3E09': display: EE09.3 description: No synchronization signal type: 2 resettable: true -'0x5E090E09': +'0x5E09': display: EE09.5 description: PDO mapping beyond the limit type: 2 resettable: true # (Note: EE08.0 out of order in manual) -'0x0E080E08': +'0x0E08': display: EE08.0 description: Synchronization loss type: 2 resettable: true -'0x1E080E08': +'0x1E08': display: EE08.1 description: Network status switchover error type: 2 resettable: true -'0x2E080E08': +'0x2E08': display: EE08.2 description: IRQ loss type: 2 resettable: true -'0x3E080E08': +'0x3E08': display: EE08.3 description: LAN cable connected improperly type: 2 resettable: true -'0x4E080E08': +'0x4E08': display: EE08.4 description: Data frame loss protection error type: 2 resettable: true -'0x5E080E08': +'0x5E08': display: EE08.5 description: Data frame transfer error type: 2 resettable: true -'0x6E080E08': +'0x6E08': display: EE08.6 description: Data update timeout type: 2 resettable: true -'0x0E110E11': +'0x0E11': display: EE11.0 description: ESI check error type: 2 resettable: true -'0x1E110E11': +'0x1E11': display: EE11.1 description: EEPROM read failure type: 2 resettable: true -'0x2E110E11': +'0x2E11': display: EE11.2 description: EEPROM update failure type: 2 resettable: true -'0x0E120E12': +'0x0E12': display: EE12.0 description: EtherCAT external device error type: 1 resettable: false -'0x0E130E13': +'0x0E13': display: EE13.0 description: Synchronization cycle setting error type: 2 resettable: true -'0x0E150E15': +'0x0E15': display: EE15.0 description: Number of synchronization cycle errors too large type: 2 @@ -469,97 +469,97 @@ # # List of warning codes # -'0x01210121': +'0x0121': display: E121.0 description: Invalid S-ON command type: 3 resettable: true -'0x06000600': +'0x0600': display: E600.0 description: Inertia auto-tuning failure type: 3 resettable: true -'0x06010601': +'0x0601': display: E601.0 description: Homing timeout type: 3 resettable: true -'0x16010601': +'0x1601': display: E601.1 description: Home switch error type: 3 resettable: true -'0x26010601': +'0x2601': display: E601.2 description: Homing mode setting error type: 3 resettable: true -'0x07300730': +'0x0730': display: E730.0 description: Encoder battery warning type: 3 resettable: true -'0x09000900': +'0x0900': display: E900.0 description: Emergency stop type: 3 resettable: true -'0x09020902': +'0x0902': display: E902.0 description: Invalid DI setting type: 3 resettable: true -'0x19020902': +'0x1902': display: E902.1 description: Invalid DO setting type: 3 resettable: true -'0x09080908': +'0x0908': display: E908.0 description: Model identification check byte invalid type: 3 resettable: true -'0x09090909': +'0x0909': display: E909.0 description: Motor overload warning type: 3 resettable: true -'0x09200920': +'0x0920': display: E920.0 description: Regenerative resistor overload type: 3 resettable: true -'0x09220922': +'0x0922': display: E922.0 description: Resistance of external regenerative resistor too small type: 3 resettable: true -'0x09240924': +'0x0924': display: E924.0 description: Braking transistor over-temperature type: 3 resettable: true -'0x09410941': +'0x0941': display: E941.0 description: Parameter modifications not activated type: 3 resettable: true -'0x09420942': +'0x0942': display: E942.0 description: Parameter saved frequently type: 3 resettable: true -'0x09500950': +'0x0950': display: E950.0 description: Forward overtravel warning type: 3 resettable: true -'0x09520952': +'0x0952': display: E952.0 description: Reverse overtravel warning type: 3 resettable: true -'0x0A410A41': +'0x0A41': display: EA41.0 description: Torque ripple compensation failure type: 3 diff --git a/hw_device_mgr/devices/inovance_sv660.py b/hw_device_mgr/devices/inovance_sv660.py index 96de82d0..643c2b79 100644 --- a/hw_device_mgr/devices/inovance_sv660.py +++ b/hw_device_mgr/devices/inovance_sv660.py @@ -2,6 +2,7 @@ from ..ethercat.config import EtherCATConfig from ..cia_402.device import CiA402Device, CiA402SimDevice from ..errors.device import ErrorDevice +from functools import lru_cache import time @@ -66,12 +67,25 @@ class InovanceSV660(EtherCATDevice, CiA402Device, ErrorDevice): feedback_out_data_types = dict( home_found="bit", + error_code="uint16", # Override uint32 ) + feedback_out_overlap = {"error_code"} # Override uint32 feedback_out_defaults = dict( home_found=False, ) + @classmethod + @lru_cache + def to_error_code_data_type(cls, value): + # Ignore least significant word, "manufacturer external fault code" + dt = cls.data_type_class.by_shared_name("uint16") + return dt(value >> 16) + + def get_error_code(self): + error_code = self.interface("feedback_in").get("error_code") + return self.to_error_code_data_type(error_code) + def get_feedback(self): fb_out = super().get_feedback() sw = self.interface("feedback_in").get("status_word") diff --git a/hw_device_mgr/devices/tests/test_device_read_update_write.py b/hw_device_mgr/devices/tests/test_device_read_update_write.py index dbb6021b..2ed61e94 100644 --- a/hw_device_mgr/devices/tests/test_device_read_update_write.py +++ b/hw_device_mgr/devices/tests/test_device_read_update_write.py @@ -2,7 +2,31 @@ from ...ethercat.tests.test_device_read_update_write import ( TestEtherCATDeviceRUW as _TestEtherCATDeviceRUW, ) +import re +from functools import lru_cache class TestDevicesRUW(BaseDevicesTestClass, _TestEtherCATDeviceRUW): - pass + + error_code_re = re.compile(r"0x([0-9A-F]{4})[0-9A-F]{4}") + expected_error_code_attrs = ( + 'fault_desc', 'description', 'goal_reason' + ) + + @classmethod + @lru_cache + def fix_expected_str(cls, expected): + return cls.error_code_re.sub(r"0x\1", expected) + + def check_interface_values(self, interface, indent=4, expected=None): + if self.obj.product_code == 0x000C010D and interface == "feedback_out": + # Hack test data expected error_code value for SV660N + expected = self.test_data[interface].copy() + assert "error_code" in expected + expected["error_code"] = expected["error_code"] >> 16 + for attr in self.expected_error_code_attrs: + if attr in expected: + expected[attr] = self.fix_expected_str(expected[attr]) + return super().check_interface_values( + interface, indent=indent, expected=expected + ) diff --git a/hw_device_mgr/devices/tests/test_devices.py b/hw_device_mgr/devices/tests/test_devices.py index c88a1f19..6efda5f8 100644 --- a/hw_device_mgr/devices/tests/test_devices.py +++ b/hw_device_mgr/devices/tests/test_devices.py @@ -10,3 +10,10 @@ class TestDevices(BaseDevicesTestClass, _TestEtherCATDevice): for c in _TestEtherCATDevice.expected_mro if c != "RelocatableESIDevice" ] + + def test_sv660_error_code_str(self, obj): + if obj.product_code != 0x000C010D: + return + print(obj.feedback_out.data_types) + assert obj.feedback_out_data_types["error_code"] == "uint16" + assert obj.feedback_out.get_data_type("error_code").shared_name == "uint16" diff --git a/hw_device_mgr/errors/device.py b/hw_device_mgr/errors/device.py index 9670c776..9c2da93b 100644 --- a/hw_device_mgr/errors/device.py +++ b/hw_device_mgr/errors/device.py @@ -51,13 +51,16 @@ def error_descriptions(cls): errs[int(err_code_str, 0)] = err_data return errs + def get_error_code(self): + return self.feedback_in.get("error_code") + def get_feedback(self): fb_out = super().get_feedback() - error_code = self.feedback_in.get("error_code") + error_code = self.get_error_code() if not error_code: - if self.feedback_in.changed("error_code"): + fb_out.update(**self.no_error) + if fb_out.changed("error_code"): self.logger.info(f"{str(self)}: error code cleared") - self.feedback_out.update(**self.no_error) return fb_out error_info = self.error_descriptions().get(error_code, None) diff --git a/hw_device_mgr/tests/test_device_read_update_write.py b/hw_device_mgr/tests/test_device_read_update_write.py index 9039fd43..5bc0b86d 100644 --- a/hw_device_mgr/tests/test_device_read_update_write.py +++ b/hw_device_mgr/tests/test_device_read_update_write.py @@ -175,9 +175,9 @@ def print_dict(self, d, name, indent=0, prefix=""): d = "null" print(f"{' ' * indent}{prefix}{name}: {d}") - def check_interface_values(self, interface, indent=4): + def check_interface_values(self, interface, indent=4, expected=None): # Prepare expected data - expected = self.test_data[interface] + expected = expected or self.test_data[interface] # self.print_dict(expected, f"Expected {interface}", indent=2) # Prepare actual data From 156ba5ade7d37e3b588269d6a59e630cbe2d023c Mon Sep 17 00:00:00 2001 From: Daniel Solis Date: Wed, 11 Sep 2024 09:37:40 -0600 Subject: [PATCH 054/121] Add SV670N ESI file --- .../SV670_EOE_1Axis_05003_220801.xml | 17157 ++++++++++++++++ 1 file changed, 17157 insertions(+) create mode 100644 hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml diff --git a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml new file mode 100644 index 00000000..efd0483a --- /dev/null +++ b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml @@ -0,0 +1,17157 @@ + + + + + #x00100000 + Inovance + 汇川技术 + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + + InoServo + Servo Drives + 伺服驱动器 + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + + InoSV670N + SV670_1Axis_05003 + ServoDrive + http://www.inovance.cn + + + + 3000 + 9000 + 5000 + 200 + + + + + 100 + 2000 + + + + InoServo + + + 402 + + + + + + BIT2 + 2 + + + + BOOL + 1 + + + + DINT + 32 + + + + INT + 16 + + + + UDINT + 32 + + + + UINT + 16 + + + + USINT + 8 + + + + SINT + 8 + + + + STRING(10) + 80 + + + + STRING(4) + 32 + + + DT1018 + 144 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Vendor ID + UDINT + 32 + 16 + + ro + + + + 2 + Product Code + UDINT + 32 + 48 + + ro + + + + 3 + Revision + UDINT + 32 + 80 + + ro + + + + 4 + Serial number + UDINT + 32 + 112 + + ro + + + + + DT1600 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + + DT1601 + 368 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + + DT1701 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1702 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1703 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1704 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1705 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1A00 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + + DT1A01 + 368 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + + DT1B01 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B02 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B03 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B04 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1C00ARR + USINT + 32 + + 1 + 4 + + + + DT1C00 + 48 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + o + + + + Elements + DT1C00ARR + 32 + 16 + + ro + o + + + + + + DT1C32 + 488 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + m + + + + 1 + Sync mode + UINT + 16 + 16 + + rw + + + + 2 + Cycle time + UDINT + 32 + 32 + + ro + o + + + + 4 + Sync modes supported + UINT + 16 + 96 + + ro + o + + + + 5 + Minimum cycle time + UDINT + 32 + 112 + + ro + o + + + + 6 + Calc and copy time + UDINT + 32 + 144 + + ro + o + + + + 8 + Get Cycle Time + UINT + 16 + 208 + + rw + c + + + + 9 + Delay Time + UDINT + 32 + 224 + + ro + c + + + + 10 + Sync0 Cycle Time + UDINT + 32 + 256 + + rw + o + + + + 11 + SM-Event Missed + UINT + 16 + 288 + + ro + c + + + + 12 + Cycle Time Too Small + UINT + 16 + 304 + + ro + c + + + + 32 + Sync Error + BOOL + 1 + 480 + + ro + c + + + + + + DT1C33 + 488 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + o + + + + 1 + Sync mode + UINT + 16 + 16 + + rw + + + + 2 + Cycle time + UDINT + 32 + 32 + + ro + o + + + + 4 + Sync modes supported + UINT + 16 + 96 + + ro + o + + + + 5 + Minimum cycle time + UDINT + 32 + 112 + + ro + o + + + + 6 + Calc and copy time + UDINT + 32 + 144 + + ro + o + + + + 8 + Get Cycle Time + UINT + 16 + 208 + + rw + c + + + + 9 + Delay Time + UDINT + 32 + 224 + + ro + c + + + + 10 + Sync0 Cycle Time + UDINT + 32 + 256 + + rw + o + + + + 11 + SM-Event Missed + UINT + 16 + 288 + + ro + c + + + + 12 + Cycle Time Too Small + UINT + 16 + 304 + + ro + c + + + + 32 + Sync Error + BOOL + 1 + 480 + + ro + c + + + + + DT1C12ARR + UINT + 16 + + 1 + 1 + + + + DT1C12 + 32 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + Elements + DT1C12ARR + 16 + 16 + + rw + o + + + + + DT1C13ARR + UINT + 16 + + 1 + 1 + + + + DT1C13 + 32 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + Elements + DT1C13ARR + 16 + 16 + + rw + o + + + + + + DT2000 + 128 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Motor SN + UINT + 16 + 16 + + rw + + + + 3 + Customized firmware version + UDINT + 32 + 48 + + ro + + + + 5 + Encoder Version + UINT + 16 + 96 + + ro + + + + 6 + Serial encoder motor SN + UINT + 16 + 112 + + ro + + + + + + DT2001 + 672 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + MCU firmware Version + UINT + 16 + 16 + + ro + + + + 2 + Fpga firmware Version + UINT + 16 + 32 + + ro + + + + 11 + Drive serial number + UINT + 16 + 176 + + rw + + + + 12 + Drive voltage class + UINT + 16 + 192 + + ro + + + + 13 + Drive rated power + UDINT + 32 + 208 + + ro + + + + 15 + Drive maximum output power + UDINT + 32 + 240 + + ro + + + + 17 + Drive rated output current + UDINT + 32 + 272 + + ro + + + + 19 + Drive maximum output current + UDINT + 32 + 304 + + ro + + + + 41 + DC bus overvoltage protective point + UINT + 16 + 656 + + rw + + + + + + DT2002 + 688 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Control mode selection + UINT + 16 + 16 + + rw + + + + 2 + Absolute system selection + UINT + 16 + 32 + + rw + + + + 3 + Rotating direction + UINT + 16 + 48 + + rw + + + + 4 + Output pulse phase + UINT + 16 + 64 + + rw + + + + 6 + Disable operation option Code + INT + 16 + 96 + + rw + + + + 7 + NO2 Fault Reaction option Code + INT + 16 + 112 + + rw + + + + 8 + Stop mode at limit switch signal + UINT + 16 + 128 + + rw + + + + 9 + Stop mode at NO.1 fault + UINT + 16 + 144 + + rw + + + + 10 + Delay from brake output on to command received + UINT + 16 + 160 + + rw + + + + 11 + Delay from brake output off to motor de-energized + UINT + 16 + 176 + + rw + + + + 12 + Motor speed threshold at brake output off in rotating state + UINT + 16 + 192 + + rw + + + + 13 + Delay from servo off to brake output off in the rotating state + UINT + 16 + 208 + + rw + + + + 16 + LED warning display selection + UINT + 16 + 256 + + rw + + + + 18 + MainPower Cutoff Reaction Option Code + UINT + 16 + 288 + + rw + + + + 19 + QuickStop Reaction Option Code + UINT + 16 + 304 + + rw + + + + 22 + Allowed minimum braking resistance + UINT + 16 + 352 + + ro + + + + 23 + Power of built-in braking resistor + UINT + 16 + 368 + + ro + + + + 24 + Resistance of built-in braking resistor + UINT + 16 + 384 + + ro + + + + 25 + Resistor heat dissipation coefficient + UINT + 16 + 400 + + rw + + + + 26 + braking resistor type + UINT + 16 + 416 + + rw + + + + 27 + Power of external dynamic resistor + UINT + 16 + 432 + + rw + + + + 28 + Resistance of external braking resistor + UINT + 16 + 448 + + rw + + + + 31 + User password + UINT + 16 + 496 + + wo + + + + 32 + Parameter initialization + UINT + 16 + 512 + + rw + + + + 33 + Default keypad display + UINT + 16 + 528 + + rw + + + + 36 + Panel data refresh rate + UINT + 16 + 576 + + rw + + + + 42 + OEM password + UINT + 16 + 672 + + wo + + + + + DT2003 + 1056 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 3 + DI1 function selection + UINT + 16 + 48 + + rw + + + + 4 + DI1 logic selection + UINT + 16 + 64 + + rw + + + + 5 + DI2 function selection + UINT + 16 + 80 + + rw + + + + 6 + DI2 logic selection + UINT + 16 + 96 + + rw + + + + 7 + DI3 function selection + UINT + 16 + 112 + + rw + + + + 8 + DI3 logic selection + UINT + 16 + 128 + + rw + + + + 9 + DI4 function selection + UINT + 16 + 144 + + rw + + + + 10 + DI4 logic selection + UINT + 16 + 160 + + rw + + + + 11 + DI5 function selection + UINT + 16 + 176 + + rw + + + + 12 + DI5 logic selection + UINT + 16 + 192 + + rw + + + + 51 + AI1 Offset + INT + 16 + 816 + + rw + + + + 52 + AI1 Filter + UINT + 16 + 832 + + rw + + + + 54 + AI1 Dead Zone + UINT + 16 + 864 + + rw + + + + 55 + AI1 Zero Drifting + INT + 16 + 880 + + rw + + + + 61 + DI1 filtertime constant + UINT + 16 + 976 + + rw + + + + 62 + DI2 filtertime constant + UINT + 16 + 992 + + rw + + + + 63 + DI3 filtertime constant + UINT + 16 + 1008 + + rw + + + + 64 + DI4 filtertime constant + UINT + 16 + 1024 + + rw + + + + 65 + DI5 filtertime constant + UINT + 16 + 1040 + + rw + + + + + DT2004 + 864 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + DO1 Function Selection + UINT + 16 + 16 + + rw + + + + 2 + DO1 Logic Level Selection + UINT + 16 + 32 + + rw + + + + 3 + DO2 function selection + UINT + 16 + 48 + + rw + + + + 4 + DO2 Logic Level Selection + UINT + 16 + 64 + + rw + + + + 23 + DO OutPut Source Select + UINT + 16 + 368 + + rw + + + + 24 + ECAT Lost Force DO OutPut Logic + UINT + 16 + 384 + + rw + + + + 51 + AO1 Source Select + UINT + 16 + 816 + + rw + + + + 52 + AO1 Offset + INT + 16 + 832 + + rw + + + + 53 + AO1 Multiplying + INT + 16 + 848 + + rw + + + + + DT2005 + 1152 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 5 + Time constant of first-order low-pass filter + UINT + 16 + 80 + + rw + + + + 7 + Time constant of moving average filter 1 + UINT + 16 + 112 + + rw + + + + 18 + Encoder frequency division pulses + UDINT + 32 + 288 + + rw + + + + 20 + Speed feedforward control selection + UINT + 16 + 320 + + rw + + + + 31 + Local home mode + UINT + 16 + 496 + + rw + + + + 36 + Time of home searching + UINT + 16 + 576 + + rw + + + + 37 + Local home position offset + DINT + 32 + 592 + + rw + + + + 39 + Servo pulse output source + UINT + 16 + 624 + + rw + + + + 42 + Output polarity of Z pulse + UINT + 16 + 672 + + rw + + + + 51 + Mechanical Gear ratio numerator of absolute encode mode 2 + UINT + 16 + 816 + + rw + + + + 52 + Mechanical Gear ratio denominator of absolute encode mode 2 + UINT + 16 + 832 + + rw + + + + 53 + Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) + UDINT + 32 + 848 + + rw + + + + 55 + Max value of mechanical absolute position(inc) of absolute encode mode 2(High) + UDINT + 32 + 880 + + rw + + + + 59 + Trq Reference of Mechanical Homing + UINT + 16 + 944 + + rw + + + + 61 + Position Coin Hold Time + UINT + 16 + 976 + + rw + + + + 67 + Time Unit of Homing + UINT + 16 + 1072 + + rw + + + + 71 + Time constant of moving average filter 2 + UINT + 16 + 1136 + + rw + + + + + DT2006 + 896 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 4 + Keypad setting value of speed reference + INT + 16 + 64 + + rw + + + + 5 + DI Jog speed reference + UINT + 16 + 80 + + rw + + + + 6 + Acceleration ramp time constant of speed reference + UINT + 16 + 96 + + rw + + + + 7 + Deceleration ramp time constant of speed reference + UINT + 16 + 112 + + rw + + + + 11 + Quick decelaration coefficient + UINT + 16 + 176 + + rw + + + + 12 + Torque feedforward selection + UINT + 16 + 192 + + rw + + + + 13 + Acceleration/Deceleration ramp time constant of jog speed reference + UINT + 16 + 208 + + rw + + + + 14 + Speed feedforward filter time constant + UINT + 16 + 224 + + rw + + + + 16 + Speed threshold of Zero Hold signal + UINT + 16 + 256 + + rw + + + + 17 + Speed threshold of motor rotation signal + UINT + 16 + 272 + + rw + + + + 18 + Speed threshold of Spd Reach signal + UINT + 16 + 288 + + rw + + + + 19 + Speed threshold of Spd Arrive signal + UINT + 16 + 304 + + rw + + + + 20 + Speed threshold of Zero Spd signal + UINT + 16 + 320 + + rw + + + + 51 + Spd SCurve Enable + UINT + 16 + 816 + + rw + + + + 52 + Spd SCurve Acceleration UP + UINT + 16 + 832 + + rw + + + + 53 + Spd SCurve Acceleration Down + UINT + 16 + 848 + + rw + + + + 54 + Spd SCurve Deceleration UP + UINT + 16 + 864 + + rw + + + + 55 + Spd SCurve Deceleration Down + UINT + 16 + 880 + + rw + + + + + DT2007 + 640 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 4 + Keypad setting value of torque reference + INT + 16 + 64 + + rw + + + + 6 + Torque reference filter time 1 + UINT + 16 + 96 + + rw + + + + 7 + Torque reference filter time 2 + UINT + 16 + 112 + + rw + + + + 16 + Emergency stop torque + UINT + 16 + 256 + + rw + + + + 22 + Base value for torque reached + UINT + 16 + 352 + + rw + + + + 23 + Threshold of torque reached valid + UINT + 16 + 368 + + rw + + + + 24 + Threshold of torque reached invalid + UINT + 16 + 384 + + rw + + + + 25 + Depth of field-weakening + UINT + 16 + 400 + + rw + + + + 26 + Maximum field-weakening current + UINT + 16 + 416 + + rw + + + + 27 + Field-weakening enable + UINT + 16 + 432 + + rw + + + + 28 + Field-weakening gain + UINT + 16 + 448 + + rw + + + + 29 + Field-weakening point speed + UINT + 16 + 464 + + ro + + + + 36 + Motor output calibration enable + UINT + 16 + 576 + + rw + + + + 37 + The second-stage torque reference filter time + UINT + 16 + 592 + + rw + + + + 38 + Torque reference filter type select + UINT + 16 + 608 + + rw + + + + 39 + Biquad low pass filter damping + UINT + 16 + 624 + + rw + + + + + DT2008 + 1056 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Speed-loop Gain + UINT + 16 + 16 + + rw + + + + 2 + Speed-loop integral time constant + UINT + 16 + 32 + + rw + + + + 3 + Position-loop Gain + UINT + 16 + 48 + + rw + + + + 4 + The second speed loop gain + UINT + 16 + 64 + + rw + + + + 5 + The second speed loop integral time constant + UINT + 16 + 80 + + rw + + + + 6 + The second position loop gain + UINT + 16 + 96 + + rw + + + + 9 + Second gain mode setting + UINT + 16 + 144 + + rw + + + + 10 + Gain switchover condition + UINT + 16 + 160 + + rw + + + + 11 + Gain switchover delay + UINT + 16 + 176 + + rw + + + + 12 + Gain switchover level + UINT + 16 + 192 + + rw + + + + 13 + Gain switchover hysteresis + UINT + 16 + 208 + + rw + + + + 14 + Position gain switchover time + UINT + 16 + 224 + + rw + + + + 16 + Average value of load inertia ratio + UINT + 16 + 256 + + rw + + + + 18 + Zero-Phase delay time + UINT + 16 + 288 + + rw + + + + 19 + Speed feedforward filter time constant + UINT + 16 + 304 + + rw + + + + 20 + Speed feedforward gain + UINT + 16 + 320 + + rw + + + + 21 + Torque feedforward filter time constant + UINT + 16 + 336 + + rw + + + + 22 + Torque feedforward gain + UINT + 16 + 352 + + rw + + + + 23 + Speed feedback filter + UINT + 16 + 368 + + rw + + + + 24 + Cut-off frequency of speed feedback low-pass filter + UINT + 16 + 384 + + rw + + + + 25 + Pseudo-differential forward feedback control coefficient + UINT + 16 + 400 + + rw + + + + 28 + Cut-off frequency of speed observer + UINT + 16 + 448 + + rw + + + + 29 + Modified inertia coefficient of speed observer + UINT + 16 + 464 + + rw + + + + 30 + Filter time of speed observer + UINT + 16 + 480 + + rw + + + + 32 + Cut-off frequency of torque disturbance observer + UINT + 16 + 512 + + rw + + + + 33 + Compensation gain of torque disturbance observer + UINT + 16 + 528 + + rw + + + + 34 + Modified inertia coefficient of torque disturbance observer + UINT + 16 + 544 + + rw + + + + 41 + Speed observer enable + UINT + 16 + 656 + + rw + + + + 43 + Module control enable + UINT + 16 + 688 + + rw + + + + 44 + Module control gain + UINT + 16 + 704 + + rw + + + + 47 + Module feedforward value + UINT + 16 + 752 + + rw + + + + 54 + 3rd medium and low-frequency vibration suppression frequency + UINT + 16 + 864 + + rw + + + + 55 + 3rd compensation gain of medium and low-frequency vibration suppression frequency + UINT + 16 + 880 + + rw + + + + 57 + 3rd phase modulation of medium and low-frequency vibration suppression frequency + UINT + 16 + 912 + + rw + + + + 60 + 4th medium and low-frequency vibration suppression frequency + UINT + 16 + 960 + + rw + + + + 61 + 4th compensation gain of medium and low-frequency vibration suppression frequency + UINT + 16 + 976 + + rw + + + + 62 + 4th phase modulation of medium and low-frequency vibration suppression frequency + UINT + 16 + 992 + + rw + + + + 63 + Time constant of position loop integration + UINT + 16 + 1008 + + rw + + + + 64 + 2nd time constant of position loop integration + UINT + 16 + 1024 + + rw + + + + 65 + Speed observation feedback source selection + UINT + 16 + 1040 + + rw + + + + + DT2009 + 848 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Auto-adjusting mode + UINT + 16 + 16 + + rw + + + + 2 + Rigidity level selection + UINT + 16 + 32 + + rw + + + + 3 + Working mode of self-adaptive notch + UINT + 16 + 48 + + rw + + + + 4 + Online inertia auto-tuning mode + UINT + 16 + 64 + + rw + + + + 6 + Offline inertia auto-tuning mode + UINT + 16 + 96 + + rw + + + + 7 + Maximum speed for inertia autotuning + UINT + 16 + 112 + + rw + + + + 8 + Acceleration/Deceleration time for inertia autotuning + UINT + 16 + 128 + + rw + + + + 9 + Interval after an inertia autotuning + UINT + 16 + 144 + + rw + + + + 10 + Motor revolutions for an inertia auto-tuning + UINT + 16 + 160 + + rw + + + + 12 + Vibration threshold setting + UINT + 16 + 192 + + rw + + + + 13 + 1st notch frequency + UINT + 16 + 208 + + rw + + + + 14 + 1st notch width level + UINT + 16 + 224 + + rw + + + + 15 + 1st notch attenuation level + UINT + 16 + 240 + + rw + + + + 16 + 2nd notch frequency + UINT + 16 + 256 + + rw + + + + 17 + 2nd notch width level + UINT + 16 + 272 + + rw + + + + 18 + 2nd notch attenuation level + UINT + 16 + 288 + + rw + + + + 19 + 3rd notch frequency + UINT + 16 + 304 + + rw + + + + 20 + 3rd notch width level + UINT + 16 + 320 + + rw + + + + 21 + 3rd notch attenuation level + UINT + 16 + 336 + + rw + + + + 22 + 4th notch frequency + UINT + 16 + 352 + + rw + + + + 23 + 4th notch width level + UINT + 16 + 368 + + rw + + + + 24 + 4th notch attenuation level + UINT + 16 + 384 + + rw + + + + 25 + Obtained resonance frequency + UINT + 16 + 400 + + ro + + + + 26 + 1st anti-resonance point frequency + UINT + 16 + 416 + + rw + + + + 27 + 2nd anti-resonance point frequency + UINT + 16 + 432 + + rw + + + + 33 + Gravity compensation value + INT + 16 + 528 + + rw + + + + 34 + Forward friction compensation + INT + 16 + 544 + + rw + + + + 35 + Reverse friction compensation + INT + 16 + 560 + + rw + + + + 36 + Friction compensation speed + UINT + 16 + 576 + + rw + + + + 37 + Friction compensation speed selection + UINT + 16 + 592 + + rw + + + + 38 + Vibration monitor time + UINT + 16 + 608 + + rw + + + + 39 + 1st terminal low-frequency vibration suppression frequency + UINT + 16 + 624 + + rw + + + + 40 + 1st filter order of low-frequency vibration suppression frequency + UINT + 16 + 640 + + rw + + + + 42 + 5th notch frequency + UINT + 16 + 672 + + rw + + + + 43 + 5th notch width level + UINT + 16 + 688 + + rw + + + + 44 + 5th notch attenuation level + UINT + 16 + 704 + + rw + + + + 45 + 2nd terminal low-frequency vibration suppression frequency + UINT + 16 + 720 + + rw + + + + 46 + 2nd damping frequency ratio of low-frequency vibration suppression frequency + UINT + 16 + 736 + + rw + + + + 48 + 2nd damping coefficient of low-frequency vibration suppression frequency + UINT + 16 + 768 + + rw + + + + 50 + 3rd terminal low-frequency vibration suppression frequency + UINT + 16 + 800 + + rw + + + + 51 + 3rd damping frequency ratio of low-frequency vibration suppression frequency + UINT + 16 + 816 + + rw + + + + 53 + 3rd damping coefficient of low-frequency vibration suppression frequency + UINT + 16 + 832 + + rw + + + + + DT200A + 1536 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Power inputphase loss protection disable + UINT + 16 + 16 + + rw + + + + 2 + Absolute position limit set + UINT + 16 + 32 + + rw + + + + 5 + Motor overload protection gain + UINT + 16 + 80 + + rw + + + + 9 + Overspeed threshold + UINT + 16 + 144 + + rw + + + + 11 + Local following error window + UDINT + 32 + 176 + + rw + + + + 13 + Runaway protection enable + UINT + 16 + 208 + + rw + + + + 19 + Over Temperature value of IPM + UINT + 16 + 304 + + rw + + + + 20 + Touch Probe 1 filter time constant + UINT + 16 + 320 + + rw + + + + 21 + Touch Probe 2 filter time constant + UINT + 16 + 336 + + rw + + + + 24 + Filter time constant of TZ signal + UINT + 16 + 384 + + rw + + + + 27 + Motor overload shielding + UINT + 16 + 432 + + rw + + + + 28 + Speed DO Filter time constant + UINT + 16 + 448 + + rw + + + + 30 + Full Closed-loop(ABZ) Filter time constant + UINT + 16 + 480 + + rw + + + + 33 + Overheat protection time duration for locked rotor + UINT + 16 + 528 + + rw + + + + 34 + Overheat protection for locked rotor enable + UINT + 16 + 544 + + rw + + + + 37 + Absolute Encode multi-turns error forbidden + UINT + 16 + 592 + + rw + + + + 41 + Compensation Function + UINT + 16 + 656 + + rw + + + + 50 + Over Temperature value of discharge tube + UINT + 16 + 800 + + rw + + + + 51 + Encoder communiction error threshold + UINT + 16 + 816 + + rw + + + + 52 + Phase lack threshold + UINT + 16 + 832 + + rw + + + + 53 + Over Temperature value of Encoder + UINT + 16 + 848 + + rw + + + + 54 + TouchProbe DI Turn-on Compensation Time + INT + 16 + 864 + + rw + + + + 55 + TouchProbe DI Turn-off Compensation Time + INT + 16 + 880 + + rw + + + + 56 + Runaway current threshold + UINT + 16 + 896 + + rw + + + + 57 + Fault reset delay time + UINT + 16 + 912 + + rw + + + + 58 + Runaway speed threshold + UINT + 16 + 928 + + rw + + + + 59 + Runaway speed filter time constant + UINT + 16 + 944 + + rw + + + + 60 + Runaway protection time window + UINT + 16 + 960 + + rw + + + + 61 + BlackBox Mode Select + UINT + 16 + 976 + + rw + + + + 62 + BlackBox Selected Error Code + UINT + 16 + 992 + + rw + + + + 63 + BlackBox Trig Source + UINT + 16 + 1008 + + rw + + + + 64 + BlackBox Trig Level + DINT + 32 + 1024 + + rw + + + + 66 + BlackBox Trig Level Select + UINT + 16 + 1056 + + rw + + + + 67 + BlackBox Trig Position + UINT + 16 + 1072 + + rw + + + + 68 + BlackBox Trig Frequency Select + UINT + 16 + 1088 + + rw + + + + 71 + The 2nd over speed threshold + UINT + 16 + 1136 + + rw + + + + 72 + Motor over load monitor switch + UINT + 16 + 1152 + + rw + + + + 73 + Maximum ramp stop time + UINT + 16 + 1168 + + rw + + + + 74 + STO Disconnect filter time + UINT + 16 + 1184 + + rw + + + + 75 + STO Mismatch filter time + UINT + 16 + 1200 + + rw + + + + 76 + STO Servo off filter time + UINT + 16 + 1216 + + rw + + + + 86 + Motor Offline Trq Limit + UINT + 16 + 1376 + + rw + + + + 87 + Motor Offline Filter Time + UINT + 16 + 1392 + + rw + + + + 91 + Filter Time Constant of Spd Display + UINT + 16 + 1456 + + rw + + + + 92 + Filter Time Constant of Trq Display + INT + 16 + 1472 + + rw + + + + 93 + Filter Time Constant of Position Display + UINT + 16 + 1488 + + rw + + + + 94 + Filter Time Constant of Voltage Display + UINT + 16 + 1504 + + rw + + + + 95 + Filter Time Constant of Temp Display + UINT + 16 + 1520 + + rw + + + + + DT200B + 1584 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Actual motor rotational speed + INT + 16 + 16 + + ro + T + + + + 2 + Speed reference + INT + 16 + 32 + + ro + T + + + + 3 + Internal torque reference + INT + 16 + 48 + + ro + T + + + + 4 + Monitored DI states + UINT + 16 + 64 + + ro + T + + + + 6 + Monitored DO states + UINT + 16 + 96 + + ro + T + + + + 8 + Absolute position counter + DINT + 32 + 128 + + ro + T + + + + 10 + Mechanical angle + UINT + 16 + 160 + + ro + T + + + + 11 + Electrical angle + UINT + 16 + 176 + + ro + T + + + + 13 + Average load rate + UINT + 16 + 208 + + ro + T + + + + 16 + Encoder position deviation counter + DINT + 32 + 256 + + ro + T + + + + 18 + Feedback pulse counter + DINT + 32 + 288 + + ro + T + + + + 20 + Total power-on time + UDINT + 32 + 320 + + ro + T + + + + 22 + AI1 Voltage DisPlay + INT + 16 + 352 + + ro + T + + + + 25 + Phase current valid value + UINT + 16 + 400 + + ro + T + + + + 27 + Bus voltage + UINT + 16 + 432 + + ro + T + + + + 28 + Module temperature + UINT + 16 + 448 + + ro + T + + + + 29 + Absolute encoder fault info. from FPGA + UINT + 16 + 464 + + ro + + + + 30 + Axis state from FPGA + UINT + 16 + 480 + + ro + + + + 31 + Axis fault info. from FPGA + UINT + 16 + 496 + + ro + + + + 32 + Encoder internal fault info. + UINT + 16 + 512 + + rw + + + + 34 + Displayed fault record + UINT + 16 + 544 + + rw + + + + 35 + Fault code + UINT + 16 + 560 + + ro + + + + 36 + Time stamp upon displayed fault + UDINT + 32 + 576 + + ro + + + + 38 + Current rotational speed upon displayed fault + INT + 16 + 608 + + ro + + + + 39 + Current U upon displayed fault + INT + 16 + 624 + + ro + + + + 40 + Current V upon displayed fault + INT + 16 + 640 + + ro + + + + 41 + Bus voltage upon displayed fault + UINT + 16 + 656 + + ro + + + + 42 + Input terminal state upon displayed fault + UINT + 16 + 672 + + ro + + + + 44 + Output terminal state upon displayed fault + UINT + 16 + 704 + + ro + + + + 46 + Inner error code + UINT + 16 + 736 + + ro + + + + 47 + Fault message of absolute encode from Fpga upon displayed + UINT + 16 + 752 + + ro + + + + 48 + System state from Fpga upon displayed fault + UINT + 16 + 768 + + ro + + + + 49 + System fault message from Fpga upon displayed fault + UINT + 16 + 784 + + ro + + + + 50 + Encode state 1 upon displayed fault + UINT + 16 + 800 + + ro + + + + 52 + Inner error code upon displayed fault + UINT + 16 + 832 + + ro + + + + 53 + Fpga overtime state upon displayed fault + UINT + 16 + 848 + + ro + + + + 54 + Reference position deviation + DINT + 32 + 864 + + ro + T + + + + 56 + Actual motor rotational speed(0.1rpm) + DINT + 32 + 896 + + ro + T + + + + 58 + Control bus voltage + UINT + 16 + 928 + + ro + T + + + + 59 + Mechanical absolute position inc(Low) + UDINT + 32 + 944 + + ro + T + + + + 61 + Mechanical absolute position inc(High) + DINT + 32 + 976 + + ro + T + + + + 64 + Not ready reason + UINT + 16 + 1024 + + ro + + + + 67 + Encoder temperature + UINT + 16 + 1072 + + ro + + + + 68 + Discharge load rate + UINT + 16 + 1088 + + ro + T + + + + 69 + Fpga over time state + UINT + 16 + 1104 + + ro + + + + 71 + Number of turns of absolute encode + UINT + 16 + 1136 + + ro + T + + + + 72 + Single feedback postion of absolute encode + UDINT + 32 + 1152 + + ro + T + + + + 75 + System Error + UINT + 16 + 1200 + + ro + + + + 78 + feedback postion of absolute encode(Low) + UDINT + 32 + 1248 + + ro + T + + + + 80 + feedback postion of absolute encode(High) + DINT + 32 + 1280 + + ro + T + + + + 82 + feedback postion inc of rotating load(Low) + UDINT + 32 + 1312 + + ro + T + + + + 84 + feedback postion inc of rotating load(High) + UDINT + 32 + 1344 + + ro + T + + + + 86 + Single feedback postion of rotating load + UDINT + 32 + 1376 + + ro + T + + + + 88 + IGBT Temperature + UINT + 16 + 1408 + + ro + + + + 91 + Group of unusual function code + UINT + 16 + 1456 + + ro + + + + 92 + Offset of unusual function code + UINT + 16 + 1472 + + ro + + + + 95 + Single Power-On Time + UDINT + 32 + 1520 + + ro + T + + + + 97 + Single Power-On Time upon displayed fault + UDINT + 32 + 1552 + + ro + + + + + DT200D + 400 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Software reset + UINT + 16 + 16 + + rw + + + + 2 + Fault reset + UINT + 16 + 32 + + rw + + + + 5 + Encoder ROM reading/writing + UINT + 16 + 80 + + rw + + + + 6 + Emergency stop + UINT + 16 + 96 + + rw + + + + 11 + AI1 Self-Adjust of Voltage Offset + UINT + 16 + 176 + + rw + + + + 13 + UV phase current auto-tuning + UINT + 16 + 208 + + rw + + + + 18 + Forced DI/DO setting + UINT + 16 + 288 + + rw + + + + 19 + Forced DI level + UINT + 16 + 304 + + rw + + + + 20 + Forced DO setting + UINT + 16 + 320 + + rw + + + + 21 + Absolute Encode Fault Reset + UINT + 16 + 336 + + rw + + + + 24 + Cogging torque self-learning + UINT + 16 + 384 + + rw + + + + + DT200E + 1568 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Node address + UINT + 16 + 16 + + rw + + + + 2 + Update function code values written via communication to EEPROM + UINT + 16 + 32 + + rw + + + + 21 + station auto inc address + UINT + 16 + 336 + + ro + + + + 22 + station alias + UINT + 16 + 352 + + rw + + + + 23 + Sync lost window + UINT + 16 + 368 + + rw + + + + 25 + Sync lost counter + UINT + 16 + 400 + + ro + + + + 26 + Port 0 invalid frame counter + UINT + 16 + 416 + + ro + + + + 27 + Port 1 invalid frame counter + UINT + 16 + 432 + + ro + + + + 28 + Port 0/1 transfer error counter + UINT + 16 + 448 + + ro + + + + 29 + process unit and PDI error counter + UINT + 16 + 464 + + ro + + + + 30 + Port 0/1 lost counter + UINT + 16 + 480 + + ro + + + + 32 + Sync mode set + UINT + 16 + 512 + + rw + + + + 33 + Sync error window + UINT + 16 + 528 + + rw + + + + 34 + EtherCAT network state and link state + UINT + 16 + 544 + + ro + + + + 35 + CSP postion increment over counter + UINT + 16 + 560 + + rw + + + + 36 + ECAT AL Error Code + UINT + 16 + 576 + + ro + + + + 37 + Enhanced link detection enable + UINT + 16 + 592 + + rw + + + + 38 + Reset EtherCAT xml file + UINT + 16 + 608 + + rw + + + + 74 + EtherCAT port control mode and state display + UINT + 16 + 1184 + + ro + + + + 94 + EtherCAT COE version number + UINT + 16 + 1504 + + ro + + + + 97 + EtherCAT xml file version number + UINT + 16 + 1552 + + ro + + + + + DT200F + 720 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Encoder feedback mode + UINT + 16 + 16 + + rw + + + + 2 + Running mode of external encoder + UINT + 16 + 32 + + rw + + + + 3 + SecEncoder Absolute system selection + UINT + 16 + 48 + + rw + + + + 4 + SecEncoder Type selection + UINT + 16 + 64 + + rw + + + + 5 + External encoder pulses per motor revolution + UDINT + 32 + 80 + + rw + + + + 9 + Hybrid deviation excess setting + UDINT + 32 + 144 + + rw + + + + 11 + Hybrid deviation clear setting + UINT + 16 + 176 + + rw + + + + 14 + First-order lowpass filter time of external/internal deviation + UINT + 16 + 224 + + rw + + + + 17 + Hybrid deviation counter + DINT + 32 + 272 + + ro + T + + + + 19 + Pulse feedback display of internal encoder + DINT + 32 + 304 + + ro + T + + + + 21 + Pulse feedback display of external encoder + DINT + 32 + 336 + + ro + T + + + + 23 + SecEncoder Pulse ZPhase Ignore + UINT + 16 + 368 + + rw + + + + 26 + SecEncoder Pulse Z-TouchProbe Selection + UINT + 16 + 416 + + rw + + + + + DT2012 + 1104 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + MultiSpd Function Select + UINT + 16 + 16 + + rw + R + + + + 2 + MultiSpd Final Part Select + UINT + 16 + 32 + + rw + R + + + + 3 + Time Uint of Runing + UINT + 16 + 48 + + rw + R + + + + 4 + AccTime1 + UINT + 16 + 64 + + rw + R + + + + 5 + DecTime1 + UINT + 16 + 80 + + rw + R + + + + 6 + AccTime2 + UINT + 16 + 96 + + rw + R + + + + 7 + DecTime2 + UINT + 16 + 112 + + rw + R + + + + 8 + AccTime3 + UINT + 16 + 128 + + rw + R + + + + 9 + DecTime3 + UINT + 16 + 144 + + rw + R + + + + 10 + AccTime4 + UINT + 16 + 160 + + rw + R + + + + 11 + DecTime4 + UINT + 16 + 176 + + rw + R + + + + 21 + 1st Part Spd Cmd + INT + 16 + 336 + + rw + R + + + + 22 + 1st Part Spd Runing Time + UINT + 16 + 352 + + rw + R + + + + 23 + 1st Part AccDec Time Select + UINT + 16 + 368 + + rw + R + + + + 24 + 2nd Part Spd Cmd + INT + 16 + 384 + + rw + R + + + + 25 + 2nd Part Spd Runing Time + UINT + 16 + 400 + + rw + R + + + + 26 + 2nd Part AccDec Time Select + UINT + 16 + 416 + + rw + R + + + + 27 + 3rd Part Spd Cmd + INT + 16 + 432 + + rw + R + + + + 28 + 3rd Part Spd Runing Time + UINT + 16 + 448 + + rw + R + + + + 29 + 3rd Part AccDec Time Select + UINT + 16 + 464 + + rw + R + + + + 30 + 4th Part Spd Cmd + INT + 16 + 480 + + rw + R + + + + 31 + 4th Part Spd Runing Time + UINT + 16 + 496 + + rw + R + + + + 32 + 4th Part AccDec Time Select + UINT + 16 + 512 + + rw + R + + + + 33 + 5th Part Spd Cmd + INT + 16 + 528 + + rw + R + + + + 34 + 5th Part Spd Runing Time + UINT + 16 + 544 + + rw + R + + + + 35 + 5th Part AccDec Time Select + UINT + 16 + 560 + + rw + R + + + + 36 + 6th Part Spd Cmd + INT + 16 + 576 + + rw + R + + + + 37 + 6th Part Spd Runing Time + UINT + 16 + 592 + + rw + R + + + + 38 + 6th Part AccDec Time Select + UINT + 16 + 608 + + rw + R + + + + 39 + 7th Part Spd Cmd + INT + 16 + 624 + + rw + R + + + + 40 + 7th Part Spd Runing Time + UINT + 16 + 640 + + rw + R + + + + 41 + 7th Part AccDec Time Select + UINT + 16 + 656 + + rw + R + + + + 42 + 8th Part Spd Cmd + INT + 16 + 672 + + rw + R + + + + 43 + 8th Part Spd Runing Time + UINT + 16 + 688 + + rw + R + + + + 44 + 8th Part AccDec Time Select + UINT + 16 + 704 + + rw + R + + + + 45 + 9th Part Spd Cmd + INT + 16 + 720 + + rw + R + + + + 46 + 9th Part Spd Runing Time + UINT + 16 + 736 + + rw + R + + + + 47 + 9th Part AccDec Time Select + UINT + 16 + 752 + + rw + R + + + + 48 + 10th Part Spd Cmd + INT + 16 + 768 + + rw + R + + + + 49 + 10th Part Spd Runing Time + UINT + 16 + 784 + + rw + R + + + + 50 + 10th Part AccDec Time Select + UINT + 16 + 800 + + rw + R + + + + 51 + 11th Part Spd Cmd + INT + 16 + 816 + + rw + R + + + + 52 + 11th Part Spd Runing Time + UINT + 16 + 832 + + rw + R + + + + 53 + 11th Part AccDec Time Select + UINT + 16 + 848 + + rw + R + + + + 54 + 12th Part Spd Cmd + INT + 16 + 864 + + rw + R + + + + 55 + 12th Part Spd Runing Time + UINT + 16 + 880 + + rw + R + + + + 56 + 12th Part AccDec Time Select + UINT + 16 + 896 + + rw + R + + + + 57 + 13th Part Spd Cmd + INT + 16 + 912 + + rw + R + + + + 58 + 13th Part Spd Runing Time + UINT + 16 + 928 + + rw + R + + + + 59 + 13th Part AccDec Time Select + UINT + 16 + 944 + + rw + R + + + + 60 + 14th Part Spd Cmd + INT + 16 + 960 + + rw + R + + + + 61 + 14th Part Spd Runing Time + UINT + 16 + 976 + + rw + R + + + + 62 + 14th Part AccDec Time Select + UINT + 16 + 992 + + rw + R + + + + 63 + 15th Part Spd Cmd + INT + 16 + 1008 + + rw + R + + + + 64 + 15th Part Spd Runing Time + UINT + 16 + 1024 + + rw + R + + + + 65 + 15th Part AccDec Time Select + UINT + 16 + 1040 + + rw + R + + + + 66 + 16th Part Spd Cmd + INT + 16 + 1056 + + rw + R + + + + 67 + 16th Part Spd Runing Time + UINT + 16 + 1072 + + rw + R + + + + 68 + 16th Part AccDec Time Select + UINT + 16 + 1088 + + rw + R + + + + + DT2017 + 1520 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + VDI1 Terminal Function Selection + UINT + 16 + 16 + + rw + + + + 2 + VDI1 Terminal Logic Selection + UINT + 16 + 32 + + rw + + + + 3 + VDI2 Terminal Function Selection + UINT + 16 + 48 + + rw + + + + 4 + VDI2 Terminal Logic Selection + UINT + 16 + 64 + + rw + + + + 5 + VDI3 Terminal Function Selection + UINT + 16 + 80 + + rw + + + + 6 + VDI3 Terminal Logic Selection + UINT + 16 + 96 + + rw + + + + 7 + VDI4 Terminal Function Selection + UINT + 16 + 112 + + rw + + + + 8 + VDI4 Terminal Logic Selection + UINT + 16 + 128 + + rw + + + + 9 + VDI5 Terminal Function Selection + UINT + 16 + 144 + + rw + + + + 10 + VDI5 Terminal Logic Selection + UINT + 16 + 160 + + rw + + + + 11 + VDI6 Terminal Function Selection + UINT + 16 + 176 + + rw + + + + 12 + VDI6 Terminal Logic Selection + UINT + 16 + 192 + + rw + + + + 13 + VDI7 Terminal Function Selection + UINT + 16 + 208 + + rw + + + + 14 + VDI7 Terminal Logic Selection + UINT + 16 + 224 + + rw + + + + 15 + VDI8 Terminal Function Selection + UINT + 16 + 240 + + rw + + + + 16 + VDI8 Terminal Logic Selection + UINT + 16 + 256 + + rw + + + + 17 + VDI9 Terminal Function Selection + UINT + 16 + 272 + + rw + + + + 18 + VDI9 Terminal Logic Selection + UINT + 16 + 288 + + rw + + + + 19 + VDI10 Terminal Function Selection + UINT + 16 + 304 + + rw + + + + 20 + VDI10 Terminal Logic Selection + UINT + 16 + 320 + + rw + + + + 21 + VDI11 Terminal Function Selection + UINT + 16 + 336 + + rw + + + + 22 + VDI11 Terminal Logic Selection + UINT + 16 + 352 + + rw + + + + 23 + VDI12 Terminal Function Selection + UINT + 16 + 368 + + rw + + + + 24 + VDI12 Terminal Logic Selection + UINT + 16 + 384 + + rw + + + + 25 + VDI13 Terminal Function Selection + UINT + 16 + 400 + + rw + + + + 26 + VDI13 Terminal Logic Selection + UINT + 16 + 416 + + rw + + + + 27 + VDI14 Terminal Function Selection + UINT + 16 + 432 + + rw + + + + 28 + VDI14 Terminal Logic Selection + UINT + 16 + 448 + + rw + + + + 29 + VDI15 Terminal Function Selection + UINT + 16 + 464 + + rw + + + + 30 + VDI15 Terminal Logic Selection + UINT + 16 + 480 + + rw + + + + 31 + VDI16 Terminal Function Selection + UINT + 16 + 496 + + rw + + + + 32 + VDI16 Terminal Logic Selection + UINT + 16 + 512 + + rw + + + + 33 + VDO virtual level + UINT + 16 + 528 + + ro + + + + 34 + VDO1 Terminal Function Selection + UINT + 16 + 544 + + rw + + + + 35 + VDO1 Terminal Logic Level Selection + UINT + 16 + 560 + + rw + + + + 36 + VDO2 Terminal Function Selection + UINT + 16 + 576 + + rw + + + + 37 + VDO2 Terminal Logic Level Selection + UINT + 16 + 592 + + rw + + + + 38 + VDO3 Terminal Function Selection + UINT + 16 + 608 + + rw + + + + 39 + VDO3 Terminal Logic Level Selection + UINT + 16 + 624 + + rw + + + + 40 + VDO4 Terminal Function Selection + UINT + 16 + 640 + + rw + + + + 41 + VDO4 Terminal Logic Level Selection + UINT + 16 + 656 + + rw + + + + 42 + VDO5 Terminal Function Selection + UINT + 16 + 672 + + rw + + + + 43 + VDO5 Terminal Logic Level Selection + UINT + 16 + 688 + + rw + + + + 44 + VDO6 Terminal Function Selection + UINT + 16 + 704 + + rw + + + + 45 + VDO6 Terminal Logic Level Selection + UINT + 16 + 720 + + rw + + + + 46 + VDO7 Terminal Function Selection + UINT + 16 + 736 + + rw + + + + 47 + VDO7 Terminal Logic Level Selection + UINT + 16 + 752 + + rw + + + + 48 + VDO8 Terminal Function Selection + UINT + 16 + 768 + + rw + + + + 49 + VDO8 Terminal Logic Level Selection + UINT + 16 + 784 + + rw + + + + 50 + VDO9 Terminal Function Selection + UINT + 16 + 800 + + rw + + + + 51 + VDO9 Terminal Logic Level Selection + UINT + 16 + 816 + + rw + + + + 52 + VDO10 Terminal Function Selection + UINT + 16 + 832 + + rw + + + + 53 + VDO10 Terminal Logic Level Selection + UINT + 16 + 848 + + rw + + + + 54 + VDO11 Terminal Function Selection + UINT + 16 + 864 + + rw + + + + 55 + VDO11 Terminal Logic Level Selection + UINT + 16 + 880 + + rw + + + + 56 + VDO12 Terminal Function Selection + UINT + 16 + 896 + + rw + + + + 57 + VDO12 Terminal Logic Level Selection + UINT + 16 + 912 + + rw + + + + 58 + VDO13 Terminal Function Selection + UINT + 16 + 928 + + rw + + + + 59 + VDO13 Terminal Logic Level Selection + UINT + 16 + 944 + + rw + + + + 60 + VDO14 Terminal Function Selection + UINT + 16 + 960 + + rw + + + + 61 + VDO14 Terminal Logic Level Selection + UINT + 16 + 976 + + rw + + + + 62 + VDO15 Terminal Function Selection + UINT + 16 + 992 + + rw + + + + 63 + VDO15 Terminal Logic Level Selection + UINT + 16 + 1008 + + rw + + + + 64 + VDO16 Terminal Function Selection + UINT + 16 + 1024 + + rw + + + + 65 + VDO16 Terminal Logic Level Selection + UINT + 16 + 1040 + + rw + + + + 91 + VDI Enable + UINT + 16 + 1456 + + rw + R + + + + 92 + VDI Default Value + UINT + 16 + 1472 + + rw + R + + + + 93 + VDO Enable + UINT + 16 + 1488 + + rw + R + + + + 94 + VDO Default Value + UINT + 16 + 1504 + + rw + R + + + + + DT2018 + 288 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Enable Comparison + UINT + 16 + 16 + + rw + R + + + + 2 + Comparison PosFdb Source Select + UINT + 16 + 32 + + rw + R + + + + 3 + Encoder Resolution + UINT + 16 + 48 + + rw + R + + + + 4 + Mode Of Comparison + UINT + 16 + 64 + + rw + R + + + + 5 + Current Position As Zero + UINT + 16 + 80 + + rw + R + + + + 6 + Output Duration + UINT + 16 + 96 + + rw + R + + + + 7 + Comparison ABZ OutPut Logic + UINT + 16 + 112 + + rw + R + + + + 8 + Starting Point Number + UINT + 16 + 128 + + rw + R + + + + 9 + Ending Point Number + UINT + 16 + 144 + + rw + R + + + + 10 + Comparison Status + UINT + 16 + 160 + + ro + T + + + + 11 + Current Position + DINT + 32 + 176 + + ro + T + + + + 13 + Position Offset + DINT + 32 + 208 + + rw + R + + + + 15 + Comparison OutPut Delay Compensation + INT + 16 + 240 + + rw + R + + + + 16 + Lilited number of Comparison Cycle Times + UINT + 16 + 256 + + rw + R + + + + 17 + Comparison ABZ OutPut Function + UINT + 16 + 272 + + rw + R + + + + + DT2019 + 1936 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Comparing Position + DINT + 32 + 16 + + rw + R + + + + 3 + 1st Point Property + UINT + 16 + 48 + + rw + R + + + + 4 + 2nd Comparing Position + DINT + 32 + 64 + + rw + R + + + + 6 + 2nd Point Property + UINT + 16 + 96 + + rw + R + + + + 7 + 3rd Comparing Position + DINT + 32 + 112 + + rw + R + + + + 9 + 3rd Point Property + UINT + 16 + 144 + + rw + R + + + + 10 + 4th Comparing Position + DINT + 32 + 160 + + rw + R + + + + 12 + 4th Point Property + UINT + 16 + 192 + + rw + R + + + + 13 + 5th Comparing Position + DINT + 32 + 208 + + rw + R + + + + 15 + 5th Point Property + UINT + 16 + 240 + + rw + R + + + + 16 + 6th Comparing Position + DINT + 32 + 256 + + rw + R + + + + 18 + 6th Point Property + UINT + 16 + 288 + + rw + R + + + + 19 + 7th Comparing Position + DINT + 32 + 304 + + rw + R + + + + 21 + 7th Point Property + UINT + 16 + 336 + + rw + R + + + + 22 + 8th Comparing Position + DINT + 32 + 352 + + rw + R + + + + 24 + 8th Point Property + UINT + 16 + 384 + + rw + R + + + + 25 + 9th Comparing Position + DINT + 32 + 400 + + rw + R + + + + 27 + 9th Point Property + UINT + 16 + 432 + + rw + R + + + + 28 + 10th Comparing Position + DINT + 32 + 448 + + rw + R + + + + 30 + 10th Point Property + UINT + 16 + 480 + + rw + R + + + + 31 + 11th Comparing Position + DINT + 32 + 496 + + rw + R + + + + 33 + 11th Point Property + UINT + 16 + 528 + + rw + R + + + + 34 + 12th Comparing Position + DINT + 32 + 544 + + rw + R + + + + 36 + 12th Point Property + UINT + 16 + 576 + + rw + R + + + + 37 + 13th Comparing Position + DINT + 32 + 592 + + rw + R + + + + 39 + 13th Point Property + UINT + 16 + 624 + + rw + R + + + + 40 + 14th Comparing Position + DINT + 32 + 640 + + rw + R + + + + 42 + 14th Point Property + UINT + 16 + 672 + + rw + R + + + + 43 + 15th Comparing Position + DINT + 32 + 688 + + rw + R + + + + 45 + 15th Point Property + UINT + 16 + 720 + + rw + R + + + + 46 + 16th Comparing Position + DINT + 32 + 736 + + rw + R + + + + 48 + 16th Point Property + UINT + 16 + 768 + + rw + R + + + + 49 + 17th Comparing Position + DINT + 32 + 784 + + rw + R + + + + 51 + 17th Point Property + UINT + 16 + 816 + + rw + R + + + + 52 + 18th Comparing Position + DINT + 32 + 832 + + rw + R + + + + 54 + 18th Point Property + UINT + 16 + 864 + + rw + R + + + + 55 + 19th Comparing Position + DINT + 32 + 880 + + rw + R + + + + 57 + 19th Point Property + UINT + 16 + 912 + + rw + R + + + + 58 + 20th Comparing Position + DINT + 32 + 928 + + rw + R + + + + 60 + 20th Point Property + UINT + 16 + 960 + + rw + R + + + + 61 + 21st Comparing Position + DINT + 32 + 976 + + rw + R + + + + 63 + 21st Point Property + UINT + 16 + 1008 + + rw + R + + + + 64 + 22nd Comparing Position + DINT + 32 + 1024 + + rw + R + + + + 66 + 22nd Point Property + UINT + 16 + 1056 + + rw + R + + + + 67 + 23rd Comparing Position + DINT + 32 + 1072 + + rw + R + + + + 69 + 23rd Point Property + UINT + 16 + 1104 + + rw + R + + + + 70 + 24th Comparing Position + DINT + 32 + 1120 + + rw + R + + + + 72 + 24th Point Property + UINT + 16 + 1152 + + rw + R + + + + 73 + 25th Comparing Position + DINT + 32 + 1168 + + rw + R + + + + 75 + 25th Point Property + UINT + 16 + 1200 + + rw + R + + + + 76 + 26th Comparing Position + DINT + 32 + 1216 + + rw + R + + + + 78 + 26th Point Property + UINT + 16 + 1248 + + rw + R + + + + 79 + 27th Comparing Position + DINT + 32 + 1264 + + rw + R + + + + 81 + 27th Point Property + UINT + 16 + 1296 + + rw + R + + + + 82 + 28th Comparing Position + DINT + 32 + 1312 + + rw + R + + + + 84 + 28th Point Property + UINT + 16 + 1344 + + rw + R + + + + 85 + 29th Comparing Position + DINT + 32 + 1360 + + rw + R + + + + 87 + 29th Point Property + UINT + 16 + 1392 + + rw + R + + + + 88 + 30th Comparing Position + DINT + 32 + 1408 + + rw + R + + + + 90 + 30th Point Property + UINT + 16 + 1440 + + rw + R + + + + 91 + 31st Comparing Position + DINT + 32 + 1456 + + rw + R + + + + 93 + 31st Point Property + UINT + 16 + 1488 + + rw + R + + + + 94 + 32nd Comparing Position + DINT + 32 + 1504 + + rw + R + + + + 96 + 32nd Point Property + UINT + 16 + 1536 + + rw + R + + + + 97 + 33rd Comparing Position + DINT + 32 + 1552 + + rw + R + + + + 99 + 33rd Point Property + UINT + 16 + 1584 + + rw + R + + + + 100 + 34th Comparing Position + DINT + 32 + 1600 + + rw + R + + + + 102 + 34th Point Property + UINT + 16 + 1632 + + rw + R + + + + 103 + 35th Comparing Position + DINT + 32 + 1648 + + rw + R + + + + 105 + 35th Point Property + UINT + 16 + 1680 + + rw + R + + + + 106 + 36th Comparing Position + DINT + 32 + 1696 + + rw + R + + + + 108 + 36th Point Property + UINT + 16 + 1728 + + rw + R + + + + 109 + 37th Comparing Position + DINT + 32 + 1744 + + rw + R + + + + 111 + 37th Point Property + UINT + 16 + 1776 + + rw + R + + + + 112 + 38th Comparing Position + DINT + 32 + 1792 + + rw + R + + + + 114 + 38th Point Property + UINT + 16 + 1824 + + rw + R + + + + 115 + 39th Comparing Position + DINT + 32 + 1840 + + rw + R + + + + 117 + 39th Point Property + UINT + 16 + 1872 + + rw + R + + + + 118 + 40th Comparing Position + DINT + 32 + 1888 + + rw + R + + + + 120 + 40th Point Property + UINT + 16 + 1920 + + rw + R + + + + + DT2030 + 64 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Servo Status + UINT + 16 + 16 + + ro + T + + + + 2 + DO Function1 + UINT + 16 + 32 + + ro + T + + + + 3 + DO Function2 + UINT + 16 + 48 + + ro + T + + + + + DT2031 + 224 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Comm Set VDI + UINT + 16 + 16 + + rw + R + + + + 5 + Comm Set DO + UINT + 16 + 80 + + rw + R + + + + 6 + Comm Set AO + INT + 16 + 96 + + rw + R + + + + 10 + Comm Set Local SpdRef + DINT + 32 + 160 + + rw + R + + + + 12 + Comm Set Local TrqRef + DINT + 32 + 192 + + rw + R + + + + + DT607D + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Min position limit + DINT + 32 + 16 + + rw + R + + + + 2 + Max position limit + DINT + 32 + 48 + + rw + R + + + + + DT6091 + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Motor revolutions + UDINT + 32 + 16 + + rw + R + + + + 2 + Shaft revolutions + UDINT + 32 + 48 + + rw + R + + + + + DT6099 + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Speed during search for switch + UDINT + 32 + 16 + + rw + R + + + + 2 + Speed during search for zero + UDINT + 32 + 48 + + rw + R + + + + + DT60FE + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Physical outputs + UDINT + 32 + 16 + + rw + R + + + + 2 + Bit Mask + UDINT + 32 + 48 + + rw + R + + + + + DT60E3 + 544 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Support homing method 1 + INT + 16 + 16 + + ro + + + + 2 + Support homing method 2 + INT + 16 + 32 + + ro + + + + 3 + Support homing method 3 + INT + 16 + 48 + + ro + + + + 4 + Support homing method 4 + INT + 16 + 64 + + ro + + + + 5 + Support homing method 5 + INT + 16 + 80 + + ro + + + + 6 + Support homing method 6 + INT + 16 + 96 + + ro + + + + 7 + Support homing method 7 + INT + 16 + 112 + + ro + + + + 8 + Support homing method 8 + INT + 16 + 128 + + ro + + + + 9 + Support homing method 9 + INT + 16 + 144 + + ro + + + + 10 + Support homing method 10 + INT + 16 + 160 + + ro + + + + 11 + Support homing method 11 + INT + 16 + 176 + + ro + + + + 12 + Support homing method 12 + INT + 16 + 192 + + ro + + + + 13 + Support homing method 13 + INT + 16 + 208 + + ro + + + + 14 + Support homing method 14 + INT + 16 + 224 + + ro + + + + 15 + Support homing method 15 + INT + 16 + 240 + + ro + + + + 16 + Support homing method 16 + INT + 16 + 256 + + ro + + + + 17 + Support homing method 17 + INT + 16 + 272 + + ro + + + + 18 + Support homing method 18 + INT + 16 + 288 + + ro + + + + 19 + Support homing method 19 + INT + 16 + 304 + + ro + + + + 20 + Support homing method 20 + INT + 16 + 320 + + ro + + + + 21 + Support homing method 21 + INT + 16 + 336 + + ro + + + + 22 + Support homing method 22 + INT + 16 + 352 + + ro + + + + 23 + Support homing method 23 + INT + 16 + 368 + + ro + + + + 24 + Support homing method 24 + INT + 16 + 384 + + ro + + + + 25 + Support homing method 25 + INT + 16 + 400 + + ro + + + + 26 + Support homing method 26 + INT + 16 + 416 + + ro + + + + 27 + Support homing method 27 + INT + 16 + 432 + + ro + + + + 28 + Support homing method 28 + INT + 16 + 448 + + ro + + + + 29 + Support homing method 29 + INT + 16 + 464 + + ro + + + + 30 + Support homing method 30 + INT + 16 + 480 + + ro + + + + 31 + Support homing method 31 + INT + 16 + 496 + + ro + + + + 32 + Support homing method 32 + INT + 16 + 512 + + ro + + + + 33 + Support homing method 33 + INT + 16 + 528 + + ro + + + + + + + #x1000 + Device type + UDINT + 32 + + #x00020192 + + + ro + o + + + + #x1001 + Error Register + USINT + 8 + + 00 + + + ro + o + + + + #x1008 + Device name + STRING(10) + 80 + + SV670_ECAT + + + ro + + + + #x1009 + Hardware version + STRING(4) + 32 + + V1.0 + + + ro + + + + #x100a + Software version + STRING(4) + 32 + + V1.0 + + + ro + o + + + + #x1c00 + Sync manager type + DT1C00 + 48 + + + SubIndex 000 + + 04 + + + + SubIndex 001 + + 01 + + + + SubIndex 002 + + 02 + + + + SubIndex 003 + + 03 + + + + SubIndex 004 + + 04 + + + + + ro + o + + + + #x1018 + Identity + DT1018 + 144 + + + SubIndex 000 + + 04 + + + + Vendor ID + + #x00100000 + + + + Product Code + + #x000C011E + + + + Revision + + #x00010000 + + + + Serial number + + 00000000 + + + + + ro + o + + + + #x1600 + Outputs + DT1600 + 336 + + + SubIndex 000 + + 00 + 10 + #x03 + + + + 1st Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60400010 + + + + 2nd Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x607A0020 + + + + 3rd Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60B80010 + + + + 4th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 5th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 6th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 7th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 8th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 9th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 10th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + rw + + + + #x1601 + Outputs + DT1601 + 368 + + + SubIndex 000 + + #x0B + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x60600008 + + + + 3rd Output Object to be mapped + + #x60710010 + + + + 4th Output Object to be mapped + + #x607A0020 + + + + 5th Output Object to be mapped + + #x607F0020 + + + + 6th Output Object to be mapped + + #x60810020 + + + + 7th Output Object to be mapped + + #x60830020 + + + + 8th Output Object to be mapped + + #x60840020 + + + + 9th Output Object to be mapped + + #x60870020 + + + + 10th Output Object to be mapped + + #x60B80010 + + + + 11th Output Object to be mapped + + #x60FF0020 + + + + + rw + + + + #x1701 + Outputs + DT1701 + 336 + + + SubIndex 000 + + #x04 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60B80010 + + + + 4th Output Object to be mapped + + #x60FE0120 + + + + + ro + + + + #x1702 + Outputs + DT1702 + 336 + + + SubIndex 000 + + #x07 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60B80010 + + + + 4th Output Object to be mapped + + #x60710010 + + + + 5th Output Object to be mapped + + #x60600008 + + + + 6th Output Object to be mapped + + #x60B80010 + + + + 7th Output Object to be mapped + + #x607F0020 + + + + + ro + + + + #x1703 + Outputs + DT1702 + 336 + + + SubIndex 000 + + #x07 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60600008 + + + + 5th Output Object to be mapped + + #x60B80010 + + + + 6th Output Object to be mapped + + #x60E00010 + + + + 7th Output Object to be mapped + + #x60E10010 + + + + + ro + + + + #x1704 + Outputs + DT1704 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60710010 + + + + 5th Output Object to be mapped + + #x60600008 + + + + 6th Output Object to be mapped + + #x60B80010 + + + + 7th Output Object to be mapped + + #x607F0020 + + + + 8th Output Object to be mapped + + #x60E00010 + + + + 9th Output Object to be mapped + + #x60E10010 + + + + + ro + + + + #x1705 + Outputs + DT1705 + 336 + + + SubIndex 000 + + #x08 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60600008 + + + + 5th Output Object to be mapped + + #x60B80010 + + + + 6th Output Object to be mapped + + #x60E00010 + + + + 7th Output Object to be mapped + + #x60E10010 + + + + 8th Output Object to be mapped + + #x60B20010 + + + + + ro + + + + #x1A00 + Inputs + DT1A00 + 336 + + + SubIndex 000 + + 00 + 10 + #x07 + + + + 1st Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60410010 + + + + 2nd Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60640020 + + + + 3rd Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60B90010 + + + + 4th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60BA0020 + + + + 5th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60BC0020 + + + + 6th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x603F0010 + + + + 7th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60FD0020 + + + + 8th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 9th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 10th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + rw + + + + #x1A01 + Inputs + DT1A01 + 368 + + + SubIndex 000 + + #x0B + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60610008 + + + + 4th Input Object to be mapped + + #x60640020 + + + + 5th Input Object to be mapped + + #x606C0020 + + + + 6th Input Object to be mapped + + #x60770010 + + + + 7th Input Object to be mapped + + #x60B90010 + + + + 8th Input Object to be mapped + + #x60BA0020 + + + + 9th Input Object to be mapped + + #x60BC0020 + + + + 10th Input Object to be mapped + + #x60F40020 + + + + 11th Input Object to be mapped + + #x60FD0020 + + + + + rw + + + + #x1B01 + Inputs + DT1B01 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60F40020 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B02 + Inputs + DT1B01 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60610008 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B03 + Inputs + DT1B03 + 336 + + + SubIndex 000 + + #x0A + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60F40020 + + + + 6th Input Object to be mapped + + #x60610008 + + + + 7th Input Object to be mapped + + #x60B90010 + + + + 8th Input Object to be mapped + + #x60BA0020 + + + + 9th Input Object to be mapped + + #x60BC0020 + + + + 10th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B04 + Inputs + DT1B04 + 336 + + + SubIndex 000 + + #x0A + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60610008 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + 10th Input Object to be mapped + + #x606C0020 + + + + + ro + + + + #x1c32 + SM output parameter + DT1C32 + 488 + + + SubIndex 000 + + 20 + + + + Sync mode + + 0200 + + + + Cycle time + + 00000000 + + + + Sync modes supported + + 0004 + + + + Minimum cycle time + + 00000000 + + + + Calc and copy time + + #x0003d090 + + + + Get Cycle Time + + 0000 + + + + Delay Time + + 00000000 + + + + Sync0 Cycle Time + + 00000000 + + + + SM-Event Missed + + 0000 + + + + Cycle Time Too Small + + 0000 + + + + Sync Error + + 00 + + + + + ro + o + + + + #x1c33 + SM input parameter + DT1C33 + 488 + + + SubIndex 000 + + 20 + + + + Sync mode + + 0002 + + + + Cycle time + + 00000000 + + + + Sync modes supported + + 4 + + + + Minimum cycle time + + 00000000 + + + + Calc and copy time + + 00000000 + + + + Get Cycle Time + + 0000 + + + + Delay Time + + 00000000 + + + + Sync0 Cycle Time + + 00000000 + + + + SM-Event Missed + + 0000 + + + + Cycle Time Too Small + + 0000 + + + + Sync Error + + 00 + + + + + ro + o + + + + #x1c12 + RxPDO assign + DT1C12 + 32 + + + SubIndex 000 + + 00 + + + + SubIndex 001 + + 0000 + + + + + ro + + + + #x1c13 + TxPDO assign + DT1C13 + 32 + + + SubIndex 000 + + 00 + + + + SubIndex 001 + + 0000 + + + + + ro + + + + #x2000 + Servo Motor Parameters + 伺服电机参数 + DT2000 + 128 + + + SubIndex 000 + + 6 + + + + Motor SN + + 0 + 65535 + 14101 + + + + Customized firmware version + + 0 + 65535 + 0 + + + + Encoder Version + + 0 + 65535 + 0 + + + + Serial encoder motor SN + + 0 + 65535 + 0 + + + + + ro + + + + #x2001 + Servo Drive Parameters + 伺服驱动器参数 + DT2001 + 672 + + + SubIndex 000 + + 41 + + + + MCU firmware Version + + 0 + 65535 + 0 + + + + Fpga firmware Version + + 0 + 65535 + 0 + + + + Drive serial number + + 0 + 65535 + 3 + + + + Drive voltage class + + 0 + 65535 + 220 + + + + Drive rated power + + 0 + 1073741824 + 400 + + + + Drive maximum output power + + 0 + 1073741824 + 400 + + + + Drive rated output current + + 0 + 1073741824 + 280 + + + + Drive maximum output current + + 0 + 1073741824 + 1010 + + + + DC bus overvoltage protective point + + 0 + 2000 + 420 + + + + + ro + + + + #x2002 + Basic control + 基本控制参数 + DT2002 + 688 + + + SubIndex 000 + + 36 + + + + Control mode selection + + 0 + 9 + 9 + + + + Absolute system selection + + 0 + 4 + 0 + + + + Rotating direction + + 0 + 1 + 0 + + + + Output pulse phase + + 0 + 1 + 0 + + + + Disable operation option Code + + -4 + 2 + 0 + + + + NO2 Fault Reaction option Code + + -5 + 4 + 2 + + + + Stop mode at limit switch signal + + 0 + 7 + 1 + + + + Stop mode at NO.1 fault + + 0 + 2 + 2 + + + + Delay from brake output on to command received + + 0 + 500 + 250 + + + + Delay from brake output off to motor de-energized + + 50 + 1000 + 150 + + + + Motor speed threshold at brake output off in rotating state + + 20 + 3000 + 30 + + + + Delay from servo off to brake output off in the rotating state + + 1 + 65535 + 500 + + + + LED warning display selection + + 0 + 1 + 0 + + + + MainPower Cutoff Reaction Option Code + + 0 + 3 + 2 + + + + QuickStop Reaction Option Code + + 0 + 7 + 2 + + + + Allowed minimum braking resistance + + 1 + 1000 + 40 + + + + Power of built-in braking resistor + + 0 + 65535 + 50 + + + + Resistance of built-in braking resistor + + 0 + 65535 + 50 + + + + Resistor heat dissipation coefficient + + 10 + 100 + 30 + + + + braking resistor type + + 0 + 3 + 3 + + + + Power of external dynamic resistor + + 1 + 65535 + 40 + + + + Resistance of external braking resistor + + 15 + 1000 + 50 + + + + User password + + 0 + 65535 + 0 + + + + Parameter initialization + + 0 + 2 + 0 + + + + Default keypad display + + 0 + 99 + 50 + + + + Panel data refresh rate + + 0 + 20 + 0 + + + + OEM password + + 0 + 65535 + 0 + + + + + ro + + + + #x2003 + Input Terminal Parameters + 端子输入参数 + DT2003 + 1056 + + + SubIndex 000 + + 65 + + + + DI1 function selection + + 0 + 40 + 14 + + + + DI1 logic selection + + 0 + 1 + 0 + + + + DI2 function selection + + 0 + 40 + 15 + + + + DI2 logic selection + + 0 + 1 + 0 + + + + DI3 function selection + + 0 + 40 + 31 + + + + DI3 logic selection + + 0 + 1 + 0 + + + + DI4 function selection + + 0 + 40 + 34 + + + + DI4 logic selection + + 0 + 1 + 0 + + + + DI5 function selection + + 0 + 40 + 38 + + + + DI5 logic selection + + 0 + 1 + 0 + + + + AI1 Offset + + -5000 + 5000 + 0 + + + + AI1 Filter + + 0 + 65535 + 200 + + + + AI1 Dead Zone + + 0 + 10000 + 100 + + + + AI1 Zero Drifting + + -5000 + 5000 + 0 + + + + DI1 filtertime constant + + 0 + 50000 + 300 + + + + DI2 filtertime constant + + 0 + 50000 + 300 + + + + DI3 filtertime constant + + 0 + 50000 + 300 + + + + DI4 filtertime constant + + 0 + 50000 + 300 + + + + DI5 filtertime constant + + 0 + 50000 + 300 + + + + + ro + + + + #x2004 + Output terminal Parameters + 端子输出参数 + DT2004 + 864 + + + SubIndex 000 + + 53 + + + + DO1 Function Selection + + 0 + 65535 + 1 + + + + DO1 Logic Level Selection + + 0 + 1 + 0 + + + + DO2 function selection + + 0 + 65535 + 9 + + + + DO2 Logic Level Selection + + 0 + 1 + 0 + + + + DO OutPut Source Select + + 0 + 3 + 0 + + + + ECAT Lost Force DO OutPut Logic + + 0 + 3 + 0 + + + + AO1 Source Select + + 0 + 10 + 0 + + + + AO1 Offset + + -10000 + 10000 + 0 + + + + AO1 Multiplying + + -10000 + 10000 + 100 + + + + + ro + + + + #x2005 + Position Control Parameters + 位置控制参数组 + DT2005 + 1152 + + + SubIndex 000 + + 55 + + + + Time constant of first-order low-pass filter + + 0 + 65535 + 0 + + + + Time constant of moving average filter 1 + + 0 + 1280 + 0 + + + + Encoder frequency division pulses + + 0 + 4194303 + 2500 + + + + Speed feedforward control selection + + 0 + 3 + 1 + + + + Local home mode + + 0 + 8 + 0 + + + + Time of home searching + + 0 + 65535 + 10000 + + + + Local home position offset + + -2147483648 + 2147483647 + 0 + + + + Servo pulse output source + + 0 + 3 + 0 + + + + Output polarity of Z pulse + + 0 + 65535 + 1 + + + + Mechanical Gear ratio numerator of absolute encode mode 2 + + 1 + 65535 + 1 + + + + Mechanical Gear ratio denominator of absolute encode mode 2 + + 1 + 65535 + 1 + + + + Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) + + 0 + 4294967295 + 0 + + + + Max value of mechanical absolute position(inc) of absolute encode mode 2(High) + + 0 + 4294967295 + 0 + + + + Trq Reference of Mechanical Homing + + 0 + 4000 + 1000 + + + + Position Coin Hold Time + + 0 + 30000 + 0 + + + + Time Unit of Homing + + 0 + 2 + 2 + + + + Time constant of moving average filter 2 + + 0 + 10000 + 0 + + + + + ro + + + + #x2006 + Speed control + 速度控制 + DT2006 + 896 + + + SubIndex 000 + + 16 + + + + Keypad setting value of speed reference + + -10000 + 10000 + 200 + + + + DI Jog speed reference + + 0 + 10000 + 150 + + + + Acceleration ramp time constant of speed reference + + 0 + 65535 + 0 + + + + Deceleration ramp time constant of speed reference + + 0 + 65535 + 0 + + + + Quick decelaration coefficient + + 0 + 2 + 0 + + + + Torque feedforward selection + + 0 + 2 + 1 + + + + Acceleration/Deceleration ramp time constant of jog speed reference + + 0 + 65535 + 10 + + + + Speed feedforward filter time constant + + 0 + 65535 + 0 + + + + Speed threshold of Zero Hold signal + + 0 + 10000 + 10 + + + + Speed threshold of motor rotation signal + + 0 + 1000 + 20 + + + + Speed threshold of Spd Reach signal + + 0 + 100 + 10 + + + + Speed threshold of Spd Arrive signal + + 20 + 10000 + 1000 + + + + Speed threshold of Zero Spd signal + + 1 + 10000 + 10 + + + + Spd SCurve Enable + + 0 + 1 + 1 + + + + Spd SCurve Acceleration UP + + 0 + 1000 + 500 + + + + Spd SCurve Acceleration Down + + 0 + 1000 + 500 + + + + Spd SCurve Deceleration UP + + 0 + 1000 + 500 + + + + Spd SCurve Deceleration Down + + 0 + 1000 + 500 + + + + + ro + + + + #x2007 + Torque control + 转矩控制参数 + DT2007 + 640 + + + SubIndex 000 + + 40 + + + + Keypad setting value of torque reference + + -4000 + 4000 + 0 + + + + Torque reference filter time 1 + + 0 + 3000 + 50 + + + + Torque reference filter time 2 + + 0 + 3000 + 27 + + + + Emergency stop torque + + 0 + 4000 + 1000 + + + + Base value for torque reached + + 0 + 4000 + 0 + + + + Threshold of torque reached valid + + 0 + 4000 + 200 + + + + Threshold of torque reached invalid + + 0 + 4000 + 100 + + + + Depth of field-weakening + + 60 + 115 + 115 + + + + Maximum field-weakening current + + 0 + 300 + 100 + + + + Field-weakening enable + + 0 + 1 + 0 + + + + Field-weakening gain + + 1 + 1000 + 30 + + + + Field-weakening point speed + + 0 + 65535 + 0 + + + + Motor output calibration enable + + 0 + 1 + 0 + + + + The second-stage torque reference filter time + + 0 + 1000 + 0 + + + + Torque reference filter type select + + 0 + 1 + 0 + + + + Biquad low pass filter damping + + 0 + 50 + 16 + + + + + ro + + + + #x2008 + Gain Parameters + 增益参数 + DT2008 + 1056 + + + SubIndex 000 + + 65 + + + + Speed-loop Gain + + 1 + 20000 + 400 + + + + Speed-loop integral time constant + + 15 + 51200 + 1989 + + + + Position-loop Gain + + 1 + 20000 + 640 + + + + The second speed loop gain + + 1 + 20000 + 750 + + + + The second speed loop integral time constant + + 15 + 51200 + 1061 + + + + The second position loop gain + + 1 + 20000 + 1200 + + + + Second gain mode setting + + 0 + 1 + 1 + + + + Gain switchover condition + + 0 + 10 + 0 + + + + Gain switchover delay + + 0 + 10000 + 50 + + + + Gain switchover level + + 0 + 20000 + 50 + + + + Gain switchover hysteresis + + 0 + 20000 + 30 + + + + Position gain switchover time + + 0 + 10000 + 30 + + + + Average value of load inertia ratio + + 0 + 12000 + 100 + + + + Zero-Phase delay time + + 0 + 40 + 0 + + + + Speed feedforward filter time constant + + 0 + 6400 + 50 + + + + Speed feedforward gain + + 0 + 1000 + 0 + + + + Torque feedforward filter time constant + + 0 + 6400 + 50 + + + + Torque feedforward gain + + 0 + 3000 + 0 + + + + Speed feedback filter + + 0 + 4 + 0 + + + + Cut-off frequency of speed feedback low-pass filter + + 100 + 8000 + 8000 + + + + Pseudo-differential forward feedback control coefficient + + 0 + 2000 + 1000 + + + + Cut-off frequency of speed observer + + 50 + 600 + 170 + + + + Modified inertia coefficient of speed observer + + 1 + 1600 + 100 + + + + Filter time of speed observer + + 0 + 1000 + 80 + + + + Cut-off frequency of torque disturbance observer + + 10 + 4000 + 600 + + + + Compensation gain of torque disturbance observer + + 0 + 100 + 0 + + + + Modified inertia coefficient of torque disturbance observer + + 1 + 1600 + 100 + + + + Speed observer enable + + 0 + 1 + 0 + + + + Module control enable + + 0 + 2 + 0 + + + + Module control gain + + 1 + 20000 + 400 + + + + Module feedforward value + + 0 + 1024 + 950 + + + + 3rd medium and low-frequency vibration suppression frequency + + 0 + 3000 + 0 + + + + 3rd compensation gain of medium and low-frequency vibration suppression frequency + + 0 + 200 + 0 + + + + 3rd phase modulation of medium and low-frequency vibration suppression frequency + + 0 + 600 + 100 + + + + 4th medium and low-frequency vibration suppression frequency + + 0 + 3000 + 0 + + + + 4th compensation gain of medium and low-frequency vibration suppression frequency + + 0 + 200 + 0 + + + + 4th phase modulation of medium and low-frequency vibration suppression frequency + + 0 + 600 + 100 + + + + Time constant of position loop integration + + 15 + 51200 + 51200 + + + + 2nd time constant of position loop integration + + 15 + 51200 + 51200 + + + + Speed observation feedback source selection + + 0 + 1 + 0 + + + + + ro + + + + #x2009 + Auto-adjusting Parameters + 自整定参数 + DT2009 + 848 + + + SubIndex 000 + + 60 + + + + Auto-adjusting mode + + 0 + 7 + 4 + + + + Rigidity level selection + + 0 + 41 + 15 + + + + Working mode of self-adaptive notch + + 0 + 4 + 0 + + + + Online inertia auto-tuning mode + + 0 + 3 + 0 + + + + Offline inertia auto-tuning mode + + 0 + 1 + 0 + + + + Maximum speed for inertia autotuning + + 100 + 1000 + 500 + + + + Acceleration/Deceleration time for inertia autotuning + + 20 + 800 + 125 + + + + Interval after an inertia autotuning + + 50 + 10000 + 800 + + + + Motor revolutions for an inertia auto-tuning + + 0 + 10000 + 100 + + + + Vibration threshold setting + + 0 + 1000 + 50 + + + + 1st notch frequency + + 50 + 8000 + 8000 + + + + 1st notch width level + + 0 + 20 + 2 + + + + 1st notch attenuation level + + 0 + 99 + 0 + + + + 2nd notch frequency + + 50 + 8000 + 8000 + + + + 2nd notch width level + + 0 + 20 + 2 + + + + 2nd notch attenuation level + + 0 + 99 + 0 + + + + 3rd notch frequency + + 50 + 8000 + 8000 + + + + 3rd notch width level + + 0 + 20 + 2 + + + + 3rd notch attenuation level + + 0 + 99 + 0 + + + + 4th notch frequency + + 50 + 8000 + 8000 + + + + 4th notch width level + + 0 + 20 + 2 + + + + 4th notch attenuation level + + 0 + 99 + 0 + + + + Obtained resonance frequency + + 0 + 5000 + 0 + + + + 1st anti-resonance point frequency + + 0 + 5000 + 0 + + + + 2nd anti-resonance point frequency + + 0 + 5000 + 0 + + + + Gravity compensation value + + 0 + 1000 + 0 + + + + Forward friction compensation + + 0 + 1000 + 0 + + + + Reverse friction compensation + + -1000 + 0 + 0 + + + + Friction compensation speed + + 0 + 200 + 20 + + + + Friction compensation speed selection + + 0 + 19 + 0 + + + + Vibration monitor time + + 0 + 65535 + 300 + + + + 1st terminal low-frequency vibration suppression frequency + + 10 + 1000 + 1000 + + + + 1st filter order of low-frequency vibration suppression frequency + + 0 + 3 + 2 + + + + 5th notch frequency + + 50 + 8000 + 8000 + + + + 5th notch width level + + 0 + 20 + 2 + + + + 5th notch attenuation level + + 0 + 99 + 0 + + + + 2nd terminal low-frequency vibration suppression frequency + + 0 + 2000 + 0 + + + + 2nd damping frequency ratio of low-frequency vibration suppression frequency + + 1 + 1000 + 100 + + + + 2nd damping coefficient of low-frequency vibration suppression frequency + + 0 + 200 + 100 + + + + 3rd terminal low-frequency vibration suppression frequency + + 0 + 2000 + 0 + + + + 3rd damping frequency ratio of low-frequency vibration suppression frequency + + 1 + 1000 + 100 + + + + 3rd damping coefficient of low-frequency vibration suppression frequency + + 0 + 200 + 100 + + + + + ro + + + + #x200A + Error and Protection Parameter + 故障与保护参数 + DT200A + 1536 + + + SubIndex 000 + + 60 + + + + Power inputphase loss protection disable + + 0 + 1 + 0 + + + + Absolute position limit set + + 0 + 2 + 0 + + + + Motor overload protection gain + + 50 + 300 + 100 + + + + Overspeed threshold + + 0 + 20000 + 0 + + + + Local following error window + + 0 + 4294967295 + 27486951 + + + + Runaway protection enable + + 0 + 1 + 1 + + + + Over Temperature value of IPM + + 120 + 175 + 140 + + + + Touch Probe 1 filter time constant + + 0 + 630 + 200 + + + + Touch Probe 2 filter time constant + + 0 + 630 + 200 + + + + Filter time constant of TZ signal + + 0 + 31 + 15 + + + + Motor overload shielding + + 0 + 1 + 0 + + + + Speed DO Filter time constant + + 0 + 5000 + 50 + + + + Full Closed-loop(ABZ) Filter time constant + + 0 + 255 + 15 + + + + Overheat protection time duration for locked rotor + + 10 + 65535 + 200 + + + + Overheat protection for locked rotor enable + + 0 + 1 + 1 + + + + Absolute Encode multi-turns error forbidden + + 0 + 1 + 0 + + + + Compensation Function + + 0 + 15 + 6 + + + + Over Temperature value of discharge tube + + 100 + 175 + 115 + + + + Encoder communiction error threshold + + 0 + 31 + 5 + + + + Phase lack threshold + + 3 + 36 + 20 + + + + Over Temperature value of Encoder + + 0 + 175 + 125 + + + + TouchProbe DI Turn-on Compensation Time + + -3000 + 3000 + 200 + + + + TouchProbe DI Turn-off Compensation Time + + -3000 + 3000 + 1512 + + + + Runaway current threshold + + 1000 + 4000 + 2000 + + + + Fault reset delay time + + 0 + 60000 + 10000 + + + + Runaway speed threshold + + 1 + 1000 + 50 + + + + Runaway speed filter time constant + + 1 + 1000 + 20 + + + + Runaway protection time window + + 10 + 1000 + 30 + + + + BlackBox Mode Select + + 0 + 3 + 1 + + + + BlackBox Selected Error Code + + 0 + 65535 + 0 + + + + BlackBox Trig Source + + 0 + 25 + 0 + + + + BlackBox Trig Level + + -2147483648 + 2147483647 + 0 + + + + BlackBox Trig Level Select + + 0 + 3 + 0 + + + + BlackBox Trig Position + + 0 + 100 + 75 + + + + BlackBox Trig Frequency Select + + 0 + 2 + 0 + + + + The 2nd over speed threshold + + 0 + 20000 + 0 + + + + Motor over load monitor switch + + 0 + 65535 + 4098 + + + + Maximum ramp stop time + + 0 + 65535 + 10000 + + + + STO Disconnect filter time + + 1 + 5 + 5 + + + + STO Mismatch filter time + + 1 + 1000 + 100 + + + + STO Servo off filter time + + 0 + 25 + 20 + + + + Motor Offline Trq Limit + + 40 + 4000 + 50 + + + + Motor Offline Filter Time + + 5 + 1000 + 30 + + + + Filter Time Constant of Spd Display + + 0 + 100 + 0 + + + + Filter Time Constant of Trq Display + + 0 + 100 + 0 + + + + Filter Time Constant of Position Display + + 0 + 100 + 0 + + + + Filter Time Constant of Voltage Display + + 0 + 250 + 0 + + + + Filter Time Constant of Temp Display + + 0 + 250 + 0 + + + + + ro + + + + #x200B + Display Parameters + 显示参数 + DT200B + 1584 + + + Number of Entries + + 92 + + + + Actual motor rotational speed + + 0 + + + + Speed reference + + 0 + + + + Internal torque reference + + 0 + + + + Monitored DI states + + 0 + + + + Monitored DO states + + 0 + + + + Absolute position counter + + 0 + + + + Mechanical angle + + 0 + + + + Electrical angle + + 0 + + + + Average load rate + + 0 + + + + Encoder position deviation counter + + 0 + + + + Feedback pulse counter + + 0 + + + + Total power-on time + + 0 + + + + AI1 Voltage DisPlay + + 0 + + + + Phase current valid value + + 0 + + + + Bus voltage + + 0 + + + + Module temperature + + 0 + + + + Absolute encoder fault info. from FPGA + + 0 + + + + Axis state from FPGA + + 0 + + + + Axis fault info. from FPGA + + 0 + + + + Encoder internal fault info. + + 0 + + + + Displayed fault record + + 0 + 19 + 0 + + + + Fault code + + 0 + + + + Time stamp upon displayed fault + + 0 + + + + Current rotational speed upon displayed fault + + 0 + + + + Current U upon displayed fault + + 0 + + + + Current V upon displayed fault + + 0 + + + + Bus voltage upon displayed fault + + 0 + + + + Input terminal state upon displayed fault + + 0 + + + + Output terminal state upon displayed fault + + 0 + + + + Inner error code + + 0 + + + + Fault message of absolute encode from Fpga upon displayed + + 0 + + + + System state from Fpga upon displayed fault + + 0 + + + + System fault message from Fpga upon displayed fault + + 0 + + + + Encode state 1 upon displayed fault + + 0 + + + + Inner error code upon displayed fault + + 0 + + + + Fpga overtime state upon displayed fault + + 0 + + + + Reference position deviation + + 0 + + + + Actual motor rotational speed(0.1rpm) + + 0 + + + + Control bus voltage + + 0 + + + + Mechanical absolute position inc(Low) + + 0 + + + + Mechanical absolute position inc(High) + + 0 + + + + Not ready reason + + 0 + + + + Encoder temperature + + 0 + + + + Discharge load rate + + 0 + + + + Fpga over time state + + 0 + + + + Number of turns of absolute encode + + 0 + + + + Single feedback postion of absolute encode + + 0 + + + + System Error + + 0 + + + + feedback postion of absolute encode(Low) + + 0 + + + + feedback postion of absolute encode(High) + + 0 + + + + feedback postion inc of rotating load(Low) + + 0 + + + + feedback postion inc of rotating load(High) + + 0 + + + + Single feedback postion of rotating load + + 0 + + + + IGBT Temperature + + 0 + + + + Group of unusual function code + + 0 + + + + Offset of unusual function code + + 0 + + + + Single Power-On Time + + 0 + + + + Single Power-On Time upon displayed fault + + 0 + + + + + ro + + + + #x200D + Auxiliary Function Parameters + 辅助功能参数 + DT200D + 400 + + + Number of Entries + + 21 + + + + Software reset + + 0 + 1 + 0 + + + + Fault reset + + 0 + 1 + 0 + + + + Encoder ROM reading/writing + + 0 + 3 + 0 + + + + Emergency stop + + 0 + 1 + 0 + + + + AI1 Self-Adjust of Voltage Offset + + 0 + 1 + 0 + + + + UV phase current auto-tuning + + 0 + 1 + 0 + + + + Forced DI/DO setting + + 0 + 3 + 0 + + + + Forced DI level + + 0 + 31 + 31 + + + + Forced DO setting + + 0 + 3 + 0 + + + + Absolute Encode Fault Reset + + 0 + 2 + 0 + + + + Cogging torque self-learning + + 0 + 1 + 0 + + + + + ro + + + + #x200E + Communication parameters + 通信参数 + DT200E + 1568 + + + Number of Entries + + 97 + + + + Node address + + 1 + 127 + 1 + + + + Update function code values written via communication to EEPROM + + 0 + 4 + 4 + + + + station auto inc address + + 0 + 65535 + 0 + + + + station alias + + 0 + 65535 + 0 + + + + Sync lost window + + 1 + 20 + 8 + + + + Sync lost counter + + 0 + 65535 + 0 + + + + Port 0 invalid frame counter + + 0 + 65535 + 0 + + + + Port 1 invalid frame counter + + 0 + 65535 + 0 + + + + Port 0/1 transfer error counter + + 0 + 65535 + 0 + + + + process unit and PDI error counter + + 0 + 255 + 0 + + + + Port 0/1 lost counter + + 0 + 65535 + 0 + + + + Sync mode set + + 0 + 2 + 2 + + + + Sync error window + + 100 + 4000 + 4000 + + + + EtherCAT network state and link state + + 0 + 65535 + 0 + + + + CSP postion increment over counter + + 1 + 30 + 20 + + + + ECAT AL Error Code + + 0 + 65535 + 0 + + + + Enhanced link detection enable + + 0 + 1 + 0 + + + + Reset EtherCAT xml file + + 0 + 1 + 0 + + + + EtherCAT port control mode and state display + + 0 + 65535 + 0 + + + + EtherCAT COE version number + + 0 + 65535 + 0 + + + + EtherCAT xml file version number + + 0 + 65535 + 0 + + + + + ro + + + + #x200F + Closed Loop Function + 全闭环功能 + DT200F + 720 + + + SubIndex 000 + + 26 + + + + Encoder feedback mode + + 0 + 2 + 0 + + + + Running mode of external encoder + + 0 + 1 + 0 + + + + SecEncoder Absolute system selection + + 0 + 1 + 0 + + + + SecEncoder Type selection + + 0 + 2 + 0 + + + + External encoder pulses per motor revolution + + 0 + 2147483647 + 100000 + + + + Hybrid deviation excess setting + + 0 + 2147483647 + 10000 + + + + Hybrid deviation clear setting + + 0 + 100 + 1 + + + + First-order lowpass filter time of external/internal deviation + + 0 + 65535 + 0 + + + + Hybrid deviation counter + + -2147483648 + 2147483647 + 0 + + + + Pulse feedback display of internal encoder + + -2147483648 + 2147483647 + 0 + + + + Pulse feedback display of external encoder + + -2147483648 + 2147483647 + 0 + + + + SecEncoder Pulse ZPhase Ignore + + 0 + 1 + 0 + + + + SecEncoder Pulse Z-TouchProbe Selection + + 0 + 1 + 0 + + + + + ro + + + + #x2012 + MultiSpd Function + 多段速功能 + DT2012 + 1104 + + + SubIndex 000 + + 59 + + + + MultiSpd Function Select + + 0 + 2 + 1 + + + + MultiSpd Final Part Select + + 1 + 16 + 16 + + + + Time Uint of Runing + + 0 + 1 + 0 + + + + AccTime1 + + 0 + 65535 + 10 + + + + DecTime1 + + 0 + 65535 + 10 + + + + AccTime2 + + 0 + 65535 + 50 + + + + DecTime2 + + 0 + 65535 + 50 + + + + AccTime3 + + 0 + 65535 + 100 + + + + DecTime3 + + 0 + 65535 + 100 + + + + AccTime4 + + 0 + 65535 + 150 + + + + DecTime4 + + 0 + 65535 + 150 + + + + 1st Part Spd Cmd + + -10000 + 10000 + 0 + + + + 1st Part Spd Runing Time + + 0 + 65535 + 50 + + + + 1st Part AccDec Time Select + + 0 + 4 + 0 + + + + 2nd Part Spd Cmd + + -10000 + 10000 + 100 + + + + 2nd Part Spd Runing Time + + 0 + 65535 + 50 + + + + 2nd Part AccDec Time Select + + 0 + 4 + 0 + + + + 3rd Part Spd Cmd + + -10000 + 10000 + 300 + + + + 3rd Part Spd Runing Time + + 0 + 65535 + 50 + + + + 3rd Part AccDec Time Select + + 0 + 4 + 0 + + + + 4th Part Spd Cmd + + -10000 + 10000 + 500 + + + + 4th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 4th Part AccDec Time Select + + 0 + 4 + 0 + + + + 5th Part Spd Cmd + + -10000 + 10000 + 700 + + + + 5th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 5th Part AccDec Time Select + + 0 + 4 + 0 + + + + 6th Part Spd Cmd + + -10000 + 10000 + 900 + + + + 6th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 6th Part AccDec Time Select + + 0 + 4 + 0 + + + + 7th Part Spd Cmd + + -10000 + 10000 + 600 + + + + 7th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 7th Part AccDec Time Select + + 0 + 4 + 0 + + + + 8th Part Spd Cmd + + -10000 + 10000 + 300 + + + + 8th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 8th Part AccDec Time Select + + 0 + 4 + 0 + + + + 9th Part Spd Cmd + + -10000 + 10000 + 100 + + + + 9th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 9th Part AccDec Time Select + + 0 + 4 + 0 + + + + 10th Part Spd Cmd + + -10000 + 10000 + -100 + + + + 10th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 10th Part AccDec Time Select + + 0 + 4 + 0 + + + + 11th Part Spd Cmd + + -10000 + 10000 + -300 + + + + 11th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 11th Part AccDec Time Select + + 0 + 4 + 0 + + + + 12th Part Spd Cmd + + -10000 + 10000 + -500 + + + + 12th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 12th Part AccDec Time Select + + 0 + 4 + 0 + + + + 13th Part Spd Cmd + + -10000 + 10000 + -700 + + + + 13th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 13th Part AccDec Time Select + + 0 + 4 + 0 + + + + 14th Part Spd Cmd + + -10000 + 10000 + -900 + + + + 14th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 14th Part AccDec Time Select + + 0 + 4 + 0 + + + + 15th Part Spd Cmd + + -10000 + 10000 + -600 + + + + 15th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 15th Part AccDec Time Select + + 0 + 4 + 0 + + + + 16th Part Spd Cmd + + -10000 + 10000 + -300 + + + + 16th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 16th Part AccDec Time Select + + 0 + 4 + 0 + + + + + ro + + + + #x2017 + VDI VDO + 虚拟DI、DO + DT2017 + 1520 + + + SubIndex 000 + + 68 + + + + SubIndex 000 + + 65 + + + + VDI1 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI1 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI2 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI2 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI3 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI3 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI4 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI4 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI5 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI5 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI6 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI6 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI7 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI7 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI8 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI8 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI9 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI9 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI10 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI10 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI11 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI11 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI12 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI12 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI13 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI13 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI14 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI14 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI15 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI15 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI16 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI16 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDO virtual level + + 0 + 65535 + 0 + + + + VDO1 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO1 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO2 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO2 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO3 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO3 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO4 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO4 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO5 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO5 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO6 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO6 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO7 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO7 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO8 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO8 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO9 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO9 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO10 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO10 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO11 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO11 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO12 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO12 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO13 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO13 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO14 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO14 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO15 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO15 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO16 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO16 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDI Enable + + 0 + 1 + 0 + + + + VDI Default Value + + 0 + 65535 + 0 + + + + VDO Enable + + 0 + 1 + 0 + + + + VDO Default Value + + 0 + 65535 + 0 + + + + + ro + + + + #x2018 + Position Comparison + 位置比较参数 + DT2018 + 288 + + + SubIndex 000 + + 17 + + + + Enable Comparison + + 0 + + + + Comparison PosFdb Source Select + + 0 + 1 + 0 + + + + Encoder Resolution + + 0 + 7 + 1 + + + + Mode Of Comparison + + 0 + 2 + 0 + + + + Current Position As Zero + + 0 + 1 + 0 + + + + Output Duration + + 1 + 2047 + 1 + + + + Comparison ABZ OutPut Logic + + 0 + 65535 + 0 + + + + Starting Point Number + + 0 + 40 + 0 + + + + Ending Point Number + + 0 + 40 + 0 + + + + Comparison Status + + 0 + 1024 + 0 + + + + Current Position + + -2147483648 + 2147483647 + 0 + + + + Position Offset + + -2147483648 + 2147483647 + 0 + + + + Comparison OutPut Delay Compensation + + -1200 + 1200 + 0 + + + + Lilited number of Comparison Cycle Times + + 1 + 65535 + 1 + + + + Comparison ABZ OutPut Function + + 0 + 65535 + 0 + + + + + ro + + + + #x2019 + Comparing Points + 位置比较点 + DT2019 + 1936 + + + SubIndex 000 + + 120 + + + + 1st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 1st Point Property + + 0 + + + + 2nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 2nd Point Property + + 0 + + + + 3rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 3rd Point Property + + 0 + + + + 4th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 4th Point Property + + 0 + + + + 5th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 5th Point Property + + 0 + + + + 6th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 6th Point Property + + 0 + + + + 7th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 7th Point Property + + 0 + + + + 8th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 8th Point Property + + 0 + + + + 9th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 9th Point Property + + 0 + + + + 10th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 10th Point Property + + 0 + + + + 11th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 11th Point Property + + 0 + + + + 12th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 12th Point Property + + 0 + + + + 13th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 13th Point Property + + 0 + + + + 14th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 14th Point Property + + 0 + + + + 15th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 15th Point Property + + 0 + + + + 16th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 16th Point Property + + 0 + + + + 17th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 17th Point Property + + 0 + + + + 18th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 18th Point Property + + 0 + + + + 19th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 19th Point Property + + 0 + + + + 20th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 20th Point Property + + 0 + + + + 21st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 21st Point Property + + 0 + + + + 22nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 22nd Point Property + + 0 + + + + 23rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 23rd Point Property + + 0 + + + + 24th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 24th Point Property + + 0 + + + + 25th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 25th Point Property + + 0 + + + + 26th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 26th Point Property + + 0 + + + + 27th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 27th Point Property + + 0 + + + + 28th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 28th Point Property + + 0 + + + + 29th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 29th Point Property + + 0 + + + + 30th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 30th Point Property + + 0 + + + + 31st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 31st Point Property + + 0 + + + + 32nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 32nd Point Property + + 0 + + + + 33rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 33rd Point Property + + 0 + + + + 34th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 34th Point Property + + 0 + + + + 35th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 35th Point Property + + 0 + + + + 36th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 36th Point Property + + 0 + + + + 37th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 37th Point Property + + 0 + + + + 38th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 38th Point Property + + 0 + + + + 39th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 39th Point Property + + 0 + + + + 40th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 40th Point Property + + 0 + + + + + ro + + + + #x2030 + Comm Read Servo Variable + 通讯读取相关变量 + DT2030 + 64 + + + SubIndex 000 + + 3 + + + + Servo Status + + 0 + 65535 + 0 + + + + DO Function1 + + 0 + 65535 + 0 + + + + DO Function2 + + 0 + 65535 + 0 + + + + + ro + + + + #x2031 + Comm Set Servo Variable + 通讯给定相关变量 + DT2031 + 224 + + + SubIndex 000 + + 5 + + + + Comm Set VDI + + 0 + 65535 + 0 + + + + Comm Set DO + + 0 + 65535 + 0 + + + + Comm Set AO + + -10000 + 10000 + 0 + + + + Comm Set Local SpdRef + + -9000000 + 9000000 + 0 + + + + Comm Set Local TrqRef + + -100000 + 100000 + 0 + + + + + ro + + + + #x203F + Manufacturor Error code + 伺服故障码 + UDINT + 32 + + #x00000000 + #xFFFFFFFF + #x00000000 + + + ro + T + + + + #x603F + Error code + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + ro + T + + + + #x6040 + Control word + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + rw + R + + + + #x6041 + Status word + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + ro + T + + + + #x605A + Quick stop option code + INT + 16 + + #x0000 + #x0007 + #x0002 + + + rw + + + + #x605C + Disable operation option code + INT + 16 + + #xFFFC + #x0002 + #x0000 + + + rw + + + + #x605D + Halt option Code + INT + 16 + + #x0001 + #x0003 + #x0001 + + + rw + + + + #x605E + Fault Reaction option Code + INT + 16 + + #xFFFB + #x0004 + #x0002 + + + rw + + + + #x6060 + Modes of operation + SINT + 8 + + 0 + 10 + 0 + + + rw + R + + + + #x6061 + Modes of operation display + SINT + 8 + + 0 + 10 + 0 + + + ro + T + + + + #x6062 + Position demand value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6063 + Position actual internal value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6064 + Position actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6065 + Following error window + UDINT + 32 + + #x0 + #xFFFFFFFF + #x1A36AE7 + + + rw + R + + + + #x6066 + Following error time out + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x6067 + Position window + UDINT + 32 + + #x0 + #xFFFFFFFF + #x16F0 + + + rw + R + + + + #x6068 + Position window time + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x606C + Velocity actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + 0 + + + ro + T + + + + #x606D + Velocity window + UINT + 16 + + #x0000 + #xFFFF + #xA + + + rw + R + + + + #x606E + Velocity window time + UINT + 16 + + #x0000 + #xFFFF + #x0 + + + rw + + + + #x606F + Velocity threshold + UINT + 16 + + #x0000 + #xFFFF + #xA + + + rw + R + + + + #x6070 + Velocity threshold time + UINT + 16 + + #x0000 + #xFFFF + #x0 + + + rw + + + + #x6071 + Target torque + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + rw + R + + + + #x6072 + Max Torque + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x6074 + Torque demand + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + ro + T + + + + #x6077 + Torque actual value + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + ro + T + + + + #x607A + Target position + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x607C + Home offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x607D + Software position limit + DT607D + 80 + + + SubIndex 000 + + #x02 + + + + Min position limit + + #x80000000 + #x7FFFFFFF + #x80000000 + + + + Max position limit + + #x80000000 + #x7FFFFFFF + #x7FFFFFFF + + + + + ro + + + + #x607E + Polarity + USINT + 8 + + #x0 + #xFF + #x0 + + + rw + R + + + + #x607F + Max profile velocity + UDINT + 32 + + #x0 + #xFFFFFFFF + #x32000000 + + + rw + R + + + + #x6081 + Profile velocity + UDINT + 32 + + #x0 + #xFFFFFFFF + #xD55555 + + + rw + R + + + + #x6083 + Profile acceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x6084 + Profile deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x6085 + Quick stop deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x7FFFFFFF + + + rw + R + + + + #x6086 + Motion profile type + INT + 16 + + #x8000 + #x7FFF + #x0 + + + rw + R + + + + #x6087 + Torque slope + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x6091 + Gear ratio + DT6091 + 80 + + + SubIndex 000 + + #x02 + + + + Motor revolutions + + #x1 + #xFFFFFFFF + #x1 + + + + Shaft revolutions + + #x1 + #xFFFFFFFF + #x1 + + + + + ro + + + + #x6098 + Homing method + SINT + 8 + + #xFD + #x23 + 1 + + + rw + R + + + + #x6099 + Homing speeds + DT6099 + 80 + + + SubIndex 000 + + #x02 + + + + Speed during search for switch + + 0 + #xFFFFFFFF + #xD55555 + + + + Speed during search for zero + + 0 + #xFFFFFFFF + #x155555 + + + + + ro + + + + #x609A + Homing acceleration + UDINT + 32 + + 0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x60B0 + Position offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x60B1 + Velocity offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x60B2 + Torque offset + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + rw + R + + + + #x60B8 + Touch probe function + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x60B9 + Touch Probe Status + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60BA + Touch probe 1 positive edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BB + Touch probe 1 negative edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BC + Touch probe 2 positive edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BD + Touch probe 2 negative edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60C5 + Max Acceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x60C6 + Max Deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x60D5 + Touch probe 1 positive edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D6 + Touch probe 1 negative edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D7 + Touch probe 2 positive edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D8 + Touch probe 2 negative edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60E0 + Positive torque limit value + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x60E1 + Negative torque limit value + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x60E3 + Supported homing methods + DT60E3 + 544 + + + SubIndex 000 + + #x0 + #x22 + 33 + + + + Support homing method 1 + + #x01 + + + + Support homing method 2 + + #x02 + + + + Support homing method 3 + + #x03 + + + + Support homing method 4 + + #x04 + + + + Support homing method 5 + + #x05 + + + + Support homing method 6 + + #x06 + + + + Support homing method 7 + + #x07 + + + + Support homing method 8 + + #x08 + + + + Support homing method 9 + + #x09 + + + + Support homing method 10 + + #x0A + + + + Support homing method 11 + + #x0B + + + + Support homing method 12 + + #x0C + + + + Support homing method 13 + + #x0D + + + + Support homing method 14 + + #x0E + + + + Support homing method 15 + + #x11 + + + + Support homing method 16 + + #x12 + + + + Support homing method 17 + + #x13 + + + + Support homing method 18 + + #x14 + + + + Support homing method 19 + + #x15 + + + + Support homing method 20 + + #x16 + + + + Support homing method 21 + + #x17 + + + + Support homing method 22 + + #x18 + + + + Support homing method 23 + + #x19 + + + + Support homing method 24 + + #x1A + + + + Support homing method 25 + + #x1B + + + + Support homing method 26 + + #x1C + + + + Support homing method 27 + + #x1D + + + + Support homing method 28 + + #x1E + + + + Support homing method 29 + + #x21 + + + + Support homing method 30 + + #x22 + + + + Support homing method 31 + + #x23 + + + + Support homing method 32 + + #xFF + + + + Support homing method 33 + + #xFE + + + + + ro + + + + #x60F4 + Following error actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60FC + Position demand internal value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60FD + Digital inputs + UDINT + 32 + + #x0 + #xFFFFFFFF + #x0 + + + ro + T + + + + #x60FE + Digital outputs + DT60FE + 80 + + + SubIndex 000 + + #x02 + + + + Physical outputs + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + Bit Mask + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + ro + + + + #x60FF + Target velocity + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x6502 + Supported drive modes + UDINT + 32 + + #x00000000 + #xFFFFFFFF + #x000003AD + + + ro + + + + + + Outputs + Inputs + MBoxState + MBoxOut + MBoxIn + Outputs + Inputs + + #x1600 + Outputs + #x1601 + #x1701 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + + #x1601 + Outputs + #x1600 + #x1701 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x607A + 0 + 32 + Target position + DINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + #x6081 + 0 + 32 + profile velocity + UDINT + + + #x6083 + 0 + 32 + profile acceleration + UDINT + + + #x6084 + 0 + 32 + profile deceleration + UDINT + + + #x6087 + 0 + 32 + Torque Slope + UDINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + + #x1701 + Outputs + #x1600 + #x1601 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60FE + 1 + 32 + Physical outputs + UDINT + + + + #x1702 + Outputs + #x1600 + #x1601 + #x1701 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + + #x1703 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + + #x1704 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1703 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + + #x1705 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1703 + #x1704 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + #x60B2 + 0 + 16 + Torque offset + INT + + + + #x1A00 + Inputs + #x1A01 + #x1B01 + #x1B02 + #x1B03 + #x1B04 + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x603F + 0 + 16 + Error code + UINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1A01 + Inputs + #x1A00 + #x1B01 + #x1B02 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x606C + 0 + 32 + Velocity actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B01 + Inputs + #x1A00 + #x1A01 + #x1B02 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B02 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B03 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B02 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B04 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B02 + #x1B03 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x606C + 0 + 32 + Velocity actual value + DINT + + + + + + + PS + #x6060 + 0 + 08 + Modes of operation + + + + + + DC + DC-Sync + #x300 + 0 + 0 + 0 + + + Synchron + FreeRun + #x0 + + + + 2048 + 080C0004640000000000 + + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + From f6e134095b5c67de53632cf269a74d0dc93ad9eb Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Tue, 17 Sep 2024 10:24:46 -0500 Subject: [PATCH 055/121] add SV670N py/yaml, disable duplicate xml tag --- .../devices/device_err/inovance_sv670n.yaml | 566 ++++++++++++++++++ .../SV670_EOE_1Axis_05003_220801.xml | 2 + hw_device_mgr/devices/inovance_sv670.py | 21 + 3 files changed, 589 insertions(+) create mode 100644 hw_device_mgr/devices/device_err/inovance_sv670n.yaml create mode 100644 hw_device_mgr/devices/inovance_sv670.py diff --git a/hw_device_mgr/devices/device_err/inovance_sv670n.yaml b/hw_device_mgr/devices/device_err/inovance_sv670n.yaml new file mode 100644 index 00000000..7384f3f3 --- /dev/null +++ b/hw_device_mgr/devices/device_err/inovance_sv670n.yaml @@ -0,0 +1,566 @@ +# From Inovance SV660N "Advanced User Guide" 2020-10-20, table 10.2 +# "Communication Faults and Warning Codes" +# +# Parameter 603Fh shows the basic error code, but the +# manufacturer-specific SV660N parameter 203Fh "Manufacturer fault +# code" shows an extended error value. The manual's table 10.2 shows +# e.g. "fault" E101, with "display" broken down into E101.0 and E101.1 +# with different "name" and occasional differences in "fault range" +# column ("type" and "resettable or not" columns appear not to +# change). +# +# key: "Auxiliary Code" column most significant word +# display: "Display" column; code displayed on drive LED panel +# description: "Name" column +# type: "Type" column; indicates severity, with 1 most severe +# resettable: "Resettable" column; indicates whether resettable +# without power cycle + +# +# List of fault codes +# +'0x0101': + display: E101.0 + description: System parameter error + type: 1 + resettable: false +'0x1101': + display: E101.1 + description: 2000h/2001h parameter error + type: 1 + resettable: false +'0x0102': + display: E102.0 + description: FPGA communication initialization error + type: 1 + resettable: false +'0x8102': + display: E102.8 + description: Software version mismatch + type: 1 + resettable: false +'0x1104': + display: E104.1 + description: MCU operation timeout + type: 1 + resettable: false +'0x2104': + display: E104.2 + description: Current loop operation timeout + type: 1 + resettable: false +'0x4104': + display: E104.4 + description: MCU reference update timeout + type: 1 + resettable: false +'0x0108': + display: E108.0 + description: Parameter write error + type: 1 + resettable: true +'0x1108': + display: E108.1 + description: Parameter read error + type: 1 + resettable: true +'0x2108': + display: E108.2 + description: Invalid check on data written in EEPROM + type: 1 + resettable: true +'0x3108': + display: E108.3 + description: Invalid check on data read in EEPROM + type: 1 + resettable: true +'0x0120': + display: E120.0 + description: Unknown encoder type + type: 1 + resettable: false +'0x1120': + display: E120.1 + description: Unknown motor model + type: 1 + resettable: false +'0x2120': + display: E120.2 + description: Unknown drive model + type: 1 + resettable: false +'0x5120': + display: E120.5 + description: Motor current and drive current mismatch + type: 1 + resettable: false +'0x6120': + display: E120.6 + description: FPGA and motor model mismatch + type: 1 + resettable: false +'0x0122': + display: E122.0 + description: Multi-turn absolute encoder setting error + type: 2 + resettable: true +'0x1122': + display: E122.1 + description: Different DIs allocated with the same function + type: 2 + resettable: true +'0x3122': + display: E122.3 + description: Upper limit invalid + type: 2 + resettable: true +'0x0136': + display: E136.0 + description: Encoder parameter error + type: 1 + resettable: false +'0x1136': + display: E136.1 + description: Encoder communication error + type: 1 + resettable: false +'0x0140': + display: E140.0 + description: Encryption chip check error + type: 1 + resettable: false +'0x1140': + display: E140.1 + description: Encryption chip check failure + type: 1 + resettable: false +'0x0150': + display: E150.0 + description: STO signal input protection activated + type: 1 + resettable: true +'0x1150': + display: E150.1 + description: STO signal input error + type: 1 + resettable: true +'0x2150': + display: E150.2 + description: Abnormal voltage detected + type: 1 + resettable: true +'0x3150': + display: E150.3 + description: STO upstream optocoupler detection failure + type: 1 + resettable: true +'0x4150': + display: E150.4 + description: PWM Buffer detection failure + type: 1 + resettable: true +'0x0201': + display: E201.0 + description: Phase-P overcurrent + type: 1 + resettable: false +'0x1201': + display: E201.1 + description: Phase-U overcurrent + type: 1 + resettable: false +'0x2201': + display: E201.2 + description: Phase-V overcurrent + type: 1 + resettable: false +'0x4201': + display: E201.4 + description: Phase-N overcurrent + type: 1 + resettable: false +'0x0208': + display: E208.0 + description: MCU position reference updated frequently + type: 1 + resettable: true +'0x2208': + display: E208.2 + description: Encoder communication timeout + type: 1 + resettable: true +'0x3208': + display: E208.3 + description: Current sampling fault + type: 1 + resettable: true +'0x4208': + display: E208.4 + description: FPGA current loop operation timeout + type: 1 + resettable: true +'0x0210': + display: E210.0 + description: Output shorted to ground + type: 1 + resettable: false +'0x0234': + display: E234.0 + description: Runaway protection + type: 1 + resettable: false +'0x0400': + display: E400.0 + description: Main circuit overvoltage + type: 1 + resettable: true +'0x0410': + display: E410.0 + description: Main circuit undervoltage + type: 1 + resettable: true +'0x0420': + display: E420.0 + description: Phase loss fault + type: 2 + resettable: true +'0x0430': + display: E430.0 + description: Control circuit undervoltage + type: 2 + resettable: true +'0x0500': + display: E500.0 + description: Motor overspeed + type: 1 + resettable: true +'0x1500': + display: E500.1 + description: Speed feedback overflow + type: 1 + resettable: true +'0x2500': + display: E500.2 + description: FPGA position feedback pulse overspeed + type: 1 + resettable: true +'0x0602': + display: E602.0 + description: Angle auto-tuning error + type: 1 + resettable: true +'0x2602': + display: E602.2 + description: Wrong UVW phase sequence detected during angle auto-tuning + type: 1 + resettable: true +'0x0605': + display: E605.0 + description: Speed upon S-ON too high + type: 1 + resettable: true +'0x0620': + display: E620.0 + description: Motor overload + type: 1 + resettable: true +'0x0630': + display: E630.0 + description: Motor stall + type: 1 + resettable: true +'0x0640': + display: E640.0 + description: IGBT over-temperature + type: 1 + resettable: true +'0x1640': + display: E640.1 + description: Flywheel diode over-temperature + type: 1 + resettable: true +'0x0650': + display: E650.0 + description: Heatsink over-temperature + type: 1 + resettable: true +'0x0660': + display: E660.0 + description: Air-cooled motor over-temperature + type: 1 + resettable: true +'0x0661': + display: E661.0 + description: Auto-tuned gain values too low + type: 2 + resettable: true +'0x0731': + display: E731.0 + description: Encoder battery failure + type: 2 + resettable: true +'0x0733': + display: E733.0 + description: Encoder multi-turn counting error + type: 2 + resettable: true +'0x0735': + display: E735.0 + description: Encoder multi-turn counting overflow + type: 2 + resettable: true +'0x2740': + display: E740.2 + description: Absolute encoder error + type: 1 + resettable: false +'0x3740': + display: E740.3 + description: Absolute encoder single-turn calculation error + type: 1 + resettable: false +'0x6740': + display: E740.6 + description: Encoder write error + type: 1 + resettable: false +'0x0755': + display: E755.0 + description: Nikon encoder communication failure + type: 1 + resettable: false +'0x0760': + display: E760.0 + description: Encoder over-temperature + type: 2 + resettable: true +'0x0765': + display: E765.0 + description: Nikon encoder beyond the limit + type: 1 + resettable: false +'0x0B00': + display: EB00.0 + description: Position deviation too large + type: 2 + resettable: true +'0x1B00': + display: EB00.1 + description: Position deviation overflow + type: 2 + resettable: true +# (Note: out of numerical order in manual) +'0x0A33': + display: EA33.0 + description: Encoder read/write check error + type: 1 + resettable: false +'0x1B01': + display: EB01.1 + description: Position reference increment too large for once + type: 2 + resettable: true +'0x2B01': + display: EB01.2 + description: Position reference increment too large continuously + type: 2 + resettable: true +'0x3B01': + display: EB01.3 + description: Reference overflow + type: 2 + resettable: true +'0x4B01': + display: EB01.4 + description: Target position beyond upper/lower limit + type: 2 + resettable: true +'0x0E09': + display: EE09.0 + description: Software position limit setting error + type: 2 + resettable: true +'0x1E09': + display: EE09.1 + description: Home setting error + type: 2 + resettable: true +'0x2E09': + display: EE09.2 + description: Gear ratio beyond the limit + type: 2 + resettable: true +'0x3E09': + display: EE09.3 + description: No synchronization signal + type: 2 + resettable: true +'0x5E09': + display: EE09.5 + description: PDO mapping beyond the limit + type: 2 + resettable: true +# (Note: EE08.0 out of order in manual) +'0x0E08': + display: EE08.0 + description: Synchronization loss + type: 2 + resettable: true +'0x1E08': + display: EE08.1 + description: Network status switchover error + type: 2 + resettable: true +'0x2E08': + display: EE08.2 + description: IRQ loss + type: 2 + resettable: true +'0x3E08': + display: EE08.3 + description: LAN cable connected improperly + type: 2 + resettable: true +'0x4E08': + display: EE08.4 + description: Data frame loss protection error + type: 2 + resettable: true +'0x5E08': + display: EE08.5 + description: Data frame transfer error + type: 2 + resettable: true +'0x6E08': + display: EE08.6 + description: Data update timeout + type: 2 + resettable: true +'0x0E11': + display: EE11.0 + description: ESI check error + type: 2 + resettable: true +'0x1E11': + display: EE11.1 + description: EEPROM read failure + type: 2 + resettable: true +'0x2E11': + display: EE11.2 + description: EEPROM update failure + type: 2 + resettable: true +'0x0E12': + display: EE12.0 + description: EtherCAT external device error + type: 1 + resettable: false +'0x0E13': + display: EE13.0 + description: Synchronization cycle setting error + type: 2 + resettable: true +'0x0E15': + display: EE15.0 + description: Number of synchronization cycle errors too large + type: 2 + resettable: true +# +# List of warning codes +# +'0x0121': + display: E121.0 + description: Invalid S-ON command + type: 3 + resettable: true +'0x0600': + display: E600.0 + description: Inertia auto-tuning failure + type: 3 + resettable: true +'0x0601': + display: E601.0 + description: Homing timeout + type: 3 + resettable: true +'0x1601': + display: E601.1 + description: Home switch error + type: 3 + resettable: true +'0x2601': + display: E601.2 + description: Homing mode setting error + type: 3 + resettable: true +'0x0730': + display: E730.0 + description: Encoder battery warning + type: 3 + resettable: true +'0x0900': + display: E900.0 + description: Emergency stop + type: 3 + resettable: true +'0x0902': + display: E902.0 + description: Invalid DI setting + type: 3 + resettable: true +'0x1902': + display: E902.1 + description: Invalid DO setting + type: 3 + resettable: true +'0x0908': + display: E908.0 + description: Model identification check byte invalid + type: 3 + resettable: true +'0x0909': + display: E909.0 + description: Motor overload warning + type: 3 + resettable: true +'0x0920': + display: E920.0 + description: Regenerative resistor overload + type: 3 + resettable: true +'0x0922': + display: E922.0 + description: Resistance of external regenerative resistor too small + type: 3 + resettable: true +'0x0924': + display: E924.0 + description: Braking transistor over-temperature + type: 3 + resettable: true +'0x0941': + display: E941.0 + description: Parameter modifications not activated + type: 3 + resettable: true +'0x0942': + display: E942.0 + description: Parameter saved frequently + type: 3 + resettable: true +'0x0950': + display: E950.0 + description: Forward overtravel warning + type: 3 + resettable: true +'0x0952': + display: E952.0 + description: Reverse overtravel warning + type: 3 + resettable: true +'0x0A41': + display: EA41.0 + description: Torque ripple compensation failure + type: 3 + resettable: true diff --git a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml index efd0483a..8d64dcd0 100644 --- a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml +++ b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml @@ -13630,12 +13630,14 @@ 68 + VDI1 Terminal Function Selection diff --git a/hw_device_mgr/devices/inovance_sv670.py b/hw_device_mgr/devices/inovance_sv670.py new file mode 100644 index 00000000..d8146387 --- /dev/null +++ b/hw_device_mgr/devices/inovance_sv670.py @@ -0,0 +1,21 @@ +from .inovance_sv660 import InovanceSV660Config, InovanceSV660, SimInovanceSV660 + +class InovanceSV670Config(InovanceSV660Config): + """Inovance SV670 servo drive config.""" + def maybe_later(self): + self.logger.info('do we even need this?') + +class InovanceSV670(InovanceSV660): + """Inovance SV670 servo drives.""" + vendor_id = 0x00100000 + product_code = 0x000C011E + xml_description_package = "hw_device_mgr.devices.device_xml" + xml_description_fname = "SV670_EOE_1Axis_05003_220801.xml" + device_error_package = "hw_device_mgr.devices.device_err" + device_error_yaml = "inovance_sv670n.yaml" + config_class = InovanceSV670Config + have_sto = True + +class SimInovanceSV670(SimInovanceSV660): + def maybe_later(self): + self.logger.info('do we even need this?') From a9f3fcb1db6a0cea983d806566d9a6a624b9b96c Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Wed, 18 Sep 2024 17:12:19 -0500 Subject: [PATCH 056/121] update sv670 py for sim --- hw_device_mgr/devices/inovance_sv670.py | 118 ++++++++++++++++++++++-- 1 file changed, 109 insertions(+), 9 deletions(-) diff --git a/hw_device_mgr/devices/inovance_sv670.py b/hw_device_mgr/devices/inovance_sv670.py index d8146387..0b07c5c4 100644 --- a/hw_device_mgr/devices/inovance_sv670.py +++ b/hw_device_mgr/devices/inovance_sv670.py @@ -1,12 +1,61 @@ -from .inovance_sv660 import InovanceSV660Config, InovanceSV660, SimInovanceSV660 +from ..ethercat.device import EtherCATDevice, EtherCATSimDevice +from ..ethercat.config import EtherCATConfig +from ..cia_402.device import CiA402Device, CiA402SimDevice +from ..errors.device import ErrorDevice +from functools import lru_cache +import time -class InovanceSV670Config(InovanceSV660Config): - """Inovance SV670 servo drive config.""" - def maybe_later(self): - self.logger.info('do we even need this?') -class InovanceSV670(InovanceSV660): +class InovanceSV670Config(EtherCATConfig): + """Inovance SV660 servo drive config.""" + + # Device params non-volatile setting in 200E-02h: + # 0: params not updated + # 1: 2000h series changed from serial or EtherCAT saved + # 2: 6000h series changed from EtherCAT (only) saved + # 3: 2000h and 6000h series changed from EtherCAT (only) saved + + def get_device_params_nv(self): + return self.config.upload("200E-02h") == 3 + + def set_device_params_nv(self, nv=True, dry_run=False): + curr_setting = self.get_device_params_nv() + if curr_setting != nv: + self.logger.info( + f"Setting params {'non' if nv else ''}volatile mode" + ) + self.config.download( + "200E-02h", (0, 3)[nv], force=True, dry_run=dry_run + ) + else: + self.logger.info( + f"Params already {'non' if nv else ''}volatile mode" + ) + + def clear_fault(self): + err_code = self.upload("203Fh") + self.logger.info(f"Resetting device fault; code: {err_code}") + time.sleep(0.5) # This may or may not be needed + self.download("200D-02h", 1) + time.sleep(0.5) # This may or may not be needed + err_code = self.upload("203Fh") + self.logger.info(f" After fault reset, code: {err_code}") + + def soft_reset(self): + self.logger.info("Performing soft reset on drive") + time.sleep(0.5) # This may or may not be needed + self.download("200D-01h", 1) + time.sleep(2.0) # Give the drive time to react + + def reset_error_and_restart(self): + self.logger.info(f"Queueing fault reset and rebooting drive") + self.enqueue_command(self.clear_fault) + self.enqueue_command(self.soft_reset) + + +class InovanceSV670(EtherCATDevice, CiA402Device, ErrorDevice): """Inovance SV670 servo drives.""" + vendor_id = 0x00100000 product_code = 0x000C011E xml_description_package = "hw_device_mgr.devices.device_xml" @@ -16,6 +65,57 @@ class InovanceSV670(InovanceSV660): config_class = InovanceSV670Config have_sto = True -class SimInovanceSV670(SimInovanceSV660): - def maybe_later(self): - self.logger.info('do we even need this?') + feedback_out_data_types = dict( + home_found="bit", + error_code="uint16", # Override uint32 + ) + feedback_out_overlap = {"error_code"} # Override uint32 + + feedback_out_defaults = dict( + home_found=False, + ) + + @classmethod + @lru_cache + def to_error_code_data_type(cls, value): + # Ignore least significant word, "manufacturer external fault code" + dt = cls.data_type_class.by_shared_name("uint16") + return dt(value >> 16) + + def get_error_code(self): + error_code = self.interface("feedback_in").get("error_code") + return self.to_error_code_data_type(error_code) + + def get_feedback(self): + fb_out = super().get_feedback() + sw = self.interface("feedback_in").get("status_word") + if self.test_sw_bit(sw, "MANUFACTURER_SPECIFIC_3"): # "Home found" + fb_out.update(home_found=True) + return fb_out + + def set_command(self, **kwargs): + cmd_out = super().set_command(**kwargs) + cmd_in = self._interfaces["command_in"] + fb_in = self._interfaces["feedback_in"] + if cmd_in.rising_edge("reset_fault"): + if fb_in.get("error_code") == 0x07310731: + self.config.reset_error_and_restart() + return cmd_out + + +class SimInovanceSV670(InovanceSV670, EtherCATSimDevice, CiA402SimDevice): + def set_sim_feedback(self): + # Simulate home_found feedback + sfb = super().set_sim_feedback() + sw, old_sw = sfb.changed("status_word", return_vals=True) + # In MODE_HM, OPERATION_MODE_SPECIFIC_1 is "homing attained" + homing_attained = False + if sfb.get("control_mode_fb") == self.MODE_HM: + homing_attained = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") + # SV660N: MANUFACTURER_SPECIFIC_3 (bit 15) is "Home found" + old_home_found = self.test_sw_bit(old_sw, "MANUFACTURER_SPECIFIC_3") + home_found = old_home_found or homing_attained + if home_found: + sw = self.add_status_word_flags(sw, MANUFACTURER_SPECIFIC_3=True) + sfb.update(status_word=sw) + return sfb From 8e8b89a7f6cb0d2d559fbb7e1bcf8159d629c58d Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Wed, 2 Oct 2024 13:19:05 -0500 Subject: [PATCH 057/121] PP-4571 - add missing SV670N params --- .../SV670_EOE_1Axis_05003_220801.xml | 246 +++++++++++++++++- 1 file changed, 236 insertions(+), 10 deletions(-) diff --git a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml index 8d64dcd0..d459cedc 100644 --- a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml +++ b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml @@ -2707,7 +2707,7 @@ 3 - DO2 function selection + DO2 Function Selection UINT 16 48 @@ -2725,6 +2725,26 @@ rw + + 5 + DO3 Function Selection + UINT + 16 + 80 + + rw + + + + 6 + DO3 Logic Level Selection + UINT + 16 + 96 + + rw + + 23 DO OutPut Source Select @@ -2809,6 +2829,26 @@ rw + + 8 + Numerator of electronic gear ratio + UDINT + 32 + 128 + + rw + + + + 10 + Denominator of electronic gear ratio + UDINT + 32 + 160 + + rw + + 18 Encoder frequency division pulses @@ -3013,6 +3053,26 @@ rw + + 9 + Forward speed threshold + UINT + 16 + 144 + + rw + + + + 10 + Reverse speed threshold + UINT + 16 + 160 + + rw + + 11 Quick decelaration coefficient @@ -3197,6 +3257,26 @@ rw + + 10 + Internal forward torque limit + UINT + 16 + 160 + + rw + + + + 11 + Internal reverse torque limit + UINT + 16 + 176 + + rw + + 16 Emergency stop torque @@ -3207,6 +3287,26 @@ rw + + 20 + Forward speed limit/Speed limit 1 in local torque control + UINT + 16 + 320 + + rw + + + + 21 + Reverse speed limit/Speed limit 2 in local torque control + UINT + 16 + 336 + + rw + + 22 Base value for torque reached @@ -4279,6 +4379,16 @@ rw + + 22 + STO Display Function Selection + UINT + 16 + 352 + + rw + + 24 Filter time constant of TZ signal @@ -4289,6 +4399,16 @@ rw + + 26 + Filter time of speed feedback display + UINT + 16 + 416 + + rw + + 27 Motor overload shielding @@ -5327,6 +5447,16 @@ rw + + 3 + Offline inertia autotuning selection + UINT + 16 + 48 + + rw + + 5 Encoder ROM reading/writing @@ -10729,7 +10859,7 @@ - DO2 function selection + DO2 Function Selection 0 65535 @@ -10744,6 +10874,22 @@ 0 + + DO3 Function Selection + + 0 + 65535 + 9 + + + + DO3 Logic Level Selection + + 0 + 1 + 0 + + DO OutPut Source Select @@ -10818,6 +10964,22 @@ 0 + + Numerator of electronic gear ratio + + 1 + 1073741824 + 1 + + + + Denominator of electronic gear ratio + + 1 + 1073741824 + 1 + + Encoder frequency division pulses @@ -10988,6 +11150,22 @@ 0 + + Forward speed threshold + + 0 + 10000 + 7000 + + + + Reverse speed threshold + + 0 + 10000 + 7000 + + Quick decelaration coefficient @@ -11142,6 +11320,22 @@ 27 + + Internal forward torque limit + + 0 + 4000 + 3500 + + + + Internal reverse torque limit + + 0 + 4000 + 3500 + + Emergency stop torque @@ -11150,6 +11344,22 @@ 1000 + + Forward speed limit/Speed limit 1 in local torque control + + 0 + 6000 + 3000 + + + + Reverse speed limit/Speed limit 2 in local torque control + + 0 + 6000 + 3000 + + Base value for torque reached @@ -12028,6 +12238,14 @@ 200 + + STO Display Function Selection + + 0 + 1 + 0 + + Filter time constant of TZ signal @@ -12036,6 +12254,14 @@ 15 + + Filter time of speed feedback display + + 0 + 5000 + 50 + + Motor overload shielding @@ -12742,6 +12968,14 @@ 0 + + Offline inertia autotuning selection + + 0 + 1 + 0 + + Encoder ROM reading/writing @@ -13630,14 +13864,6 @@ 68 - VDI1 Terminal Function Selection From 679dd0082f79c8a77e3073275dff23792325c8c1 Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Wed, 2 Oct 2024 17:33:01 -0500 Subject: [PATCH 058/121] add 2006-08h --- .../SV670_EOE_1Axis_05003_220801.xml | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml index d459cedc..ba6b927e 100644 --- a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml +++ b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml @@ -3053,6 +3053,16 @@ rw + + 8 + Maximum speed limit + UINT + 16 + 128 + + rw + + 9 Forward speed threshold @@ -11150,6 +11160,14 @@ 0 + + Maximum speed limit + + 0 + 10000 + 7000 + + Forward speed threshold From 07d63b65f190c9d69e5a3b4d47fd3f9f51906399 Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Mon, 14 Oct 2024 20:55:47 -0500 Subject: [PATCH 059/121] PP-4619 - ignore ecat alias 9999 --- hw_device_mgr/cia_301/command.py | 2 ++ hw_device_mgr/lcec/command.py | 2 ++ 2 files changed, 4 insertions(+) diff --git a/hw_device_mgr/cia_301/command.py b/hw_device_mgr/cia_301/command.py index 94de971e..234c881f 100644 --- a/hw_device_mgr/cia_301/command.py +++ b/hw_device_mgr/cia_301/command.py @@ -112,6 +112,8 @@ def scan_bus(self, bus=0): for dd in self.sim_device_data.values(): if dd["address"][0] != bus: continue + if dd["address"][2] == 9999: + continue res.append([dd["address"], dd["model_id"]]) return res diff --git a/hw_device_mgr/lcec/command.py b/hw_device_mgr/lcec/command.py index 519d295f..a108716a 100644 --- a/hw_device_mgr/lcec/command.py +++ b/hw_device_mgr/lcec/command.py @@ -62,6 +62,8 @@ def scan_bus(self, bus=None, **kwargs): alias = int(line.split(":", 1)[1].strip()) addr = device[-1][0:2] + (alias,) device[0] = addr + if alias == 9999: + del devices[-1] elif line.startswith("Vendor Id:"): # Vendor Id: 0x00100000 vi = line.split(":", 1)[1].strip() From 5a3aa2bf5a5cc32f6447dc77c0b55fc1ca2e9e4f Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Fri, 8 Nov 2024 10:29:10 -0600 Subject: [PATCH 060/121] PP-4605 - add PV and PT wrappers --- hw_device_mgr/cia_402/device.py | 177 ++++++++++++++++++++++++++++++-- 1 file changed, 171 insertions(+), 6 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index b80a1ffa..71c041a5 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -21,6 +21,8 @@ class CiA402Device(CiA301Device, ErrorDevice): - `home_request`: Command homing operation (HM mode) - `move_request`: Command move operation (PP mode) - `relative_target`: Relative vs Absolute move operation (PP mode) + - `velocity_request`: Command move operation (PV mode) + - `torque_request`: Command move operation (PT mode) Feedback parameters: - `home_success`: Drive completed homing successfully @@ -28,6 +30,9 @@ class CiA402Device(CiA301Device, ErrorDevice): - `move_setpoint_ack`: Drive acknowledges PP-mode `move_request` - `move_success`: Drive reports PP-mode move succeeded - `following_error`: Drive reports following error in various modes + - `velocity_success`: Drive reports PV-mode velocity reached + - `velocity_zero`: Drive reports zero speed in PV mode + - `torque_success`: Drive reports PT-mode torque reached """ data_types = CiA301DataType @@ -51,6 +56,8 @@ class CiA402Device(CiA301Device, ErrorDevice): home_timeout = 15 # seconds move_timeout = 15 # seconds + velocity_timeout = 15 # seconds + torque_timeout = 15 #seconds @classmethod def control_mode_str(cls, mode): @@ -83,8 +90,8 @@ def control_mode_str(cls, mode): REMOTE=9, TARGET_REACHED=10, INTERNAL_LIMIT_ACTIVE=11, - OPERATION_MODE_SPECIFIC_1=12, # HM=HOMING_ATTAINED, PP=SETPOINT_ACK - OPERATION_MODE_SPECIFIC_2=13, # HM=HOMING_ERROR; PP/CSP=FOLLOWING_ERROR + OPERATION_MODE_SPECIFIC_1=12, # HM=HOMING_ATTAINED, PP=SETPOINT_ACK, PV=STOPPED, PT=0 + OPERATION_MODE_SPECIFIC_2=13, # HM=HOMING_ERROR, PP/CSP=FOLLOWING_ERROR, PV=0, PT=0 MANUFACTURER_SPECIFIC_2=14, MANUFACTURER_SPECIFIC_3=15, ) @@ -113,6 +120,9 @@ def control_mode_str(cls, mode): move_setpoint_ack="bit", move_success="bit", following_error="bit", + velocity_success="bit", + velocity_zero="bit", + torque_success="bit" ) feedback_out_defaults = dict( **feedback_in_defaults, @@ -123,6 +133,9 @@ def control_mode_str(cls, mode): move_setpoint_ack=False, move_success=False, following_error=False, + velocity_success=False, + velocity_zero=False, + torque_success=False ) log_status_word_changes = True @@ -196,6 +209,64 @@ def get_feedback_pp(self, sw): self.feedback_out.update(move_success=success, move_setpoint_ack=sp_ack) return success, reason + def get_feedback_pv(self, sw): + # Control mode is PV + if not self.command_in.get("velocity_request"): + self.feedback_out.update( + velocity_success=False + ) + return True, None + if self.feedback_out.get("state") != "OPERATION ENABLED": + reason = "Velocity request while drive not enabled" + self.feedback_out.update( + velocity_success=False, + fault=True, + fault_desc=reason, + ) + return False, reason + + success, reason = False, None + zero_speed = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") + if self.test_sw_bit(sw, "TARGET_REACHED"): + # done bit set + success = True + else: + reason = "velocity not reached" + + self.feedback_out.update( + velocity_success=success, + velocity_zero=zero_speed + ) + return success, reason + + def get_feedback_pt(self, sw): + # Control mode is PT + if not self.command_in.get("torque_request"): + self.feedback_out.update( + torque_success=False + ) + return True, None + if self.feedback_out.get("state") != "OPERATION ENABLED": + reason = "Torque request while drive not enabled" + self.feedback_out.update( + torque_success=False, + fault=True, + fault_desc=reason, + ) + return False, reason + + success, reason = False, None + if self.test_sw_bit(sw, "TARGET_REACHED"): + # done bit set + success = True + else: + reason = "torque not reached" + + self.feedback_out.update( + torque_success=success + ) + return success, reason + def get_feedback_sto(self): # Process active STO: Raise fault on OPERATION ENABLED command if not self.feedback_in.get("sto"): @@ -229,6 +300,10 @@ def goal_reached_timeout(self): return self.home_timeout if self.command_in.get("move_request"): return self.move_timeout + if self.command_in.get("velocity_request"): + return self.velocity_timeout + if self.command_in.get("torque_request"): + return self.torque_timeout return super().goal_reached_timeout def get_feedback(self): @@ -324,6 +399,18 @@ def get_feedback(self): if not pp_success: goal_reached = False goal_reasons.append(pp_reason) + elif cm == self.MODE_PV: + # Calculate velocity status + pv_success, pv_reason = self.get_feedback_pv(sw) + if not pv_success: + goal_reached = False + goal_reasons.append(pv_reason) + elif cm == self.MODE_PT: + # Calculate torque status + pt_success, pt_reason = self.get_feedback_pt(sw) + if not pt_success: + goal_reached = False + goal_reasons.append(pt_reason) # Handle STO if self.have_sto: @@ -409,6 +496,8 @@ def sw_to_str(cls, sw): home_request=False, move_request=False, relative_target=False, + velocity_request=False, + torque_request=False ) command_in_data_types = dict( state="str", @@ -416,6 +505,8 @@ def sw_to_str(cls, sw): home_request="bit", move_request="bit", relative_target="bit", + velocity_request="bit", + torque_request="bit" ) # ------- Command out ------- @@ -550,6 +641,40 @@ def pp_request_cw_flags(self): OPERATION_MODE_SPECIFIC_3=relative_target, ) + def pv_request_cw_flags(self): + # there are no operation specific flags for PV mode + # this is just here for logging consistency + # + # Check for velocity request + if self.command_in.get("velocity_request"): + if self.command_in.changed("velocity_request"): + self.logger.info("Velocity operation requested") + # Fast track as long as request in effect + self.command_out.update(fasttrack=True) + else: + # Clear request + #sw = self.feedback_in.get("status_word") + #stopped = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") + if self.command_in.changed("velocity_request"): + self.logger.info("velocity request cleared") + return dict() + + def pt_request_cw_flags(self): + # there are no operation specific flags for PT mode + # this is just here for logging consistency + # + # Check for torque request + if self.command_in.get("torque_request"): + if self.command_in.changed("torque_request"): + self.logger.info("Torque operation requested") + # Fast track as long as request in effect + self.command_out.update(fasttrack=True) + else: + # Clear request + if self.command_in.changed("torque_request"): + self.logger.info("torque request cleared") + return dict() + @classmethod @lru_cache def cw_to_str(cls, cw): @@ -584,6 +709,10 @@ def _get_next_control_word(self, cmd_out): cw_flags.update(self.hm_request_cw_flags()) elif next_cm == self.MODE_PP: cw_flags.update(self.pp_request_cw_flags()) + elif next_cm == self.MODE_PV: + cw_flags.update(self.pv_request_cw_flags()) + elif next_cm == self.MODE_PT: + cw_flags.update(self.pt_request_cw_flags()) else: cw_flags.update(OPERATION_MODE_SPECIFIC_1=False) next_cw = self._add_control_word_flags(control_word, **cw_flags) @@ -662,9 +791,9 @@ def _get_hold_state_control_word(self): ENABLE_VOLTAGE=1, # (state machine) QUICK_STOP=2, # (state machine) ENABLE_OPERATION=3, # (state machine) AKA S-ON - OPERATION_MODE_SPECIFIC_1=4, # HM=HOMING_START; PP=NEW_SETPOINT - OPERATION_MODE_SPECIFIC_2=5, # PP=CHANGE_SET_IMMEDIATE - OPERATION_MODE_SPECIFIC_3=6, + OPERATION_MODE_SPECIFIC_1=4, # HM=HOMING_START; PP=NEW_SETPOINT; PV=0; PT=0 + OPERATION_MODE_SPECIFIC_2=5, # PP=CHANGE_SET_IMMEDIATE; PV=0; PT=0 + OPERATION_MODE_SPECIFIC_3=6, # PP=RELATIVE_POS; PV=0; PT=0 FAULT_RESET=7, # (state machine) HALT=8, NA_1=9, @@ -720,8 +849,13 @@ def _add_control_word_flags(cls, control_word, **flags): def _get_next_control_mode(self, cmd_out): if self.command_in.get("home_request"): - # If `home_request` is set, command homing mode next_cm = self.MODE_HM + elif self.command_in.get("move_request"): + next_cm = self.MODE_PP + elif self.command_in.get("velocity_request"): + next_cm = self.MODE_PV + elif self.command_in.get("torque_request"): + next_cm = self.MODE_PT else: # Otherwise, copy control_mode from command_in next_cm = self.command_in.get("control_mode") @@ -746,10 +880,18 @@ class CiA402SimDevice(CiA402Device, CiA301SimDevice, ErrorSimDevice): feedback_in_data_types = dict( position_cmd="float", position_fb="float", + velocity_cmd="float", + velocity_fb="float", + torque_cmd="float", + torque_fb="float" ) feedback_in_defaults = dict( position_cmd=0.0, position_fb=0.0, + velocity_cmd=0.0, + velocity_fb=0.0, + torque_cmd=0.0, + torque_fb=0.0 ) feedback_out_data_types = dict(**feedback_in_data_types) @@ -802,6 +944,24 @@ def set_sim_feedback_pp(self, cw, sw): else: return dict() + def set_sim_feedback_pv(self, cw, sw): + if self.target_reached(sw, cw): + # Target reached when target velocity reached + if not self.test_sw_bit(sw, "TARGET_REACHED"): + self.logger.info("sim TARGET_REACHED set") + return dict(TARGET_REACHED=True) + else: + return dict() + + def set_sim_feedback_pt(self, cw, sw): + if self.target_reached(sw, cw): + # Target reached when target torque reached + if not self.test_sw_bit(sw, "TARGET_REACHED"): + self.logger.info("sim TARGET_REACHED set") + return dict(TARGET_REACHED=True) + else: + return dict() + def set_sim_feedback(self): sw_prev = self.sim_feedback.get("status_word") sfb = super().set_sim_feedback() @@ -855,6 +1015,11 @@ def set_sim_feedback(self): # Test previous cw because target_reached() looks at fb_in, which is # set after command_in sw_flags.update(self.set_sim_feedback_pp(cw_prev, sw_prev)) + elif control_mode == self.MODE_PV: + sw_flags.update(self.set_sim_feedback_pv(cw_prev, sw_prev)) + elif control_mode == self.MODE_PT: + sw_flags.update(self.set_sim_feedback_pt(cw_prev, sw_prev)) + status_word = self.add_status_word_flags(status_word, **sw_flags) sfb.update( From 0b5d95886a068196f5bf340928250b2b77aa5721 Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Mon, 11 Nov 2024 16:43:34 -0600 Subject: [PATCH 061/121] disable mode false-positives for now --- hw_device_mgr/cia_402/device.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 71c041a5..dda7ec7c 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -327,11 +327,11 @@ def get_feedback(self): cm = fb_in.get("control_mode_fb") fb_out.update(status_word=sw, control_mode_fb=cm) cm_cmd = self.command_in.get("control_mode") - if cm != self.MODE_HM and cm != cm_cmd: - goal_reached = False - cm_str = self.control_mode_str(cm) - cm_cmd_str = self.control_mode_str(cm_cmd) - goal_reasons.append(f"control_mode {cm_str} != {cm_cmd_str}") + #if cm != self.MODE_HM and cm != cm_cmd: + #goal_reached = False + #cm_str = self.control_mode_str(cm) + #cm_cmd_str = self.control_mode_str(cm_cmd) + #goal_reasons.append(f"control_mode {cm_str} != {cm_cmd_str}") # Calculate 'state' feedback for state, bits in self.state_bits.items(): From 067d181908894c49194b9ac3280a9b4df51b3746 Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Mon, 11 Nov 2024 20:52:07 -0600 Subject: [PATCH 062/121] sim updates --- hw_device_mgr/cia_402/device.py | 26 +++++++++++++++++++------- hw_device_mgr/mgr/mgr.py | 4 ++++ 2 files changed, 23 insertions(+), 7 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index dda7ec7c..0cbdcc38 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -908,6 +908,8 @@ class CiA402SimDevice(CiA402Device, CiA301SimDevice, ErrorSimDevice): # diff. btw. pos. cmd + fb to signal target reached position_goal_tolerance = 0.01 + velocity_goal_tolerance = 0.01 # TBD + torque_goal_tolerance = 0.01 # TBD # ------- Sim feedback ------- @@ -920,14 +922,24 @@ def set_sim_feedback_hm(self, cw): return dict() def target_reached(self, sw, cw): + control_mode = self.command_out.get("control_mode") fb_in = self.interface("feedback_in") - setpoint_ack = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") - new_setpoint = self.test_cw_bit(cw, "OPERATION_MODE_SPECIFIC_1") - if new_setpoint or setpoint_ack: - # Pretend we haven't reached new target before it's even set - return False - dtg = abs(fb_in.get("position_cmd") - fb_in.get("position_fb")) - return dtg < self.position_goal_tolerance + if control_mode == self.MODE_PP: + setpoint_ack = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") + new_setpoint = self.test_cw_bit(cw, "OPERATION_MODE_SPECIFIC_1") + if new_setpoint or setpoint_ack: + # Pretend we haven't reached new target before it's even set + return False + dtg = abs(fb_in.get("position_cmd") - fb_in.get("position_fb")) + return dtg < self.position_goal_tolerance + elif control_mode == self.MODE_PV: + #zero_speed = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") + #if zero_speed: ?? + dtg = abs(fb_in.get("velocity_cmd") - fb_in.get("velocity_fb")) + return dtg < self.velocity_goal_tolerance + elif control_mode == self.MODE_PT: + dtg = abs(fb_in.get("torque_cmd") - fb_in.get("torque_fb")) + return dtg < self.torque_goal_tolerance def set_sim_feedback_pp(self, cw, sw): # In MODE_PP, cw OPERATION_MODE_SPECIFIC_1 is NEW_SETPOINT cmd, sw diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 0f16faa1..a7b390f2 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -131,6 +131,10 @@ def scan_devices(cls, **kwargs): # These are sim only, not needed in debug output "position_cmd", "position_fb", + "velocity_cmd", + "velocity_fb", + "torque_cmd", + "torque_fb" }, # - Don't expose device `state` or `reset_fault`, controlled by manager command_in={"state", "reset_fault"}, From bef33f2e00223056c67d6654c209f9847330cf1d Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Thu, 21 Nov 2024 12:24:03 -0600 Subject: [PATCH 063/121] restore control_mode warning --- hw_device_mgr/cia_402/device.py | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 0cbdcc38..60545760 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -327,11 +327,21 @@ def get_feedback(self): cm = fb_in.get("control_mode_fb") fb_out.update(status_word=sw, control_mode_fb=cm) cm_cmd = self.command_in.get("control_mode") - #if cm != self.MODE_HM and cm != cm_cmd: - #goal_reached = False - #cm_str = self.control_mode_str(cm) - #cm_cmd_str = self.control_mode_str(cm_cmd) - #goal_reasons.append(f"control_mode {cm_str} != {cm_cmd_str}") + if cm != cm_cmd: + unexpected_mode = True + if self.MODE_HM == cm: + unexpected_mode = False + elif self.command_in.get("move_request"): + unexpected_mode = (self.MODE_PP != cm) + elif self.command_in.get("velocity_request"): + unexpected_mode = (self.MODE_PV != cm) + elif self.command_in.get("torque_request"): + unexpected_mode = (self.MODE_PT != cm) + if unexpected_mode: + goal_reached = False + cm_str = self.control_mode_str(cm) + cm_cmd_str = self.control_mode_str(cm_cmd) + goal_reasons.append(f"control_mode {cm_str} != {cm_cmd_str}") # Calculate 'state' feedback for state, bits in self.state_bits.items(): From f00c64d0f7b4639b3dc32da6d302930932ea7a26 Mon Sep 17 00:00:00 2001 From: John Morris Date: Fri, 22 Nov 2024 16:20:14 -0600 Subject: [PATCH 064/121] Revert "PP-4619 - ignore ecat alias 9999" This reverts commit 07d63b65f190c9d69e5a3b4d47fd3f9f51906399. Application-specific change moved out of general code --- hw_device_mgr/cia_301/command.py | 2 -- hw_device_mgr/lcec/command.py | 2 -- 2 files changed, 4 deletions(-) diff --git a/hw_device_mgr/cia_301/command.py b/hw_device_mgr/cia_301/command.py index 234c881f..94de971e 100644 --- a/hw_device_mgr/cia_301/command.py +++ b/hw_device_mgr/cia_301/command.py @@ -112,8 +112,6 @@ def scan_bus(self, bus=0): for dd in self.sim_device_data.values(): if dd["address"][0] != bus: continue - if dd["address"][2] == 9999: - continue res.append([dd["address"], dd["model_id"]]) return res diff --git a/hw_device_mgr/lcec/command.py b/hw_device_mgr/lcec/command.py index a108716a..519d295f 100644 --- a/hw_device_mgr/lcec/command.py +++ b/hw_device_mgr/lcec/command.py @@ -62,8 +62,6 @@ def scan_bus(self, bus=None, **kwargs): alias = int(line.split(":", 1)[1].strip()) addr = device[-1][0:2] + (alias,) device[0] = addr - if alias == 9999: - del devices[-1] elif line.startswith("Vendor Id:"): # Vendor Id: 0x00100000 vi = line.split(":", 1)[1].strip() From 8df413dbd1bc89acbf7b41f6a1eb961960b9cf26 Mon Sep 17 00:00:00 2001 From: John Morris Date: Fri, 22 Nov 2024 16:49:17 -0600 Subject: [PATCH 065/121] Clean up & dedup SV670 configs --- .../devices/device_err/inovance_sv670n.yaml | 566 - .../device_xml/SV660_EOE_1Axis_V9.12.xml | 2 +- .../SV670_EOE_1Axis_05003_220801.xml | 34798 ++++++++-------- hw_device_mgr/devices/inovance_sv670.py | 2 +- 4 files changed, 17401 insertions(+), 17967 deletions(-) delete mode 100644 hw_device_mgr/devices/device_err/inovance_sv670n.yaml diff --git a/hw_device_mgr/devices/device_err/inovance_sv670n.yaml b/hw_device_mgr/devices/device_err/inovance_sv670n.yaml deleted file mode 100644 index 7384f3f3..00000000 --- a/hw_device_mgr/devices/device_err/inovance_sv670n.yaml +++ /dev/null @@ -1,566 +0,0 @@ -# From Inovance SV660N "Advanced User Guide" 2020-10-20, table 10.2 -# "Communication Faults and Warning Codes" -# -# Parameter 603Fh shows the basic error code, but the -# manufacturer-specific SV660N parameter 203Fh "Manufacturer fault -# code" shows an extended error value. The manual's table 10.2 shows -# e.g. "fault" E101, with "display" broken down into E101.0 and E101.1 -# with different "name" and occasional differences in "fault range" -# column ("type" and "resettable or not" columns appear not to -# change). -# -# key: "Auxiliary Code" column most significant word -# display: "Display" column; code displayed on drive LED panel -# description: "Name" column -# type: "Type" column; indicates severity, with 1 most severe -# resettable: "Resettable" column; indicates whether resettable -# without power cycle - -# -# List of fault codes -# -'0x0101': - display: E101.0 - description: System parameter error - type: 1 - resettable: false -'0x1101': - display: E101.1 - description: 2000h/2001h parameter error - type: 1 - resettable: false -'0x0102': - display: E102.0 - description: FPGA communication initialization error - type: 1 - resettable: false -'0x8102': - display: E102.8 - description: Software version mismatch - type: 1 - resettable: false -'0x1104': - display: E104.1 - description: MCU operation timeout - type: 1 - resettable: false -'0x2104': - display: E104.2 - description: Current loop operation timeout - type: 1 - resettable: false -'0x4104': - display: E104.4 - description: MCU reference update timeout - type: 1 - resettable: false -'0x0108': - display: E108.0 - description: Parameter write error - type: 1 - resettable: true -'0x1108': - display: E108.1 - description: Parameter read error - type: 1 - resettable: true -'0x2108': - display: E108.2 - description: Invalid check on data written in EEPROM - type: 1 - resettable: true -'0x3108': - display: E108.3 - description: Invalid check on data read in EEPROM - type: 1 - resettable: true -'0x0120': - display: E120.0 - description: Unknown encoder type - type: 1 - resettable: false -'0x1120': - display: E120.1 - description: Unknown motor model - type: 1 - resettable: false -'0x2120': - display: E120.2 - description: Unknown drive model - type: 1 - resettable: false -'0x5120': - display: E120.5 - description: Motor current and drive current mismatch - type: 1 - resettable: false -'0x6120': - display: E120.6 - description: FPGA and motor model mismatch - type: 1 - resettable: false -'0x0122': - display: E122.0 - description: Multi-turn absolute encoder setting error - type: 2 - resettable: true -'0x1122': - display: E122.1 - description: Different DIs allocated with the same function - type: 2 - resettable: true -'0x3122': - display: E122.3 - description: Upper limit invalid - type: 2 - resettable: true -'0x0136': - display: E136.0 - description: Encoder parameter error - type: 1 - resettable: false -'0x1136': - display: E136.1 - description: Encoder communication error - type: 1 - resettable: false -'0x0140': - display: E140.0 - description: Encryption chip check error - type: 1 - resettable: false -'0x1140': - display: E140.1 - description: Encryption chip check failure - type: 1 - resettable: false -'0x0150': - display: E150.0 - description: STO signal input protection activated - type: 1 - resettable: true -'0x1150': - display: E150.1 - description: STO signal input error - type: 1 - resettable: true -'0x2150': - display: E150.2 - description: Abnormal voltage detected - type: 1 - resettable: true -'0x3150': - display: E150.3 - description: STO upstream optocoupler detection failure - type: 1 - resettable: true -'0x4150': - display: E150.4 - description: PWM Buffer detection failure - type: 1 - resettable: true -'0x0201': - display: E201.0 - description: Phase-P overcurrent - type: 1 - resettable: false -'0x1201': - display: E201.1 - description: Phase-U overcurrent - type: 1 - resettable: false -'0x2201': - display: E201.2 - description: Phase-V overcurrent - type: 1 - resettable: false -'0x4201': - display: E201.4 - description: Phase-N overcurrent - type: 1 - resettable: false -'0x0208': - display: E208.0 - description: MCU position reference updated frequently - type: 1 - resettable: true -'0x2208': - display: E208.2 - description: Encoder communication timeout - type: 1 - resettable: true -'0x3208': - display: E208.3 - description: Current sampling fault - type: 1 - resettable: true -'0x4208': - display: E208.4 - description: FPGA current loop operation timeout - type: 1 - resettable: true -'0x0210': - display: E210.0 - description: Output shorted to ground - type: 1 - resettable: false -'0x0234': - display: E234.0 - description: Runaway protection - type: 1 - resettable: false -'0x0400': - display: E400.0 - description: Main circuit overvoltage - type: 1 - resettable: true -'0x0410': - display: E410.0 - description: Main circuit undervoltage - type: 1 - resettable: true -'0x0420': - display: E420.0 - description: Phase loss fault - type: 2 - resettable: true -'0x0430': - display: E430.0 - description: Control circuit undervoltage - type: 2 - resettable: true -'0x0500': - display: E500.0 - description: Motor overspeed - type: 1 - resettable: true -'0x1500': - display: E500.1 - description: Speed feedback overflow - type: 1 - resettable: true -'0x2500': - display: E500.2 - description: FPGA position feedback pulse overspeed - type: 1 - resettable: true -'0x0602': - display: E602.0 - description: Angle auto-tuning error - type: 1 - resettable: true -'0x2602': - display: E602.2 - description: Wrong UVW phase sequence detected during angle auto-tuning - type: 1 - resettable: true -'0x0605': - display: E605.0 - description: Speed upon S-ON too high - type: 1 - resettable: true -'0x0620': - display: E620.0 - description: Motor overload - type: 1 - resettable: true -'0x0630': - display: E630.0 - description: Motor stall - type: 1 - resettable: true -'0x0640': - display: E640.0 - description: IGBT over-temperature - type: 1 - resettable: true -'0x1640': - display: E640.1 - description: Flywheel diode over-temperature - type: 1 - resettable: true -'0x0650': - display: E650.0 - description: Heatsink over-temperature - type: 1 - resettable: true -'0x0660': - display: E660.0 - description: Air-cooled motor over-temperature - type: 1 - resettable: true -'0x0661': - display: E661.0 - description: Auto-tuned gain values too low - type: 2 - resettable: true -'0x0731': - display: E731.0 - description: Encoder battery failure - type: 2 - resettable: true -'0x0733': - display: E733.0 - description: Encoder multi-turn counting error - type: 2 - resettable: true -'0x0735': - display: E735.0 - description: Encoder multi-turn counting overflow - type: 2 - resettable: true -'0x2740': - display: E740.2 - description: Absolute encoder error - type: 1 - resettable: false -'0x3740': - display: E740.3 - description: Absolute encoder single-turn calculation error - type: 1 - resettable: false -'0x6740': - display: E740.6 - description: Encoder write error - type: 1 - resettable: false -'0x0755': - display: E755.0 - description: Nikon encoder communication failure - type: 1 - resettable: false -'0x0760': - display: E760.0 - description: Encoder over-temperature - type: 2 - resettable: true -'0x0765': - display: E765.0 - description: Nikon encoder beyond the limit - type: 1 - resettable: false -'0x0B00': - display: EB00.0 - description: Position deviation too large - type: 2 - resettable: true -'0x1B00': - display: EB00.1 - description: Position deviation overflow - type: 2 - resettable: true -# (Note: out of numerical order in manual) -'0x0A33': - display: EA33.0 - description: Encoder read/write check error - type: 1 - resettable: false -'0x1B01': - display: EB01.1 - description: Position reference increment too large for once - type: 2 - resettable: true -'0x2B01': - display: EB01.2 - description: Position reference increment too large continuously - type: 2 - resettable: true -'0x3B01': - display: EB01.3 - description: Reference overflow - type: 2 - resettable: true -'0x4B01': - display: EB01.4 - description: Target position beyond upper/lower limit - type: 2 - resettable: true -'0x0E09': - display: EE09.0 - description: Software position limit setting error - type: 2 - resettable: true -'0x1E09': - display: EE09.1 - description: Home setting error - type: 2 - resettable: true -'0x2E09': - display: EE09.2 - description: Gear ratio beyond the limit - type: 2 - resettable: true -'0x3E09': - display: EE09.3 - description: No synchronization signal - type: 2 - resettable: true -'0x5E09': - display: EE09.5 - description: PDO mapping beyond the limit - type: 2 - resettable: true -# (Note: EE08.0 out of order in manual) -'0x0E08': - display: EE08.0 - description: Synchronization loss - type: 2 - resettable: true -'0x1E08': - display: EE08.1 - description: Network status switchover error - type: 2 - resettable: true -'0x2E08': - display: EE08.2 - description: IRQ loss - type: 2 - resettable: true -'0x3E08': - display: EE08.3 - description: LAN cable connected improperly - type: 2 - resettable: true -'0x4E08': - display: EE08.4 - description: Data frame loss protection error - type: 2 - resettable: true -'0x5E08': - display: EE08.5 - description: Data frame transfer error - type: 2 - resettable: true -'0x6E08': - display: EE08.6 - description: Data update timeout - type: 2 - resettable: true -'0x0E11': - display: EE11.0 - description: ESI check error - type: 2 - resettable: true -'0x1E11': - display: EE11.1 - description: EEPROM read failure - type: 2 - resettable: true -'0x2E11': - display: EE11.2 - description: EEPROM update failure - type: 2 - resettable: true -'0x0E12': - display: EE12.0 - description: EtherCAT external device error - type: 1 - resettable: false -'0x0E13': - display: EE13.0 - description: Synchronization cycle setting error - type: 2 - resettable: true -'0x0E15': - display: EE15.0 - description: Number of synchronization cycle errors too large - type: 2 - resettable: true -# -# List of warning codes -# -'0x0121': - display: E121.0 - description: Invalid S-ON command - type: 3 - resettable: true -'0x0600': - display: E600.0 - description: Inertia auto-tuning failure - type: 3 - resettable: true -'0x0601': - display: E601.0 - description: Homing timeout - type: 3 - resettable: true -'0x1601': - display: E601.1 - description: Home switch error - type: 3 - resettable: true -'0x2601': - display: E601.2 - description: Homing mode setting error - type: 3 - resettable: true -'0x0730': - display: E730.0 - description: Encoder battery warning - type: 3 - resettable: true -'0x0900': - display: E900.0 - description: Emergency stop - type: 3 - resettable: true -'0x0902': - display: E902.0 - description: Invalid DI setting - type: 3 - resettable: true -'0x1902': - display: E902.1 - description: Invalid DO setting - type: 3 - resettable: true -'0x0908': - display: E908.0 - description: Model identification check byte invalid - type: 3 - resettable: true -'0x0909': - display: E909.0 - description: Motor overload warning - type: 3 - resettable: true -'0x0920': - display: E920.0 - description: Regenerative resistor overload - type: 3 - resettable: true -'0x0922': - display: E922.0 - description: Resistance of external regenerative resistor too small - type: 3 - resettable: true -'0x0924': - display: E924.0 - description: Braking transistor over-temperature - type: 3 - resettable: true -'0x0941': - display: E941.0 - description: Parameter modifications not activated - type: 3 - resettable: true -'0x0942': - display: E942.0 - description: Parameter saved frequently - type: 3 - resettable: true -'0x0950': - display: E950.0 - description: Forward overtravel warning - type: 3 - resettable: true -'0x0952': - display: E952.0 - description: Reverse overtravel warning - type: 3 - resettable: true -'0x0A41': - display: EA41.0 - description: Torque ripple compensation failure - type: 3 - resettable: true diff --git a/hw_device_mgr/devices/device_xml/SV660_EOE_1Axis_V9.12.xml b/hw_device_mgr/devices/device_xml/SV660_EOE_1Axis_V9.12.xml index 648b9f3f..0e1dc5d4 100644 --- a/hw_device_mgr/devices/device_xml/SV660_EOE_1Axis_V9.12.xml +++ b/hw_device_mgr/devices/device_xml/SV660_EOE_1Axis_V9.12.xml @@ -7387,7 +7387,7 @@ 7 1 - + ro diff --git a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml index ba6b927e..55ceb5dd 100644 --- a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml +++ b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml @@ -1,17403 +1,17403 @@ - - #x00100000 - Inovance - 汇川技术 - 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 - - - - - InoServo - Servo Drives - 伺服驱动器 - 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 - - - - - InoSV670N - SV670_1Axis_05003 - ServoDrive - http://www.inovance.cn - - - - 3000 - 9000 - 5000 - 200 - - - - - 100 - 2000 - - - - InoServo - - - 402 - - - - - - BIT2 - 2 - - - - BOOL - 1 - - - - DINT - 32 - - - - INT - 16 - - - - UDINT - 32 - - - - UINT - 16 - - - - USINT - 8 - - - - SINT - 8 - - - - STRING(10) - 80 - - - - STRING(4) - 32 - - - DT1018 - 144 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Vendor ID - UDINT - 32 - 16 - - ro - - - - 2 - Product Code - UDINT - 32 - 48 - - ro - - - - 3 - Revision - UDINT - 32 - 80 - - ro - - - - 4 - Serial number - UDINT - 32 - 112 - - ro - - - - - DT1600 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - rw - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - rw - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - rw - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - rw - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - rw - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - rw - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - rw - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - rw - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - rw - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - rw - - - - - DT1601 - 368 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - rw - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - rw - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - rw - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - rw - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - rw - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - rw - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - rw - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - rw - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - rw - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - rw - - - - 11 - 11th Output Object to be mapped - UDINT - 32 - 336 - - rw - - - - - DT1701 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1702 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1703 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1704 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1705 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1A00 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - rw - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - rw - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - rw - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - rw - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - rw - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - rw - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - rw - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - rw - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - rw - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - rw - - - - - DT1A01 - 368 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - rw - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - rw - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - rw - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - rw - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - rw - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - rw - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - rw - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - rw - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - rw - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - rw - - - - 11 - 11th Input Object to be mapped - UDINT - 32 - 336 - - rw - - - - - DT1B01 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1B02 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1B03 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1B04 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1C00ARR - USINT - 32 - - 1 - 4 - - - - DT1C00 - 48 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - o - - - - Elements - DT1C00ARR - 32 - 16 - - ro - o - - - - - - DT1C32 - 488 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - m - - - - 1 - Sync mode - UINT - 16 - 16 - - rw - - - - 2 - Cycle time - UDINT - 32 - 32 - - ro - o - - - - 4 - Sync modes supported - UINT - 16 - 96 - - ro - o - - - - 5 - Minimum cycle time - UDINT - 32 - 112 - - ro - o - - - - 6 - Calc and copy time - UDINT - 32 - 144 - - ro - o - - - - 8 - Get Cycle Time - UINT - 16 - 208 - - rw - c - - - - 9 - Delay Time - UDINT - 32 - 224 - - ro - c - - - - 10 - Sync0 Cycle Time - UDINT - 32 - 256 - - rw - o - - - - 11 - SM-Event Missed - UINT - 16 - 288 - - ro - c - - - - 12 - Cycle Time Too Small - UINT - 16 - 304 - - ro - c - - - - 32 - Sync Error - BOOL - 1 - 480 - - ro - c - - - - - - DT1C33 - 488 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - o - - - - 1 - Sync mode - UINT - 16 - 16 - - rw - - - - 2 - Cycle time - UDINT - 32 - 32 - - ro - o - - - - 4 - Sync modes supported - UINT - 16 - 96 - - ro - o - - - - 5 - Minimum cycle time - UDINT - 32 - 112 - - ro - o - - - - 6 - Calc and copy time - UDINT - 32 - 144 - - ro - o - - - - 8 - Get Cycle Time - UINT - 16 - 208 - - rw - c - - - - 9 - Delay Time - UDINT - 32 - 224 - - ro - c - - - - 10 - Sync0 Cycle Time - UDINT - 32 - 256 - - rw - o - - - - 11 - SM-Event Missed - UINT - 16 - 288 - - ro - c - - - - 12 - Cycle Time Too Small - UINT - 16 - 304 - - ro - c - - - - 32 - Sync Error - BOOL - 1 - 480 - - ro - c - - - - - DT1C12ARR - UINT - 16 - - 1 - 1 - - - - DT1C12 - 32 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - Elements - DT1C12ARR - 16 - 16 - - rw - o - - - - - DT1C13ARR - UINT - 16 - - 1 - 1 - - - - DT1C13 - 32 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - Elements - DT1C13ARR - 16 - 16 - - rw - o - - - - - - DT2000 - 128 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Motor SN - UINT - 16 - 16 - - rw - - - - 3 - Customized firmware version - UDINT - 32 - 48 - - ro - - - - 5 - Encoder Version - UINT - 16 - 96 - - ro - - - - 6 - Serial encoder motor SN - UINT - 16 - 112 - - ro - - - - - - DT2001 - 672 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - MCU firmware Version - UINT - 16 - 16 - - ro - - - - 2 - Fpga firmware Version - UINT - 16 - 32 - - ro - - - - 11 - Drive serial number - UINT - 16 - 176 - - rw - - - - 12 - Drive voltage class - UINT - 16 - 192 - - ro - - - - 13 - Drive rated power - UDINT - 32 - 208 - - ro - - - - 15 - Drive maximum output power - UDINT - 32 - 240 - - ro - - - - 17 - Drive rated output current - UDINT - 32 - 272 - - ro - - - - 19 - Drive maximum output current - UDINT - 32 - 304 - - ro - - - - 41 - DC bus overvoltage protective point - UINT - 16 - 656 - - rw - - - - - - DT2002 - 688 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Control mode selection - UINT - 16 - 16 - - rw - - - - 2 - Absolute system selection - UINT - 16 - 32 - - rw - - - - 3 - Rotating direction - UINT - 16 - 48 - - rw - - - - 4 - Output pulse phase - UINT - 16 - 64 - - rw - - - - 6 - Disable operation option Code - INT - 16 - 96 - - rw - - - - 7 - NO2 Fault Reaction option Code - INT - 16 - 112 - - rw - - - - 8 - Stop mode at limit switch signal - UINT - 16 - 128 - - rw - - - - 9 - Stop mode at NO.1 fault - UINT - 16 - 144 - - rw - - - - 10 - Delay from brake output on to command received - UINT - 16 - 160 - - rw - - - - 11 - Delay from brake output off to motor de-energized - UINT - 16 - 176 - - rw - - - - 12 - Motor speed threshold at brake output off in rotating state - UINT - 16 - 192 - - rw - - - - 13 - Delay from servo off to brake output off in the rotating state - UINT - 16 - 208 - - rw - - - - 16 - LED warning display selection - UINT - 16 - 256 - - rw - - - - 18 - MainPower Cutoff Reaction Option Code - UINT - 16 - 288 - - rw - - - - 19 - QuickStop Reaction Option Code - UINT - 16 - 304 - - rw - - - - 22 - Allowed minimum braking resistance - UINT - 16 - 352 - - ro - - - - 23 - Power of built-in braking resistor - UINT - 16 - 368 - - ro - - - - 24 - Resistance of built-in braking resistor - UINT - 16 - 384 - - ro - - - - 25 - Resistor heat dissipation coefficient - UINT - 16 - 400 - - rw - - - - 26 - braking resistor type - UINT - 16 - 416 - - rw - - - - 27 - Power of external dynamic resistor - UINT - 16 - 432 - - rw - - - - 28 - Resistance of external braking resistor - UINT - 16 - 448 - - rw - - - - 31 - User password - UINT - 16 - 496 - - wo - - - - 32 - Parameter initialization - UINT - 16 - 512 - - rw - - - - 33 - Default keypad display - UINT - 16 - 528 - - rw - - - - 36 - Panel data refresh rate - UINT - 16 - 576 - - rw - - - - 42 - OEM password - UINT - 16 - 672 - - wo - - - - - DT2003 - 1056 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 3 - DI1 function selection - UINT - 16 - 48 - - rw - - - - 4 - DI1 logic selection - UINT - 16 - 64 - - rw - - - - 5 - DI2 function selection - UINT - 16 - 80 - - rw - - - - 6 - DI2 logic selection - UINT - 16 - 96 - - rw - - - - 7 - DI3 function selection - UINT - 16 - 112 - - rw - - - - 8 - DI3 logic selection - UINT - 16 - 128 - - rw - - - - 9 - DI4 function selection - UINT - 16 - 144 - - rw - - - - 10 - DI4 logic selection - UINT - 16 - 160 - - rw - - - - 11 - DI5 function selection - UINT - 16 - 176 - - rw - - - - 12 - DI5 logic selection - UINT - 16 - 192 - - rw - - - - 51 - AI1 Offset - INT - 16 - 816 - - rw - - - - 52 - AI1 Filter - UINT - 16 - 832 - - rw - - - - 54 - AI1 Dead Zone - UINT - 16 - 864 - - rw - - - - 55 - AI1 Zero Drifting - INT - 16 - 880 - - rw - - - - 61 - DI1 filtertime constant - UINT - 16 - 976 - - rw - - - - 62 - DI2 filtertime constant - UINT - 16 - 992 - - rw - - - - 63 - DI3 filtertime constant - UINT - 16 - 1008 - - rw - - - - 64 - DI4 filtertime constant - UINT - 16 - 1024 - - rw - - - - 65 - DI5 filtertime constant - UINT - 16 - 1040 - - rw - - - - - DT2004 - 864 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - DO1 Function Selection - UINT - 16 - 16 - - rw - - - - 2 - DO1 Logic Level Selection - UINT - 16 - 32 - - rw - - - - 3 - DO2 Function Selection - UINT - 16 - 48 - - rw - - - - 4 - DO2 Logic Level Selection - UINT - 16 - 64 - - rw - - - - 5 - DO3 Function Selection - UINT - 16 - 80 - - rw - - - - 6 - DO3 Logic Level Selection - UINT - 16 - 96 - - rw - - - - 23 - DO OutPut Source Select - UINT - 16 - 368 - - rw - - - - 24 - ECAT Lost Force DO OutPut Logic - UINT - 16 - 384 - - rw - - - - 51 - AO1 Source Select - UINT - 16 - 816 - - rw - - - - 52 - AO1 Offset - INT - 16 - 832 - - rw - - - - 53 - AO1 Multiplying - INT - 16 - 848 - - rw - - - - - DT2005 - 1152 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 5 - Time constant of first-order low-pass filter - UINT - 16 - 80 - - rw - - - - 7 - Time constant of moving average filter 1 - UINT - 16 - 112 - - rw - - - - 8 - Numerator of electronic gear ratio - UDINT - 32 - 128 - - rw - - - - 10 - Denominator of electronic gear ratio - UDINT - 32 - 160 - - rw - - - - 18 - Encoder frequency division pulses - UDINT - 32 - 288 - - rw - - - - 20 - Speed feedforward control selection - UINT - 16 - 320 - - rw - - - - 31 - Local home mode - UINT - 16 - 496 - - rw - - - - 36 - Time of home searching - UINT - 16 - 576 - - rw - - - - 37 - Local home position offset - DINT - 32 - 592 - - rw - - - - 39 - Servo pulse output source - UINT - 16 - 624 - - rw - - - - 42 - Output polarity of Z pulse - UINT - 16 - 672 - - rw - - - - 51 - Mechanical Gear ratio numerator of absolute encode mode 2 - UINT - 16 - 816 - - rw - - - - 52 - Mechanical Gear ratio denominator of absolute encode mode 2 - UINT - 16 - 832 - - rw - - - - 53 - Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) - UDINT - 32 - 848 - - rw - - - - 55 - Max value of mechanical absolute position(inc) of absolute encode mode 2(High) - UDINT - 32 - 880 - - rw - - - - 59 - Trq Reference of Mechanical Homing - UINT - 16 - 944 - - rw - - - - 61 - Position Coin Hold Time - UINT - 16 - 976 - - rw - - - - 67 - Time Unit of Homing - UINT - 16 - 1072 - - rw - - - - 71 - Time constant of moving average filter 2 - UINT - 16 - 1136 - - rw - - - - - DT2006 - 896 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 4 - Keypad setting value of speed reference - INT - 16 - 64 - - rw - - - - 5 - DI Jog speed reference - UINT - 16 - 80 - - rw - - - - 6 - Acceleration ramp time constant of speed reference - UINT - 16 - 96 - - rw - - - - 7 - Deceleration ramp time constant of speed reference - UINT - 16 - 112 - - rw - - - - 8 - Maximum speed limit - UINT - 16 - 128 - - rw - - - - 9 - Forward speed threshold - UINT - 16 - 144 - - rw - - - - 10 - Reverse speed threshold - UINT - 16 - 160 - - rw - - - - 11 - Quick decelaration coefficient - UINT - 16 - 176 - - rw - - - - 12 - Torque feedforward selection - UINT - 16 - 192 - - rw - - - - 13 - Acceleration/Deceleration ramp time constant of jog speed reference - UINT - 16 - 208 - - rw - - - - 14 - Speed feedforward filter time constant - UINT - 16 - 224 - - rw - - - - 16 - Speed threshold of Zero Hold signal - UINT - 16 - 256 - - rw - - - - 17 - Speed threshold of motor rotation signal - UINT - 16 - 272 - - rw - - - - 18 - Speed threshold of Spd Reach signal - UINT - 16 - 288 - - rw - - - - 19 - Speed threshold of Spd Arrive signal - UINT - 16 - 304 - - rw - - - - 20 - Speed threshold of Zero Spd signal - UINT - 16 - 320 - - rw - - - - 51 - Spd SCurve Enable - UINT - 16 - 816 - - rw - - - - 52 - Spd SCurve Acceleration UP - UINT - 16 - 832 - - rw - - - - 53 - Spd SCurve Acceleration Down - UINT - 16 - 848 - - rw - - - - 54 - Spd SCurve Deceleration UP - UINT - 16 - 864 - - rw - - - - 55 - Spd SCurve Deceleration Down - UINT - 16 - 880 - - rw - - - - - DT2007 - 640 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 4 - Keypad setting value of torque reference - INT - 16 - 64 - - rw - - - - 6 - Torque reference filter time 1 - UINT - 16 - 96 - - rw - - - - 7 - Torque reference filter time 2 - UINT - 16 - 112 - - rw - - - - 10 - Internal forward torque limit - UINT - 16 - 160 - - rw - - - - 11 - Internal reverse torque limit - UINT - 16 - 176 - - rw - - - - 16 - Emergency stop torque - UINT - 16 - 256 - - rw - - - - 20 - Forward speed limit/Speed limit 1 in local torque control - UINT - 16 - 320 - - rw - - - - 21 - Reverse speed limit/Speed limit 2 in local torque control - UINT - 16 - 336 - - rw - - - - 22 - Base value for torque reached - UINT - 16 - 352 - - rw - - - - 23 - Threshold of torque reached valid - UINT - 16 - 368 - - rw - - - - 24 - Threshold of torque reached invalid - UINT - 16 - 384 - - rw - - - - 25 - Depth of field-weakening - UINT - 16 - 400 - - rw - - - - 26 - Maximum field-weakening current - UINT - 16 - 416 - - rw - - - - 27 - Field-weakening enable - UINT - 16 - 432 - - rw - - - - 28 - Field-weakening gain - UINT - 16 - 448 - - rw - - - - 29 - Field-weakening point speed - UINT - 16 - 464 - - ro - - - - 36 - Motor output calibration enable - UINT - 16 - 576 - - rw - - - - 37 - The second-stage torque reference filter time - UINT - 16 - 592 - - rw - - - - 38 - Torque reference filter type select - UINT - 16 - 608 - - rw - - - - 39 - Biquad low pass filter damping - UINT - 16 - 624 - - rw - - - - - DT2008 - 1056 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Speed-loop Gain - UINT - 16 - 16 - - rw - - - - 2 - Speed-loop integral time constant - UINT - 16 - 32 - - rw - - - - 3 - Position-loop Gain - UINT - 16 - 48 - - rw - - - - 4 - The second speed loop gain - UINT - 16 - 64 - - rw - - - - 5 - The second speed loop integral time constant - UINT - 16 - 80 - - rw - - - - 6 - The second position loop gain - UINT - 16 - 96 - - rw - - - - 9 - Second gain mode setting - UINT - 16 - 144 - - rw - - - - 10 - Gain switchover condition - UINT - 16 - 160 - - rw - - - - 11 - Gain switchover delay - UINT - 16 - 176 - - rw - - - - 12 - Gain switchover level - UINT - 16 - 192 - - rw - - - - 13 - Gain switchover hysteresis - UINT - 16 - 208 - - rw - - - - 14 - Position gain switchover time - UINT - 16 - 224 - - rw - - - - 16 - Average value of load inertia ratio - UINT - 16 - 256 - - rw - - - - 18 - Zero-Phase delay time - UINT - 16 - 288 - - rw - - - - 19 - Speed feedforward filter time constant - UINT - 16 - 304 - - rw - - - - 20 - Speed feedforward gain - UINT - 16 - 320 - - rw - - - - 21 - Torque feedforward filter time constant - UINT - 16 - 336 - - rw - - - - 22 - Torque feedforward gain - UINT - 16 - 352 - - rw - - - - 23 - Speed feedback filter - UINT - 16 - 368 - - rw - - - - 24 - Cut-off frequency of speed feedback low-pass filter - UINT - 16 - 384 - - rw - - - - 25 - Pseudo-differential forward feedback control coefficient - UINT - 16 - 400 - - rw - - - - 28 - Cut-off frequency of speed observer - UINT - 16 - 448 - - rw - - - - 29 - Modified inertia coefficient of speed observer - UINT - 16 - 464 - - rw - - - - 30 - Filter time of speed observer - UINT - 16 - 480 - - rw - - - - 32 - Cut-off frequency of torque disturbance observer - UINT - 16 - 512 - - rw - - - - 33 - Compensation gain of torque disturbance observer - UINT - 16 - 528 - - rw - - - - 34 - Modified inertia coefficient of torque disturbance observer - UINT - 16 - 544 - - rw - - - - 41 - Speed observer enable - UINT - 16 - 656 - - rw - - - - 43 - Module control enable - UINT - 16 - 688 - - rw - - - - 44 - Module control gain - UINT - 16 - 704 - - rw - - - - 47 - Module feedforward value - UINT - 16 - 752 - - rw - - - - 54 - 3rd medium and low-frequency vibration suppression frequency - UINT - 16 - 864 - - rw - - - - 55 - 3rd compensation gain of medium and low-frequency vibration suppression frequency - UINT - 16 - 880 - - rw - - - - 57 - 3rd phase modulation of medium and low-frequency vibration suppression frequency - UINT - 16 - 912 - - rw - - - - 60 - 4th medium and low-frequency vibration suppression frequency - UINT - 16 - 960 - - rw - - - - 61 - 4th compensation gain of medium and low-frequency vibration suppression frequency - UINT - 16 - 976 - - rw - - - - 62 - 4th phase modulation of medium and low-frequency vibration suppression frequency - UINT - 16 - 992 - - rw - - - - 63 - Time constant of position loop integration - UINT - 16 - 1008 - - rw - - - - 64 - 2nd time constant of position loop integration - UINT - 16 - 1024 - - rw - - - - 65 - Speed observation feedback source selection - UINT - 16 - 1040 - - rw - - - - - DT2009 - 848 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Auto-adjusting mode - UINT - 16 - 16 - - rw - - - - 2 - Rigidity level selection - UINT - 16 - 32 - - rw - - - - 3 - Working mode of self-adaptive notch - UINT - 16 - 48 - - rw - - - - 4 - Online inertia auto-tuning mode - UINT - 16 - 64 - - rw - - - - 6 - Offline inertia auto-tuning mode - UINT - 16 - 96 - - rw - - - - 7 - Maximum speed for inertia autotuning - UINT - 16 - 112 - - rw - - - - 8 - Acceleration/Deceleration time for inertia autotuning - UINT - 16 - 128 - - rw - - - - 9 - Interval after an inertia autotuning - UINT - 16 - 144 - - rw - - - - 10 - Motor revolutions for an inertia auto-tuning - UINT - 16 - 160 - - rw - - - - 12 - Vibration threshold setting - UINT - 16 - 192 - - rw - - - - 13 - 1st notch frequency - UINT - 16 - 208 - - rw - - - - 14 - 1st notch width level - UINT - 16 - 224 - - rw - - - - 15 - 1st notch attenuation level - UINT - 16 - 240 - - rw - - - - 16 - 2nd notch frequency - UINT - 16 - 256 - - rw - - - - 17 - 2nd notch width level - UINT - 16 - 272 - - rw - - - - 18 - 2nd notch attenuation level - UINT - 16 - 288 - - rw - - - - 19 - 3rd notch frequency - UINT - 16 - 304 - - rw - - - - 20 - 3rd notch width level - UINT - 16 - 320 - - rw - - - - 21 - 3rd notch attenuation level - UINT - 16 - 336 - - rw - - - - 22 - 4th notch frequency - UINT - 16 - 352 - - rw - - - - 23 - 4th notch width level - UINT - 16 - 368 - - rw - - - - 24 - 4th notch attenuation level - UINT - 16 - 384 - - rw - - - - 25 - Obtained resonance frequency - UINT - 16 - 400 - - ro - - - - 26 - 1st anti-resonance point frequency - UINT - 16 - 416 - - rw - - - - 27 - 2nd anti-resonance point frequency - UINT - 16 - 432 - - rw - - - - 33 - Gravity compensation value - INT - 16 - 528 - - rw - - - - 34 - Forward friction compensation - INT - 16 - 544 - - rw - - - - 35 - Reverse friction compensation - INT - 16 - 560 - - rw - - - - 36 - Friction compensation speed - UINT - 16 - 576 - - rw - - - - 37 - Friction compensation speed selection - UINT - 16 - 592 - - rw - - - - 38 - Vibration monitor time - UINT - 16 - 608 - - rw - - - - 39 - 1st terminal low-frequency vibration suppression frequency - UINT - 16 - 624 - - rw - - - - 40 - 1st filter order of low-frequency vibration suppression frequency - UINT - 16 - 640 - - rw - - - - 42 - 5th notch frequency - UINT - 16 - 672 - - rw - - - - 43 - 5th notch width level - UINT - 16 - 688 - - rw - - - - 44 - 5th notch attenuation level - UINT - 16 - 704 - - rw - - - - 45 - 2nd terminal low-frequency vibration suppression frequency - UINT - 16 - 720 - - rw - - - - 46 - 2nd damping frequency ratio of low-frequency vibration suppression frequency - UINT - 16 - 736 - - rw - - - - 48 - 2nd damping coefficient of low-frequency vibration suppression frequency - UINT - 16 - 768 - - rw - - - - 50 - 3rd terminal low-frequency vibration suppression frequency - UINT - 16 - 800 - - rw - - - - 51 - 3rd damping frequency ratio of low-frequency vibration suppression frequency - UINT - 16 - 816 - - rw - - - - 53 - 3rd damping coefficient of low-frequency vibration suppression frequency - UINT - 16 - 832 - - rw - - - - - DT200A - 1536 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Power inputphase loss protection disable - UINT - 16 - 16 - - rw - - - - 2 - Absolute position limit set - UINT - 16 - 32 - - rw - - - - 5 - Motor overload protection gain - UINT - 16 - 80 - - rw - - - - 9 - Overspeed threshold - UINT - 16 - 144 - - rw - - - - 11 - Local following error window - UDINT - 32 - 176 - - rw - - - - 13 - Runaway protection enable - UINT - 16 - 208 - - rw - - - - 19 - Over Temperature value of IPM - UINT - 16 - 304 - - rw - - - - 20 - Touch Probe 1 filter time constant - UINT - 16 - 320 - - rw - - - - 21 - Touch Probe 2 filter time constant - UINT - 16 - 336 - - rw - - - - 22 - STO Display Function Selection - UINT - 16 - 352 - - rw - - - - 24 - Filter time constant of TZ signal - UINT - 16 - 384 - - rw - - - - 26 - Filter time of speed feedback display - UINT - 16 - 416 - - rw - - - - 27 - Motor overload shielding - UINT - 16 - 432 - - rw - - - - 28 - Speed DO Filter time constant - UINT - 16 - 448 - - rw - - - - 30 - Full Closed-loop(ABZ) Filter time constant - UINT - 16 - 480 - - rw - - - - 33 - Overheat protection time duration for locked rotor - UINT - 16 - 528 - - rw - - - - 34 - Overheat protection for locked rotor enable - UINT - 16 - 544 - - rw - - - - 37 - Absolute Encode multi-turns error forbidden - UINT - 16 - 592 - - rw - - - - 41 - Compensation Function - UINT - 16 - 656 - - rw - - - - 50 - Over Temperature value of discharge tube - UINT - 16 - 800 - - rw - - - - 51 - Encoder communiction error threshold - UINT - 16 - 816 - - rw - - - - 52 - Phase lack threshold - UINT - 16 - 832 - - rw - - - - 53 - Over Temperature value of Encoder - UINT - 16 - 848 - - rw - - - - 54 - TouchProbe DI Turn-on Compensation Time - INT - 16 - 864 - - rw - - - - 55 - TouchProbe DI Turn-off Compensation Time - INT - 16 - 880 - - rw - - - - 56 - Runaway current threshold - UINT - 16 - 896 - - rw - - - - 57 - Fault reset delay time - UINT - 16 - 912 - - rw - - - - 58 - Runaway speed threshold - UINT - 16 - 928 - - rw - - - - 59 - Runaway speed filter time constant - UINT - 16 - 944 - - rw - - - - 60 - Runaway protection time window - UINT - 16 - 960 - - rw - - - - 61 - BlackBox Mode Select - UINT - 16 - 976 - - rw - - - - 62 - BlackBox Selected Error Code - UINT - 16 - 992 - - rw - - - - 63 - BlackBox Trig Source - UINT - 16 - 1008 - - rw - - - - 64 - BlackBox Trig Level - DINT - 32 - 1024 - - rw - - - - 66 - BlackBox Trig Level Select - UINT - 16 - 1056 - - rw - - - - 67 - BlackBox Trig Position - UINT - 16 - 1072 - - rw - - - - 68 - BlackBox Trig Frequency Select - UINT - 16 - 1088 - - rw - - - - 71 - The 2nd over speed threshold - UINT - 16 - 1136 - - rw - - - - 72 - Motor over load monitor switch - UINT - 16 - 1152 - - rw - - - - 73 - Maximum ramp stop time - UINT - 16 - 1168 - - rw - - - - 74 - STO Disconnect filter time - UINT - 16 - 1184 - - rw - - - - 75 - STO Mismatch filter time - UINT - 16 - 1200 - - rw - - - - 76 - STO Servo off filter time - UINT - 16 - 1216 - - rw - - - - 86 - Motor Offline Trq Limit - UINT - 16 - 1376 - - rw - - - - 87 - Motor Offline Filter Time - UINT - 16 - 1392 - - rw - - - - 91 - Filter Time Constant of Spd Display - UINT - 16 - 1456 - - rw - - - - 92 - Filter Time Constant of Trq Display - INT - 16 - 1472 - - rw - - - - 93 - Filter Time Constant of Position Display - UINT - 16 - 1488 - - rw - - - - 94 - Filter Time Constant of Voltage Display - UINT - 16 - 1504 - - rw - - - - 95 - Filter Time Constant of Temp Display - UINT - 16 - 1520 - - rw - - - - - DT200B - 1584 - - 0 - Number of Entries - USINT - 8 - 0 - - ro - - - - 1 - Actual motor rotational speed - INT - 16 - 16 - - ro - T - - - - 2 - Speed reference - INT - 16 - 32 - - ro - T - - - - 3 - Internal torque reference - INT - 16 - 48 - - ro - T - - - - 4 - Monitored DI states - UINT - 16 - 64 - - ro - T - - - - 6 - Monitored DO states - UINT - 16 - 96 - - ro - T - - - - 8 - Absolute position counter - DINT - 32 - 128 - - ro - T - - - - 10 - Mechanical angle - UINT - 16 - 160 - - ro - T - - - - 11 - Electrical angle - UINT - 16 - 176 - - ro - T - - - - 13 - Average load rate - UINT - 16 - 208 - - ro - T - - - - 16 - Encoder position deviation counter - DINT - 32 - 256 - - ro - T - - - - 18 - Feedback pulse counter - DINT - 32 - 288 - - ro - T - - - - 20 - Total power-on time - UDINT - 32 - 320 - - ro - T - - - - 22 - AI1 Voltage DisPlay - INT - 16 - 352 - - ro - T - - - - 25 - Phase current valid value - UINT - 16 - 400 - - ro - T - - - - 27 - Bus voltage - UINT - 16 - 432 - - ro - T - - - - 28 - Module temperature - UINT - 16 - 448 - - ro - T - - - - 29 - Absolute encoder fault info. from FPGA - UINT - 16 - 464 - - ro - - - - 30 - Axis state from FPGA - UINT - 16 - 480 - - ro - - - - 31 - Axis fault info. from FPGA - UINT - 16 - 496 - - ro - - - - 32 - Encoder internal fault info. - UINT - 16 - 512 - - rw - - - - 34 - Displayed fault record - UINT - 16 - 544 - - rw - - - - 35 - Fault code - UINT - 16 - 560 - - ro - - - - 36 - Time stamp upon displayed fault - UDINT - 32 - 576 - - ro - - - - 38 - Current rotational speed upon displayed fault - INT - 16 - 608 - - ro - - - - 39 - Current U upon displayed fault - INT - 16 - 624 - - ro - - - - 40 - Current V upon displayed fault - INT - 16 - 640 - - ro - - - - 41 - Bus voltage upon displayed fault - UINT - 16 - 656 - - ro - - - - 42 - Input terminal state upon displayed fault - UINT - 16 - 672 - - ro - - - - 44 - Output terminal state upon displayed fault - UINT - 16 - 704 - - ro - - - - 46 - Inner error code - UINT - 16 - 736 - - ro - - - - 47 - Fault message of absolute encode from Fpga upon displayed - UINT - 16 - 752 - - ro - - - - 48 - System state from Fpga upon displayed fault - UINT - 16 - 768 - - ro - - - - 49 - System fault message from Fpga upon displayed fault - UINT - 16 - 784 - - ro - - - - 50 - Encode state 1 upon displayed fault - UINT - 16 - 800 - - ro - - - - 52 - Inner error code upon displayed fault - UINT - 16 - 832 - - ro - - - - 53 - Fpga overtime state upon displayed fault - UINT - 16 - 848 - - ro - - - - 54 - Reference position deviation - DINT - 32 - 864 - - ro - T - - - - 56 - Actual motor rotational speed(0.1rpm) - DINT - 32 - 896 - - ro - T - - - - 58 - Control bus voltage - UINT - 16 - 928 - - ro - T - - - - 59 - Mechanical absolute position inc(Low) - UDINT - 32 - 944 - - ro - T - - - - 61 - Mechanical absolute position inc(High) - DINT - 32 - 976 - - ro - T - - - - 64 - Not ready reason - UINT - 16 - 1024 - - ro - - - - 67 - Encoder temperature - UINT - 16 - 1072 - - ro - - - - 68 - Discharge load rate - UINT - 16 - 1088 - - ro - T - - - - 69 - Fpga over time state - UINT - 16 - 1104 - - ro - - - - 71 - Number of turns of absolute encode - UINT - 16 - 1136 - - ro - T - - - - 72 - Single feedback postion of absolute encode - UDINT - 32 - 1152 - - ro - T - - - - 75 - System Error - UINT - 16 - 1200 - - ro - - - - 78 - feedback postion of absolute encode(Low) - UDINT - 32 - 1248 - - ro - T - - - - 80 - feedback postion of absolute encode(High) - DINT - 32 - 1280 - - ro - T - - - - 82 - feedback postion inc of rotating load(Low) - UDINT - 32 - 1312 - - ro - T - - - - 84 - feedback postion inc of rotating load(High) - UDINT - 32 - 1344 - - ro - T - - - - 86 - Single feedback postion of rotating load - UDINT - 32 - 1376 - - ro - T - - - - 88 - IGBT Temperature - UINT - 16 - 1408 - - ro - - - - 91 - Group of unusual function code - UINT - 16 - 1456 - - ro - - - - 92 - Offset of unusual function code - UINT - 16 - 1472 - - ro - - - - 95 - Single Power-On Time - UDINT - 32 - 1520 - - ro - T - - - - 97 - Single Power-On Time upon displayed fault - UDINT - 32 - 1552 - - ro - - - - - DT200D - 400 - - 0 - Number of Entries - USINT - 8 - 0 - - ro - - - - 1 - Software reset - UINT - 16 - 16 - - rw - - - - 2 - Fault reset - UINT - 16 - 32 - - rw - - - - 3 - Offline inertia autotuning selection - UINT - 16 - 48 - - rw - - - - 5 - Encoder ROM reading/writing - UINT - 16 - 80 - - rw - - - - 6 - Emergency stop - UINT - 16 - 96 - - rw - - - - 11 - AI1 Self-Adjust of Voltage Offset - UINT - 16 - 176 - - rw - - - - 13 - UV phase current auto-tuning - UINT - 16 - 208 - - rw - - - - 18 - Forced DI/DO setting - UINT - 16 - 288 - - rw - - - - 19 - Forced DI level - UINT - 16 - 304 - - rw - - - - 20 - Forced DO setting - UINT - 16 - 320 - - rw - - - - 21 - Absolute Encode Fault Reset - UINT - 16 - 336 - - rw - - - - 24 - Cogging torque self-learning - UINT - 16 - 384 - - rw - - - - - DT200E - 1568 - - 0 - Number of Entries - USINT - 8 - 0 - - ro - - - - 1 - Node address - UINT - 16 - 16 - - rw - - - - 2 - Update function code values written via communication to EEPROM - UINT - 16 - 32 - - rw - - - - 21 - station auto inc address - UINT - 16 - 336 - - ro - - - - 22 - station alias - UINT - 16 - 352 - - rw - - - - 23 - Sync lost window - UINT - 16 - 368 - - rw - - - - 25 - Sync lost counter - UINT - 16 - 400 - - ro - - - - 26 - Port 0 invalid frame counter - UINT - 16 - 416 - - ro - - - - 27 - Port 1 invalid frame counter - UINT - 16 - 432 - - ro - - - - 28 - Port 0/1 transfer error counter - UINT - 16 - 448 - - ro - - - - 29 - process unit and PDI error counter - UINT - 16 - 464 - - ro - - - - 30 - Port 0/1 lost counter - UINT - 16 - 480 - - ro - - - - 32 - Sync mode set - UINT - 16 - 512 - - rw - - - - 33 - Sync error window - UINT - 16 - 528 - - rw - - - - 34 - EtherCAT network state and link state - UINT - 16 - 544 - - ro - - - - 35 - CSP postion increment over counter - UINT - 16 - 560 - - rw - - - - 36 - ECAT AL Error Code - UINT - 16 - 576 - - ro - - - - 37 - Enhanced link detection enable - UINT - 16 - 592 - - rw - - - - 38 - Reset EtherCAT xml file - UINT - 16 - 608 - - rw - - - - 74 - EtherCAT port control mode and state display - UINT - 16 - 1184 - - ro - - - - 94 - EtherCAT COE version number - UINT - 16 - 1504 - - ro - - - - 97 - EtherCAT xml file version number - UINT - 16 - 1552 - - ro - - - - - DT200F - 720 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Encoder feedback mode - UINT - 16 - 16 - - rw - - - - 2 - Running mode of external encoder - UINT - 16 - 32 - - rw - - - - 3 - SecEncoder Absolute system selection - UINT - 16 - 48 - - rw - - - - 4 - SecEncoder Type selection - UINT - 16 - 64 - - rw - - - - 5 - External encoder pulses per motor revolution - UDINT - 32 - 80 - - rw - - - - 9 - Hybrid deviation excess setting - UDINT - 32 - 144 - - rw - - - - 11 - Hybrid deviation clear setting - UINT - 16 - 176 - - rw - - - - 14 - First-order lowpass filter time of external/internal deviation - UINT - 16 - 224 - - rw - - - - 17 - Hybrid deviation counter - DINT - 32 - 272 - - ro - T - - - - 19 - Pulse feedback display of internal encoder - DINT - 32 - 304 - - ro - T - - - - 21 - Pulse feedback display of external encoder - DINT - 32 - 336 - - ro - T - - - - 23 - SecEncoder Pulse ZPhase Ignore - UINT - 16 - 368 - - rw - - - - 26 - SecEncoder Pulse Z-TouchProbe Selection - UINT - 16 - 416 - - rw - - - - - DT2012 - 1104 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - MultiSpd Function Select - UINT - 16 - 16 - - rw - R - - - - 2 - MultiSpd Final Part Select - UINT - 16 - 32 - - rw - R - - - - 3 - Time Uint of Runing - UINT - 16 - 48 - - rw - R - - - - 4 - AccTime1 - UINT - 16 - 64 - - rw - R - - - - 5 - DecTime1 - UINT - 16 - 80 - - rw - R - - - - 6 - AccTime2 - UINT - 16 - 96 - - rw - R - - - - 7 - DecTime2 - UINT - 16 - 112 - - rw - R - - - - 8 - AccTime3 - UINT - 16 - 128 - - rw - R - - - - 9 - DecTime3 - UINT - 16 - 144 - - rw - R - - - - 10 - AccTime4 - UINT - 16 - 160 - - rw - R - - - - 11 - DecTime4 - UINT - 16 - 176 - - rw - R - - - - 21 - 1st Part Spd Cmd - INT - 16 - 336 - - rw - R - - - - 22 - 1st Part Spd Runing Time - UINT - 16 - 352 - - rw - R - - - - 23 - 1st Part AccDec Time Select - UINT - 16 - 368 - - rw - R - - - - 24 - 2nd Part Spd Cmd - INT - 16 - 384 - - rw - R - - - - 25 - 2nd Part Spd Runing Time - UINT - 16 - 400 - - rw - R - - - - 26 - 2nd Part AccDec Time Select - UINT - 16 - 416 - - rw - R - - - - 27 - 3rd Part Spd Cmd - INT - 16 - 432 - - rw - R - - - - 28 - 3rd Part Spd Runing Time - UINT - 16 - 448 - - rw - R - - - - 29 - 3rd Part AccDec Time Select - UINT - 16 - 464 - - rw - R - - - - 30 - 4th Part Spd Cmd - INT - 16 - 480 - - rw - R - - - - 31 - 4th Part Spd Runing Time - UINT - 16 - 496 - - rw - R - - - - 32 - 4th Part AccDec Time Select - UINT - 16 - 512 - - rw - R - - - - 33 - 5th Part Spd Cmd - INT - 16 - 528 - - rw - R - - - - 34 - 5th Part Spd Runing Time - UINT - 16 - 544 - - rw - R - - - - 35 - 5th Part AccDec Time Select - UINT - 16 - 560 - - rw - R - - - - 36 - 6th Part Spd Cmd - INT - 16 - 576 - - rw - R - - - - 37 - 6th Part Spd Runing Time - UINT - 16 - 592 - - rw - R - - - - 38 - 6th Part AccDec Time Select - UINT - 16 - 608 - - rw - R - - - - 39 - 7th Part Spd Cmd - INT - 16 - 624 - - rw - R - - - - 40 - 7th Part Spd Runing Time - UINT - 16 - 640 - - rw - R - - - - 41 - 7th Part AccDec Time Select - UINT - 16 - 656 - - rw - R - - - - 42 - 8th Part Spd Cmd - INT - 16 - 672 - - rw - R - - - - 43 - 8th Part Spd Runing Time - UINT - 16 - 688 - - rw - R - - - - 44 - 8th Part AccDec Time Select - UINT - 16 - 704 - - rw - R - - - - 45 - 9th Part Spd Cmd - INT - 16 - 720 - - rw - R - - - - 46 - 9th Part Spd Runing Time - UINT - 16 - 736 - - rw - R - - - - 47 - 9th Part AccDec Time Select - UINT - 16 - 752 - - rw - R - - - - 48 - 10th Part Spd Cmd - INT - 16 - 768 - - rw - R - - - - 49 - 10th Part Spd Runing Time - UINT - 16 - 784 - - rw - R - - - - 50 - 10th Part AccDec Time Select - UINT - 16 - 800 - - rw - R - - - - 51 - 11th Part Spd Cmd - INT - 16 - 816 - - rw - R - - - - 52 - 11th Part Spd Runing Time - UINT - 16 - 832 - - rw - R - - - - 53 - 11th Part AccDec Time Select - UINT - 16 - 848 - - rw - R - - - - 54 - 12th Part Spd Cmd - INT - 16 - 864 - - rw - R - - - - 55 - 12th Part Spd Runing Time - UINT - 16 - 880 - - rw - R - - - - 56 - 12th Part AccDec Time Select - UINT - 16 - 896 - - rw - R - - - - 57 - 13th Part Spd Cmd - INT - 16 - 912 - - rw - R - - - - 58 - 13th Part Spd Runing Time - UINT - 16 - 928 - - rw - R - - - - 59 - 13th Part AccDec Time Select - UINT - 16 - 944 - - rw - R - - - - 60 - 14th Part Spd Cmd - INT - 16 - 960 - - rw - R - - - - 61 - 14th Part Spd Runing Time - UINT - 16 - 976 - - rw - R - - - - 62 - 14th Part AccDec Time Select - UINT - 16 - 992 - - rw - R - - - - 63 - 15th Part Spd Cmd - INT - 16 - 1008 - - rw - R - - - - 64 - 15th Part Spd Runing Time - UINT - 16 - 1024 - - rw - R - - - - 65 - 15th Part AccDec Time Select - UINT - 16 - 1040 - - rw - R - - - - 66 - 16th Part Spd Cmd - INT - 16 - 1056 - - rw - R - - - - 67 - 16th Part Spd Runing Time - UINT - 16 - 1072 - - rw - R - - - - 68 - 16th Part AccDec Time Select - UINT - 16 - 1088 - - rw - R - - - - - DT2017 - 1520 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - VDI1 Terminal Function Selection - UINT - 16 - 16 - - rw - - - - 2 - VDI1 Terminal Logic Selection - UINT - 16 - 32 - - rw - - - - 3 - VDI2 Terminal Function Selection - UINT - 16 - 48 - - rw - - - - 4 - VDI2 Terminal Logic Selection - UINT - 16 - 64 - - rw - - - - 5 - VDI3 Terminal Function Selection - UINT - 16 - 80 - - rw - - - - 6 - VDI3 Terminal Logic Selection - UINT - 16 - 96 - - rw - - - - 7 - VDI4 Terminal Function Selection - UINT - 16 - 112 - - rw - - - - 8 - VDI4 Terminal Logic Selection - UINT - 16 - 128 - - rw - - - - 9 - VDI5 Terminal Function Selection - UINT - 16 - 144 - - rw - - - - 10 - VDI5 Terminal Logic Selection - UINT - 16 - 160 - - rw - - - - 11 - VDI6 Terminal Function Selection - UINT - 16 - 176 - - rw - - - - 12 - VDI6 Terminal Logic Selection - UINT - 16 - 192 - - rw - - - - 13 - VDI7 Terminal Function Selection - UINT - 16 - 208 - - rw - - - - 14 - VDI7 Terminal Logic Selection - UINT - 16 - 224 - - rw - - - - 15 - VDI8 Terminal Function Selection - UINT - 16 - 240 - - rw - - - - 16 - VDI8 Terminal Logic Selection - UINT - 16 - 256 - - rw - - - - 17 - VDI9 Terminal Function Selection - UINT - 16 - 272 - - rw - - - - 18 - VDI9 Terminal Logic Selection - UINT - 16 - 288 - - rw - - - - 19 - VDI10 Terminal Function Selection - UINT - 16 - 304 - - rw - - - - 20 - VDI10 Terminal Logic Selection - UINT - 16 - 320 - - rw - - - - 21 - VDI11 Terminal Function Selection - UINT - 16 - 336 - - rw - - - - 22 - VDI11 Terminal Logic Selection - UINT - 16 - 352 - - rw - - - - 23 - VDI12 Terminal Function Selection - UINT - 16 - 368 - - rw - - - - 24 - VDI12 Terminal Logic Selection - UINT - 16 - 384 - - rw - - - - 25 - VDI13 Terminal Function Selection - UINT - 16 - 400 - - rw - - - - 26 - VDI13 Terminal Logic Selection - UINT - 16 - 416 - - rw - - - - 27 - VDI14 Terminal Function Selection - UINT - 16 - 432 - - rw - - - - 28 - VDI14 Terminal Logic Selection - UINT - 16 - 448 - - rw - - - - 29 - VDI15 Terminal Function Selection - UINT - 16 - 464 - - rw - - - - 30 - VDI15 Terminal Logic Selection - UINT - 16 - 480 - - rw - - - - 31 - VDI16 Terminal Function Selection - UINT - 16 - 496 - - rw - - - - 32 - VDI16 Terminal Logic Selection - UINT - 16 - 512 - - rw - - - - 33 - VDO virtual level - UINT - 16 - 528 - - ro - - - - 34 - VDO1 Terminal Function Selection - UINT - 16 - 544 - - rw - - - - 35 - VDO1 Terminal Logic Level Selection - UINT - 16 - 560 - - rw - - - - 36 - VDO2 Terminal Function Selection - UINT - 16 - 576 - - rw - - - - 37 - VDO2 Terminal Logic Level Selection - UINT - 16 - 592 - - rw - - - - 38 - VDO3 Terminal Function Selection - UINT - 16 - 608 - - rw - - - - 39 - VDO3 Terminal Logic Level Selection - UINT - 16 - 624 - - rw - - - - 40 - VDO4 Terminal Function Selection - UINT - 16 - 640 - - rw - - - - 41 - VDO4 Terminal Logic Level Selection - UINT - 16 - 656 - - rw - - - - 42 - VDO5 Terminal Function Selection - UINT - 16 - 672 - - rw - - - - 43 - VDO5 Terminal Logic Level Selection - UINT - 16 - 688 - - rw - - - - 44 - VDO6 Terminal Function Selection - UINT - 16 - 704 - - rw - - - - 45 - VDO6 Terminal Logic Level Selection - UINT - 16 - 720 - - rw - - - - 46 - VDO7 Terminal Function Selection - UINT - 16 - 736 - - rw - - - - 47 - VDO7 Terminal Logic Level Selection - UINT - 16 - 752 - - rw - - - - 48 - VDO8 Terminal Function Selection - UINT - 16 - 768 - - rw - - - - 49 - VDO8 Terminal Logic Level Selection - UINT - 16 - 784 - - rw - - - - 50 - VDO9 Terminal Function Selection - UINT - 16 - 800 - - rw - - - - 51 - VDO9 Terminal Logic Level Selection - UINT - 16 - 816 - - rw - - - - 52 - VDO10 Terminal Function Selection - UINT - 16 - 832 - - rw - - - - 53 - VDO10 Terminal Logic Level Selection - UINT - 16 - 848 - - rw - - - - 54 - VDO11 Terminal Function Selection - UINT - 16 - 864 - - rw - - - - 55 - VDO11 Terminal Logic Level Selection - UINT - 16 - 880 - - rw - - - - 56 - VDO12 Terminal Function Selection - UINT - 16 - 896 - - rw - - - - 57 - VDO12 Terminal Logic Level Selection - UINT - 16 - 912 - - rw - - - - 58 - VDO13 Terminal Function Selection - UINT - 16 - 928 - - rw - - - - 59 - VDO13 Terminal Logic Level Selection - UINT - 16 - 944 - - rw - - - - 60 - VDO14 Terminal Function Selection - UINT - 16 - 960 - - rw - - - - 61 - VDO14 Terminal Logic Level Selection - UINT - 16 - 976 - - rw - - - - 62 - VDO15 Terminal Function Selection - UINT - 16 - 992 - - rw - - - - 63 - VDO15 Terminal Logic Level Selection - UINT - 16 - 1008 - - rw - - - - 64 - VDO16 Terminal Function Selection - UINT - 16 - 1024 - - rw - - - - 65 - VDO16 Terminal Logic Level Selection - UINT - 16 - 1040 - - rw - - - - 91 - VDI Enable - UINT - 16 - 1456 - - rw - R - - - - 92 - VDI Default Value - UINT - 16 - 1472 - - rw - R - - - - 93 - VDO Enable - UINT - 16 - 1488 - - rw - R - - - - 94 - VDO Default Value - UINT - 16 - 1504 - - rw - R - - - - - DT2018 - 288 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Enable Comparison - UINT - 16 - 16 - - rw - R - - - - 2 - Comparison PosFdb Source Select - UINT - 16 - 32 - - rw - R - - - - 3 - Encoder Resolution - UINT - 16 - 48 - - rw - R - - - - 4 - Mode Of Comparison - UINT - 16 - 64 - - rw - R - - - - 5 - Current Position As Zero - UINT - 16 - 80 - - rw - R - - - - 6 - Output Duration - UINT - 16 - 96 - - rw - R - - - - 7 - Comparison ABZ OutPut Logic - UINT - 16 - 112 - - rw - R - - - - 8 - Starting Point Number - UINT - 16 - 128 - - rw - R - - - - 9 - Ending Point Number - UINT - 16 - 144 - - rw - R - - - - 10 - Comparison Status - UINT - 16 - 160 - - ro - T - - - - 11 - Current Position - DINT - 32 - 176 - - ro - T - - - - 13 - Position Offset - DINT - 32 - 208 - - rw - R - - - - 15 - Comparison OutPut Delay Compensation - INT - 16 - 240 - - rw - R - - - - 16 - Lilited number of Comparison Cycle Times - UINT - 16 - 256 - - rw - R - - - - 17 - Comparison ABZ OutPut Function - UINT - 16 - 272 - - rw - R - - - - - DT2019 - 1936 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Comparing Position - DINT - 32 - 16 - - rw - R - - - - 3 - 1st Point Property - UINT - 16 - 48 - - rw - R - - - - 4 - 2nd Comparing Position - DINT - 32 - 64 - - rw - R - - - - 6 - 2nd Point Property - UINT - 16 - 96 - - rw - R - - - - 7 - 3rd Comparing Position - DINT - 32 - 112 - - rw - R - - - - 9 - 3rd Point Property - UINT - 16 - 144 - - rw - R - - - - 10 - 4th Comparing Position - DINT - 32 - 160 - - rw - R - - - - 12 - 4th Point Property - UINT - 16 - 192 - - rw - R - - - - 13 - 5th Comparing Position - DINT - 32 - 208 - - rw - R - - - - 15 - 5th Point Property - UINT - 16 - 240 - - rw - R - - - - 16 - 6th Comparing Position - DINT - 32 - 256 - - rw - R - - - - 18 - 6th Point Property - UINT - 16 - 288 - - rw - R - - - - 19 - 7th Comparing Position - DINT - 32 - 304 - - rw - R - - - - 21 - 7th Point Property - UINT - 16 - 336 - - rw - R - - - - 22 - 8th Comparing Position - DINT - 32 - 352 - - rw - R - - - - 24 - 8th Point Property - UINT - 16 - 384 - - rw - R - - - - 25 - 9th Comparing Position - DINT - 32 - 400 - - rw - R - - - - 27 - 9th Point Property - UINT - 16 - 432 - - rw - R - - - - 28 - 10th Comparing Position - DINT - 32 - 448 - - rw - R - - - - 30 - 10th Point Property - UINT - 16 - 480 - - rw - R - - - - 31 - 11th Comparing Position - DINT - 32 - 496 - - rw - R - - - - 33 - 11th Point Property - UINT - 16 - 528 - - rw - R - - - - 34 - 12th Comparing Position - DINT - 32 - 544 - - rw - R - - - - 36 - 12th Point Property - UINT - 16 - 576 - - rw - R - - - - 37 - 13th Comparing Position - DINT - 32 - 592 - - rw - R - - - - 39 - 13th Point Property - UINT - 16 - 624 - - rw - R - - - - 40 - 14th Comparing Position - DINT - 32 - 640 - - rw - R - - - - 42 - 14th Point Property - UINT - 16 - 672 - - rw - R - - - - 43 - 15th Comparing Position - DINT - 32 - 688 - - rw - R - - - - 45 - 15th Point Property - UINT - 16 - 720 - - rw - R - - - - 46 - 16th Comparing Position - DINT - 32 - 736 - - rw - R - - - - 48 - 16th Point Property - UINT - 16 - 768 - - rw - R - - - - 49 - 17th Comparing Position - DINT - 32 - 784 - - rw - R - - - - 51 - 17th Point Property - UINT - 16 - 816 - - rw - R - - - - 52 - 18th Comparing Position - DINT - 32 - 832 - - rw - R - - - - 54 - 18th Point Property - UINT - 16 - 864 - - rw - R - - - - 55 - 19th Comparing Position - DINT - 32 - 880 - - rw - R - - - - 57 - 19th Point Property - UINT - 16 - 912 - - rw - R - - - - 58 - 20th Comparing Position - DINT - 32 - 928 - - rw - R - - - - 60 - 20th Point Property - UINT - 16 - 960 - - rw - R - - - - 61 - 21st Comparing Position - DINT - 32 - 976 - - rw - R - - - - 63 - 21st Point Property - UINT - 16 - 1008 - - rw - R - - - - 64 - 22nd Comparing Position - DINT - 32 - 1024 - - rw - R - - - - 66 - 22nd Point Property - UINT - 16 - 1056 - - rw - R - - - - 67 - 23rd Comparing Position - DINT - 32 - 1072 - - rw - R - - - - 69 - 23rd Point Property - UINT - 16 - 1104 - - rw - R - - - - 70 - 24th Comparing Position - DINT - 32 - 1120 - - rw - R - - - - 72 - 24th Point Property - UINT - 16 - 1152 - - rw - R - - - - 73 - 25th Comparing Position - DINT - 32 - 1168 - - rw - R - - - - 75 - 25th Point Property - UINT - 16 - 1200 - - rw - R - - - - 76 - 26th Comparing Position - DINT - 32 - 1216 - - rw - R - - - - 78 - 26th Point Property - UINT - 16 - 1248 - - rw - R - - - - 79 - 27th Comparing Position - DINT - 32 - 1264 - - rw - R - - - - 81 - 27th Point Property - UINT - 16 - 1296 - - rw - R - - - - 82 - 28th Comparing Position - DINT - 32 - 1312 - - rw - R - - - - 84 - 28th Point Property - UINT - 16 - 1344 - - rw - R - - - - 85 - 29th Comparing Position - DINT - 32 - 1360 - - rw - R - - - - 87 - 29th Point Property - UINT - 16 - 1392 - - rw - R - - - - 88 - 30th Comparing Position - DINT - 32 - 1408 - - rw - R - - - - 90 - 30th Point Property - UINT - 16 - 1440 - - rw - R - - - - 91 - 31st Comparing Position - DINT - 32 - 1456 - - rw - R - - - - 93 - 31st Point Property - UINT - 16 - 1488 - - rw - R - - - - 94 - 32nd Comparing Position - DINT - 32 - 1504 - - rw - R - - - - 96 - 32nd Point Property - UINT - 16 - 1536 - - rw - R - - - - 97 - 33rd Comparing Position - DINT - 32 - 1552 - - rw - R - - - - 99 - 33rd Point Property - UINT - 16 - 1584 - - rw - R - - - - 100 - 34th Comparing Position - DINT - 32 - 1600 - - rw - R - - - - 102 - 34th Point Property - UINT - 16 - 1632 - - rw - R - - - - 103 - 35th Comparing Position - DINT - 32 - 1648 - - rw - R - - - - 105 - 35th Point Property - UINT - 16 - 1680 - - rw - R - - - - 106 - 36th Comparing Position - DINT - 32 - 1696 - - rw - R - - - - 108 - 36th Point Property - UINT - 16 - 1728 - - rw - R - - - - 109 - 37th Comparing Position - DINT - 32 - 1744 - - rw - R - - - - 111 - 37th Point Property - UINT - 16 - 1776 - - rw - R - - - - 112 - 38th Comparing Position - DINT - 32 - 1792 - - rw - R - - - - 114 - 38th Point Property - UINT - 16 - 1824 - - rw - R - - - - 115 - 39th Comparing Position - DINT - 32 - 1840 - - rw - R - - - - 117 - 39th Point Property - UINT - 16 - 1872 - - rw - R - - - - 118 - 40th Comparing Position - DINT - 32 - 1888 - - rw - R - - - - 120 - 40th Point Property - UINT - 16 - 1920 - - rw - R - - - - - DT2030 - 64 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Servo Status - UINT - 16 - 16 - - ro - T - - - - 2 - DO Function1 - UINT - 16 - 32 - - ro - T - - - - 3 - DO Function2 - UINT - 16 - 48 - - ro - T - - - - - DT2031 - 224 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Comm Set VDI - UINT - 16 - 16 - - rw - R - - - - 5 - Comm Set DO - UINT - 16 - 80 - - rw - R - - - - 6 - Comm Set AO - INT - 16 - 96 - - rw - R - - - - 10 - Comm Set Local SpdRef - DINT - 32 - 160 - - rw - R - - - - 12 - Comm Set Local TrqRef - DINT - 32 - 192 - - rw - R - - - - - DT607D - 80 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Min position limit - DINT - 32 - 16 - - rw - R - - - - 2 - Max position limit - DINT - 32 - 48 - - rw - R - - - - - DT6091 - 80 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Motor revolutions - UDINT - 32 - 16 - - rw - R - - - - 2 - Shaft revolutions - UDINT - 32 - 48 - - rw - R - - - - - DT6099 - 80 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Speed during search for switch - UDINT - 32 - 16 - - rw - R - - - - 2 - Speed during search for zero - UDINT - 32 - 48 - - rw - R - - - - - DT60FE - 80 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Physical outputs - UDINT - 32 - 16 - - rw - R - - - - 2 - Bit Mask - UDINT - 32 - 48 - - rw - R - - - - - DT60E3 - 544 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Support homing method 1 - INT - 16 - 16 - - ro - - - - 2 - Support homing method 2 - INT - 16 - 32 - - ro - - - - 3 - Support homing method 3 - INT - 16 - 48 - - ro - - - - 4 - Support homing method 4 - INT - 16 - 64 - - ro - - - - 5 - Support homing method 5 - INT - 16 - 80 - - ro - - - - 6 - Support homing method 6 - INT - 16 - 96 - - ro - - - - 7 - Support homing method 7 - INT - 16 - 112 - - ro - - - - 8 - Support homing method 8 - INT - 16 - 128 - - ro - - - - 9 - Support homing method 9 - INT - 16 - 144 - - ro - - - - 10 - Support homing method 10 - INT - 16 - 160 - - ro - - - - 11 - Support homing method 11 - INT - 16 - 176 - - ro - - - - 12 - Support homing method 12 - INT - 16 - 192 - - ro - - - - 13 - Support homing method 13 - INT - 16 - 208 - - ro - - - - 14 - Support homing method 14 - INT - 16 - 224 - - ro - - - - 15 - Support homing method 15 - INT - 16 - 240 - - ro - - - - 16 - Support homing method 16 - INT - 16 - 256 - - ro - - - - 17 - Support homing method 17 - INT - 16 - 272 - - ro - - - - 18 - Support homing method 18 - INT - 16 - 288 - - ro - - - - 19 - Support homing method 19 - INT - 16 - 304 - - ro - - - - 20 - Support homing method 20 - INT - 16 - 320 - - ro - - - - 21 - Support homing method 21 - INT - 16 - 336 - - ro - - - - 22 - Support homing method 22 - INT - 16 - 352 - - ro - - - - 23 - Support homing method 23 - INT - 16 - 368 - - ro - - - - 24 - Support homing method 24 - INT - 16 - 384 - - ro - - - - 25 - Support homing method 25 - INT - 16 - 400 - - ro - - - - 26 - Support homing method 26 - INT - 16 - 416 - - ro - - - - 27 - Support homing method 27 - INT - 16 - 432 - - ro - - - - 28 - Support homing method 28 - INT - 16 - 448 - - ro - - - - 29 - Support homing method 29 - INT - 16 - 464 - - ro - - - - 30 - Support homing method 30 - INT - 16 - 480 - - ro - - - - 31 - Support homing method 31 - INT - 16 - 496 - - ro - - - - 32 - Support homing method 32 - INT - 16 - 512 - - ro - - - - 33 - Support homing method 33 - INT - 16 - 528 - - ro - - - - - - - #x1000 - Device type - UDINT - 32 - - #x00020192 - - - ro - o - - - - #x1001 - Error Register - USINT - 8 - - 00 - - - ro - o - - - - #x1008 - Device name - STRING(10) - 80 - - SV670_ECAT - - - ro - - - - #x1009 - Hardware version - STRING(4) - 32 - - V1.0 - - - ro - - - - #x100a - Software version - STRING(4) - 32 - - V1.0 - - - ro - o - - - - #x1c00 - Sync manager type - DT1C00 - 48 - - - SubIndex 000 - - 04 - - - - SubIndex 001 - - 01 - - - - SubIndex 002 - - 02 - - - - SubIndex 003 - - 03 - - - - SubIndex 004 - - 04 - - - - - ro - o - - - - #x1018 - Identity - DT1018 - 144 - - - SubIndex 000 - - 04 - - - - Vendor ID - - #x00100000 - - - - Product Code - - #x000C011E - - - - Revision - - #x00010000 - - - - Serial number - - 00000000 - - - - - ro - o - - - - #x1600 - Outputs - DT1600 - 336 - - - SubIndex 000 - - 00 - 10 - #x03 - - - - 1st Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60400010 - - - - 2nd Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x607A0020 - - - - 3rd Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60B80010 - - - - 4th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 5th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 6th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 7th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 8th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 9th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 10th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - - rw - - - - #x1601 - Outputs - DT1601 - 368 - - - SubIndex 000 - - #x0B - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x60600008 - - - - 3rd Output Object to be mapped - - #x60710010 - - - - 4th Output Object to be mapped - - #x607A0020 - - - - 5th Output Object to be mapped - - #x607F0020 - - - - 6th Output Object to be mapped - - #x60810020 - - - - 7th Output Object to be mapped - - #x60830020 - - - - 8th Output Object to be mapped - - #x60840020 - - - - 9th Output Object to be mapped - - #x60870020 - - - - 10th Output Object to be mapped - - #x60B80010 - - - - 11th Output Object to be mapped - - #x60FF0020 - - - - - rw - - - - #x1701 - Outputs - DT1701 - 336 - - - SubIndex 000 - - #x04 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60B80010 - - - - 4th Output Object to be mapped - - #x60FE0120 - - - - - ro - - - - #x1702 - Outputs - DT1702 - 336 - - - SubIndex 000 - - #x07 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60B80010 - - - - 4th Output Object to be mapped - - #x60710010 - - - - 5th Output Object to be mapped - - #x60600008 - - - - 6th Output Object to be mapped - - #x60B80010 - - - - 7th Output Object to be mapped - - #x607F0020 - - - - - ro - - - - #x1703 - Outputs - DT1702 - 336 - - - SubIndex 000 - - #x07 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60FF0020 - - - - 4th Output Object to be mapped - - #x60600008 - - - - 5th Output Object to be mapped - - #x60B80010 - - - - 6th Output Object to be mapped - - #x60E00010 - - - - 7th Output Object to be mapped - - #x60E10010 - - - - - ro - - - - #x1704 - Outputs - DT1704 - 336 - - - SubIndex 000 - - #x09 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60FF0020 - - - - 4th Output Object to be mapped - - #x60710010 - - - - 5th Output Object to be mapped - - #x60600008 - - - - 6th Output Object to be mapped - - #x60B80010 - - - - 7th Output Object to be mapped - - #x607F0020 - - - - 8th Output Object to be mapped - - #x60E00010 - - - - 9th Output Object to be mapped - - #x60E10010 - - - - - ro - - - - #x1705 - Outputs - DT1705 - 336 - - - SubIndex 000 - - #x08 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60FF0020 - - - - 4th Output Object to be mapped - - #x60600008 - - - - 5th Output Object to be mapped - - #x60B80010 - - - - 6th Output Object to be mapped - - #x60E00010 - - - - 7th Output Object to be mapped - - #x60E10010 - - - - 8th Output Object to be mapped - - #x60B20010 - - - - - ro - - - - #x1A00 - Inputs - DT1A00 - 336 - - - SubIndex 000 - - 00 - 10 - #x07 - - - - 1st Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60410010 - - - - 2nd Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60640020 - - - - 3rd Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60B90010 - - - - 4th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60BA0020 - - - - 5th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60BC0020 - - - - 6th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x603F0010 - - - - 7th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60FD0020 - - - - 8th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 9th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 10th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - - rw - - - - #x1A01 - Inputs - DT1A01 - 368 - - - SubIndex 000 - - #x0B - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60610008 - - - - 4th Input Object to be mapped - - #x60640020 - - - - 5th Input Object to be mapped - - #x606C0020 - - - - 6th Input Object to be mapped - - #x60770010 - - - - 7th Input Object to be mapped - - #x60B90010 - - - - 8th Input Object to be mapped - - #x60BA0020 - - - - 9th Input Object to be mapped - - #x60BC0020 - - - - 10th Input Object to be mapped - - #x60F40020 - - - - 11th Input Object to be mapped - - #x60FD0020 - - - - - rw - - - - #x1B01 - Inputs - DT1B01 - 336 - - - SubIndex 000 - - #x09 - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60640020 - - - - 4th Input Object to be mapped - - #x60770010 - - - - 5th Input Object to be mapped - - #x60F40020 - - - - 6th Input Object to be mapped - - #x60B90010 - - - - 7th Input Object to be mapped - - #x60BA0020 - - - - 8th Input Object to be mapped - - #x60BC0020 - - - - 9th Input Object to be mapped - - #x60FD0020 - - - - - ro - - - - #x1B02 - Inputs - DT1B01 - 336 - - - SubIndex 000 - - #x09 - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60640020 - - - - 4th Input Object to be mapped - - #x60770010 - - - - 5th Input Object to be mapped - - #x60610008 - - - - 6th Input Object to be mapped - - #x60B90010 - - - - 7th Input Object to be mapped - - #x60BA0020 - - - - 8th Input Object to be mapped - - #x60BC0020 - - - - 9th Input Object to be mapped - - #x60FD0020 - - - - - ro - - - - #x1B03 - Inputs - DT1B03 - 336 - - - SubIndex 000 - - #x0A - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60640020 - - - - 4th Input Object to be mapped - - #x60770010 - - - - 5th Input Object to be mapped - - #x60F40020 - - - - 6th Input Object to be mapped - - #x60610008 - - - - 7th Input Object to be mapped - - #x60B90010 - - - - 8th Input Object to be mapped - - #x60BA0020 - - - - 9th Input Object to be mapped - - #x60BC0020 - - - - 10th Input Object to be mapped - - #x60FD0020 - - - - - ro - - - - #x1B04 - Inputs - DT1B04 - 336 - - - SubIndex 000 - - #x0A - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60640020 - - - - 4th Input Object to be mapped - - #x60770010 - - - - 5th Input Object to be mapped - - #x60610008 - - - - 6th Input Object to be mapped - - #x60B90010 - - - - 7th Input Object to be mapped - - #x60BA0020 - - - - 8th Input Object to be mapped - - #x60BC0020 - - - - 9th Input Object to be mapped - - #x60FD0020 - - - - 10th Input Object to be mapped - - #x606C0020 - - - - - ro - - - - #x1c32 - SM output parameter - DT1C32 - 488 - - - SubIndex 000 - - 20 - - - - Sync mode - - 0200 - - - - Cycle time - - 00000000 - - - - Sync modes supported - - 0004 - - - - Minimum cycle time - - 00000000 - - - - Calc and copy time - - #x0003d090 - - - - Get Cycle Time - - 0000 - - - - Delay Time - - 00000000 - - - - Sync0 Cycle Time - - 00000000 - - - - SM-Event Missed - - 0000 - - - - Cycle Time Too Small - - 0000 - - - - Sync Error - - 00 - - - - - ro - o - - - - #x1c33 - SM input parameter - DT1C33 - 488 - - - SubIndex 000 - - 20 - - - - Sync mode - - 0002 - - - - Cycle time - - 00000000 - - - - Sync modes supported - - 4 - - - - Minimum cycle time - - 00000000 - - - - Calc and copy time - - 00000000 - - - - Get Cycle Time - - 0000 - - - - Delay Time - - 00000000 - - - - Sync0 Cycle Time - - 00000000 - - - - SM-Event Missed - - 0000 - - - - Cycle Time Too Small - - 0000 - - - - Sync Error - - 00 - - - - - ro - o - - - - #x1c12 - RxPDO assign - DT1C12 - 32 - - - SubIndex 000 - - 00 - - - - SubIndex 001 - - 0000 - - - - - ro - - - - #x1c13 - TxPDO assign - DT1C13 - 32 - - - SubIndex 000 - - 00 - - - - SubIndex 001 - - 0000 - - - - - ro - - - - #x2000 - Servo Motor Parameters - 伺服电机参数 - DT2000 - 128 - - - SubIndex 000 - - 6 - - - - Motor SN - - 0 - 65535 - 14101 - - - - Customized firmware version - - 0 - 65535 - 0 - - - - Encoder Version - - 0 - 65535 - 0 - - - - Serial encoder motor SN - - 0 - 65535 - 0 - - - - - ro - - - - #x2001 - Servo Drive Parameters - 伺服驱动器参数 - DT2001 - 672 - - - SubIndex 000 - - 41 - - - - MCU firmware Version - - 0 - 65535 - 0 - - - - Fpga firmware Version - - 0 - 65535 - 0 - - - - Drive serial number - - 0 - 65535 - 3 - - - - Drive voltage class - - 0 - 65535 - 220 - - - - Drive rated power - - 0 - 1073741824 - 400 - - - - Drive maximum output power - - 0 - 1073741824 - 400 - - - - Drive rated output current - - 0 - 1073741824 - 280 - - - - Drive maximum output current - - 0 - 1073741824 - 1010 - - - - DC bus overvoltage protective point - - 0 - 2000 - 420 - - - - - ro - - - - #x2002 - Basic control - 基本控制参数 - DT2002 - 688 - - - SubIndex 000 - - 36 - - - - Control mode selection - - 0 - 9 - 9 - - - - Absolute system selection - - 0 - 4 - 0 - - - - Rotating direction - - 0 - 1 - 0 - - - - Output pulse phase - - 0 - 1 - 0 - - - - Disable operation option Code - - -4 - 2 - 0 - - - - NO2 Fault Reaction option Code - - -5 - 4 - 2 - - - - Stop mode at limit switch signal - - 0 - 7 - 1 - - - - Stop mode at NO.1 fault - - 0 - 2 - 2 - - - - Delay from brake output on to command received - - 0 - 500 - 250 - - - - Delay from brake output off to motor de-energized - - 50 - 1000 - 150 - - - - Motor speed threshold at brake output off in rotating state - - 20 - 3000 - 30 - - - - Delay from servo off to brake output off in the rotating state - - 1 - 65535 - 500 - - - - LED warning display selection - - 0 - 1 - 0 - - - - MainPower Cutoff Reaction Option Code - - 0 - 3 - 2 - - - - QuickStop Reaction Option Code - - 0 - 7 - 2 - - - - Allowed minimum braking resistance - - 1 - 1000 - 40 - - - - Power of built-in braking resistor - - 0 - 65535 - 50 - - - - Resistance of built-in braking resistor - - 0 - 65535 - 50 - - - - Resistor heat dissipation coefficient - - 10 - 100 - 30 - - - - braking resistor type - - 0 - 3 - 3 - - - - Power of external dynamic resistor - - 1 - 65535 - 40 - - - - Resistance of external braking resistor - - 15 - 1000 - 50 - - - - User password - - 0 - 65535 - 0 - - - - Parameter initialization - - 0 - 2 - 0 - - - - Default keypad display - - 0 - 99 - 50 - - - - Panel data refresh rate - - 0 - 20 - 0 - - - - OEM password - - 0 - 65535 - 0 - - - - - ro - - - - #x2003 - Input Terminal Parameters - 端子输入参数 - DT2003 - 1056 - - - SubIndex 000 - - 65 - - - - DI1 function selection - - 0 - 40 - 14 - - - - DI1 logic selection - - 0 - 1 - 0 - - - - DI2 function selection - - 0 - 40 - 15 - - - - DI2 logic selection - - 0 - 1 - 0 - - - - DI3 function selection - - 0 - 40 - 31 - - - - DI3 logic selection - - 0 - 1 - 0 - - - - DI4 function selection - - 0 - 40 - 34 - - - - DI4 logic selection - - 0 - 1 - 0 - - - - DI5 function selection - - 0 - 40 - 38 - - - - DI5 logic selection - - 0 - 1 - 0 - - - - AI1 Offset - - -5000 - 5000 - 0 - - - - AI1 Filter - - 0 - 65535 - 200 - - - - AI1 Dead Zone - - 0 - 10000 - 100 - - - - AI1 Zero Drifting - - -5000 - 5000 - 0 - - - - DI1 filtertime constant - - 0 - 50000 - 300 - - - - DI2 filtertime constant - - 0 - 50000 - 300 - - - - DI3 filtertime constant - - 0 - 50000 - 300 - - - - DI4 filtertime constant - - 0 - 50000 - 300 - - - - DI5 filtertime constant - - 0 - 50000 - 300 - - - - - ro - - - - #x2004 - Output terminal Parameters - 端子输出参数 - DT2004 - 864 - - - SubIndex 000 - - 53 - - - - DO1 Function Selection - - 0 - 65535 - 1 - - - - DO1 Logic Level Selection - - 0 - 1 - 0 - - - - DO2 Function Selection - - 0 - 65535 - 9 - - - - DO2 Logic Level Selection - - 0 - 1 - 0 - - - - DO3 Function Selection - - 0 - 65535 - 9 - - - - DO3 Logic Level Selection - - 0 - 1 - 0 - - - - DO OutPut Source Select - - 0 - 3 - 0 - - - - ECAT Lost Force DO OutPut Logic - - 0 - 3 - 0 - - - - AO1 Source Select - - 0 - 10 - 0 - - - - AO1 Offset - - -10000 - 10000 - 0 - - - - AO1 Multiplying - - -10000 - 10000 - 100 - - - - - ro - - - - #x2005 - Position Control Parameters - 位置控制参数组 - DT2005 - 1152 - - - SubIndex 000 - - 55 - - - - Time constant of first-order low-pass filter - - 0 - 65535 - 0 - - - - Time constant of moving average filter 1 - - 0 - 1280 - 0 - - - - Numerator of electronic gear ratio - - 1 - 1073741824 - 1 - - - - Denominator of electronic gear ratio - - 1 - 1073741824 - 1 - - - - Encoder frequency division pulses - - 0 - 4194303 - 2500 - - - - Speed feedforward control selection - - 0 - 3 - 1 - - - - Local home mode - - 0 - 8 - 0 - - - - Time of home searching - - 0 - 65535 - 10000 - - - - Local home position offset - - -2147483648 - 2147483647 - 0 - - - - Servo pulse output source - - 0 - 3 - 0 - - - - Output polarity of Z pulse - - 0 - 65535 - 1 - - - - Mechanical Gear ratio numerator of absolute encode mode 2 - - 1 - 65535 - 1 - - - - Mechanical Gear ratio denominator of absolute encode mode 2 - - 1 - 65535 - 1 - - - - Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) - - 0 - 4294967295 - 0 - - - - Max value of mechanical absolute position(inc) of absolute encode mode 2(High) - - 0 - 4294967295 - 0 - - - - Trq Reference of Mechanical Homing - - 0 - 4000 - 1000 - - - - Position Coin Hold Time - - 0 - 30000 - 0 - - - - Time Unit of Homing - - 0 - 2 - 2 - - - - Time constant of moving average filter 2 - - 0 - 10000 - 0 - - - - - ro - - - - #x2006 - Speed control - 速度控制 - DT2006 - 896 - - - SubIndex 000 - - 16 - - - - Keypad setting value of speed reference - - -10000 - 10000 - 200 - - - - DI Jog speed reference - - 0 - 10000 - 150 - - - - Acceleration ramp time constant of speed reference - - 0 - 65535 - 0 - - - - Deceleration ramp time constant of speed reference - - 0 - 65535 - 0 - - - - Maximum speed limit - - 0 - 10000 - 7000 - - - - Forward speed threshold - - 0 - 10000 - 7000 - - - - Reverse speed threshold - - 0 - 10000 - 7000 - - - - Quick decelaration coefficient - - 0 - 2 - 0 - - - - Torque feedforward selection - - 0 - 2 - 1 - - - - Acceleration/Deceleration ramp time constant of jog speed reference - - 0 - 65535 - 10 - - - - Speed feedforward filter time constant - - 0 - 65535 - 0 - - - - Speed threshold of Zero Hold signal - - 0 - 10000 - 10 - - - - Speed threshold of motor rotation signal - - 0 - 1000 - 20 - - - - Speed threshold of Spd Reach signal - - 0 - 100 - 10 - - - - Speed threshold of Spd Arrive signal - - 20 - 10000 - 1000 - - - - Speed threshold of Zero Spd signal - - 1 - 10000 - 10 - - - - Spd SCurve Enable - - 0 - 1 - 1 - - - - Spd SCurve Acceleration UP - - 0 - 1000 - 500 - - - - Spd SCurve Acceleration Down - - 0 - 1000 - 500 - - - - Spd SCurve Deceleration UP - - 0 - 1000 - 500 - - - - Spd SCurve Deceleration Down - - 0 - 1000 - 500 - - - - - ro - - - - #x2007 - Torque control - 转矩控制参数 - DT2007 - 640 - - - SubIndex 000 - - 40 - - - - Keypad setting value of torque reference - - -4000 - 4000 - 0 - - - - Torque reference filter time 1 - - 0 - 3000 - 50 - - - - Torque reference filter time 2 - - 0 - 3000 - 27 - - - - Internal forward torque limit - - 0 - 4000 - 3500 - - - - Internal reverse torque limit - - 0 - 4000 - 3500 - - - - Emergency stop torque - - 0 - 4000 - 1000 - - - - Forward speed limit/Speed limit 1 in local torque control - - 0 - 6000 - 3000 - - - - Reverse speed limit/Speed limit 2 in local torque control - - 0 - 6000 - 3000 - - - - Base value for torque reached - - 0 - 4000 - 0 - - - - Threshold of torque reached valid - - 0 - 4000 - 200 - - - - Threshold of torque reached invalid - - 0 - 4000 - 100 - - - - Depth of field-weakening - - 60 - 115 - 115 - - - - Maximum field-weakening current - - 0 - 300 - 100 - - - - Field-weakening enable - - 0 - 1 - 0 - - - - Field-weakening gain - - 1 - 1000 - 30 - - - - Field-weakening point speed - - 0 - 65535 - 0 - - - - Motor output calibration enable - - 0 - 1 - 0 - - - - The second-stage torque reference filter time - - 0 - 1000 - 0 - - - - Torque reference filter type select - - 0 - 1 - 0 - - - - Biquad low pass filter damping - - 0 - 50 - 16 - - - - - ro - - - - #x2008 - Gain Parameters - 增益参数 - DT2008 - 1056 - - - SubIndex 000 - - 65 - - - - Speed-loop Gain - - 1 - 20000 - 400 - - - - Speed-loop integral time constant - - 15 - 51200 - 1989 - - - - Position-loop Gain - - 1 - 20000 - 640 - - - - The second speed loop gain - - 1 - 20000 - 750 - - - - The second speed loop integral time constant - - 15 - 51200 - 1061 - - - - The second position loop gain - - 1 - 20000 - 1200 - - - - Second gain mode setting - - 0 - 1 - 1 - - - - Gain switchover condition - - 0 - 10 - 0 - - - - Gain switchover delay - - 0 - 10000 - 50 - - - - Gain switchover level - - 0 - 20000 - 50 - - - - Gain switchover hysteresis - - 0 - 20000 - 30 - - - - Position gain switchover time - - 0 - 10000 - 30 - - - - Average value of load inertia ratio - - 0 - 12000 - 100 - - - - Zero-Phase delay time - - 0 - 40 - 0 - - - - Speed feedforward filter time constant - - 0 - 6400 - 50 - - - - Speed feedforward gain - - 0 - 1000 - 0 - - - - Torque feedforward filter time constant - - 0 - 6400 - 50 - - - - Torque feedforward gain - - 0 - 3000 - 0 - - - - Speed feedback filter - - 0 - 4 - 0 - - - - Cut-off frequency of speed feedback low-pass filter - - 100 - 8000 - 8000 - - - - Pseudo-differential forward feedback control coefficient - - 0 - 2000 - 1000 - - - - Cut-off frequency of speed observer - - 50 - 600 - 170 - - - - Modified inertia coefficient of speed observer - - 1 - 1600 - 100 - - - - Filter time of speed observer - - 0 - 1000 - 80 - - - - Cut-off frequency of torque disturbance observer - - 10 - 4000 - 600 - - - - Compensation gain of torque disturbance observer - - 0 - 100 - 0 - - - - Modified inertia coefficient of torque disturbance observer - - 1 - 1600 - 100 - - - - Speed observer enable - - 0 - 1 - 0 - - - - Module control enable - - 0 - 2 - 0 - - - - Module control gain - - 1 - 20000 - 400 - - - - Module feedforward value - - 0 - 1024 - 950 - - - - 3rd medium and low-frequency vibration suppression frequency - - 0 - 3000 - 0 - - - - 3rd compensation gain of medium and low-frequency vibration suppression frequency - - 0 - 200 - 0 - - - - 3rd phase modulation of medium and low-frequency vibration suppression frequency - - 0 - 600 - 100 - - - - 4th medium and low-frequency vibration suppression frequency - - 0 - 3000 - 0 - - - - 4th compensation gain of medium and low-frequency vibration suppression frequency - - 0 - 200 - 0 - - - - 4th phase modulation of medium and low-frequency vibration suppression frequency - - 0 - 600 - 100 - - - - Time constant of position loop integration - - 15 - 51200 - 51200 - - - - 2nd time constant of position loop integration - - 15 - 51200 - 51200 - - - - Speed observation feedback source selection - - 0 - 1 - 0 - - - - - ro - - - - #x2009 - Auto-adjusting Parameters - 自整定参数 - DT2009 - 848 - - - SubIndex 000 - - 60 - - - - Auto-adjusting mode - - 0 - 7 - 4 - - - - Rigidity level selection - - 0 - 41 - 15 - - - - Working mode of self-adaptive notch - - 0 - 4 - 0 - - - - Online inertia auto-tuning mode - - 0 - 3 - 0 - - - - Offline inertia auto-tuning mode - - 0 - 1 - 0 - - - - Maximum speed for inertia autotuning - - 100 - 1000 - 500 - - - - Acceleration/Deceleration time for inertia autotuning - - 20 - 800 - 125 - - - - Interval after an inertia autotuning - - 50 - 10000 - 800 - - - - Motor revolutions for an inertia auto-tuning - - 0 - 10000 - 100 - - - - Vibration threshold setting - - 0 - 1000 - 50 - - - - 1st notch frequency - - 50 - 8000 - 8000 - - - - 1st notch width level - - 0 - 20 - 2 - - - - 1st notch attenuation level - - 0 - 99 - 0 - - - - 2nd notch frequency - - 50 - 8000 - 8000 - - - - 2nd notch width level - - 0 - 20 - 2 - - - - 2nd notch attenuation level - - 0 - 99 - 0 - - - - 3rd notch frequency - - 50 - 8000 - 8000 - - - - 3rd notch width level - - 0 - 20 - 2 - - - - 3rd notch attenuation level - - 0 - 99 - 0 - - - - 4th notch frequency - - 50 - 8000 - 8000 - - - - 4th notch width level - - 0 - 20 - 2 - - - - 4th notch attenuation level - - 0 - 99 - 0 - - - - Obtained resonance frequency - - 0 - 5000 - 0 - - - - 1st anti-resonance point frequency - - 0 - 5000 - 0 - - - - 2nd anti-resonance point frequency - - 0 - 5000 - 0 - - - - Gravity compensation value - - 0 - 1000 - 0 - - - - Forward friction compensation - - 0 - 1000 - 0 - - - - Reverse friction compensation - - -1000 - 0 - 0 - - - - Friction compensation speed - - 0 - 200 - 20 - - - - Friction compensation speed selection - - 0 - 19 - 0 - - - - Vibration monitor time - - 0 - 65535 - 300 - - - - 1st terminal low-frequency vibration suppression frequency - - 10 - 1000 - 1000 - - - - 1st filter order of low-frequency vibration suppression frequency - - 0 - 3 - 2 - - - - 5th notch frequency - - 50 - 8000 - 8000 - - - - 5th notch width level - - 0 - 20 - 2 - - - - 5th notch attenuation level - - 0 - 99 - 0 - - - - 2nd terminal low-frequency vibration suppression frequency - - 0 - 2000 - 0 - - - - 2nd damping frequency ratio of low-frequency vibration suppression frequency - - 1 - 1000 - 100 - - - - 2nd damping coefficient of low-frequency vibration suppression frequency - - 0 - 200 - 100 - - - - 3rd terminal low-frequency vibration suppression frequency - - 0 - 2000 - 0 - - - - 3rd damping frequency ratio of low-frequency vibration suppression frequency - - 1 - 1000 - 100 - - - - 3rd damping coefficient of low-frequency vibration suppression frequency - - 0 - 200 - 100 - - - - - ro - - - - #x200A - Error and Protection Parameter - 故障与保护参数 - DT200A - 1536 - - - SubIndex 000 - - 60 - - - - Power inputphase loss protection disable - - 0 - 1 - 0 - - - - Absolute position limit set - - 0 - 2 - 0 - - - - Motor overload protection gain - - 50 - 300 - 100 - - - - Overspeed threshold - - 0 - 20000 - 0 - - - - Local following error window - - 0 - 4294967295 - 27486951 - - - - Runaway protection enable - - 0 - 1 - 1 - - - - Over Temperature value of IPM - - 120 - 175 - 140 - - - - Touch Probe 1 filter time constant - - 0 - 630 - 200 - - - - Touch Probe 2 filter time constant - - 0 - 630 - 200 - - - - STO Display Function Selection - - 0 - 1 - 0 - - - - Filter time constant of TZ signal - - 0 - 31 - 15 - - - - Filter time of speed feedback display - - 0 - 5000 - 50 - - - - Motor overload shielding - - 0 - 1 - 0 - - - - Speed DO Filter time constant - - 0 - 5000 - 50 - - - - Full Closed-loop(ABZ) Filter time constant - - 0 - 255 - 15 - - - - Overheat protection time duration for locked rotor - - 10 - 65535 - 200 - - - - Overheat protection for locked rotor enable - - 0 - 1 - 1 - - - - Absolute Encode multi-turns error forbidden - - 0 - 1 - 0 - - - - Compensation Function - - 0 - 15 - 6 - - - - Over Temperature value of discharge tube - - 100 - 175 - 115 - - - - Encoder communiction error threshold - - 0 - 31 - 5 - - - - Phase lack threshold - - 3 - 36 - 20 - - - - Over Temperature value of Encoder - - 0 - 175 - 125 - - - - TouchProbe DI Turn-on Compensation Time - - -3000 - 3000 - 200 - - - - TouchProbe DI Turn-off Compensation Time - - -3000 - 3000 - 1512 - - - - Runaway current threshold - - 1000 - 4000 - 2000 - - - - Fault reset delay time - - 0 - 60000 - 10000 - - - - Runaway speed threshold - - 1 - 1000 - 50 - - - - Runaway speed filter time constant - - 1 - 1000 - 20 - - - - Runaway protection time window - - 10 - 1000 - 30 - - - - BlackBox Mode Select - - 0 - 3 - 1 - - - - BlackBox Selected Error Code - - 0 - 65535 - 0 - - - - BlackBox Trig Source - - 0 - 25 - 0 - - - - BlackBox Trig Level - - -2147483648 - 2147483647 - 0 - - - - BlackBox Trig Level Select - - 0 - 3 - 0 - - - - BlackBox Trig Position - - 0 - 100 - 75 - - - - BlackBox Trig Frequency Select - - 0 - 2 - 0 - - - - The 2nd over speed threshold - - 0 - 20000 - 0 - - - - Motor over load monitor switch - - 0 - 65535 - 4098 - - - - Maximum ramp stop time - - 0 - 65535 - 10000 - - - - STO Disconnect filter time - - 1 - 5 - 5 - - - - STO Mismatch filter time - - 1 - 1000 - 100 - - - - STO Servo off filter time - - 0 - 25 - 20 - - - - Motor Offline Trq Limit - - 40 - 4000 - 50 - - - - Motor Offline Filter Time - - 5 - 1000 - 30 - - - - Filter Time Constant of Spd Display - - 0 - 100 - 0 - - - - Filter Time Constant of Trq Display - - 0 - 100 - 0 - - - - Filter Time Constant of Position Display - - 0 - 100 - 0 - - - - Filter Time Constant of Voltage Display - - 0 - 250 - 0 - - - - Filter Time Constant of Temp Display - - 0 - 250 - 0 - - - - - ro - - - - #x200B - Display Parameters - 显示参数 - DT200B - 1584 - - - Number of Entries - - 92 - - - - Actual motor rotational speed - - 0 - - - - Speed reference - - 0 - - - - Internal torque reference - - 0 - - - - Monitored DI states - - 0 - - - - Monitored DO states - - 0 - - - - Absolute position counter - - 0 - - - - Mechanical angle - - 0 - - - - Electrical angle - - 0 - - - - Average load rate - - 0 - - - - Encoder position deviation counter - - 0 - - - - Feedback pulse counter - - 0 - - - - Total power-on time - - 0 - - - - AI1 Voltage DisPlay - - 0 - - - - Phase current valid value - - 0 - - - - Bus voltage - - 0 - - - - Module temperature - - 0 - - - - Absolute encoder fault info. from FPGA - - 0 - - - - Axis state from FPGA - - 0 - - - - Axis fault info. from FPGA - - 0 - - - - Encoder internal fault info. - - 0 - - - - Displayed fault record - - 0 - 19 - 0 - - - - Fault code - - 0 - - - - Time stamp upon displayed fault - - 0 - - - - Current rotational speed upon displayed fault - - 0 - - - - Current U upon displayed fault - - 0 - - - - Current V upon displayed fault - - 0 - - - - Bus voltage upon displayed fault - - 0 - - - - Input terminal state upon displayed fault - - 0 - - - - Output terminal state upon displayed fault - - 0 - - - - Inner error code - - 0 - - - - Fault message of absolute encode from Fpga upon displayed - - 0 - - - - System state from Fpga upon displayed fault - - 0 - - - - System fault message from Fpga upon displayed fault - - 0 - - - - Encode state 1 upon displayed fault - - 0 - - - - Inner error code upon displayed fault - - 0 - - - - Fpga overtime state upon displayed fault - - 0 - - - - Reference position deviation - - 0 - - - - Actual motor rotational speed(0.1rpm) - - 0 - - - - Control bus voltage - - 0 - - - - Mechanical absolute position inc(Low) - - 0 - - - - Mechanical absolute position inc(High) - - 0 - - - - Not ready reason - - 0 - - - - Encoder temperature - - 0 - - - - Discharge load rate - - 0 - - - - Fpga over time state - - 0 - - - - Number of turns of absolute encode - - 0 - - - - Single feedback postion of absolute encode - - 0 - - - - System Error - - 0 - - - - feedback postion of absolute encode(Low) - - 0 - - - - feedback postion of absolute encode(High) - - 0 - - - - feedback postion inc of rotating load(Low) - - 0 - - - - feedback postion inc of rotating load(High) - - 0 - - - - Single feedback postion of rotating load - - 0 - - - - IGBT Temperature - - 0 - - - - Group of unusual function code - - 0 - - - - Offset of unusual function code - - 0 - - - - Single Power-On Time - - 0 - - - - Single Power-On Time upon displayed fault - - 0 - - - - - ro - - - - #x200D - Auxiliary Function Parameters - 辅助功能参数 - DT200D - 400 - - - Number of Entries - - 21 - - - - Software reset - - 0 - 1 - 0 - - - - Fault reset - - 0 - 1 - 0 - - - - Offline inertia autotuning selection - - 0 - 1 - 0 - - - - Encoder ROM reading/writing - - 0 - 3 - 0 - - - - Emergency stop - - 0 - 1 - 0 - - - - AI1 Self-Adjust of Voltage Offset - - 0 - 1 - 0 - - - - UV phase current auto-tuning - - 0 - 1 - 0 - - - - Forced DI/DO setting - - 0 - 3 - 0 - - - - Forced DI level - - 0 - 31 - 31 - - - - Forced DO setting - - 0 - 3 - 0 - - - - Absolute Encode Fault Reset - - 0 - 2 - 0 - - - - Cogging torque self-learning - - 0 - 1 - 0 - - - - - ro - - - - #x200E - Communication parameters - 通信参数 - DT200E - 1568 - - - Number of Entries - - 97 - - - - Node address - - 1 - 127 - 1 - - - - Update function code values written via communication to EEPROM - - 0 - 4 - 4 - - - - station auto inc address - - 0 - 65535 - 0 - - - - station alias - - 0 - 65535 - 0 - - - - Sync lost window - - 1 - 20 - 8 - - - - Sync lost counter - - 0 - 65535 - 0 - - - - Port 0 invalid frame counter - - 0 - 65535 - 0 - - - - Port 1 invalid frame counter - - 0 - 65535 - 0 - - - - Port 0/1 transfer error counter - - 0 - 65535 - 0 - - - - process unit and PDI error counter - - 0 - 255 - 0 - - - - Port 0/1 lost counter - - 0 - 65535 - 0 - - - - Sync mode set - - 0 - 2 - 2 - - - - Sync error window - - 100 - 4000 - 4000 - - - - EtherCAT network state and link state - - 0 - 65535 - 0 - - - - CSP postion increment over counter - - 1 - 30 - 20 - - - - ECAT AL Error Code - - 0 - 65535 - 0 - - - - Enhanced link detection enable - - 0 - 1 - 0 - - - - Reset EtherCAT xml file - - 0 - 1 - 0 - - - - EtherCAT port control mode and state display - - 0 - 65535 - 0 - - - - EtherCAT COE version number - - 0 - 65535 - 0 - - - - EtherCAT xml file version number - - 0 - 65535 - 0 - - - - - ro - - - - #x200F - Closed Loop Function - 全闭环功能 - DT200F - 720 - - - SubIndex 000 - - 26 - - - - Encoder feedback mode - - 0 - 2 - 0 - - - - Running mode of external encoder - - 0 - 1 - 0 - - - - SecEncoder Absolute system selection - - 0 - 1 - 0 - - - - SecEncoder Type selection - - 0 - 2 - 0 - - - - External encoder pulses per motor revolution - - 0 - 2147483647 - 100000 - - - - Hybrid deviation excess setting - - 0 - 2147483647 - 10000 - - - - Hybrid deviation clear setting - - 0 - 100 - 1 - - - - First-order lowpass filter time of external/internal deviation - - 0 - 65535 - 0 - - - - Hybrid deviation counter - - -2147483648 - 2147483647 - 0 - - - - Pulse feedback display of internal encoder - - -2147483648 - 2147483647 - 0 - - - - Pulse feedback display of external encoder - - -2147483648 - 2147483647 - 0 - - - - SecEncoder Pulse ZPhase Ignore - - 0 - 1 - 0 - - - - SecEncoder Pulse Z-TouchProbe Selection - - 0 - 1 - 0 - - - - - ro - - - - #x2012 - MultiSpd Function - 多段速功能 - DT2012 - 1104 - - - SubIndex 000 - - 59 - - - - MultiSpd Function Select - - 0 - 2 - 1 - - - - MultiSpd Final Part Select - - 1 - 16 - 16 - - - - Time Uint of Runing - - 0 - 1 - 0 - - - - AccTime1 - - 0 - 65535 - 10 - - - - DecTime1 - - 0 - 65535 - 10 - - - - AccTime2 - - 0 - 65535 - 50 - - - - DecTime2 - - 0 - 65535 - 50 - - - - AccTime3 - - 0 - 65535 - 100 - - - - DecTime3 - - 0 - 65535 - 100 - - - - AccTime4 - - 0 - 65535 - 150 - - - - DecTime4 - - 0 - 65535 - 150 - - - - 1st Part Spd Cmd - - -10000 - 10000 - 0 - - - - 1st Part Spd Runing Time - - 0 - 65535 - 50 - - - - 1st Part AccDec Time Select - - 0 - 4 - 0 - - - - 2nd Part Spd Cmd - - -10000 - 10000 - 100 - - - - 2nd Part Spd Runing Time - - 0 - 65535 - 50 - - - - 2nd Part AccDec Time Select - - 0 - 4 - 0 - - - - 3rd Part Spd Cmd - - -10000 - 10000 - 300 - - - - 3rd Part Spd Runing Time - - 0 - 65535 - 50 - - - - 3rd Part AccDec Time Select - - 0 - 4 - 0 - - - - 4th Part Spd Cmd - - -10000 - 10000 - 500 - - - - 4th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 4th Part AccDec Time Select - - 0 - 4 - 0 - - - - 5th Part Spd Cmd - - -10000 - 10000 - 700 - - - - 5th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 5th Part AccDec Time Select - - 0 - 4 - 0 - - - - 6th Part Spd Cmd - - -10000 - 10000 - 900 - - - - 6th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 6th Part AccDec Time Select - - 0 - 4 - 0 - - - - 7th Part Spd Cmd - - -10000 - 10000 - 600 - - - - 7th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 7th Part AccDec Time Select - - 0 - 4 - 0 - - - - 8th Part Spd Cmd - - -10000 - 10000 - 300 - - - - 8th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 8th Part AccDec Time Select - - 0 - 4 - 0 - - - - 9th Part Spd Cmd - - -10000 - 10000 - 100 - - - - 9th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 9th Part AccDec Time Select - - 0 - 4 - 0 - - - - 10th Part Spd Cmd - - -10000 - 10000 - -100 - - - - 10th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 10th Part AccDec Time Select - - 0 - 4 - 0 - - - - 11th Part Spd Cmd - - -10000 - 10000 - -300 - - - - 11th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 11th Part AccDec Time Select - - 0 - 4 - 0 - - - - 12th Part Spd Cmd - - -10000 - 10000 - -500 - - - - 12th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 12th Part AccDec Time Select - - 0 - 4 - 0 - - - - 13th Part Spd Cmd - - -10000 - 10000 - -700 - - - - 13th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 13th Part AccDec Time Select - - 0 - 4 - 0 - - - - 14th Part Spd Cmd - - -10000 - 10000 - -900 - - - - 14th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 14th Part AccDec Time Select - - 0 - 4 - 0 - - - - 15th Part Spd Cmd - - -10000 - 10000 - -600 - - - - 15th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 15th Part AccDec Time Select - - 0 - 4 - 0 - - - - 16th Part Spd Cmd - - -10000 - 10000 - -300 - - - - 16th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 16th Part AccDec Time Select - - 0 - 4 - 0 - - - - - ro - - - - #x2017 - VDI VDO - 虚拟DI、DO - DT2017 - 1520 - - - SubIndex 000 - - 68 - - - - VDI1 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI1 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI2 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI2 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI3 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI3 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI4 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI4 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI5 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI5 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI6 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI6 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI7 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI7 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI8 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI8 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI9 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI9 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI10 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI10 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI11 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI11 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI12 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI12 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI13 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI13 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI14 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI14 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI15 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI15 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI16 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI16 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDO virtual level - - 0 - 65535 - 0 - - - - VDO1 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO1 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO2 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO2 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO3 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO3 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO4 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO4 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO5 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO5 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO6 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO6 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO7 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO7 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO8 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO8 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO9 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO9 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO10 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO10 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO11 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO11 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO12 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO12 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO13 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO13 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO14 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO14 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO15 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO15 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO16 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO16 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDI Enable - - 0 - 1 - 0 - - - - VDI Default Value - - 0 - 65535 - 0 - - - - VDO Enable - - 0 - 1 - 0 - - - - VDO Default Value - - 0 - 65535 - 0 - - - - - ro - - - - #x2018 - Position Comparison - 位置比较参数 - DT2018 - 288 - - - SubIndex 000 - - 17 - - - - Enable Comparison - - 0 - - - - Comparison PosFdb Source Select - - 0 - 1 - 0 - - - - Encoder Resolution - - 0 - 7 - 1 - - - - Mode Of Comparison - - 0 - 2 - 0 - - - - Current Position As Zero - - 0 - 1 - 0 - - - - Output Duration - - 1 - 2047 - 1 - - - - Comparison ABZ OutPut Logic - - 0 - 65535 - 0 - - - - Starting Point Number - - 0 - 40 - 0 - - - - Ending Point Number - - 0 - 40 - 0 - - - - Comparison Status - - 0 - 1024 - 0 - - - - Current Position - - -2147483648 - 2147483647 - 0 - - - - Position Offset - - -2147483648 - 2147483647 - 0 - - - - Comparison OutPut Delay Compensation - - -1200 - 1200 - 0 - - - - Lilited number of Comparison Cycle Times - - 1 - 65535 - 1 - - - - Comparison ABZ OutPut Function - - 0 - 65535 - 0 - - - - - ro - - - - #x2019 - Comparing Points - 位置比较点 - DT2019 - 1936 - - - SubIndex 000 - - 120 - - - - 1st Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 1st Point Property - - 0 - - - - 2nd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 2nd Point Property - - 0 - - - - 3rd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 3rd Point Property - - 0 - - - - 4th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 4th Point Property - - 0 - - - - 5th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 5th Point Property - - 0 - - - - 6th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 6th Point Property - - 0 - - - - 7th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 7th Point Property - - 0 - - - - 8th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 8th Point Property - - 0 - - - - 9th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 9th Point Property - - 0 - - - - 10th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 10th Point Property - - 0 - - - - 11th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 11th Point Property - - 0 - - - - 12th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 12th Point Property - - 0 - - - - 13th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 13th Point Property - - 0 - - - - 14th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 14th Point Property - - 0 - - - - 15th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 15th Point Property - - 0 - - - - 16th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 16th Point Property - - 0 - - - - 17th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 17th Point Property - - 0 - - - - 18th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 18th Point Property - - 0 - - - - 19th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 19th Point Property - - 0 - - - - 20th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 20th Point Property - - 0 - - - - 21st Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 21st Point Property - - 0 - - - - 22nd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 22nd Point Property - - 0 - - - - 23rd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 23rd Point Property - - 0 - - - - 24th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 24th Point Property - - 0 - - - - 25th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 25th Point Property - - 0 - - - - 26th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 26th Point Property - - 0 - - - - 27th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 27th Point Property - - 0 - - - - 28th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 28th Point Property - - 0 - - - - 29th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 29th Point Property - - 0 - - - - 30th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 30th Point Property - - 0 - - - - 31st Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 31st Point Property - - 0 - - - - 32nd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 32nd Point Property - - 0 - - - - 33rd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 33rd Point Property - - 0 - - - - 34th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 34th Point Property - - 0 - - - - 35th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 35th Point Property - - 0 - - - - 36th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 36th Point Property - - 0 - - - - 37th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 37th Point Property - - 0 - - - - 38th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 38th Point Property - - 0 - - - - 39th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 39th Point Property - - 0 - - - - 40th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 40th Point Property - - 0 - - - - - ro - - - - #x2030 - Comm Read Servo Variable - 通讯读取相关变量 - DT2030 - 64 - - - SubIndex 000 - - 3 - - - - Servo Status - - 0 - 65535 - 0 - - - - DO Function1 - - 0 - 65535 - 0 - - - - DO Function2 - - 0 - 65535 - 0 - - - - - ro - - - - #x2031 - Comm Set Servo Variable - 通讯给定相关变量 - DT2031 - 224 - - - SubIndex 000 - - 5 - - - - Comm Set VDI - - 0 - 65535 - 0 - - - - Comm Set DO - - 0 - 65535 - 0 - - - - Comm Set AO - - -10000 - 10000 - 0 - - - - Comm Set Local SpdRef - - -9000000 - 9000000 - 0 - - - - Comm Set Local TrqRef - - -100000 - 100000 - 0 - - - - - ro - - - - #x203F - Manufacturor Error code - 伺服故障码 - UDINT - 32 - - #x00000000 - #xFFFFFFFF - #x00000000 - - - ro - T - - - - #x603F - Error code - UINT - 16 - - #x0000 - #xFFFF - #x0000 - - - ro - T - - - - #x6040 - Control word - UINT - 16 - - #x0000 - #xFFFF - #x0000 - - - rw - R - - - - #x6041 - Status word - UINT - 16 - - #x0000 - #xFFFF - #x0000 - - - ro - T - - - - #x605A - Quick stop option code - INT - 16 - - #x0000 - #x0007 - #x0002 - - - rw - - - - #x605C - Disable operation option code - INT - 16 - - #xFFFC - #x0002 - #x0000 - - - rw - - - - #x605D - Halt option Code - INT - 16 - - #x0001 - #x0003 - #x0001 - - - rw - - - - #x605E - Fault Reaction option Code - INT - 16 - - #xFFFB - #x0004 - #x0002 - - - rw - - - - #x6060 - Modes of operation - SINT - 8 - - 0 - 10 - 0 - - - rw - R - - - - #x6061 - Modes of operation display - SINT - 8 - - 0 - 10 - 0 - - - ro - T - - - - #x6062 - Position demand value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x6063 - Position actual internal value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x6064 - Position actual value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x6065 - Following error window - UDINT - 32 - - #x0 - #xFFFFFFFF - #x1A36AE7 - - - rw - R - - - - #x6066 - Following error time out - UINT - 16 - - #x0 - #xFFFF - #x0 - - - rw - R - - - - #x6067 - Position window - UDINT - 32 - - #x0 - #xFFFFFFFF - #x16F0 - - - rw - R - - - - #x6068 - Position window time - UINT - 16 - - #x0 - #xFFFF - #x0 - - - rw - R - - - - #x606C - Velocity actual value - DINT - 32 - - #x80000000 - #x7FFFFFFF - 0 - - - ro - T - - - - #x606D - Velocity window - UINT - 16 - - #x0000 - #xFFFF - #xA - - - rw - R - - - - #x606E - Velocity window time - UINT - 16 - - #x0000 - #xFFFF - #x0 - - - rw - - - - #x606F - Velocity threshold - UINT - 16 - - #x0000 - #xFFFF - #xA - - - rw - R - - - - #x6070 - Velocity threshold time - UINT - 16 - - #x0000 - #xFFFF - #x0 - - - rw - - - - #x6071 - Target torque - INT - 16 - - #xF060 - #x0FA0 - #x0 - - - rw - R - - - - #x6072 - Max Torque - UINT - 16 - - #x0 - #x0FA0 - #x0DAC - - - rw - R - - - - #x6074 - Torque demand - INT - 16 - - #xF060 - #x0FA0 - #x0 - - - ro - T - - - - #x6077 - Torque actual value - INT - 16 - - #xF060 - #x0FA0 - #x0 - - - ro - T - - - - #x607A - Target position - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x607C - Home offset - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x607D - Software position limit - DT607D - 80 - - - SubIndex 000 - - #x02 - - - - Min position limit - - #x80000000 - #x7FFFFFFF - #x80000000 - - - - Max position limit - - #x80000000 - #x7FFFFFFF - #x7FFFFFFF - - - - - ro - - - - #x607E - Polarity - USINT - 8 - - #x0 - #xFF - #x0 - - - rw - R - - - - #x607F - Max profile velocity - UDINT - 32 - - #x0 - #xFFFFFFFF - #x32000000 - - - rw - R - - - - #x6081 - Profile velocity - UDINT - 32 - - #x0 - #xFFFFFFFF - #xD55555 - - - rw - R - - - - #x6083 - Profile acceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #x53555555 - - - rw - R - - - - #x6084 - Profile deceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #x53555555 - - - rw - R - - - - #x6085 - Quick stop deceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #x7FFFFFFF - - - rw - R - - - - #x6086 - Motion profile type - INT - 16 - - #x8000 - #x7FFF - #x0 - - - rw - R - - - - #x6087 - Torque slope - UDINT - 32 - - #x0 - #xFFFFFFFF - #xFFFFFFFF - - - rw - R - - - - #x6091 - Gear ratio - DT6091 - 80 - - - SubIndex 000 - - #x02 - - - - Motor revolutions - - #x1 - #xFFFFFFFF - #x1 - - - - Shaft revolutions - - #x1 - #xFFFFFFFF - #x1 - - - - - ro - - - - #x6098 - Homing method - SINT - 8 - - #xFD - #x23 - 1 - - - rw - R - - - - #x6099 - Homing speeds - DT6099 - 80 - - - SubIndex 000 - - #x02 - - - - Speed during search for switch - - 0 - #xFFFFFFFF - #xD55555 - - - - Speed during search for zero - - 0 - #xFFFFFFFF - #x155555 - - - - - ro - - - - #x609A - Homing acceleration - UDINT - 32 - - 0 - #xFFFFFFFF - #x53555555 - - - rw - R - - - - #x60B0 - Position offset - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x60B1 - Velocity offset - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x60B2 - Torque offset - INT - 16 - - #xF060 - #x0FA0 - #x0 - - - rw - R - - - - #x60B8 - Touch probe function - UINT - 16 - - #x0 - #xFFFF - #x0 - - - rw - R - - - - #x60B9 - Touch Probe Status - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60BA - Touch probe 1 positive edge - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60BB - Touch probe 1 negative edge - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60BC - Touch probe 2 positive edge - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60BD - Touch probe 2 negative edge - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60C5 - Max Acceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #xFFFFFFFF - - - rw - R - - - - #x60C6 - Max Deceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #xFFFFFFFF - - - rw - R - - - - #x60D5 - Touch probe 1 positive edge counter - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60D6 - Touch probe 1 negative edge counter - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60D7 - Touch probe 2 positive edge counter - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60D8 - Touch probe 2 negative edge counter - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60E0 - Positive torque limit value - UINT - 16 - - #x0 - #x0FA0 - #x0DAC - - - rw - R - - - - #x60E1 - Negative torque limit value - UINT - 16 - - #x0 - #x0FA0 - #x0DAC - - - rw - R - - - - #x60E3 - Supported homing methods - DT60E3 - 544 - - - SubIndex 000 - - #x0 - #x22 - 33 - - - - Support homing method 1 - - #x01 - - - - Support homing method 2 - - #x02 - - - - Support homing method 3 - - #x03 - - - - Support homing method 4 - - #x04 - - - - Support homing method 5 - - #x05 - - - - Support homing method 6 - - #x06 - - - - Support homing method 7 - - #x07 - - - - Support homing method 8 - - #x08 - - - - Support homing method 9 - - #x09 - - - - Support homing method 10 - - #x0A - - - - Support homing method 11 - - #x0B - - - - Support homing method 12 - - #x0C - - - - Support homing method 13 - - #x0D - - - - Support homing method 14 - - #x0E - - - - Support homing method 15 - - #x11 - - - - Support homing method 16 - - #x12 - - - - Support homing method 17 - - #x13 - - - - Support homing method 18 - - #x14 - - - - Support homing method 19 - - #x15 - - - - Support homing method 20 - - #x16 - - - - Support homing method 21 - - #x17 - - - - Support homing method 22 - - #x18 - - - - Support homing method 23 - - #x19 - - - - Support homing method 24 - - #x1A - - - - Support homing method 25 - - #x1B - - - - Support homing method 26 - - #x1C - - - - Support homing method 27 - - #x1D - - - - Support homing method 28 - - #x1E - - - - Support homing method 29 - - #x21 - - - - Support homing method 30 - - #x22 - - - - Support homing method 31 - - #x23 - - - - Support homing method 32 - - #xFF - - - - Support homing method 33 - - #xFE - - - - - ro - - - - #x60F4 - Following error actual value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60FC - Position demand internal value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60FD - Digital inputs - UDINT - 32 - - #x0 - #xFFFFFFFF - #x0 - - - ro - T - - - - #x60FE - Digital outputs - DT60FE - 80 - - - SubIndex 000 - - #x02 - - - - Physical outputs - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - Bit Mask - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - - ro - - - - #x60FF - Target velocity - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x6502 - Supported drive modes - UDINT - 32 - - #x00000000 - #xFFFFFFFF - #x000003AD - - - ro - - - - - - Outputs - Inputs - MBoxState - MBoxOut - MBoxIn - Outputs - Inputs - - #x1600 - Outputs - #x1601 - #x1701 - #x1702 - #x1703 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - - #x1601 - Outputs - #x1600 - #x1701 - #x1702 - #x1703 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x6071 - 0 - 16 - Target torque - INT - - - #x607A - 0 - 32 - Target position - DINT - - - #x607F - 0 - 32 - Max profile velocity - UDINT - - - #x6081 - 0 - 32 - profile velocity - UDINT - - - #x6083 - 0 - 32 - profile acceleration - UDINT - - - #x6084 - 0 - 32 - profile deceleration - UDINT - - - #x6087 - 0 - 32 - Torque Slope - UDINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - - #x1701 - Outputs - #x1600 - #x1601 - #x1702 - #x1703 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x60FE - 1 - 32 - Physical outputs - UDINT - - - - #x1702 - Outputs - #x1600 - #x1601 - #x1701 - #x1703 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - #x6071 - 0 - 16 - Target torque - INT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x607F - 0 - 32 - Max profile velocity - UDINT - - - - #x1703 - Outputs - #x1600 - #x1601 - #x1701 - #x1702 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x60E0 - 0 - 16 - Positive torque limit value - UINT - - - #x60E1 - 0 - 16 - Negative torque limit value - UINT - - - - #x1704 - Outputs - #x1600 - #x1601 - #x1701 - #x1702 - #x1703 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - #x6071 - 0 - 16 - Target torque - INT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x607F - 0 - 32 - Max profile velocity - UDINT - - - #x60E0 - 0 - 16 - Positive torque limit value - UINT - - - #x60E1 - 0 - 16 - Negative torque limit value - UINT - - - - #x1705 - Outputs - #x1600 - #x1601 - #x1701 - #x1702 - #x1703 - #x1704 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x60E0 - 0 - 16 - Positive torque limit value - UINT - - - #x60E1 - 0 - 16 - Negative torque limit value - UINT - - - #x60B2 - 0 - 16 - Torque offset - INT - - - - #x1A00 - Inputs - #x1A01 - #x1B01 - #x1B02 - #x1B03 - #x1B04 - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x603F - 0 - 16 - Error code - UINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1A01 - Inputs - #x1A00 - #x1B01 - #x1B02 - #x1B03 - #x1B04 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6061 - 0 - 8 - Modes of operation display - SINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x606C - 0 - 32 - Velocity actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x60F4 - 0 - 32 - Following error actual value - DINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1B01 - Inputs - #x1A00 - #x1A01 - #x1B02 - #x1B03 - #x1B04 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x60F4 - 0 - 32 - Following error actual value - DINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1B02 - Inputs - #x1A00 - #x1A01 - #x1B01 - #x1B03 - #x1B04 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x6061 - 0 - 8 - Modes of operation display - SINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1B03 - Inputs - #x1A00 - #x1A01 - #x1B01 - #x1B02 - #x1B04 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x60F4 - 0 - 32 - Following error actual value - DINT - - - #x6061 - 0 - 8 - Modes of operation display - SINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1B04 - Inputs - #x1A00 - #x1A01 - #x1B01 - #x1B02 - #x1B03 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x6061 - 0 - 8 - Modes of operation display - SINT - - - #x60F4 - 0 - 32 - Following error actual value - DINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x606C - 0 - 32 - Velocity actual value - DINT - - - - - - - PS - #x6060 - 0 - 08 - Modes of operation - - - - - - DC - DC-Sync - #x300 - 0 - 0 - 0 - - - Synchron - FreeRun - #x0 - - - - 2048 - 080C0004640000000000 - - 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 - - - + + #x00100000 + Inovance + 汇川技术 + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + + InoServo + Servo Drives + 伺服驱动器 + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + + InoSV670N + SV670_1Axis_05003 + ServoDrive + http://www.inovance.cn + + + + 3000 + 9000 + 5000 + 200 + + + + + 100 + 2000 + + + + InoServo + + + 402 + + + + + + BIT2 + 2 + + + + BOOL + 1 + + + + DINT + 32 + + + + INT + 16 + + + + UDINT + 32 + + + + UINT + 16 + + + + USINT + 8 + + + + SINT + 8 + + + + STRING(10) + 80 + + + + STRING(4) + 32 + + + DT1018 + 144 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Vendor ID + UDINT + 32 + 16 + + ro + + + + 2 + Product Code + UDINT + 32 + 48 + + ro + + + + 3 + Revision + UDINT + 32 + 80 + + ro + + + + 4 + Serial number + UDINT + 32 + 112 + + ro + + + + + DT1600 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + + DT1601 + 368 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + + DT1701 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1702 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1703 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1704 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1705 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1A00 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + + DT1A01 + 368 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + + DT1B01 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B02 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B03 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B04 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1C00ARR + USINT + 32 + + 1 + 4 + + + + DT1C00 + 48 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + o + + + + Elements + DT1C00ARR + 32 + 16 + + ro + o + + + + + + DT1C32 + 488 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + m + + + + 1 + Sync mode + UINT + 16 + 16 + + rw + + + + 2 + Cycle time + UDINT + 32 + 32 + + ro + o + + + + 4 + Sync modes supported + UINT + 16 + 96 + + ro + o + + + + 5 + Minimum cycle time + UDINT + 32 + 112 + + ro + o + + + + 6 + Calc and copy time + UDINT + 32 + 144 + + ro + o + + + + 8 + Get Cycle Time + UINT + 16 + 208 + + rw + c + + + + 9 + Delay Time + UDINT + 32 + 224 + + ro + c + + + + 10 + Sync0 Cycle Time + UDINT + 32 + 256 + + rw + o + + + + 11 + SM-Event Missed + UINT + 16 + 288 + + ro + c + + + + 12 + Cycle Time Too Small + UINT + 16 + 304 + + ro + c + + + + 32 + Sync Error + BOOL + 1 + 480 + + ro + c + + + + + + DT1C33 + 488 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + o + + + + 1 + Sync mode + UINT + 16 + 16 + + rw + + + + 2 + Cycle time + UDINT + 32 + 32 + + ro + o + + + + 4 + Sync modes supported + UINT + 16 + 96 + + ro + o + + + + 5 + Minimum cycle time + UDINT + 32 + 112 + + ro + o + + + + 6 + Calc and copy time + UDINT + 32 + 144 + + ro + o + + + + 8 + Get Cycle Time + UINT + 16 + 208 + + rw + c + + + + 9 + Delay Time + UDINT + 32 + 224 + + ro + c + + + + 10 + Sync0 Cycle Time + UDINT + 32 + 256 + + rw + o + + + + 11 + SM-Event Missed + UINT + 16 + 288 + + ro + c + + + + 12 + Cycle Time Too Small + UINT + 16 + 304 + + ro + c + + + + 32 + Sync Error + BOOL + 1 + 480 + + ro + c + + + + + DT1C12ARR + UINT + 16 + + 1 + 1 + + + + DT1C12 + 32 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + Elements + DT1C12ARR + 16 + 16 + + rw + o + + + + + DT1C13ARR + UINT + 16 + + 1 + 1 + + + + DT1C13 + 32 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + Elements + DT1C13ARR + 16 + 16 + + rw + o + + + + + + DT2000 + 128 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Motor SN + UINT + 16 + 16 + + rw + + + + 3 + Customized firmware version + UDINT + 32 + 48 + + ro + + + + 5 + Encoder Version + UINT + 16 + 96 + + ro + + + + 6 + Serial encoder motor SN + UINT + 16 + 112 + + ro + + + + + + DT2001 + 672 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + MCU firmware Version + UINT + 16 + 16 + + ro + + + + 2 + Fpga firmware Version + UINT + 16 + 32 + + ro + + + + 11 + Drive serial number + UINT + 16 + 176 + + rw + + + + 12 + Drive voltage class + UINT + 16 + 192 + + ro + + + + 13 + Drive rated power + UDINT + 32 + 208 + + ro + + + + 15 + Drive maximum output power + UDINT + 32 + 240 + + ro + + + + 17 + Drive rated output current + UDINT + 32 + 272 + + ro + + + + 19 + Drive maximum output current + UDINT + 32 + 304 + + ro + + + + 41 + DC bus overvoltage protective point + UINT + 16 + 656 + + rw + + + + + + DT2002 + 688 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Control mode selection + UINT + 16 + 16 + + rw + + + + 2 + Absolute system selection + UINT + 16 + 32 + + rw + + + + 3 + Rotating direction + UINT + 16 + 48 + + rw + + + + 4 + Output pulse phase + UINT + 16 + 64 + + rw + + + + 6 + Disable operation option Code + INT + 16 + 96 + + rw + + + + 7 + NO2 Fault Reaction option Code + INT + 16 + 112 + + rw + + + + 8 + Stop mode at limit switch signal + UINT + 16 + 128 + + rw + + + + 9 + Stop mode at NO.1 fault + UINT + 16 + 144 + + rw + + + + 10 + Delay from brake output on to command received + UINT + 16 + 160 + + rw + + + + 11 + Delay from brake output off to motor de-energized + UINT + 16 + 176 + + rw + + + + 12 + Motor speed threshold at brake output off in rotating state + UINT + 16 + 192 + + rw + + + + 13 + Delay from servo off to brake output off in the rotating state + UINT + 16 + 208 + + rw + + + + 16 + LED warning display selection + UINT + 16 + 256 + + rw + + + + 18 + MainPower Cutoff Reaction Option Code + UINT + 16 + 288 + + rw + + + + 19 + QuickStop Reaction Option Code + UINT + 16 + 304 + + rw + + + + 22 + Allowed minimum braking resistance + UINT + 16 + 352 + + ro + + + + 23 + Power of built-in braking resistor + UINT + 16 + 368 + + ro + + + + 24 + Resistance of built-in braking resistor + UINT + 16 + 384 + + ro + + + + 25 + Resistor heat dissipation coefficient + UINT + 16 + 400 + + rw + + + + 26 + braking resistor type + UINT + 16 + 416 + + rw + + + + 27 + Power of external dynamic resistor + UINT + 16 + 432 + + rw + + + + 28 + Resistance of external braking resistor + UINT + 16 + 448 + + rw + + + + 31 + User password + UINT + 16 + 496 + + wo + + + + 32 + Parameter initialization + UINT + 16 + 512 + + rw + + + + 33 + Default keypad display + UINT + 16 + 528 + + rw + + + + 36 + Panel data refresh rate + UINT + 16 + 576 + + rw + + + + 42 + OEM password + UINT + 16 + 672 + + wo + + + + + DT2003 + 1056 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 3 + DI1 function selection + UINT + 16 + 48 + + rw + + + + 4 + DI1 logic selection + UINT + 16 + 64 + + rw + + + + 5 + DI2 function selection + UINT + 16 + 80 + + rw + + + + 6 + DI2 logic selection + UINT + 16 + 96 + + rw + + + + 7 + DI3 function selection + UINT + 16 + 112 + + rw + + + + 8 + DI3 logic selection + UINT + 16 + 128 + + rw + + + + 9 + DI4 function selection + UINT + 16 + 144 + + rw + + + + 10 + DI4 logic selection + UINT + 16 + 160 + + rw + + + + 11 + DI5 function selection + UINT + 16 + 176 + + rw + + + + 12 + DI5 logic selection + UINT + 16 + 192 + + rw + + + + 51 + AI1 Offset + INT + 16 + 816 + + rw + + + + 52 + AI1 Filter + UINT + 16 + 832 + + rw + + + + 54 + AI1 Dead Zone + UINT + 16 + 864 + + rw + + + + 55 + AI1 Zero Drifting + INT + 16 + 880 + + rw + + + + 61 + DI1 filtertime constant + UINT + 16 + 976 + + rw + + + + 62 + DI2 filtertime constant + UINT + 16 + 992 + + rw + + + + 63 + DI3 filtertime constant + UINT + 16 + 1008 + + rw + + + + 64 + DI4 filtertime constant + UINT + 16 + 1024 + + rw + + + + 65 + DI5 filtertime constant + UINT + 16 + 1040 + + rw + + + + + DT2004 + 864 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + DO1 Function Selection + UINT + 16 + 16 + + rw + + + + 2 + DO1 Logic Level Selection + UINT + 16 + 32 + + rw + + + + 3 + DO2 Function Selection + UINT + 16 + 48 + + rw + + + + 4 + DO2 Logic Level Selection + UINT + 16 + 64 + + rw + + + + 5 + DO3 Function Selection + UINT + 16 + 80 + + rw + + + + 6 + DO3 Logic Level Selection + UINT + 16 + 96 + + rw + + + + 23 + DO OutPut Source Select + UINT + 16 + 368 + + rw + + + + 24 + ECAT Lost Force DO OutPut Logic + UINT + 16 + 384 + + rw + + + + 51 + AO1 Source Select + UINT + 16 + 816 + + rw + + + + 52 + AO1 Offset + INT + 16 + 832 + + rw + + + + 53 + AO1 Multiplying + INT + 16 + 848 + + rw + + + + + DT2005 + 1152 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 5 + Time constant of first-order low-pass filter + UINT + 16 + 80 + + rw + + + + 7 + Time constant of moving average filter 1 + UINT + 16 + 112 + + rw + + + + 8 + Numerator of electronic gear ratio + UDINT + 32 + 128 + + rw + + + + 10 + Denominator of electronic gear ratio + UDINT + 32 + 160 + + rw + + + + 18 + Encoder frequency division pulses + UDINT + 32 + 288 + + rw + + + + 20 + Speed feedforward control selection + UINT + 16 + 320 + + rw + + + + 31 + Local home mode + UINT + 16 + 496 + + rw + + + + 36 + Time of home searching + UINT + 16 + 576 + + rw + + + + 37 + Local home position offset + DINT + 32 + 592 + + rw + + + + 39 + Servo pulse output source + UINT + 16 + 624 + + rw + + + + 42 + Output polarity of Z pulse + UINT + 16 + 672 + + rw + + + + 51 + Mechanical Gear ratio numerator of absolute encode mode 2 + UINT + 16 + 816 + + rw + + + + 52 + Mechanical Gear ratio denominator of absolute encode mode 2 + UINT + 16 + 832 + + rw + + + + 53 + Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) + UDINT + 32 + 848 + + rw + + + + 55 + Max value of mechanical absolute position(inc) of absolute encode mode 2(High) + UDINT + 32 + 880 + + rw + + + + 59 + Trq Reference of Mechanical Homing + UINT + 16 + 944 + + rw + + + + 61 + Position Coin Hold Time + UINT + 16 + 976 + + rw + + + + 67 + Time Unit of Homing + UINT + 16 + 1072 + + rw + + + + 71 + Time constant of moving average filter 2 + UINT + 16 + 1136 + + rw + + + + + DT2006 + 896 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 4 + Keypad setting value of speed reference + INT + 16 + 64 + + rw + + + + 5 + DI Jog speed reference + UINT + 16 + 80 + + rw + + + + 6 + Acceleration ramp time constant of speed reference + UINT + 16 + 96 + + rw + + + + 7 + Deceleration ramp time constant of speed reference + UINT + 16 + 112 + + rw + + + + 8 + Maximum speed limit + UINT + 16 + 128 + + rw + + + + 9 + Forward speed threshold + UINT + 16 + 144 + + rw + + + + 10 + Reverse speed threshold + UINT + 16 + 160 + + rw + + + + 11 + Quick decelaration coefficient + UINT + 16 + 176 + + rw + + + + 12 + Torque feedforward selection + UINT + 16 + 192 + + rw + + + + 13 + Acceleration/Deceleration ramp time constant of jog speed reference + UINT + 16 + 208 + + rw + + + + 14 + Speed feedforward filter time constant + UINT + 16 + 224 + + rw + + + + 16 + Speed threshold of Zero Hold signal + UINT + 16 + 256 + + rw + + + + 17 + Speed threshold of motor rotation signal + UINT + 16 + 272 + + rw + + + + 18 + Speed threshold of Spd Reach signal + UINT + 16 + 288 + + rw + + + + 19 + Speed threshold of Spd Arrive signal + UINT + 16 + 304 + + rw + + + + 20 + Speed threshold of Zero Spd signal + UINT + 16 + 320 + + rw + + + + 51 + Spd SCurve Enable + UINT + 16 + 816 + + rw + + + + 52 + Spd SCurve Acceleration UP + UINT + 16 + 832 + + rw + + + + 53 + Spd SCurve Acceleration Down + UINT + 16 + 848 + + rw + + + + 54 + Spd SCurve Deceleration UP + UINT + 16 + 864 + + rw + + + + 55 + Spd SCurve Deceleration Down + UINT + 16 + 880 + + rw + + + + + DT2007 + 640 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 4 + Keypad setting value of torque reference + INT + 16 + 64 + + rw + + + + 6 + Torque reference filter time 1 + UINT + 16 + 96 + + rw + + + + 7 + Torque reference filter time 2 + UINT + 16 + 112 + + rw + + + + 10 + Internal forward torque limit + UINT + 16 + 160 + + rw + + + + 11 + Internal reverse torque limit + UINT + 16 + 176 + + rw + + + + 16 + Emergency stop torque + UINT + 16 + 256 + + rw + + + + 20 + Forward speed limit/Speed limit 1 in local torque control + UINT + 16 + 320 + + rw + + + + 21 + Reverse speed limit/Speed limit 2 in local torque control + UINT + 16 + 336 + + rw + + + + 22 + Base value for torque reached + UINT + 16 + 352 + + rw + + + + 23 + Threshold of torque reached valid + UINT + 16 + 368 + + rw + + + + 24 + Threshold of torque reached invalid + UINT + 16 + 384 + + rw + + + + 25 + Depth of field-weakening + UINT + 16 + 400 + + rw + + + + 26 + Maximum field-weakening current + UINT + 16 + 416 + + rw + + + + 27 + Field-weakening enable + UINT + 16 + 432 + + rw + + + + 28 + Field-weakening gain + UINT + 16 + 448 + + rw + + + + 29 + Field-weakening point speed + UINT + 16 + 464 + + ro + + + + 36 + Motor output calibration enable + UINT + 16 + 576 + + rw + + + + 37 + The second-stage torque reference filter time + UINT + 16 + 592 + + rw + + + + 38 + Torque reference filter type select + UINT + 16 + 608 + + rw + + + + 39 + Biquad low pass filter damping + UINT + 16 + 624 + + rw + + + + + DT2008 + 1056 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Speed-loop Gain + UINT + 16 + 16 + + rw + + + + 2 + Speed-loop integral time constant + UINT + 16 + 32 + + rw + + + + 3 + Position-loop Gain + UINT + 16 + 48 + + rw + + + + 4 + The second speed loop gain + UINT + 16 + 64 + + rw + + + + 5 + The second speed loop integral time constant + UINT + 16 + 80 + + rw + + + + 6 + The second position loop gain + UINT + 16 + 96 + + rw + + + + 9 + Second gain mode setting + UINT + 16 + 144 + + rw + + + + 10 + Gain switchover condition + UINT + 16 + 160 + + rw + + + + 11 + Gain switchover delay + UINT + 16 + 176 + + rw + + + + 12 + Gain switchover level + UINT + 16 + 192 + + rw + + + + 13 + Gain switchover hysteresis + UINT + 16 + 208 + + rw + + + + 14 + Position gain switchover time + UINT + 16 + 224 + + rw + + + + 16 + Average value of load inertia ratio + UINT + 16 + 256 + + rw + + + + 18 + Zero-Phase delay time + UINT + 16 + 288 + + rw + + + + 19 + Speed feedforward filter time constant + UINT + 16 + 304 + + rw + + + + 20 + Speed feedforward gain + UINT + 16 + 320 + + rw + + + + 21 + Torque feedforward filter time constant + UINT + 16 + 336 + + rw + + + + 22 + Torque feedforward gain + UINT + 16 + 352 + + rw + + + + 23 + Speed feedback filter + UINT + 16 + 368 + + rw + + + + 24 + Cut-off frequency of speed feedback low-pass filter + UINT + 16 + 384 + + rw + + + + 25 + Pseudo-differential forward feedback control coefficient + UINT + 16 + 400 + + rw + + + + 28 + Cut-off frequency of speed observer + UINT + 16 + 448 + + rw + + + + 29 + Modified inertia coefficient of speed observer + UINT + 16 + 464 + + rw + + + + 30 + Filter time of speed observer + UINT + 16 + 480 + + rw + + + + 32 + Cut-off frequency of torque disturbance observer + UINT + 16 + 512 + + rw + + + + 33 + Compensation gain of torque disturbance observer + UINT + 16 + 528 + + rw + + + + 34 + Modified inertia coefficient of torque disturbance observer + UINT + 16 + 544 + + rw + + + + 41 + Speed observer enable + UINT + 16 + 656 + + rw + + + + 43 + Module control enable + UINT + 16 + 688 + + rw + + + + 44 + Module control gain + UINT + 16 + 704 + + rw + + + + 47 + Module feedforward value + UINT + 16 + 752 + + rw + + + + 54 + 3rd medium and low-frequency vibration suppression frequency + UINT + 16 + 864 + + rw + + + + 55 + 3rd compensation gain of medium and low-frequency vibration suppression frequency + UINT + 16 + 880 + + rw + + + + 57 + 3rd phase modulation of medium and low-frequency vibration suppression frequency + UINT + 16 + 912 + + rw + + + + 60 + 4th medium and low-frequency vibration suppression frequency + UINT + 16 + 960 + + rw + + + + 61 + 4th compensation gain of medium and low-frequency vibration suppression frequency + UINT + 16 + 976 + + rw + + + + 62 + 4th phase modulation of medium and low-frequency vibration suppression frequency + UINT + 16 + 992 + + rw + + + + 63 + Time constant of position loop integration + UINT + 16 + 1008 + + rw + + + + 64 + 2nd time constant of position loop integration + UINT + 16 + 1024 + + rw + + + + 65 + Speed observation feedback source selection + UINT + 16 + 1040 + + rw + + + + + DT2009 + 848 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Auto-adjusting mode + UINT + 16 + 16 + + rw + + + + 2 + Rigidity level selection + UINT + 16 + 32 + + rw + + + + 3 + Working mode of self-adaptive notch + UINT + 16 + 48 + + rw + + + + 4 + Online inertia auto-tuning mode + UINT + 16 + 64 + + rw + + + + 6 + Offline inertia auto-tuning mode + UINT + 16 + 96 + + rw + + + + 7 + Maximum speed for inertia autotuning + UINT + 16 + 112 + + rw + + + + 8 + Acceleration/Deceleration time for inertia autotuning + UINT + 16 + 128 + + rw + + + + 9 + Interval after an inertia autotuning + UINT + 16 + 144 + + rw + + + + 10 + Motor revolutions for an inertia auto-tuning + UINT + 16 + 160 + + rw + + + + 12 + Vibration threshold setting + UINT + 16 + 192 + + rw + + + + 13 + 1st notch frequency + UINT + 16 + 208 + + rw + + + + 14 + 1st notch width level + UINT + 16 + 224 + + rw + + + + 15 + 1st notch attenuation level + UINT + 16 + 240 + + rw + + + + 16 + 2nd notch frequency + UINT + 16 + 256 + + rw + + + + 17 + 2nd notch width level + UINT + 16 + 272 + + rw + + + + 18 + 2nd notch attenuation level + UINT + 16 + 288 + + rw + + + + 19 + 3rd notch frequency + UINT + 16 + 304 + + rw + + + + 20 + 3rd notch width level + UINT + 16 + 320 + + rw + + + + 21 + 3rd notch attenuation level + UINT + 16 + 336 + + rw + + + + 22 + 4th notch frequency + UINT + 16 + 352 + + rw + + + + 23 + 4th notch width level + UINT + 16 + 368 + + rw + + + + 24 + 4th notch attenuation level + UINT + 16 + 384 + + rw + + + + 25 + Obtained resonance frequency + UINT + 16 + 400 + + ro + + + + 26 + 1st anti-resonance point frequency + UINT + 16 + 416 + + rw + + + + 27 + 2nd anti-resonance point frequency + UINT + 16 + 432 + + rw + + + + 33 + Gravity compensation value + INT + 16 + 528 + + rw + + + + 34 + Forward friction compensation + INT + 16 + 544 + + rw + + + + 35 + Reverse friction compensation + INT + 16 + 560 + + rw + + + + 36 + Friction compensation speed + UINT + 16 + 576 + + rw + + + + 37 + Friction compensation speed selection + UINT + 16 + 592 + + rw + + + + 38 + Vibration monitor time + UINT + 16 + 608 + + rw + + + + 39 + 1st terminal low-frequency vibration suppression frequency + UINT + 16 + 624 + + rw + + + + 40 + 1st filter order of low-frequency vibration suppression frequency + UINT + 16 + 640 + + rw + + + + 42 + 5th notch frequency + UINT + 16 + 672 + + rw + + + + 43 + 5th notch width level + UINT + 16 + 688 + + rw + + + + 44 + 5th notch attenuation level + UINT + 16 + 704 + + rw + + + + 45 + 2nd terminal low-frequency vibration suppression frequency + UINT + 16 + 720 + + rw + + + + 46 + 2nd damping frequency ratio of low-frequency vibration suppression frequency + UINT + 16 + 736 + + rw + + + + 48 + 2nd damping coefficient of low-frequency vibration suppression frequency + UINT + 16 + 768 + + rw + + + + 50 + 3rd terminal low-frequency vibration suppression frequency + UINT + 16 + 800 + + rw + + + + 51 + 3rd damping frequency ratio of low-frequency vibration suppression frequency + UINT + 16 + 816 + + rw + + + + 53 + 3rd damping coefficient of low-frequency vibration suppression frequency + UINT + 16 + 832 + + rw + + + + + DT200A + 1536 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Power inputphase loss protection disable + UINT + 16 + 16 + + rw + + + + 2 + Absolute position limit set + UINT + 16 + 32 + + rw + + + + 5 + Motor overload protection gain + UINT + 16 + 80 + + rw + + + + 9 + Overspeed threshold + UINT + 16 + 144 + + rw + + + + 11 + Local following error window + UDINT + 32 + 176 + + rw + + + + 13 + Runaway protection enable + UINT + 16 + 208 + + rw + + + + 19 + Over Temperature value of IPM + UINT + 16 + 304 + + rw + + + + 20 + Touch Probe 1 filter time constant + UINT + 16 + 320 + + rw + + + + 21 + Touch Probe 2 filter time constant + UINT + 16 + 336 + + rw + + + + 22 + STO Display Function Selection + UINT + 16 + 352 + + rw + + + + 24 + Filter time constant of TZ signal + UINT + 16 + 384 + + rw + + + + 26 + Filter time of speed feedback display + UINT + 16 + 416 + + rw + + + + 27 + Motor overload shielding + UINT + 16 + 432 + + rw + + + + 28 + Speed DO Filter time constant + UINT + 16 + 448 + + rw + + + + 30 + Full Closed-loop(ABZ) Filter time constant + UINT + 16 + 480 + + rw + + + + 33 + Overheat protection time duration for locked rotor + UINT + 16 + 528 + + rw + + + + 34 + Overheat protection for locked rotor enable + UINT + 16 + 544 + + rw + + + + 37 + Absolute Encode multi-turns error forbidden + UINT + 16 + 592 + + rw + + + + 41 + Compensation Function + UINT + 16 + 656 + + rw + + + + 50 + Over Temperature value of discharge tube + UINT + 16 + 800 + + rw + + + + 51 + Encoder communiction error threshold + UINT + 16 + 816 + + rw + + + + 52 + Phase lack threshold + UINT + 16 + 832 + + rw + + + + 53 + Over Temperature value of Encoder + UINT + 16 + 848 + + rw + + + + 54 + TouchProbe DI Turn-on Compensation Time + INT + 16 + 864 + + rw + + + + 55 + TouchProbe DI Turn-off Compensation Time + INT + 16 + 880 + + rw + + + + 56 + Runaway current threshold + UINT + 16 + 896 + + rw + + + + 57 + Fault reset delay time + UINT + 16 + 912 + + rw + + + + 58 + Runaway speed threshold + UINT + 16 + 928 + + rw + + + + 59 + Runaway speed filter time constant + UINT + 16 + 944 + + rw + + + + 60 + Runaway protection time window + UINT + 16 + 960 + + rw + + + + 61 + BlackBox Mode Select + UINT + 16 + 976 + + rw + + + + 62 + BlackBox Selected Error Code + UINT + 16 + 992 + + rw + + + + 63 + BlackBox Trig Source + UINT + 16 + 1008 + + rw + + + + 64 + BlackBox Trig Level + DINT + 32 + 1024 + + rw + + + + 66 + BlackBox Trig Level Select + UINT + 16 + 1056 + + rw + + + + 67 + BlackBox Trig Position + UINT + 16 + 1072 + + rw + + + + 68 + BlackBox Trig Frequency Select + UINT + 16 + 1088 + + rw + + + + 71 + The 2nd over speed threshold + UINT + 16 + 1136 + + rw + + + + 72 + Motor over load monitor switch + UINT + 16 + 1152 + + rw + + + + 73 + Maximum ramp stop time + UINT + 16 + 1168 + + rw + + + + 74 + STO Disconnect filter time + UINT + 16 + 1184 + + rw + + + + 75 + STO Mismatch filter time + UINT + 16 + 1200 + + rw + + + + 76 + STO Servo off filter time + UINT + 16 + 1216 + + rw + + + + 86 + Motor Offline Trq Limit + UINT + 16 + 1376 + + rw + + + + 87 + Motor Offline Filter Time + UINT + 16 + 1392 + + rw + + + + 91 + Filter Time Constant of Spd Display + UINT + 16 + 1456 + + rw + + + + 92 + Filter Time Constant of Trq Display + INT + 16 + 1472 + + rw + + + + 93 + Filter Time Constant of Position Display + UINT + 16 + 1488 + + rw + + + + 94 + Filter Time Constant of Voltage Display + UINT + 16 + 1504 + + rw + + + + 95 + Filter Time Constant of Temp Display + UINT + 16 + 1520 + + rw + + + + + DT200B + 1584 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Actual motor rotational speed + INT + 16 + 16 + + ro + T + + + + 2 + Speed reference + INT + 16 + 32 + + ro + T + + + + 3 + Internal torque reference + INT + 16 + 48 + + ro + T + + + + 4 + Monitored DI states + UINT + 16 + 64 + + ro + T + + + + 6 + Monitored DO states + UINT + 16 + 96 + + ro + T + + + + 8 + Absolute position counter + DINT + 32 + 128 + + ro + T + + + + 10 + Mechanical angle + UINT + 16 + 160 + + ro + T + + + + 11 + Electrical angle + UINT + 16 + 176 + + ro + T + + + + 13 + Average load rate + UINT + 16 + 208 + + ro + T + + + + 16 + Encoder position deviation counter + DINT + 32 + 256 + + ro + T + + + + 18 + Feedback pulse counter + DINT + 32 + 288 + + ro + T + + + + 20 + Total power-on time + UDINT + 32 + 320 + + ro + T + + + + 22 + AI1 Voltage DisPlay + INT + 16 + 352 + + ro + T + + + + 25 + Phase current valid value + UINT + 16 + 400 + + ro + T + + + + 27 + Bus voltage + UINT + 16 + 432 + + ro + T + + + + 28 + Module temperature + UINT + 16 + 448 + + ro + T + + + + 29 + Absolute encoder fault info. from FPGA + UINT + 16 + 464 + + ro + + + + 30 + Axis state from FPGA + UINT + 16 + 480 + + ro + + + + 31 + Axis fault info. from FPGA + UINT + 16 + 496 + + ro + + + + 32 + Encoder internal fault info. + UINT + 16 + 512 + + rw + + + + 34 + Displayed fault record + UINT + 16 + 544 + + rw + + + + 35 + Fault code + UINT + 16 + 560 + + ro + + + + 36 + Time stamp upon displayed fault + UDINT + 32 + 576 + + ro + + + + 38 + Current rotational speed upon displayed fault + INT + 16 + 608 + + ro + + + + 39 + Current U upon displayed fault + INT + 16 + 624 + + ro + + + + 40 + Current V upon displayed fault + INT + 16 + 640 + + ro + + + + 41 + Bus voltage upon displayed fault + UINT + 16 + 656 + + ro + + + + 42 + Input terminal state upon displayed fault + UINT + 16 + 672 + + ro + + + + 44 + Output terminal state upon displayed fault + UINT + 16 + 704 + + ro + + + + 46 + Inner error code + UINT + 16 + 736 + + ro + + + + 47 + Fault message of absolute encode from Fpga upon displayed + UINT + 16 + 752 + + ro + + + + 48 + System state from Fpga upon displayed fault + UINT + 16 + 768 + + ro + + + + 49 + System fault message from Fpga upon displayed fault + UINT + 16 + 784 + + ro + + + + 50 + Encode state 1 upon displayed fault + UINT + 16 + 800 + + ro + + + + 52 + Inner error code upon displayed fault + UINT + 16 + 832 + + ro + + + + 53 + Fpga overtime state upon displayed fault + UINT + 16 + 848 + + ro + + + + 54 + Reference position deviation + DINT + 32 + 864 + + ro + T + + + + 56 + Actual motor rotational speed(0.1rpm) + DINT + 32 + 896 + + ro + T + + + + 58 + Control bus voltage + UINT + 16 + 928 + + ro + T + + + + 59 + Mechanical absolute position inc(Low) + UDINT + 32 + 944 + + ro + T + + + + 61 + Mechanical absolute position inc(High) + DINT + 32 + 976 + + ro + T + + + + 64 + Not ready reason + UINT + 16 + 1024 + + ro + + + + 67 + Encoder temperature + UINT + 16 + 1072 + + ro + + + + 68 + Discharge load rate + UINT + 16 + 1088 + + ro + T + + + + 69 + Fpga over time state + UINT + 16 + 1104 + + ro + + + + 71 + Number of turns of absolute encode + UINT + 16 + 1136 + + ro + T + + + + 72 + Single feedback postion of absolute encode + UDINT + 32 + 1152 + + ro + T + + + + 75 + System Error + UINT + 16 + 1200 + + ro + + + + 78 + feedback postion of absolute encode(Low) + UDINT + 32 + 1248 + + ro + T + + + + 80 + feedback postion of absolute encode(High) + DINT + 32 + 1280 + + ro + T + + + + 82 + feedback postion inc of rotating load(Low) + UDINT + 32 + 1312 + + ro + T + + + + 84 + feedback postion inc of rotating load(High) + UDINT + 32 + 1344 + + ro + T + + + + 86 + Single feedback postion of rotating load + UDINT + 32 + 1376 + + ro + T + + + + 88 + IGBT Temperature + UINT + 16 + 1408 + + ro + + + + 91 + Group of unusual function code + UINT + 16 + 1456 + + ro + + + + 92 + Offset of unusual function code + UINT + 16 + 1472 + + ro + + + + 95 + Single Power-On Time + UDINT + 32 + 1520 + + ro + T + + + + 97 + Single Power-On Time upon displayed fault + UDINT + 32 + 1552 + + ro + + + + + DT200D + 400 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Software reset + UINT + 16 + 16 + + rw + + + + 2 + Fault reset + UINT + 16 + 32 + + rw + + + + 3 + Offline inertia autotuning selection + UINT + 16 + 48 + + rw + + + + 5 + Encoder ROM reading/writing + UINT + 16 + 80 + + rw + + + + 6 + Emergency stop + UINT + 16 + 96 + + rw + + + + 11 + AI1 Self-Adjust of Voltage Offset + UINT + 16 + 176 + + rw + + + + 13 + UV phase current auto-tuning + UINT + 16 + 208 + + rw + + + + 18 + Forced DI/DO setting + UINT + 16 + 288 + + rw + + + + 19 + Forced DI level + UINT + 16 + 304 + + rw + + + + 20 + Forced DO setting + UINT + 16 + 320 + + rw + + + + 21 + Absolute Encode Fault Reset + UINT + 16 + 336 + + rw + + + + 24 + Cogging torque self-learning + UINT + 16 + 384 + + rw + + + + + DT200E + 1568 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Node address + UINT + 16 + 16 + + rw + + + + 2 + Update function code values written via communication to EEPROM + UINT + 16 + 32 + + rw + + + + 21 + station auto inc address + UINT + 16 + 336 + + ro + + + + 22 + station alias + UINT + 16 + 352 + + rw + + + + 23 + Sync lost window + UINT + 16 + 368 + + rw + + + + 25 + Sync lost counter + UINT + 16 + 400 + + ro + + + + 26 + Port 0 invalid frame counter + UINT + 16 + 416 + + ro + + + + 27 + Port 1 invalid frame counter + UINT + 16 + 432 + + ro + + + + 28 + Port 0/1 transfer error counter + UINT + 16 + 448 + + ro + + + + 29 + process unit and PDI error counter + UINT + 16 + 464 + + ro + + + + 30 + Port 0/1 lost counter + UINT + 16 + 480 + + ro + + + + 32 + Sync mode set + UINT + 16 + 512 + + rw + + + + 33 + Sync error window + UINT + 16 + 528 + + rw + + + + 34 + EtherCAT network state and link state + UINT + 16 + 544 + + ro + + + + 35 + CSP postion increment over counter + UINT + 16 + 560 + + rw + + + + 36 + ECAT AL Error Code + UINT + 16 + 576 + + ro + + + + 37 + Enhanced link detection enable + UINT + 16 + 592 + + rw + + + + 38 + Reset EtherCAT xml file + UINT + 16 + 608 + + rw + + + + 74 + EtherCAT port control mode and state display + UINT + 16 + 1184 + + ro + + + + 94 + EtherCAT COE version number + UINT + 16 + 1504 + + ro + + + + 97 + EtherCAT xml file version number + UINT + 16 + 1552 + + ro + + + + + DT200F + 720 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Encoder feedback mode + UINT + 16 + 16 + + rw + + + + 2 + Running mode of external encoder + UINT + 16 + 32 + + rw + + + + 3 + SecEncoder Absolute system selection + UINT + 16 + 48 + + rw + + + + 4 + SecEncoder Type selection + UINT + 16 + 64 + + rw + + + + 5 + External encoder pulses per motor revolution + UDINT + 32 + 80 + + rw + + + + 9 + Hybrid deviation excess setting + UDINT + 32 + 144 + + rw + + + + 11 + Hybrid deviation clear setting + UINT + 16 + 176 + + rw + + + + 14 + First-order lowpass filter time of external/internal deviation + UINT + 16 + 224 + + rw + + + + 17 + Hybrid deviation counter + DINT + 32 + 272 + + ro + T + + + + 19 + Pulse feedback display of internal encoder + DINT + 32 + 304 + + ro + T + + + + 21 + Pulse feedback display of external encoder + DINT + 32 + 336 + + ro + T + + + + 23 + SecEncoder Pulse ZPhase Ignore + UINT + 16 + 368 + + rw + + + + 26 + SecEncoder Pulse Z-TouchProbe Selection + UINT + 16 + 416 + + rw + + + + + DT2012 + 1104 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + MultiSpd Function Select + UINT + 16 + 16 + + rw + R + + + + 2 + MultiSpd Final Part Select + UINT + 16 + 32 + + rw + R + + + + 3 + Time Uint of Runing + UINT + 16 + 48 + + rw + R + + + + 4 + AccTime1 + UINT + 16 + 64 + + rw + R + + + + 5 + DecTime1 + UINT + 16 + 80 + + rw + R + + + + 6 + AccTime2 + UINT + 16 + 96 + + rw + R + + + + 7 + DecTime2 + UINT + 16 + 112 + + rw + R + + + + 8 + AccTime3 + UINT + 16 + 128 + + rw + R + + + + 9 + DecTime3 + UINT + 16 + 144 + + rw + R + + + + 10 + AccTime4 + UINT + 16 + 160 + + rw + R + + + + 11 + DecTime4 + UINT + 16 + 176 + + rw + R + + + + 21 + 1st Part Spd Cmd + INT + 16 + 336 + + rw + R + + + + 22 + 1st Part Spd Runing Time + UINT + 16 + 352 + + rw + R + + + + 23 + 1st Part AccDec Time Select + UINT + 16 + 368 + + rw + R + + + + 24 + 2nd Part Spd Cmd + INT + 16 + 384 + + rw + R + + + + 25 + 2nd Part Spd Runing Time + UINT + 16 + 400 + + rw + R + + + + 26 + 2nd Part AccDec Time Select + UINT + 16 + 416 + + rw + R + + + + 27 + 3rd Part Spd Cmd + INT + 16 + 432 + + rw + R + + + + 28 + 3rd Part Spd Runing Time + UINT + 16 + 448 + + rw + R + + + + 29 + 3rd Part AccDec Time Select + UINT + 16 + 464 + + rw + R + + + + 30 + 4th Part Spd Cmd + INT + 16 + 480 + + rw + R + + + + 31 + 4th Part Spd Runing Time + UINT + 16 + 496 + + rw + R + + + + 32 + 4th Part AccDec Time Select + UINT + 16 + 512 + + rw + R + + + + 33 + 5th Part Spd Cmd + INT + 16 + 528 + + rw + R + + + + 34 + 5th Part Spd Runing Time + UINT + 16 + 544 + + rw + R + + + + 35 + 5th Part AccDec Time Select + UINT + 16 + 560 + + rw + R + + + + 36 + 6th Part Spd Cmd + INT + 16 + 576 + + rw + R + + + + 37 + 6th Part Spd Runing Time + UINT + 16 + 592 + + rw + R + + + + 38 + 6th Part AccDec Time Select + UINT + 16 + 608 + + rw + R + + + + 39 + 7th Part Spd Cmd + INT + 16 + 624 + + rw + R + + + + 40 + 7th Part Spd Runing Time + UINT + 16 + 640 + + rw + R + + + + 41 + 7th Part AccDec Time Select + UINT + 16 + 656 + + rw + R + + + + 42 + 8th Part Spd Cmd + INT + 16 + 672 + + rw + R + + + + 43 + 8th Part Spd Runing Time + UINT + 16 + 688 + + rw + R + + + + 44 + 8th Part AccDec Time Select + UINT + 16 + 704 + + rw + R + + + + 45 + 9th Part Spd Cmd + INT + 16 + 720 + + rw + R + + + + 46 + 9th Part Spd Runing Time + UINT + 16 + 736 + + rw + R + + + + 47 + 9th Part AccDec Time Select + UINT + 16 + 752 + + rw + R + + + + 48 + 10th Part Spd Cmd + INT + 16 + 768 + + rw + R + + + + 49 + 10th Part Spd Runing Time + UINT + 16 + 784 + + rw + R + + + + 50 + 10th Part AccDec Time Select + UINT + 16 + 800 + + rw + R + + + + 51 + 11th Part Spd Cmd + INT + 16 + 816 + + rw + R + + + + 52 + 11th Part Spd Runing Time + UINT + 16 + 832 + + rw + R + + + + 53 + 11th Part AccDec Time Select + UINT + 16 + 848 + + rw + R + + + + 54 + 12th Part Spd Cmd + INT + 16 + 864 + + rw + R + + + + 55 + 12th Part Spd Runing Time + UINT + 16 + 880 + + rw + R + + + + 56 + 12th Part AccDec Time Select + UINT + 16 + 896 + + rw + R + + + + 57 + 13th Part Spd Cmd + INT + 16 + 912 + + rw + R + + + + 58 + 13th Part Spd Runing Time + UINT + 16 + 928 + + rw + R + + + + 59 + 13th Part AccDec Time Select + UINT + 16 + 944 + + rw + R + + + + 60 + 14th Part Spd Cmd + INT + 16 + 960 + + rw + R + + + + 61 + 14th Part Spd Runing Time + UINT + 16 + 976 + + rw + R + + + + 62 + 14th Part AccDec Time Select + UINT + 16 + 992 + + rw + R + + + + 63 + 15th Part Spd Cmd + INT + 16 + 1008 + + rw + R + + + + 64 + 15th Part Spd Runing Time + UINT + 16 + 1024 + + rw + R + + + + 65 + 15th Part AccDec Time Select + UINT + 16 + 1040 + + rw + R + + + + 66 + 16th Part Spd Cmd + INT + 16 + 1056 + + rw + R + + + + 67 + 16th Part Spd Runing Time + UINT + 16 + 1072 + + rw + R + + + + 68 + 16th Part AccDec Time Select + UINT + 16 + 1088 + + rw + R + + + + + DT2017 + 1520 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + VDI1 Terminal Function Selection + UINT + 16 + 16 + + rw + + + + 2 + VDI1 Terminal Logic Selection + UINT + 16 + 32 + + rw + + + + 3 + VDI2 Terminal Function Selection + UINT + 16 + 48 + + rw + + + + 4 + VDI2 Terminal Logic Selection + UINT + 16 + 64 + + rw + + + + 5 + VDI3 Terminal Function Selection + UINT + 16 + 80 + + rw + + + + 6 + VDI3 Terminal Logic Selection + UINT + 16 + 96 + + rw + + + + 7 + VDI4 Terminal Function Selection + UINT + 16 + 112 + + rw + + + + 8 + VDI4 Terminal Logic Selection + UINT + 16 + 128 + + rw + + + + 9 + VDI5 Terminal Function Selection + UINT + 16 + 144 + + rw + + + + 10 + VDI5 Terminal Logic Selection + UINT + 16 + 160 + + rw + + + + 11 + VDI6 Terminal Function Selection + UINT + 16 + 176 + + rw + + + + 12 + VDI6 Terminal Logic Selection + UINT + 16 + 192 + + rw + + + + 13 + VDI7 Terminal Function Selection + UINT + 16 + 208 + + rw + + + + 14 + VDI7 Terminal Logic Selection + UINT + 16 + 224 + + rw + + + + 15 + VDI8 Terminal Function Selection + UINT + 16 + 240 + + rw + + + + 16 + VDI8 Terminal Logic Selection + UINT + 16 + 256 + + rw + + + + 17 + VDI9 Terminal Function Selection + UINT + 16 + 272 + + rw + + + + 18 + VDI9 Terminal Logic Selection + UINT + 16 + 288 + + rw + + + + 19 + VDI10 Terminal Function Selection + UINT + 16 + 304 + + rw + + + + 20 + VDI10 Terminal Logic Selection + UINT + 16 + 320 + + rw + + + + 21 + VDI11 Terminal Function Selection + UINT + 16 + 336 + + rw + + + + 22 + VDI11 Terminal Logic Selection + UINT + 16 + 352 + + rw + + + + 23 + VDI12 Terminal Function Selection + UINT + 16 + 368 + + rw + + + + 24 + VDI12 Terminal Logic Selection + UINT + 16 + 384 + + rw + + + + 25 + VDI13 Terminal Function Selection + UINT + 16 + 400 + + rw + + + + 26 + VDI13 Terminal Logic Selection + UINT + 16 + 416 + + rw + + + + 27 + VDI14 Terminal Function Selection + UINT + 16 + 432 + + rw + + + + 28 + VDI14 Terminal Logic Selection + UINT + 16 + 448 + + rw + + + + 29 + VDI15 Terminal Function Selection + UINT + 16 + 464 + + rw + + + + 30 + VDI15 Terminal Logic Selection + UINT + 16 + 480 + + rw + + + + 31 + VDI16 Terminal Function Selection + UINT + 16 + 496 + + rw + + + + 32 + VDI16 Terminal Logic Selection + UINT + 16 + 512 + + rw + + + + 33 + VDO virtual level + UINT + 16 + 528 + + ro + + + + 34 + VDO1 Terminal Function Selection + UINT + 16 + 544 + + rw + + + + 35 + VDO1 Terminal Logic Level Selection + UINT + 16 + 560 + + rw + + + + 36 + VDO2 Terminal Function Selection + UINT + 16 + 576 + + rw + + + + 37 + VDO2 Terminal Logic Level Selection + UINT + 16 + 592 + + rw + + + + 38 + VDO3 Terminal Function Selection + UINT + 16 + 608 + + rw + + + + 39 + VDO3 Terminal Logic Level Selection + UINT + 16 + 624 + + rw + + + + 40 + VDO4 Terminal Function Selection + UINT + 16 + 640 + + rw + + + + 41 + VDO4 Terminal Logic Level Selection + UINT + 16 + 656 + + rw + + + + 42 + VDO5 Terminal Function Selection + UINT + 16 + 672 + + rw + + + + 43 + VDO5 Terminal Logic Level Selection + UINT + 16 + 688 + + rw + + + + 44 + VDO6 Terminal Function Selection + UINT + 16 + 704 + + rw + + + + 45 + VDO6 Terminal Logic Level Selection + UINT + 16 + 720 + + rw + + + + 46 + VDO7 Terminal Function Selection + UINT + 16 + 736 + + rw + + + + 47 + VDO7 Terminal Logic Level Selection + UINT + 16 + 752 + + rw + + + + 48 + VDO8 Terminal Function Selection + UINT + 16 + 768 + + rw + + + + 49 + VDO8 Terminal Logic Level Selection + UINT + 16 + 784 + + rw + + + + 50 + VDO9 Terminal Function Selection + UINT + 16 + 800 + + rw + + + + 51 + VDO9 Terminal Logic Level Selection + UINT + 16 + 816 + + rw + + + + 52 + VDO10 Terminal Function Selection + UINT + 16 + 832 + + rw + + + + 53 + VDO10 Terminal Logic Level Selection + UINT + 16 + 848 + + rw + + + + 54 + VDO11 Terminal Function Selection + UINT + 16 + 864 + + rw + + + + 55 + VDO11 Terminal Logic Level Selection + UINT + 16 + 880 + + rw + + + + 56 + VDO12 Terminal Function Selection + UINT + 16 + 896 + + rw + + + + 57 + VDO12 Terminal Logic Level Selection + UINT + 16 + 912 + + rw + + + + 58 + VDO13 Terminal Function Selection + UINT + 16 + 928 + + rw + + + + 59 + VDO13 Terminal Logic Level Selection + UINT + 16 + 944 + + rw + + + + 60 + VDO14 Terminal Function Selection + UINT + 16 + 960 + + rw + + + + 61 + VDO14 Terminal Logic Level Selection + UINT + 16 + 976 + + rw + + + + 62 + VDO15 Terminal Function Selection + UINT + 16 + 992 + + rw + + + + 63 + VDO15 Terminal Logic Level Selection + UINT + 16 + 1008 + + rw + + + + 64 + VDO16 Terminal Function Selection + UINT + 16 + 1024 + + rw + + + + 65 + VDO16 Terminal Logic Level Selection + UINT + 16 + 1040 + + rw + + + + 91 + VDI Enable + UINT + 16 + 1456 + + rw + R + + + + 92 + VDI Default Value + UINT + 16 + 1472 + + rw + R + + + + 93 + VDO Enable + UINT + 16 + 1488 + + rw + R + + + + 94 + VDO Default Value + UINT + 16 + 1504 + + rw + R + + + + + DT2018 + 288 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Enable Comparison + UINT + 16 + 16 + + rw + R + + + + 2 + Comparison PosFdb Source Select + UINT + 16 + 32 + + rw + R + + + + 3 + Encoder Resolution + UINT + 16 + 48 + + rw + R + + + + 4 + Mode Of Comparison + UINT + 16 + 64 + + rw + R + + + + 5 + Current Position As Zero + UINT + 16 + 80 + + rw + R + + + + 6 + Output Duration + UINT + 16 + 96 + + rw + R + + + + 7 + Comparison ABZ OutPut Logic + UINT + 16 + 112 + + rw + R + + + + 8 + Starting Point Number + UINT + 16 + 128 + + rw + R + + + + 9 + Ending Point Number + UINT + 16 + 144 + + rw + R + + + + 10 + Comparison Status + UINT + 16 + 160 + + ro + T + + + + 11 + Current Position + DINT + 32 + 176 + + ro + T + + + + 13 + Position Offset + DINT + 32 + 208 + + rw + R + + + + 15 + Comparison OutPut Delay Compensation + INT + 16 + 240 + + rw + R + + + + 16 + Lilited number of Comparison Cycle Times + UINT + 16 + 256 + + rw + R + + + + 17 + Comparison ABZ OutPut Function + UINT + 16 + 272 + + rw + R + + + + + DT2019 + 1936 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Comparing Position + DINT + 32 + 16 + + rw + R + + + + 3 + 1st Point Property + UINT + 16 + 48 + + rw + R + + + + 4 + 2nd Comparing Position + DINT + 32 + 64 + + rw + R + + + + 6 + 2nd Point Property + UINT + 16 + 96 + + rw + R + + + + 7 + 3rd Comparing Position + DINT + 32 + 112 + + rw + R + + + + 9 + 3rd Point Property + UINT + 16 + 144 + + rw + R + + + + 10 + 4th Comparing Position + DINT + 32 + 160 + + rw + R + + + + 12 + 4th Point Property + UINT + 16 + 192 + + rw + R + + + + 13 + 5th Comparing Position + DINT + 32 + 208 + + rw + R + + + + 15 + 5th Point Property + UINT + 16 + 240 + + rw + R + + + + 16 + 6th Comparing Position + DINT + 32 + 256 + + rw + R + + + + 18 + 6th Point Property + UINT + 16 + 288 + + rw + R + + + + 19 + 7th Comparing Position + DINT + 32 + 304 + + rw + R + + + + 21 + 7th Point Property + UINT + 16 + 336 + + rw + R + + + + 22 + 8th Comparing Position + DINT + 32 + 352 + + rw + R + + + + 24 + 8th Point Property + UINT + 16 + 384 + + rw + R + + + + 25 + 9th Comparing Position + DINT + 32 + 400 + + rw + R + + + + 27 + 9th Point Property + UINT + 16 + 432 + + rw + R + + + + 28 + 10th Comparing Position + DINT + 32 + 448 + + rw + R + + + + 30 + 10th Point Property + UINT + 16 + 480 + + rw + R + + + + 31 + 11th Comparing Position + DINT + 32 + 496 + + rw + R + + + + 33 + 11th Point Property + UINT + 16 + 528 + + rw + R + + + + 34 + 12th Comparing Position + DINT + 32 + 544 + + rw + R + + + + 36 + 12th Point Property + UINT + 16 + 576 + + rw + R + + + + 37 + 13th Comparing Position + DINT + 32 + 592 + + rw + R + + + + 39 + 13th Point Property + UINT + 16 + 624 + + rw + R + + + + 40 + 14th Comparing Position + DINT + 32 + 640 + + rw + R + + + + 42 + 14th Point Property + UINT + 16 + 672 + + rw + R + + + + 43 + 15th Comparing Position + DINT + 32 + 688 + + rw + R + + + + 45 + 15th Point Property + UINT + 16 + 720 + + rw + R + + + + 46 + 16th Comparing Position + DINT + 32 + 736 + + rw + R + + + + 48 + 16th Point Property + UINT + 16 + 768 + + rw + R + + + + 49 + 17th Comparing Position + DINT + 32 + 784 + + rw + R + + + + 51 + 17th Point Property + UINT + 16 + 816 + + rw + R + + + + 52 + 18th Comparing Position + DINT + 32 + 832 + + rw + R + + + + 54 + 18th Point Property + UINT + 16 + 864 + + rw + R + + + + 55 + 19th Comparing Position + DINT + 32 + 880 + + rw + R + + + + 57 + 19th Point Property + UINT + 16 + 912 + + rw + R + + + + 58 + 20th Comparing Position + DINT + 32 + 928 + + rw + R + + + + 60 + 20th Point Property + UINT + 16 + 960 + + rw + R + + + + 61 + 21st Comparing Position + DINT + 32 + 976 + + rw + R + + + + 63 + 21st Point Property + UINT + 16 + 1008 + + rw + R + + + + 64 + 22nd Comparing Position + DINT + 32 + 1024 + + rw + R + + + + 66 + 22nd Point Property + UINT + 16 + 1056 + + rw + R + + + + 67 + 23rd Comparing Position + DINT + 32 + 1072 + + rw + R + + + + 69 + 23rd Point Property + UINT + 16 + 1104 + + rw + R + + + + 70 + 24th Comparing Position + DINT + 32 + 1120 + + rw + R + + + + 72 + 24th Point Property + UINT + 16 + 1152 + + rw + R + + + + 73 + 25th Comparing Position + DINT + 32 + 1168 + + rw + R + + + + 75 + 25th Point Property + UINT + 16 + 1200 + + rw + R + + + + 76 + 26th Comparing Position + DINT + 32 + 1216 + + rw + R + + + + 78 + 26th Point Property + UINT + 16 + 1248 + + rw + R + + + + 79 + 27th Comparing Position + DINT + 32 + 1264 + + rw + R + + + + 81 + 27th Point Property + UINT + 16 + 1296 + + rw + R + + + + 82 + 28th Comparing Position + DINT + 32 + 1312 + + rw + R + + + + 84 + 28th Point Property + UINT + 16 + 1344 + + rw + R + + + + 85 + 29th Comparing Position + DINT + 32 + 1360 + + rw + R + + + + 87 + 29th Point Property + UINT + 16 + 1392 + + rw + R + + + + 88 + 30th Comparing Position + DINT + 32 + 1408 + + rw + R + + + + 90 + 30th Point Property + UINT + 16 + 1440 + + rw + R + + + + 91 + 31st Comparing Position + DINT + 32 + 1456 + + rw + R + + + + 93 + 31st Point Property + UINT + 16 + 1488 + + rw + R + + + + 94 + 32nd Comparing Position + DINT + 32 + 1504 + + rw + R + + + + 96 + 32nd Point Property + UINT + 16 + 1536 + + rw + R + + + + 97 + 33rd Comparing Position + DINT + 32 + 1552 + + rw + R + + + + 99 + 33rd Point Property + UINT + 16 + 1584 + + rw + R + + + + 100 + 34th Comparing Position + DINT + 32 + 1600 + + rw + R + + + + 102 + 34th Point Property + UINT + 16 + 1632 + + rw + R + + + + 103 + 35th Comparing Position + DINT + 32 + 1648 + + rw + R + + + + 105 + 35th Point Property + UINT + 16 + 1680 + + rw + R + + + + 106 + 36th Comparing Position + DINT + 32 + 1696 + + rw + R + + + + 108 + 36th Point Property + UINT + 16 + 1728 + + rw + R + + + + 109 + 37th Comparing Position + DINT + 32 + 1744 + + rw + R + + + + 111 + 37th Point Property + UINT + 16 + 1776 + + rw + R + + + + 112 + 38th Comparing Position + DINT + 32 + 1792 + + rw + R + + + + 114 + 38th Point Property + UINT + 16 + 1824 + + rw + R + + + + 115 + 39th Comparing Position + DINT + 32 + 1840 + + rw + R + + + + 117 + 39th Point Property + UINT + 16 + 1872 + + rw + R + + + + 118 + 40th Comparing Position + DINT + 32 + 1888 + + rw + R + + + + 120 + 40th Point Property + UINT + 16 + 1920 + + rw + R + + + + + DT2030 + 64 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Servo Status + UINT + 16 + 16 + + ro + T + + + + 2 + DO Function1 + UINT + 16 + 32 + + ro + T + + + + 3 + DO Function2 + UINT + 16 + 48 + + ro + T + + + + + DT2031 + 224 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Comm Set VDI + UINT + 16 + 16 + + rw + R + + + + 5 + Comm Set DO + UINT + 16 + 80 + + rw + R + + + + 6 + Comm Set AO + INT + 16 + 96 + + rw + R + + + + 10 + Comm Set Local SpdRef + DINT + 32 + 160 + + rw + R + + + + 12 + Comm Set Local TrqRef + DINT + 32 + 192 + + rw + R + + + + + DT607D + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Min position limit + DINT + 32 + 16 + + rw + R + + + + 2 + Max position limit + DINT + 32 + 48 + + rw + R + + + + + DT6091 + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Motor revolutions + UDINT + 32 + 16 + + rw + R + + + + 2 + Shaft revolutions + UDINT + 32 + 48 + + rw + R + + + + + DT6099 + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Speed during search for switch + UDINT + 32 + 16 + + rw + R + + + + 2 + Speed during search for zero + UDINT + 32 + 48 + + rw + R + + + + + DT60FE + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Physical outputs + UDINT + 32 + 16 + + rw + R + + + + 2 + Bit Mask + UDINT + 32 + 48 + + rw + R + + + + + DT60E3 + 544 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Support homing method 1 + INT + 16 + 16 + + ro + + + + 2 + Support homing method 2 + INT + 16 + 32 + + ro + + + + 3 + Support homing method 3 + INT + 16 + 48 + + ro + + + + 4 + Support homing method 4 + INT + 16 + 64 + + ro + + + + 5 + Support homing method 5 + INT + 16 + 80 + + ro + + + + 6 + Support homing method 6 + INT + 16 + 96 + + ro + + + + 7 + Support homing method 7 + INT + 16 + 112 + + ro + + + + 8 + Support homing method 8 + INT + 16 + 128 + + ro + + + + 9 + Support homing method 9 + INT + 16 + 144 + + ro + + + + 10 + Support homing method 10 + INT + 16 + 160 + + ro + + + + 11 + Support homing method 11 + INT + 16 + 176 + + ro + + + + 12 + Support homing method 12 + INT + 16 + 192 + + ro + + + + 13 + Support homing method 13 + INT + 16 + 208 + + ro + + + + 14 + Support homing method 14 + INT + 16 + 224 + + ro + + + + 15 + Support homing method 15 + INT + 16 + 240 + + ro + + + + 16 + Support homing method 16 + INT + 16 + 256 + + ro + + + + 17 + Support homing method 17 + INT + 16 + 272 + + ro + + + + 18 + Support homing method 18 + INT + 16 + 288 + + ro + + + + 19 + Support homing method 19 + INT + 16 + 304 + + ro + + + + 20 + Support homing method 20 + INT + 16 + 320 + + ro + + + + 21 + Support homing method 21 + INT + 16 + 336 + + ro + + + + 22 + Support homing method 22 + INT + 16 + 352 + + ro + + + + 23 + Support homing method 23 + INT + 16 + 368 + + ro + + + + 24 + Support homing method 24 + INT + 16 + 384 + + ro + + + + 25 + Support homing method 25 + INT + 16 + 400 + + ro + + + + 26 + Support homing method 26 + INT + 16 + 416 + + ro + + + + 27 + Support homing method 27 + INT + 16 + 432 + + ro + + + + 28 + Support homing method 28 + INT + 16 + 448 + + ro + + + + 29 + Support homing method 29 + INT + 16 + 464 + + ro + + + + 30 + Support homing method 30 + INT + 16 + 480 + + ro + + + + 31 + Support homing method 31 + INT + 16 + 496 + + ro + + + + 32 + Support homing method 32 + INT + 16 + 512 + + ro + + + + 33 + Support homing method 33 + INT + 16 + 528 + + ro + + + + + + + #x1000 + Device type + UDINT + 32 + + #x00020192 + + + ro + o + + + + #x1001 + Error Register + USINT + 8 + + 00 + + + ro + o + + + + #x1008 + Device name + STRING(10) + 80 + + SV670_ECAT + + + ro + + + + #x1009 + Hardware version + STRING(4) + 32 + + V1.0 + + + ro + + + + #x100a + Software version + STRING(4) + 32 + + V1.0 + + + ro + o + + + + #x1c00 + Sync manager type + DT1C00 + 48 + + + SubIndex 000 + + 04 + + + + SubIndex 001 + + 01 + + + + SubIndex 002 + + 02 + + + + SubIndex 003 + + 03 + + + + SubIndex 004 + + 04 + + + + + ro + o + + + + #x1018 + Identity + DT1018 + 144 + + + SubIndex 000 + + 04 + + + + Vendor ID + + #x00100000 + + + + Product Code + + #x000C011E + + + + Revision + + #x00010000 + + + + Serial number + + 00000000 + + + + + ro + o + + + + #x1600 + Outputs + DT1600 + 336 + + + SubIndex 000 + + 00 + 10 + #x03 + + + + 1st Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60400010 + + + + 2nd Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x607A0020 + + + + 3rd Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60B80010 + + + + 4th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 5th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 6th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 7th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 8th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 9th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 10th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + rw + + + + #x1601 + Outputs + DT1601 + 368 + + + SubIndex 000 + + #x0B + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x60600008 + + + + 3rd Output Object to be mapped + + #x60710010 + + + + 4th Output Object to be mapped + + #x607A0020 + + + + 5th Output Object to be mapped + + #x607F0020 + + + + 6th Output Object to be mapped + + #x60810020 + + + + 7th Output Object to be mapped + + #x60830020 + + + + 8th Output Object to be mapped + + #x60840020 + + + + 9th Output Object to be mapped + + #x60870020 + + + + 10th Output Object to be mapped + + #x60B80010 + + + + 11th Output Object to be mapped + + #x60FF0020 + + + + + rw + + + + #x1701 + Outputs + DT1701 + 336 + + + SubIndex 000 + + #x04 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60B80010 + + + + 4th Output Object to be mapped + + #x60FE0120 + + + + + ro + + + + #x1702 + Outputs + DT1702 + 336 + + + SubIndex 000 + + #x07 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60B80010 + + + + 4th Output Object to be mapped + + #x60710010 + + + + 5th Output Object to be mapped + + #x60600008 + + + + 6th Output Object to be mapped + + #x60B80010 + + + + 7th Output Object to be mapped + + #x607F0020 + + + + + ro + + + + #x1703 + Outputs + DT1702 + 336 + + + SubIndex 000 + + #x07 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60600008 + + + + 5th Output Object to be mapped + + #x60B80010 + + + + 6th Output Object to be mapped + + #x60E00010 + + + + 7th Output Object to be mapped + + #x60E10010 + + + + + ro + + + + #x1704 + Outputs + DT1704 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60710010 + + + + 5th Output Object to be mapped + + #x60600008 + + + + 6th Output Object to be mapped + + #x60B80010 + + + + 7th Output Object to be mapped + + #x607F0020 + + + + 8th Output Object to be mapped + + #x60E00010 + + + + 9th Output Object to be mapped + + #x60E10010 + + + + + ro + + + + #x1705 + Outputs + DT1705 + 336 + + + SubIndex 000 + + #x08 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60600008 + + + + 5th Output Object to be mapped + + #x60B80010 + + + + 6th Output Object to be mapped + + #x60E00010 + + + + 7th Output Object to be mapped + + #x60E10010 + + + + 8th Output Object to be mapped + + #x60B20010 + + + + + ro + + + + #x1A00 + Inputs + DT1A00 + 336 + + + SubIndex 000 + + 00 + 10 + #x07 + + + + 1st Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60410010 + + + + 2nd Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60640020 + + + + 3rd Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60B90010 + + + + 4th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60BA0020 + + + + 5th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60BC0020 + + + + 6th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x603F0010 + + + + 7th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60FD0020 + + + + 8th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 9th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 10th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + rw + + + + #x1A01 + Inputs + DT1A01 + 368 + + + SubIndex 000 + + #x0B + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60610008 + + + + 4th Input Object to be mapped + + #x60640020 + + + + 5th Input Object to be mapped + + #x606C0020 + + + + 6th Input Object to be mapped + + #x60770010 + + + + 7th Input Object to be mapped + + #x60B90010 + + + + 8th Input Object to be mapped + + #x60BA0020 + + + + 9th Input Object to be mapped + + #x60BC0020 + + + + 10th Input Object to be mapped + + #x60F40020 + + + + 11th Input Object to be mapped + + #x60FD0020 + + + + + rw + + + + #x1B01 + Inputs + DT1B01 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60F40020 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B02 + Inputs + DT1B01 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60610008 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B03 + Inputs + DT1B03 + 336 + + + SubIndex 000 + + #x0A + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60F40020 + + + + 6th Input Object to be mapped + + #x60610008 + + + + 7th Input Object to be mapped + + #x60B90010 + + + + 8th Input Object to be mapped + + #x60BA0020 + + + + 9th Input Object to be mapped + + #x60BC0020 + + + + 10th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B04 + Inputs + DT1B04 + 336 + + + SubIndex 000 + + #x0A + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60610008 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + 10th Input Object to be mapped + + #x606C0020 + + + + + ro + + + + #x1c32 + SM output parameter + DT1C32 + 488 + + + SubIndex 000 + + 20 + + + + Sync mode + + 0200 + + + + Cycle time + + 00000000 + + + + Sync modes supported + + 0004 + + + + Minimum cycle time + + 00000000 + + + + Calc and copy time + + #x0003d090 + + + + Get Cycle Time + + 0000 + + + + Delay Time + + 00000000 + + + + Sync0 Cycle Time + + 00000000 + + + + SM-Event Missed + + 0000 + + + + Cycle Time Too Small + + 0000 + + + + Sync Error + + 00 + + + + + ro + o + + + + #x1c33 + SM input parameter + DT1C33 + 488 + + + SubIndex 000 + + 20 + + + + Sync mode + + 0002 + + + + Cycle time + + 00000000 + + + + Sync modes supported + + 4 + + + + Minimum cycle time + + 00000000 + + + + Calc and copy time + + 00000000 + + + + Get Cycle Time + + 0000 + + + + Delay Time + + 00000000 + + + + Sync0 Cycle Time + + 00000000 + + + + SM-Event Missed + + 0000 + + + + Cycle Time Too Small + + 0000 + + + + Sync Error + + 00 + + + + + ro + o + + + + #x1c12 + RxPDO assign + DT1C12 + 32 + + + SubIndex 000 + + 00 + + + + SubIndex 001 + + 0000 + + + + + ro + + + + #x1c13 + TxPDO assign + DT1C13 + 32 + + + SubIndex 000 + + 00 + + + + SubIndex 001 + + 0000 + + + + + ro + + + + #x2000 + Servo Motor Parameters + 伺服电机参数 + DT2000 + 128 + + + SubIndex 000 + + 6 + + + + Motor SN + + 0 + 65535 + 14101 + + + + Customized firmware version + + 0 + 65535 + 0 + + + + Encoder Version + + 0 + 65535 + 0 + + + + Serial encoder motor SN + + 0 + 65535 + 0 + + + + + ro + + + + #x2001 + Servo Drive Parameters + 伺服驱动器参数 + DT2001 + 672 + + + SubIndex 000 + + 41 + + + + MCU firmware Version + + 0 + 65535 + 0 + + + + Fpga firmware Version + + 0 + 65535 + 0 + + + + Drive serial number + + 0 + 65535 + 3 + + + + Drive voltage class + + 0 + 65535 + 220 + + + + Drive rated power + + 0 + 1073741824 + 400 + + + + Drive maximum output power + + 0 + 1073741824 + 400 + + + + Drive rated output current + + 0 + 1073741824 + 280 + + + + Drive maximum output current + + 0 + 1073741824 + 1010 + + + + DC bus overvoltage protective point + + 0 + 2000 + 420 + + + + + ro + + + + #x2002 + Basic control + 基本控制参数 + DT2002 + 688 + + + SubIndex 000 + + 36 + + + + Control mode selection + + 0 + 9 + 9 + + + + Absolute system selection + + 0 + 4 + 0 + + + + Rotating direction + + 0 + 1 + 0 + + + + Output pulse phase + + 0 + 1 + 0 + + + + Disable operation option Code + + -4 + 2 + 0 + + + + NO2 Fault Reaction option Code + + -5 + 4 + 2 + + + + Stop mode at limit switch signal + + 0 + 7 + 1 + + + + Stop mode at NO.1 fault + + 0 + 2 + 2 + + + + Delay from brake output on to command received + + 0 + 500 + 250 + + + + Delay from brake output off to motor de-energized + + 50 + 1000 + 150 + + + + Motor speed threshold at brake output off in rotating state + + 20 + 3000 + 30 + + + + Delay from servo off to brake output off in the rotating state + + 1 + 65535 + 500 + + + + LED warning display selection + + 0 + 1 + 0 + + + + MainPower Cutoff Reaction Option Code + + 0 + 3 + 2 + + + + QuickStop Reaction Option Code + + 0 + 7 + 2 + + + + Allowed minimum braking resistance + + 1 + 1000 + 40 + + + + Power of built-in braking resistor + + 0 + 65535 + 50 + + + + Resistance of built-in braking resistor + + 0 + 65535 + 50 + + + + Resistor heat dissipation coefficient + + 10 + 100 + 30 + + + + braking resistor type + + 0 + 3 + 3 + + + + Power of external dynamic resistor + + 1 + 65535 + 40 + + + + Resistance of external braking resistor + + 15 + 1000 + 50 + + + + User password + + 0 + 65535 + 0 + + + + Parameter initialization + + 0 + 2 + 0 + + + + Default keypad display + + 0 + 99 + 50 + + + + Panel data refresh rate + + 0 + 20 + 0 + + + + OEM password + + 0 + 65535 + 0 + + + + + ro + + + + #x2003 + Input Terminal Parameters + 端子输入参数 + DT2003 + 1056 + + + SubIndex 000 + + 65 + + + + DI1 function selection + + 0 + 40 + 14 + + + + DI1 logic selection + + 0 + 1 + 0 + + + + DI2 function selection + + 0 + 40 + 15 + + + + DI2 logic selection + + 0 + 1 + 0 + + + + DI3 function selection + + 0 + 40 + 31 + + + + DI3 logic selection + + 0 + 1 + 0 + + + + DI4 function selection + + 0 + 40 + 34 + + + + DI4 logic selection + + 0 + 1 + 0 + + + + DI5 function selection + + 0 + 40 + 38 + + + + DI5 logic selection + + 0 + 1 + 0 + + + + AI1 Offset + + -5000 + 5000 + 0 + + + + AI1 Filter + + 0 + 65535 + 200 + + + + AI1 Dead Zone + + 0 + 10000 + 100 + + + + AI1 Zero Drifting + + -5000 + 5000 + 0 + + + + DI1 filtertime constant + + 0 + 50000 + 300 + + + + DI2 filtertime constant + + 0 + 50000 + 300 + + + + DI3 filtertime constant + + 0 + 50000 + 300 + + + + DI4 filtertime constant + + 0 + 50000 + 300 + + + + DI5 filtertime constant + + 0 + 50000 + 300 + + + + + ro + + + + #x2004 + Output terminal Parameters + 端子输出参数 + DT2004 + 864 + + + SubIndex 000 + + 53 + + + + DO1 Function Selection + + 0 + 65535 + 1 + + + + DO1 Logic Level Selection + + 0 + 1 + 0 + + + + DO2 Function Selection + + 0 + 65535 + 9 + + + + DO2 Logic Level Selection + + 0 + 1 + 0 + + + + DO3 Function Selection + + 0 + 65535 + 9 + + + + DO3 Logic Level Selection + + 0 + 1 + 0 + + + + DO OutPut Source Select + + 0 + 3 + 0 + + + + ECAT Lost Force DO OutPut Logic + + 0 + 3 + 0 + + + + AO1 Source Select + + 0 + 10 + 0 + + + + AO1 Offset + + -10000 + 10000 + 0 + + + + AO1 Multiplying + + -10000 + 10000 + 100 + + + + + ro + + + + #x2005 + Position Control Parameters + 位置控制参数组 + DT2005 + 1152 + + + SubIndex 000 + + 55 + + + + Time constant of first-order low-pass filter + + 0 + 65535 + 0 + + + + Time constant of moving average filter 1 + + 0 + 1280 + 0 + + + + Numerator of electronic gear ratio + + 1 + 1073741824 + 1 + + + + Denominator of electronic gear ratio + + 1 + 1073741824 + 1 + + + + Encoder frequency division pulses + + 0 + 4194303 + 2500 + + + + Speed feedforward control selection + + 0 + 3 + 1 + + + + Local home mode + + 0 + 8 + 0 + + + + Time of home searching + + 0 + 65535 + 10000 + + + + Local home position offset + + -2147483648 + 2147483647 + 0 + + + + Servo pulse output source + + 0 + 3 + 0 + + + + Output polarity of Z pulse + + 0 + 65535 + 1 + + + + Mechanical Gear ratio numerator of absolute encode mode 2 + + 1 + 65535 + 1 + + + + Mechanical Gear ratio denominator of absolute encode mode 2 + + 1 + 65535 + 1 + + + + Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) + + 0 + 4294967295 + 0 + + + + Max value of mechanical absolute position(inc) of absolute encode mode 2(High) + + 0 + 4294967295 + 0 + + + + Trq Reference of Mechanical Homing + + 0 + 4000 + 1000 + + + + Position Coin Hold Time + + 0 + 30000 + 0 + + + + Time Unit of Homing + + 0 + 2 + 2 + + + + Time constant of moving average filter 2 + + 0 + 10000 + 0 + + + + + ro + + + + #x2006 + Speed control + 速度控制 + DT2006 + 896 + + + SubIndex 000 + + 16 + + + + Keypad setting value of speed reference + + -10000 + 10000 + 200 + + + + DI Jog speed reference + + 0 + 10000 + 150 + + + + Acceleration ramp time constant of speed reference + + 0 + 65535 + 0 + + + + Deceleration ramp time constant of speed reference + + 0 + 65535 + 0 + + + + Maximum speed limit + + 0 + 10000 + 7000 + + + + Forward speed threshold + + 0 + 10000 + 7000 + + + + Reverse speed threshold + + 0 + 10000 + 7000 + + + + Quick decelaration coefficient + + 0 + 2 + 0 + + + + Torque feedforward selection + + 0 + 2 + 1 + + + + Acceleration/Deceleration ramp time constant of jog speed reference + + 0 + 65535 + 10 + + + + Speed feedforward filter time constant + + 0 + 65535 + 0 + + + + Speed threshold of Zero Hold signal + + 0 + 10000 + 10 + + + + Speed threshold of motor rotation signal + + 0 + 1000 + 20 + + + + Speed threshold of Spd Reach signal + + 0 + 100 + 10 + + + + Speed threshold of Spd Arrive signal + + 20 + 10000 + 1000 + + + + Speed threshold of Zero Spd signal + + 1 + 10000 + 10 + + + + Spd SCurve Enable + + 0 + 1 + 1 + + + + Spd SCurve Acceleration UP + + 0 + 1000 + 500 + + + + Spd SCurve Acceleration Down + + 0 + 1000 + 500 + + + + Spd SCurve Deceleration UP + + 0 + 1000 + 500 + + + + Spd SCurve Deceleration Down + + 0 + 1000 + 500 + + + + + ro + + + + #x2007 + Torque control + 转矩控制参数 + DT2007 + 640 + + + SubIndex 000 + + 40 + + + + Keypad setting value of torque reference + + -4000 + 4000 + 0 + + + + Torque reference filter time 1 + + 0 + 3000 + 50 + + + + Torque reference filter time 2 + + 0 + 3000 + 27 + + + + Internal forward torque limit + + 0 + 4000 + 3500 + + + + Internal reverse torque limit + + 0 + 4000 + 3500 + + + + Emergency stop torque + + 0 + 4000 + 1000 + + + + Forward speed limit/Speed limit 1 in local torque control + + 0 + 6000 + 3000 + + + + Reverse speed limit/Speed limit 2 in local torque control + + 0 + 6000 + 3000 + + + + Base value for torque reached + + 0 + 4000 + 0 + + + + Threshold of torque reached valid + + 0 + 4000 + 200 + + + + Threshold of torque reached invalid + + 0 + 4000 + 100 + + + + Depth of field-weakening + + 60 + 115 + 115 + + + + Maximum field-weakening current + + 0 + 300 + 100 + + + + Field-weakening enable + + 0 + 1 + 0 + + + + Field-weakening gain + + 1 + 1000 + 30 + + + + Field-weakening point speed + + 0 + 65535 + 0 + + + + Motor output calibration enable + + 0 + 1 + 0 + + + + The second-stage torque reference filter time + + 0 + 1000 + 0 + + + + Torque reference filter type select + + 0 + 1 + 0 + + + + Biquad low pass filter damping + + 0 + 50 + 16 + + + + + ro + + + + #x2008 + Gain Parameters + 增益参数 + DT2008 + 1056 + + + SubIndex 000 + + 65 + + + + Speed-loop Gain + + 1 + 20000 + 400 + + + + Speed-loop integral time constant + + 15 + 51200 + 1989 + + + + Position-loop Gain + + 1 + 20000 + 640 + + + + The second speed loop gain + + 1 + 20000 + 750 + + + + The second speed loop integral time constant + + 15 + 51200 + 1061 + + + + The second position loop gain + + 1 + 20000 + 1200 + + + + Second gain mode setting + + 0 + 1 + 1 + + + + Gain switchover condition + + 0 + 10 + 0 + + + + Gain switchover delay + + 0 + 10000 + 50 + + + + Gain switchover level + + 0 + 20000 + 50 + + + + Gain switchover hysteresis + + 0 + 20000 + 30 + + + + Position gain switchover time + + 0 + 10000 + 30 + + + + Average value of load inertia ratio + + 0 + 12000 + 100 + + + + Zero-Phase delay time + + 0 + 40 + 0 + + + + Speed feedforward filter time constant + + 0 + 6400 + 50 + + + + Speed feedforward gain + + 0 + 1000 + 0 + + + + Torque feedforward filter time constant + + 0 + 6400 + 50 + + + + Torque feedforward gain + + 0 + 3000 + 0 + + + + Speed feedback filter + + 0 + 4 + 0 + + + + Cut-off frequency of speed feedback low-pass filter + + 100 + 8000 + 8000 + + + + Pseudo-differential forward feedback control coefficient + + 0 + 2000 + 1000 + + + + Cut-off frequency of speed observer + + 50 + 600 + 170 + + + + Modified inertia coefficient of speed observer + + 1 + 1600 + 100 + + + + Filter time of speed observer + + 0 + 1000 + 80 + + + + Cut-off frequency of torque disturbance observer + + 10 + 4000 + 600 + + + + Compensation gain of torque disturbance observer + + 0 + 100 + 0 + + + + Modified inertia coefficient of torque disturbance observer + + 1 + 1600 + 100 + + + + Speed observer enable + + 0 + 1 + 0 + + + + Module control enable + + 0 + 2 + 0 + + + + Module control gain + + 1 + 20000 + 400 + + + + Module feedforward value + + 0 + 1024 + 950 + + + + 3rd medium and low-frequency vibration suppression frequency + + 0 + 3000 + 0 + + + + 3rd compensation gain of medium and low-frequency vibration suppression frequency + + 0 + 200 + 0 + + + + 3rd phase modulation of medium and low-frequency vibration suppression frequency + + 0 + 600 + 100 + + + + 4th medium and low-frequency vibration suppression frequency + + 0 + 3000 + 0 + + + + 4th compensation gain of medium and low-frequency vibration suppression frequency + + 0 + 200 + 0 + + + + 4th phase modulation of medium and low-frequency vibration suppression frequency + + 0 + 600 + 100 + + + + Time constant of position loop integration + + 15 + 51200 + 51200 + + + + 2nd time constant of position loop integration + + 15 + 51200 + 51200 + + + + Speed observation feedback source selection + + 0 + 1 + 0 + + + + + ro + + + + #x2009 + Auto-adjusting Parameters + 自整定参数 + DT2009 + 848 + + + SubIndex 000 + + 60 + + + + Auto-adjusting mode + + 0 + 7 + 4 + + + + Rigidity level selection + + 0 + 41 + 15 + + + + Working mode of self-adaptive notch + + 0 + 4 + 0 + + + + Online inertia auto-tuning mode + + 0 + 3 + 0 + + + + Offline inertia auto-tuning mode + + 0 + 1 + 0 + + + + Maximum speed for inertia autotuning + + 100 + 1000 + 500 + + + + Acceleration/Deceleration time for inertia autotuning + + 20 + 800 + 125 + + + + Interval after an inertia autotuning + + 50 + 10000 + 800 + + + + Motor revolutions for an inertia auto-tuning + + 0 + 10000 + 100 + + + + Vibration threshold setting + + 0 + 1000 + 50 + + + + 1st notch frequency + + 50 + 8000 + 8000 + + + + 1st notch width level + + 0 + 20 + 2 + + + + 1st notch attenuation level + + 0 + 99 + 0 + + + + 2nd notch frequency + + 50 + 8000 + 8000 + + + + 2nd notch width level + + 0 + 20 + 2 + + + + 2nd notch attenuation level + + 0 + 99 + 0 + + + + 3rd notch frequency + + 50 + 8000 + 8000 + + + + 3rd notch width level + + 0 + 20 + 2 + + + + 3rd notch attenuation level + + 0 + 99 + 0 + + + + 4th notch frequency + + 50 + 8000 + 8000 + + + + 4th notch width level + + 0 + 20 + 2 + + + + 4th notch attenuation level + + 0 + 99 + 0 + + + + Obtained resonance frequency + + 0 + 5000 + 0 + + + + 1st anti-resonance point frequency + + 0 + 5000 + 0 + + + + 2nd anti-resonance point frequency + + 0 + 5000 + 0 + + + + Gravity compensation value + + 0 + 1000 + 0 + + + + Forward friction compensation + + 0 + 1000 + 0 + + + + Reverse friction compensation + + -1000 + 0 + 0 + + + + Friction compensation speed + + 0 + 200 + 20 + + + + Friction compensation speed selection + + 0 + 19 + 0 + + + + Vibration monitor time + + 0 + 65535 + 300 + + + + 1st terminal low-frequency vibration suppression frequency + + 10 + 1000 + 1000 + + + + 1st filter order of low-frequency vibration suppression frequency + + 0 + 3 + 2 + + + + 5th notch frequency + + 50 + 8000 + 8000 + + + + 5th notch width level + + 0 + 20 + 2 + + + + 5th notch attenuation level + + 0 + 99 + 0 + + + + 2nd terminal low-frequency vibration suppression frequency + + 0 + 2000 + 0 + + + + 2nd damping frequency ratio of low-frequency vibration suppression frequency + + 1 + 1000 + 100 + + + + 2nd damping coefficient of low-frequency vibration suppression frequency + + 0 + 200 + 100 + + + + 3rd terminal low-frequency vibration suppression frequency + + 0 + 2000 + 0 + + + + 3rd damping frequency ratio of low-frequency vibration suppression frequency + + 1 + 1000 + 100 + + + + 3rd damping coefficient of low-frequency vibration suppression frequency + + 0 + 200 + 100 + + + + + ro + + + + #x200A + Error and Protection Parameter + 故障与保护参数 + DT200A + 1536 + + + SubIndex 000 + + 60 + + + + Power inputphase loss protection disable + + 0 + 1 + 0 + + + + Absolute position limit set + + 0 + 2 + 0 + + + + Motor overload protection gain + + 50 + 300 + 100 + + + + Overspeed threshold + + 0 + 20000 + 0 + + + + Local following error window + + 0 + 4294967295 + 27486951 + + + + Runaway protection enable + + 0 + 1 + 1 + + + + Over Temperature value of IPM + + 120 + 175 + 140 + + + + Touch Probe 1 filter time constant + + 0 + 630 + 200 + + + + Touch Probe 2 filter time constant + + 0 + 630 + 200 + + + + STO Display Function Selection + + 0 + 1 + 0 + + + + Filter time constant of TZ signal + + 0 + 31 + 15 + + + + Filter time of speed feedback display + + 0 + 5000 + 50 + + + + Motor overload shielding + + 0 + 1 + 0 + + + + Speed DO Filter time constant + + 0 + 5000 + 50 + + + + Full Closed-loop(ABZ) Filter time constant + + 0 + 255 + 15 + + + + Overheat protection time duration for locked rotor + + 10 + 65535 + 200 + + + + Overheat protection for locked rotor enable + + 0 + 1 + 1 + + + + Absolute Encode multi-turns error forbidden + + 0 + 1 + 0 + + + + Compensation Function + + 0 + 15 + 6 + + + + Over Temperature value of discharge tube + + 100 + 175 + 115 + + + + Encoder communiction error threshold + + 0 + 31 + 5 + + + + Phase lack threshold + + 3 + 36 + 20 + + + + Over Temperature value of Encoder + + 0 + 175 + 125 + + + + TouchProbe DI Turn-on Compensation Time + + -3000 + 3000 + 200 + + + + TouchProbe DI Turn-off Compensation Time + + -3000 + 3000 + 1512 + + + + Runaway current threshold + + 1000 + 4000 + 2000 + + + + Fault reset delay time + + 0 + 60000 + 10000 + + + + Runaway speed threshold + + 1 + 1000 + 50 + + + + Runaway speed filter time constant + + 1 + 1000 + 20 + + + + Runaway protection time window + + 10 + 1000 + 30 + + + + BlackBox Mode Select + + 0 + 3 + 1 + + + + BlackBox Selected Error Code + + 0 + 65535 + 0 + + + + BlackBox Trig Source + + 0 + 25 + 0 + + + + BlackBox Trig Level + + -2147483648 + 2147483647 + 0 + + + + BlackBox Trig Level Select + + 0 + 3 + 0 + + + + BlackBox Trig Position + + 0 + 100 + 75 + + + + BlackBox Trig Frequency Select + + 0 + 2 + 0 + + + + The 2nd over speed threshold + + 0 + 20000 + 0 + + + + Motor over load monitor switch + + 0 + 65535 + 4098 + + + + Maximum ramp stop time + + 0 + 65535 + 10000 + + + + STO Disconnect filter time + + 1 + 5 + 5 + + + + STO Mismatch filter time + + 1 + 1000 + 100 + + + + STO Servo off filter time + + 0 + 25 + 20 + + + + Motor Offline Trq Limit + + 40 + 4000 + 50 + + + + Motor Offline Filter Time + + 5 + 1000 + 30 + + + + Filter Time Constant of Spd Display + + 0 + 100 + 0 + + + + Filter Time Constant of Trq Display + + 0 + 100 + 0 + + + + Filter Time Constant of Position Display + + 0 + 100 + 0 + + + + Filter Time Constant of Voltage Display + + 0 + 250 + 0 + + + + Filter Time Constant of Temp Display + + 0 + 250 + 0 + + + + + ro + + + + #x200B + Display Parameters + 显示参数 + DT200B + 1584 + + + Number of Entries + + 92 + + + + Actual motor rotational speed + + 0 + + + + Speed reference + + 0 + + + + Internal torque reference + + 0 + + + + Monitored DI states + + 0 + + + + Monitored DO states + + 0 + + + + Absolute position counter + + 0 + + + + Mechanical angle + + 0 + + + + Electrical angle + + 0 + + + + Average load rate + + 0 + + + + Encoder position deviation counter + + 0 + + + + Feedback pulse counter + + 0 + + + + Total power-on time + + 0 + + + + AI1 Voltage DisPlay + + 0 + + + + Phase current valid value + + 0 + + + + Bus voltage + + 0 + + + + Module temperature + + 0 + + + + Absolute encoder fault info. from FPGA + + 0 + + + + Axis state from FPGA + + 0 + + + + Axis fault info. from FPGA + + 0 + + + + Encoder internal fault info. + + 0 + + + + Displayed fault record + + 0 + 19 + 0 + + + + Fault code + + 0 + + + + Time stamp upon displayed fault + + 0 + + + + Current rotational speed upon displayed fault + + 0 + + + + Current U upon displayed fault + + 0 + + + + Current V upon displayed fault + + 0 + + + + Bus voltage upon displayed fault + + 0 + + + + Input terminal state upon displayed fault + + 0 + + + + Output terminal state upon displayed fault + + 0 + + + + Inner error code + + 0 + + + + Fault message of absolute encode from Fpga upon displayed + + 0 + + + + System state from Fpga upon displayed fault + + 0 + + + + System fault message from Fpga upon displayed fault + + 0 + + + + Encode state 1 upon displayed fault + + 0 + + + + Inner error code upon displayed fault + + 0 + + + + Fpga overtime state upon displayed fault + + 0 + + + + Reference position deviation + + 0 + + + + Actual motor rotational speed(0.1rpm) + + 0 + + + + Control bus voltage + + 0 + + + + Mechanical absolute position inc(Low) + + 0 + + + + Mechanical absolute position inc(High) + + 0 + + + + Not ready reason + + 0 + + + + Encoder temperature + + 0 + + + + Discharge load rate + + 0 + + + + Fpga over time state + + 0 + + + + Number of turns of absolute encode + + 0 + + + + Single feedback postion of absolute encode + + 0 + + + + System Error + + 0 + + + + feedback postion of absolute encode(Low) + + 0 + + + + feedback postion of absolute encode(High) + + 0 + + + + feedback postion inc of rotating load(Low) + + 0 + + + + feedback postion inc of rotating load(High) + + 0 + + + + Single feedback postion of rotating load + + 0 + + + + IGBT Temperature + + 0 + + + + Group of unusual function code + + 0 + + + + Offset of unusual function code + + 0 + + + + Single Power-On Time + + 0 + + + + Single Power-On Time upon displayed fault + + 0 + + + + + ro + + + + #x200D + Auxiliary Function Parameters + 辅助功能参数 + DT200D + 400 + + + Number of Entries + + 21 + + + + Software reset + + 0 + 1 + 0 + + + + Fault reset + + 0 + 1 + 0 + + + + Offline inertia autotuning selection + + 0 + 1 + 0 + + + + Encoder ROM reading/writing + + 0 + 3 + 0 + + + + Emergency stop + + 0 + 1 + 0 + + + + AI1 Self-Adjust of Voltage Offset + + 0 + 1 + 0 + + + + UV phase current auto-tuning + + 0 + 1 + 0 + + + + Forced DI/DO setting + + 0 + 3 + 0 + + + + Forced DI level + + 0 + 31 + 31 + + + + Forced DO setting + + 0 + 3 + 0 + + + + Absolute Encode Fault Reset + + 0 + 2 + 0 + + + + Cogging torque self-learning + + 0 + 1 + 0 + + + + + ro + + + + #x200E + Communication parameters + 通信参数 + DT200E + 1568 + + + Number of Entries + + 97 + + + + Node address + + 1 + 127 + 1 + + + + Update function code values written via communication to EEPROM + + 0 + 4 + 4 + + + + station auto inc address + + 0 + 65535 + 0 + + + + station alias + + 0 + 65535 + 0 + + + + Sync lost window + + 1 + 20 + 8 + + + + Sync lost counter + + 0 + 65535 + 0 + + + + Port 0 invalid frame counter + + 0 + 65535 + 0 + + + + Port 1 invalid frame counter + + 0 + 65535 + 0 + + + + Port 0/1 transfer error counter + + 0 + 65535 + 0 + + + + process unit and PDI error counter + + 0 + 255 + 0 + + + + Port 0/1 lost counter + + 0 + 65535 + 0 + + + + Sync mode set + + 0 + 2 + 2 + + + + Sync error window + + 100 + 4000 + 4000 + + + + EtherCAT network state and link state + + 0 + 65535 + 0 + + + + CSP postion increment over counter + + 1 + 30 + 20 + + + + ECAT AL Error Code + + 0 + 65535 + 0 + + + + Enhanced link detection enable + + 0 + 1 + 0 + + + + Reset EtherCAT xml file + + 0 + 1 + 0 + + + + EtherCAT port control mode and state display + + 0 + 65535 + 0 + + + + EtherCAT COE version number + + 0 + 65535 + 0 + + + + EtherCAT xml file version number + + 0 + 65535 + 0 + + + + + ro + + + + #x200F + Closed Loop Function + 全闭环功能 + DT200F + 720 + + + SubIndex 000 + + 26 + + + + Encoder feedback mode + + 0 + 2 + 0 + + + + Running mode of external encoder + + 0 + 1 + 0 + + + + SecEncoder Absolute system selection + + 0 + 1 + 0 + + + + SecEncoder Type selection + + 0 + 2 + 0 + + + + External encoder pulses per motor revolution + + 0 + 2147483647 + 100000 + + + + Hybrid deviation excess setting + + 0 + 2147483647 + 10000 + + + + Hybrid deviation clear setting + + 0 + 100 + 1 + + + + First-order lowpass filter time of external/internal deviation + + 0 + 65535 + 0 + + + + Hybrid deviation counter + + -2147483648 + 2147483647 + 0 + + + + Pulse feedback display of internal encoder + + -2147483648 + 2147483647 + 0 + + + + Pulse feedback display of external encoder + + -2147483648 + 2147483647 + 0 + + + + SecEncoder Pulse ZPhase Ignore + + 0 + 1 + 0 + + + + SecEncoder Pulse Z-TouchProbe Selection + + 0 + 1 + 0 + + + + + ro + + + + #x2012 + MultiSpd Function + 多段速功能 + DT2012 + 1104 + + + SubIndex 000 + + 59 + + + + MultiSpd Function Select + + 0 + 2 + 1 + + + + MultiSpd Final Part Select + + 1 + 16 + 16 + + + + Time Uint of Runing + + 0 + 1 + 0 + + + + AccTime1 + + 0 + 65535 + 10 + + + + DecTime1 + + 0 + 65535 + 10 + + + + AccTime2 + + 0 + 65535 + 50 + + + + DecTime2 + + 0 + 65535 + 50 + + + + AccTime3 + + 0 + 65535 + 100 + + + + DecTime3 + + 0 + 65535 + 100 + + + + AccTime4 + + 0 + 65535 + 150 + + + + DecTime4 + + 0 + 65535 + 150 + + + + 1st Part Spd Cmd + + -10000 + 10000 + 0 + + + + 1st Part Spd Runing Time + + 0 + 65535 + 50 + + + + 1st Part AccDec Time Select + + 0 + 4 + 0 + + + + 2nd Part Spd Cmd + + -10000 + 10000 + 100 + + + + 2nd Part Spd Runing Time + + 0 + 65535 + 50 + + + + 2nd Part AccDec Time Select + + 0 + 4 + 0 + + + + 3rd Part Spd Cmd + + -10000 + 10000 + 300 + + + + 3rd Part Spd Runing Time + + 0 + 65535 + 50 + + + + 3rd Part AccDec Time Select + + 0 + 4 + 0 + + + + 4th Part Spd Cmd + + -10000 + 10000 + 500 + + + + 4th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 4th Part AccDec Time Select + + 0 + 4 + 0 + + + + 5th Part Spd Cmd + + -10000 + 10000 + 700 + + + + 5th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 5th Part AccDec Time Select + + 0 + 4 + 0 + + + + 6th Part Spd Cmd + + -10000 + 10000 + 900 + + + + 6th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 6th Part AccDec Time Select + + 0 + 4 + 0 + + + + 7th Part Spd Cmd + + -10000 + 10000 + 600 + + + + 7th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 7th Part AccDec Time Select + + 0 + 4 + 0 + + + + 8th Part Spd Cmd + + -10000 + 10000 + 300 + + + + 8th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 8th Part AccDec Time Select + + 0 + 4 + 0 + + + + 9th Part Spd Cmd + + -10000 + 10000 + 100 + + + + 9th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 9th Part AccDec Time Select + + 0 + 4 + 0 + + + + 10th Part Spd Cmd + + -10000 + 10000 + -100 + + + + 10th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 10th Part AccDec Time Select + + 0 + 4 + 0 + + + + 11th Part Spd Cmd + + -10000 + 10000 + -300 + + + + 11th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 11th Part AccDec Time Select + + 0 + 4 + 0 + + + + 12th Part Spd Cmd + + -10000 + 10000 + -500 + + + + 12th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 12th Part AccDec Time Select + + 0 + 4 + 0 + + + + 13th Part Spd Cmd + + -10000 + 10000 + -700 + + + + 13th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 13th Part AccDec Time Select + + 0 + 4 + 0 + + + + 14th Part Spd Cmd + + -10000 + 10000 + -900 + + + + 14th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 14th Part AccDec Time Select + + 0 + 4 + 0 + + + + 15th Part Spd Cmd + + -10000 + 10000 + -600 + + + + 15th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 15th Part AccDec Time Select + + 0 + 4 + 0 + + + + 16th Part Spd Cmd + + -10000 + 10000 + -300 + + + + 16th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 16th Part AccDec Time Select + + 0 + 4 + 0 + + + + + ro + + + + #x2017 + VDI VDO + 虚拟DI、DO + DT2017 + 1520 + + + SubIndex 000 + + 68 + + + + VDI1 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI1 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI2 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI2 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI3 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI3 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI4 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI4 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI5 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI5 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI6 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI6 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI7 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI7 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI8 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI8 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI9 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI9 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI10 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI10 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI11 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI11 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI12 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI12 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI13 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI13 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI14 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI14 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI15 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI15 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI16 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI16 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDO virtual level + + 0 + 65535 + 0 + + + + VDO1 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO1 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO2 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO2 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO3 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO3 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO4 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO4 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO5 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO5 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO6 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO6 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO7 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO7 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO8 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO8 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO9 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO9 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO10 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO10 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO11 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO11 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO12 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO12 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO13 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO13 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO14 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO14 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO15 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO15 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO16 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO16 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDI Enable + + 0 + 1 + 0 + + + + VDI Default Value + + 0 + 65535 + 0 + + + + VDO Enable + + 0 + 1 + 0 + + + + VDO Default Value + + 0 + 65535 + 0 + + + + + ro + + + + #x2018 + Position Comparison + 位置比较参数 + DT2018 + 288 + + + SubIndex 000 + + 17 + + + + Enable Comparison + + 0 + + + + Comparison PosFdb Source Select + + 0 + 1 + 0 + + + + Encoder Resolution + + 0 + 7 + 1 + + + + Mode Of Comparison + + 0 + 2 + 0 + + + + Current Position As Zero + + 0 + 1 + 0 + + + + Output Duration + + 1 + 2047 + 1 + + + + Comparison ABZ OutPut Logic + + 0 + 65535 + 0 + + + + Starting Point Number + + 0 + 40 + 0 + + + + Ending Point Number + + 0 + 40 + 0 + + + + Comparison Status + + 0 + 1024 + 0 + + + + Current Position + + -2147483648 + 2147483647 + 0 + + + + Position Offset + + -2147483648 + 2147483647 + 0 + + + + Comparison OutPut Delay Compensation + + -1200 + 1200 + 0 + + + + Lilited number of Comparison Cycle Times + + 1 + 65535 + 1 + + + + Comparison ABZ OutPut Function + + 0 + 65535 + 0 + + + + + ro + + + + #x2019 + Comparing Points + 位置比较点 + DT2019 + 1936 + + + SubIndex 000 + + 120 + + + + 1st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 1st Point Property + + 0 + + + + 2nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 2nd Point Property + + 0 + + + + 3rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 3rd Point Property + + 0 + + + + 4th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 4th Point Property + + 0 + + + + 5th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 5th Point Property + + 0 + + + + 6th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 6th Point Property + + 0 + + + + 7th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 7th Point Property + + 0 + + + + 8th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 8th Point Property + + 0 + + + + 9th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 9th Point Property + + 0 + + + + 10th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 10th Point Property + + 0 + + + + 11th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 11th Point Property + + 0 + + + + 12th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 12th Point Property + + 0 + + + + 13th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 13th Point Property + + 0 + + + + 14th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 14th Point Property + + 0 + + + + 15th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 15th Point Property + + 0 + + + + 16th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 16th Point Property + + 0 + + + + 17th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 17th Point Property + + 0 + + + + 18th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 18th Point Property + + 0 + + + + 19th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 19th Point Property + + 0 + + + + 20th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 20th Point Property + + 0 + + + + 21st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 21st Point Property + + 0 + + + + 22nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 22nd Point Property + + 0 + + + + 23rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 23rd Point Property + + 0 + + + + 24th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 24th Point Property + + 0 + + + + 25th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 25th Point Property + + 0 + + + + 26th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 26th Point Property + + 0 + + + + 27th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 27th Point Property + + 0 + + + + 28th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 28th Point Property + + 0 + + + + 29th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 29th Point Property + + 0 + + + + 30th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 30th Point Property + + 0 + + + + 31st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 31st Point Property + + 0 + + + + 32nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 32nd Point Property + + 0 + + + + 33rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 33rd Point Property + + 0 + + + + 34th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 34th Point Property + + 0 + + + + 35th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 35th Point Property + + 0 + + + + 36th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 36th Point Property + + 0 + + + + 37th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 37th Point Property + + 0 + + + + 38th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 38th Point Property + + 0 + + + + 39th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 39th Point Property + + 0 + + + + 40th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 40th Point Property + + 0 + + + + + ro + + + + #x2030 + Comm Read Servo Variable + 通讯读取相关变量 + DT2030 + 64 + + + SubIndex 000 + + 3 + + + + Servo Status + + 0 + 65535 + 0 + + + + DO Function1 + + 0 + 65535 + 0 + + + + DO Function2 + + 0 + 65535 + 0 + + + + + ro + + + + #x2031 + Comm Set Servo Variable + 通讯给定相关变量 + DT2031 + 224 + + + SubIndex 000 + + 5 + + + + Comm Set VDI + + 0 + 65535 + 0 + + + + Comm Set DO + + 0 + 65535 + 0 + + + + Comm Set AO + + -10000 + 10000 + 0 + + + + Comm Set Local SpdRef + + -9000000 + 9000000 + 0 + + + + Comm Set Local TrqRef + + -100000 + 100000 + 0 + + + + + ro + + + + #x203F + Manufacturor Error code + 伺服故障码 + UDINT + 32 + + #x00000000 + #xFFFFFFFF + #x00000000 + + + ro + T + + + + #x603F + Error code + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + ro + T + + + + #x6040 + Control word + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + rw + R + + + + #x6041 + Status word + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + ro + T + + + + #x605A + Quick stop option code + INT + 16 + + #x0000 + #x0007 + #x0002 + + + rw + + + + #x605C + Disable operation option code + INT + 16 + + #xFFFC + #x0002 + #x0000 + + + rw + + + + #x605D + Halt option Code + INT + 16 + + #x0001 + #x0003 + #x0001 + + + rw + + + + #x605E + Fault Reaction option Code + INT + 16 + + #xFFFB + #x0004 + #x0002 + + + rw + + + + #x6060 + Modes of operation + SINT + 8 + + 0 + 10 + 0 + + + rw + R + + + + #x6061 + Modes of operation display + SINT + 8 + + 0 + 10 + 0 + + + ro + T + + + + #x6062 + Position demand value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6063 + Position actual internal value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6064 + Position actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6065 + Following error window + UDINT + 32 + + #x0 + #xFFFFFFFF + #x1A36AE7 + + + rw + R + + + + #x6066 + Following error time out + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x6067 + Position window + UDINT + 32 + + #x0 + #xFFFFFFFF + #x16F0 + + + rw + R + + + + #x6068 + Position window time + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x606C + Velocity actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + 0 + + + ro + T + + + + #x606D + Velocity window + UINT + 16 + + #x0000 + #xFFFF + #xA + + + rw + R + + + + #x606E + Velocity window time + UINT + 16 + + #x0000 + #xFFFF + #x0 + + + rw + + + + #x606F + Velocity threshold + UINT + 16 + + #x0000 + #xFFFF + #xA + + + rw + R + + + + #x6070 + Velocity threshold time + UINT + 16 + + #x0000 + #xFFFF + #x0 + + + rw + + + + #x6071 + Target torque + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + rw + R + + + + #x6072 + Max Torque + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x6074 + Torque demand + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + ro + T + + + + #x6077 + Torque actual value + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + ro + T + + + + #x607A + Target position + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x607C + Home offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x607D + Software position limit + DT607D + 80 + + + SubIndex 000 + + #x02 + + + + Min position limit + + #x80000000 + #x7FFFFFFF + #x80000000 + + + + Max position limit + + #x80000000 + #x7FFFFFFF + #x7FFFFFFF + + + + + ro + + + + #x607E + Polarity + USINT + 8 + + #x0 + #xFF + #x0 + + + rw + R + + + + #x607F + Max profile velocity + UDINT + 32 + + #x0 + #xFFFFFFFF + #x32000000 + + + rw + R + + + + #x6081 + Profile velocity + UDINT + 32 + + #x0 + #xFFFFFFFF + #xD55555 + + + rw + R + + + + #x6083 + Profile acceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x6084 + Profile deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x6085 + Quick stop deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x7FFFFFFF + + + rw + R + + + + #x6086 + Motion profile type + INT + 16 + + #x8000 + #x7FFF + #x0 + + + rw + R + + + + #x6087 + Torque slope + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x6091 + Gear ratio + DT6091 + 80 + + + SubIndex 000 + + #x02 + + + + Motor revolutions + + #x1 + #xFFFFFFFF + #x1 + + + + Shaft revolutions + + #x1 + #xFFFFFFFF + #x1 + + + + + ro + + + + #x6098 + Homing method + SINT + 8 + + #xFD + #x23 + 1 + + + rw + R + + + + #x6099 + Homing speeds + DT6099 + 80 + + + SubIndex 000 + + #x02 + + + + Speed during search for switch + + 0 + #xFFFFFFFF + #xD55555 + + + + Speed during search for zero + + 0 + #xFFFFFFFF + #x155555 + + + + + ro + + + + #x609A + Homing acceleration + UDINT + 32 + + 0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x60B0 + Position offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x60B1 + Velocity offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x60B2 + Torque offset + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + rw + R + + + + #x60B8 + Touch probe function + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x60B9 + Touch Probe Status + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60BA + Touch probe 1 positive edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BB + Touch probe 1 negative edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BC + Touch probe 2 positive edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BD + Touch probe 2 negative edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60C5 + Max Acceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x60C6 + Max Deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x60D5 + Touch probe 1 positive edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D6 + Touch probe 1 negative edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D7 + Touch probe 2 positive edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D8 + Touch probe 2 negative edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60E0 + Positive torque limit value + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x60E1 + Negative torque limit value + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x60E3 + Supported homing methods + DT60E3 + 544 + + + SubIndex 000 + + #x0 + #x22 + 33 + + + + Support homing method 1 + + #x01 + + + + Support homing method 2 + + #x02 + + + + Support homing method 3 + + #x03 + + + + Support homing method 4 + + #x04 + + + + Support homing method 5 + + #x05 + + + + Support homing method 6 + + #x06 + + + + Support homing method 7 + + #x07 + + + + Support homing method 8 + + #x08 + + + + Support homing method 9 + + #x09 + + + + Support homing method 10 + + #x0A + + + + Support homing method 11 + + #x0B + + + + Support homing method 12 + + #x0C + + + + Support homing method 13 + + #x0D + + + + Support homing method 14 + + #x0E + + + + Support homing method 15 + + #x11 + + + + Support homing method 16 + + #x12 + + + + Support homing method 17 + + #x13 + + + + Support homing method 18 + + #x14 + + + + Support homing method 19 + + #x15 + + + + Support homing method 20 + + #x16 + + + + Support homing method 21 + + #x17 + + + + Support homing method 22 + + #x18 + + + + Support homing method 23 + + #x19 + + + + Support homing method 24 + + #x1A + + + + Support homing method 25 + + #x1B + + + + Support homing method 26 + + #x1C + + + + Support homing method 27 + + #x1D + + + + Support homing method 28 + + #x1E + + + + Support homing method 29 + + #x21 + + + + Support homing method 30 + + #x22 + + + + Support homing method 31 + + #x23 + + + + Support homing method 32 + + #xFF + + + + Support homing method 33 + + #xFE + + + + + ro + + + + #x60F4 + Following error actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60FC + Position demand internal value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60FD + Digital inputs + UDINT + 32 + + #x0 + #xFFFFFFFF + #x0 + + + ro + T + + + + #x60FE + Digital outputs + DT60FE + 80 + + + SubIndex 000 + + #x02 + + + + Physical outputs + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + Bit Mask + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + ro + + + + #x60FF + Target velocity + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x6502 + Supported drive modes + UDINT + 32 + + #x00000000 + #xFFFFFFFF + #x000003AD + + + ro + + + + + + Outputs + Inputs + MBoxState + MBoxOut + MBoxIn + Outputs + Inputs + + #x1600 + Outputs + #x1601 + #x1701 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + + #x1601 + Outputs + #x1600 + #x1701 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x607A + 0 + 32 + Target position + DINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + #x6081 + 0 + 32 + profile velocity + UDINT + + + #x6083 + 0 + 32 + profile acceleration + UDINT + + + #x6084 + 0 + 32 + profile deceleration + UDINT + + + #x6087 + 0 + 32 + Torque Slope + UDINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + + #x1701 + Outputs + #x1600 + #x1601 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60FE + 1 + 32 + Physical outputs + UDINT + + + + #x1702 + Outputs + #x1600 + #x1601 + #x1701 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + + #x1703 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + + #x1704 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1703 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + + #x1705 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1703 + #x1704 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + #x60B2 + 0 + 16 + Torque offset + INT + + + + #x1A00 + Inputs + #x1A01 + #x1B01 + #x1B02 + #x1B03 + #x1B04 + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x603F + 0 + 16 + Error code + UINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1A01 + Inputs + #x1A00 + #x1B01 + #x1B02 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x606C + 0 + 32 + Velocity actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B01 + Inputs + #x1A00 + #x1A01 + #x1B02 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B02 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B03 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B02 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B04 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B02 + #x1B03 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x606C + 0 + 32 + Velocity actual value + DINT + + + + + + + PS + #x6060 + 0 + 08 + Modes of operation + + + + + + DC + DC-Sync + #x300 + 0 + 0 + 0 + + + Synchron + FreeRun + #x0 + + + + 2048 + 080C0004640000000000 + + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + diff --git a/hw_device_mgr/devices/inovance_sv670.py b/hw_device_mgr/devices/inovance_sv670.py index 0b07c5c4..bf8109f0 100644 --- a/hw_device_mgr/devices/inovance_sv670.py +++ b/hw_device_mgr/devices/inovance_sv670.py @@ -61,7 +61,7 @@ class InovanceSV670(EtherCATDevice, CiA402Device, ErrorDevice): xml_description_package = "hw_device_mgr.devices.device_xml" xml_description_fname = "SV670_EOE_1Axis_05003_220801.xml" device_error_package = "hw_device_mgr.devices.device_err" - device_error_yaml = "inovance_sv670n.yaml" + device_error_yaml = "inovance_sv660n.yaml" config_class = InovanceSV670Config have_sto = True From 58d95ef7f0f1c3619dab492deeef451e8b60f510 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 12 Nov 2024 15:45:27 -0600 Subject: [PATCH 066/121] cia_301, cia_402: Log more information about state changes In cia_301, log when device comes online and again when operational. All other changes are in cia_402: Log when STO goes active, and log status word changes, even when not yet operational. The latter allows more 402-level state calculations than before, but stops before looking at higher-level functions like HM or PP, and stops before logging faults. When fault is active, be clear why goal is reached but errors apparently exist, with "Goal reached: Fault state reached; [...]" log message. In `set_command()`, log 402 state command changes. --- hw_device_mgr/cia_301/device.py | 6 ++ hw_device_mgr/cia_402/device.py | 76 +++++++++++-------- .../cia_402/tests/hm_timeout.cases.yaml | 1 + .../cia_402/tests/pp_timeout.cases.yaml | 1 + .../tests/read_update_write.cases.yaml | 29 +++---- .../mgr/tests/read_update_write.cases.yaml | 28 +++---- 6 files changed, 81 insertions(+), 60 deletions(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 9ef77644..93a5bc74 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -109,6 +109,9 @@ def get_feedback(self): # Stop param init return fb_out # Nothing more to do + if self.feedback_in.changed("online"): + self.logger.info("Drive came online") + # Device online; update CiA301 feedback goal_reached, goal_reasons = True, list() @@ -155,6 +158,9 @@ def get_feedback(self): fb_out.update( fault=True, fault_desc=fb_out.get_old("fault_desc") ) + else: # operational + if self.feedback_in.changed("oper"): + self.logger.info("Drive came online/operational") # Update feedback and return goal_reason = "Reached" if goal_reached else ", ".join(goal_reasons) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index b80a1ffa..174c7302 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -203,6 +203,12 @@ def get_feedback_sto(self): if self.feedback_in.changed("sto"): # Log once self.logger.info("STO input inactive") return True, None + else: + if self.feedback_in.changed("sto"): # Log once + self.logger.info("STO input active") + + if not self.feedback_in.get("oper"): + return True, None # STO active (high) state_cmd = self.command_in.get("state") @@ -235,11 +241,6 @@ def get_feedback(self): fb_out = super().get_feedback() fb_in = self.feedback_in - # Set default "START" state in these cases: - if not fb_out.get("oper"): - # Device not yet operational - return fb_out - # Don't clobber lower layer's feedback, but continue managing CiA 402 # states even while param init continues goal_reached = fb_out.get("goal_reached") @@ -258,6 +259,15 @@ def get_feedback(self): cm_cmd_str = self.control_mode_str(cm_cmd) goal_reasons.append(f"control_mode {cm_str} != {cm_cmd_str}") + # Log status word changes + if self.log_status_word_changes and fb_out.changed("status_word"): + self.logger.info(f"status_word: {self.sw_to_str(sw)}") + + # If device not yet operational, don't do any more, incl. log faults, + # etc. + if not fb_out.get("oper"): + return fb_out + # Calculate 'state' feedback for state, bits in self.state_bits.items(): # Compare masked status word with pattern to determine current state @@ -282,13 +292,12 @@ def get_feedback(self): ) and not self.test_sw_bit(sw, "VOLTAGE_ENABLED"): fault = True fault_desc = "Enable command while no voltage at motor" - goal_reasons.append(fault_desc) # Handle `FOLLOWING_ERROR` active ferror = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_2") fb_out.update(following_error=ferror) - # Raise fault if device unexpectedly goes offline + # Raise fault if device unexpectedly disabled if self.command_in.get( "state" ) == "OPERATION ENABLED" and not self.test_sw_bit( @@ -296,7 +305,6 @@ def get_feedback(self): ): fault = True fault_desc = "Enabled drive unexpectedly disabled" - goal_reasons.append(fault_desc) # Calculate 'transition' feedback new_st, old_st = fb_out.changed("state", return_vals=True) @@ -311,20 +319,6 @@ def get_feedback(self): else: fb_out.update(transition=-1) - # Mode-specific functions - if cm == self.MODE_HM: - # Calculate homing status - hm_success, hm_reason = self.get_feedback_hm(sw) - if not hm_success: - goal_reached = False - goal_reasons.append(hm_reason) - elif cm == self.MODE_PP: - # Calculate move status - pp_success, pp_reason = self.get_feedback_pp(sw) - if not pp_success: - goal_reached = False - goal_reasons.append(pp_reason) - # Handle STO if self.have_sto: sto_success, sto_reason = self.get_feedback_sto() @@ -335,13 +329,28 @@ def get_feedback(self): # Fault reported by drive if self.test_sw_bit(sw, "FAULT"): fault = True + fault_desc = "Drive status word FAULT bit set" if fb_out.get("error_code"): error_code = fb_out.get("error_code") - error_desc = fb_out.get("description") - fault_desc = f"{error_code} {error_desc}" + fault_desc += f", code {error_code}" + if (error_desc := fb_out.get("description")): + fault_desc += f" '{error_desc}'" else: - fault_desc = "Fault (no error code)" - goal_reasons.append(fault_desc) + fault_desc += " (no error code)" + + # Mode-specific functions + if cm == self.MODE_HM: + # Calculate homing status + hm_success, hm_reason = self.get_feedback_hm(sw) + if not hm_success: + goal_reached = False + goal_reasons.append(hm_reason) + elif cm == self.MODE_PP: + # Calculate move status + pp_success, pp_reason = self.get_feedback_pp(sw) + if not pp_success: + goal_reached = False + goal_reasons.append(pp_reason) # If in CiA402 FAULT state, set device fault if self.command_in.get("state") == "FAULT": @@ -352,18 +361,18 @@ def get_feedback(self): # If FAULT is commanded & no device fault, this will be an empty # string if not fault_desc: - fault_desc = f"FAULT command from controller (was {old_st})" - goal_reasons.append(fault_desc) + fault_desc = "FAULT command from controller" + fault_desc += f" (from state {old_st})" # Update feedback to controller if fault: fb_out.update(fault=True, fault_desc=fault_desc) - if self.log_status_word_changes and fb_out.changed("status_word"): - self.logger.info(f"status_word: {self.sw_to_str(sw)}") - if not goal_reached: - goal_reached = fault # If fault active, nothing to do, goal reached + if fault: + # If fault active, nothing to do, goal reached + goal_reasons.insert(0, "Fault state reached") + goal_reached = True goal_reason = "; ".join(goal_reasons) fb_out.update(goal_reached=goal_reached, goal_reason=goal_reason) return fb_out @@ -502,6 +511,9 @@ def sw_to_str(cls, sw): def set_command(self, **kwargs): cmd_out = super().set_command(**kwargs) + if self.command_in.changed("state"): + state_cmd = self.command_in.get("state") + self.logger.info(f"CiA 402 state command: {state_cmd}") if not self.feedback_out.get("oper"): return cmd_out self._get_next_control_mode(cmd_out) diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index 5d4cac7c..2f76935a 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -91,6 +91,7 @@ # Timeout treated as fault fault: True fault_desc: "Timeout (15s): homing not complete" + goal_reason: Fault state reached; homing not complete goal_reached: True command_in: state: FAULT diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index 89e45c81..22c0322f 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -109,6 +109,7 @@ # Timeout treated as fault fault: True fault_desc: "Timeout (15s): move not complete" + goal_reason: Fault state reached; move not complete goal_reached: True command_in: state: FAULT diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index 2ec8c163..9861d16f 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -189,8 +189,8 @@ state: FAULT REACTION ACTIVE transition: 13 # (Any)->FAULT REACTION ACTIVE fault: True - fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF - goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; 0xDEADBEEF Unknown error code 0xDEADBEEF + fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' + goal_reason: Fault state reached; state FAULT REACTION ACTIVE != OPERATION ENABLED error_code: 0xDEADBEEF # Bogus error code description: Unknown error code 0xDEADBEEF command_out: @@ -206,7 +206,7 @@ status_word: 0x0018 # FAULT + VOLTAGE_ENABLED state: FAULT transition: 14 # FAULT REACTION ACTIVE->FAULT - goal_reason: state FAULT != OPERATION ENABLED; Enabled drive unexpectedly disabled; 0xDEADBEEF Unknown error code 0xDEADBEEF + goal_reason: Fault state reached; state FAULT != OPERATION ENABLED command_out: # Goal is still OPERATION ENABLED, so automatically clear fault control_word: 0x0080 # Clear fault @@ -221,7 +221,7 @@ state: SWITCH ON DISABLED transition: 15 # FAULT->SWITCH ON DISABLED fault_desc: Enabled drive unexpectedly disabled - goal_reason: state SWITCH ON DISABLED != OPERATION ENABLED; Enabled drive unexpectedly disabled + goal_reason: Fault state reached; state SWITCH ON DISABLED != OPERATION ENABLED error_code: 0x00000000 # Cleared by control_word 0x0080 description: No error command_out: @@ -260,9 +260,9 @@ state: FAULT REACTION ACTIVE transition: 13 # (Any)->FAULT REACTION ACTIVE fault: True - fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF + fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' goal_reached: True - goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; 0xDEADBEEF Unknown error code 0xDEADBEEF + goal_reason: Fault state reached; state FAULT REACTION ACTIVE != OPERATION ENABLED error_code: 0xDEADBEEF description: Unknown error code 0xDEADBEEF command_out: @@ -278,7 +278,7 @@ status_word: 0x0018 # FAULT + VOLTAGE_ENABLED state: FAULT transition: 14 # FAULT REACTION ACTIVE->FAULT - goal_reason: state FAULT != OPERATION ENABLED; Enabled drive unexpectedly disabled; 0xDEADBEEF Unknown error code 0xDEADBEEF + goal_reason: Fault state reached; state FAULT != OPERATION ENABLED command_in: # Controller sees FAULT state and commands hold at that state state: FAULT @@ -288,6 +288,7 @@ feedback_out: transition: -1 goal_reason: Reached + fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' - desc: "Hold fault: Hold state x2" sim_feedback_set: error_code: 0xDEADBEEF # Bogus error code @@ -337,7 +338,7 @@ - desc: "Ext fault noop: Hold state x1" feedback_out: fault: True - fault_desc: FAULT command from controller (was SWITCH ON DISABLED) + fault_desc: FAULT command from controller (from state SWITCH ON DISABLED) - desc: "Ext fault noop: Hold state x2" # @@ -430,7 +431,7 @@ state: QUICK STOP ACTIVE transition: 11 fault: True - fault_desc: FAULT command from controller (was OPERATION ENABLED) + fault_desc: FAULT command from controller (from state OPERATION ENABLED) sim_feedback: status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - desc: "Disable enabled: Command disable; 402 state machine transition 12" @@ -473,7 +474,7 @@ # With no voltage, drive refuses to leave SWITCH ON DISABLED # state: SWITCH ON DISABLED transition: -1 - goal_reason: state SWITCH ON DISABLED != SWITCHED ON; Enable command while no voltage at motor + goal_reason: Fault state reached; state SWITCH ON DISABLED != SWITCHED ON # fault: True # (Already was True) fault_desc: Enable command while no voltage at motor # command_out: @@ -795,9 +796,9 @@ state: FAULT REACTION ACTIVE transition: 13 # (Any)->FAULT REACTION ACTIVE goal_reached: True - goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; Move request while drive not enabled; Fault (no error code) + goal_reason: Fault state reached; state FAULT REACTION ACTIVE != OPERATION ENABLED; Move request while drive not enabled fault: True - fault_desc: Fault (no error code) + fault_desc: Drive status word FAULT bit set (no error code) command_out: control_word: 0x0000 sim_feedback: @@ -811,7 +812,7 @@ status_word: 0x0018 # FAULT + VOLTAGE_ENABLED state: FAULT transition: 14 # FAULT REACTION ACTIVE->FAULT - goal_reason: state FAULT != OPERATION ENABLED; Enabled drive unexpectedly disabled; Move request while drive not enabled; Fault (no error code) + goal_reason: Fault state reached; state FAULT != OPERATION ENABLED; Move request while drive not enabled command_out: control_word: 0x0080 # Clear fault sim_feedback: @@ -825,7 +826,7 @@ status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - SETPOINT_ACK state: SWITCH ON DISABLED transition: 15 # FAULT->SWITCH ON DISABLED - goal_reason: state SWITCH ON DISABLED != OPERATION ENABLED; Enabled drive unexpectedly disabled; Move request while drive not enabled + goal_reason: Fault state reached; state SWITCH ON DISABLED != OPERATION ENABLED; Move request while drive not enabled # fault: True # Already True fault_desc: Enabled drive unexpectedly disabled command_in: diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index fac448c9..ca8a1a51 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -271,15 +271,15 @@ feedback_out: enabled: False fault: True - fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[1]}) + fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' ({drives[1]}) d.1.status_word: 0x001F # FAULT REACTION ACTIVE + VOLTAGE_ENABLED d.1.state: FAULT REACTION ACTIVE d.1.transition: 13 d.1.fault: True - d.1.fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF + d.1.fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' d.1.error_code: 0xDEADBEEF d.1.description: Unknown error code 0xDEADBEEF - d.1.goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; 0xDEADBEEF Unknown error code 0xDEADBEEF + d.1.goal_reason: Fault state reached; state FAULT REACTION ACTIVE != OPERATION ENABLED command_in: state_cmd: 4 # fault command_out: @@ -301,16 +301,16 @@ feedback_out: goal_reached: False goal_reason: Waiting on device manager internal transitions - fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[1]}) + fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' ({drives[1]}) # drive_1 holds state - d.1.fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF + d.1.fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED d.1.state: FAULT d.1.transition: 14 d.1.goal_reason: Reached # ...while other drives enter QUICK STOP ACTIVE d.x.fault: True - d.x.fault_desc: FAULT command from controller (was OPERATION ENABLED) + d.x.fault_desc: FAULT command from controller (from state OPERATION ENABLED) d.x.status_word: 0x0017 # QUICK STOP + VOLTAGE_ENABLED d.x.state: QUICK STOP ACTIVE d.x.transition: 11 @@ -439,16 +439,16 @@ d.1.status_word: 0x0033 # SWITCHED ON + VOLTAGE_ENABLED feedback_out: fault: True - fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[2]}) + fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' ({drives[2]}) goal_reason: Waiting on device manager internal transitions d.2.status_word: 0x001F # FAULT REACTION ACTIVE + VOLTAGE_ENABLED d.2.state: FAULT REACTION ACTIVE d.2.transition: 13 d.2.fault: True - d.2.fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF + d.2.fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' d.2.error_code: 0xDEADBEEF d.2.description: Unknown error code 0xDEADBEEF - d.2.goal_reason: state FAULT REACTION ACTIVE != SWITCHED ON; 0xDEADBEEF Unknown error code 0xDEADBEEF + d.2.goal_reason: Fault state reached; state FAULT REACTION ACTIVE != SWITCHED ON d.1.status_word: 0x0033 # SWITCHED ON + VOLTAGE_ENABLED d.1.state: SWITCHED ON d.1.transition: 3 @@ -473,13 +473,13 @@ d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED feedback_out: goal_reason: Waiting on device manager internal transitions - fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[2]}) + fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' ({drives[2]}) d.x.fault: True - d.x.fault_desc: FAULT command from controller (was SWITCHED ON) + d.x.fault_desc: FAULT command from controller (from state SWITCHED ON) d.x.status_word: 0x0050 d.x.state: SWITCH ON DISABLED d.x.transition: 10 - d.2.fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF + d.2.fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' d.2.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED d.2.state: FAULT d.2.transition: 14 @@ -803,7 +803,7 @@ d.x.goal_reached: False d.2.goal_reached: True d.x.goal_reason: state READY TO SWITCH ON != SWITCHED ON - d.2.goal_reason: state SWITCH ON DISABLED != SWITCHED ON; Enable command while no voltage at motor + d.2.goal_reason: Fault state reached; state SWITCH ON DISABLED != SWITCHED ON command_in: state_set: 0 # clear command latch command_out: @@ -827,7 +827,7 @@ d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED d.2.status_word: 0x0040 # SWITCH ON DISABLED - VOLTAGE_ENABLED d.x.fault: True - d.x.fault_desc: FAULT command from controller (was READY TO SWITCH ON) + d.x.fault_desc: FAULT command from controller (from state READY TO SWITCH ON) d.2.fault_desc: Enable command while no voltage at motor d.x.goal_reached: True d.x.goal_reason: Reached From bc3dba6e910e7319bd213d75339cae13ea5f5517 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 14 Nov 2024 13:27:03 -0600 Subject: [PATCH 067/121] cia_402: Don't attempt state transitions until params are written --- hw_device_mgr/cia_402/device.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 174c7302..2ef37f4a 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -516,6 +516,9 @@ def set_command(self, **kwargs): self.logger.info(f"CiA 402 state command: {state_cmd}") if not self.feedback_out.get("oper"): return cmd_out + complete = CiA301Device.PARAM_STATE_COMPLETE + if self.feedback_out.get("param_state") != complete: + return cmd_out self._get_next_control_mode(cmd_out) self._get_next_control_word(cmd_out) return cmd_out From 8e6a40c48111b848484d2f4af13522d30cf581e4 Mon Sep 17 00:00:00 2001 From: John Morris Date: Fri, 22 Nov 2024 15:57:43 -0600 Subject: [PATCH 068/121] Implement drive "shutdown" command --- hw_device_mgr/cia_301/device.py | 13 ++++- .../tests/read_update_write.cases.yaml | 3 ++ hw_device_mgr/cia_402/device.py | 23 +++++---- .../cia_402/tests/hm_timeout.cases.yaml | 3 ++ .../cia_402/tests/pp_timeout.cases.yaml | 3 ++ .../tests/read_update_write.cases.yaml | 3 ++ hw_device_mgr/device.py | 15 +++++- hw_device_mgr/mgr/mgr.py | 51 ++++++++++++++++--- .../mgr/tests/read_update_write.cases.yaml | 5 ++ hw_device_mgr/mgr/tests/test_mgr.py | 2 +- 10 files changed, 101 insertions(+), 20 deletions(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 93a5bc74..004b4e86 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -146,6 +146,11 @@ def get_feedback(self): # Update operational status if not self.feedback_in.get("oper"): + if self.command_in.get("shutdown"): + if self.feedback_in.changed("oper"): + self.logger.info("Drive non-operational, shutdown complete") + fb_out.update(shutdown_complete=True) + return fb_out # goal reached goal_reached = False goal_reasons.insert(0, "Not operational") @@ -161,6 +166,10 @@ def get_feedback(self): else: # operational if self.feedback_in.changed("oper"): self.logger.info("Drive came online/operational") + if self.command_out.get("shutdown_latch"): + goal_reached = False + goal_reasons.insert(0, "Drive operational during shutdown") + fb_out.update(shutdown_complete=False) # Update feedback and return goal_reason = "Reached" if goal_reached else ", ".join(goal_reasons) @@ -323,7 +332,9 @@ def init_class(cls, **kwargs): def set_sim_feedback(self, **kwargs): # Automatically step through to online/oper sfb = super().set_sim_feedback(**kwargs) - if self.feedback_in.get("online"): + if self.command_in.get("shutdown"): + sfb.update(online=True, oper=False) + elif self.feedback_in.get("online"): sfb.update(online=True, oper=True) else: sfb.update(online=True, oper=False) diff --git a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml index ff7012db..ae3c1e3b 100644 --- a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml @@ -14,11 +14,14 @@ fault: False fault_desc: "" param_state: 0x00 # PARAM_STATE_UNKNOWN + shutdown_complete: False command_in: reset_fault: False + shutdown: False command_out: init_params: False fasttrack: False + shutdown_latch: False sim_feedback: online: True oper: False diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 2ef37f4a..b23e05ea 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -241,6 +241,10 @@ def get_feedback(self): fb_out = super().get_feedback() fb_in = self.feedback_in + # If shutting down, there's nothing to do here + if self.command_out.get("shutdown_latch"): + return fb_out + # Don't clobber lower layer's feedback, but continue managing CiA 402 # states even while param init continues goal_reached = fb_out.get("goal_reached") @@ -281,9 +285,9 @@ def get_feedback(self): f"Unknown status word 0x{sw:X}; " f"state {fb_out.get('state')} unchanged" ) + state_cmd = self.command_in.get("state") if self._get_next_transition() >= 0: goal_reached = False - state_cmd = self.command_in.get("state") sw = fb_in.get("status_word") goal_reasons.append(f"state {state} != {state_cmd}") if state_cmd in ( @@ -298,13 +302,10 @@ def get_feedback(self): fb_out.update(following_error=ferror) # Raise fault if device unexpectedly disabled - if self.command_in.get( - "state" - ) == "OPERATION ENABLED" and not self.test_sw_bit( - sw, "READY_TO_SWITCH_ON" - ): - fault = True - fault_desc = "Enabled drive unexpectedly disabled" + if state_cmd == "OPERATION ENABLED": + if not self.test_sw_bit(sw, "READY_TO_SWITCH_ON"): + fault = True + fault_desc = "Enabled drive unexpectedly disabled" # Calculate 'transition' feedback new_st, old_st = fb_out.changed("state", return_vals=True) @@ -353,7 +354,7 @@ def get_feedback(self): goal_reasons.append(pp_reason) # If in CiA402 FAULT state, set device fault - if self.command_in.get("state") == "FAULT": + if state_cmd == "FAULT": fault = True if not fault_desc: # Recycle previous description if possible @@ -514,6 +515,8 @@ def set_command(self, **kwargs): if self.command_in.changed("state"): state_cmd = self.command_in.get("state") self.logger.info(f"CiA 402 state command: {state_cmd}") + if self.command_out.get("shutdown_latch"): + return cmd_out if not self.feedback_out.get("oper"): return cmd_out complete = CiA301Device.PARAM_STATE_COMPLETE @@ -715,6 +718,8 @@ def _get_transition_control_word(self): return cw def _get_next_transition(self, curr_state=None): + if not self.feedback_in.get("oper"): + return -1 return self._get_next_state(curr_state=curr_state, transition=True) def _get_next_state(self, curr_state=None, transition=False): diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index 2f76935a..4b34ed8f 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -43,6 +43,7 @@ error_code: 0x00000000 description: No error fault_desc: "" + shutdown_complete: False command_in: state: OPERATION ENABLED control_mode: 8 @@ -50,11 +51,13 @@ home_request: True move_request: False relative_target: False + shutdown: False command_out: control_word: 0x000F control_mode: 6 init_params: False fasttrack: False + shutdown_latch: False sim_feedback: online: True oper: True diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index 22c0322f..17eafe1f 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -45,6 +45,7 @@ error_code: 0x00000000 description: No error fault_desc: "" + shutdown_complete: False command_in: state: OPERATION ENABLED control_mode: 1 # MODE_PP @@ -52,11 +53,13 @@ home_request: False move_request: True relative_target: False + shutdown: False command_out: control_word: 0x001F # Bit 4 NEW_SETPOINT set control_mode: 1 # MODE_PP init_params: False fasttrack: True + shutdown_latch: False sim_feedback: online: True oper: True diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index 9861d16f..0b3762f8 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -18,6 +18,7 @@ # errors error_code: 0x00000000 feedback_out: + shutdown_complete: False # CiA 301 online: False oper: False @@ -45,6 +46,7 @@ description: No error fault_desc: "" command_in: + shutdown: False # CiA 402 state: SWITCH ON DISABLED control_mode: 8 # MODE_CSP @@ -53,6 +55,7 @@ relative_target: False reset_fault: False command_out: + shutdown_latch: False # CiA 402 control_word: 0x0000 control_mode: 8 # MODE_CSP diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 5581c5f2..86adb432 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -22,12 +22,15 @@ class Device(LoggingMixin, abc.ABC): goal_reason="str", fault="bit", fault_desc="str", + shutdown_complete="bit", ) command_in_data_types = dict( reset_fault="bit", + shutdown="bit", ) command_out_data_types = dict( fasttrack="bit", + shutdown_latch="bit", ) feedback_in_defaults = dict() @@ -36,12 +39,15 @@ class Device(LoggingMixin, abc.ABC): goal_reason="Reached", fault=False, fault_desc="", + shutdown_complete=False, ) command_in_defaults = dict( reset_fault=False, + shutdown=False, ) command_out_defaults = dict( fasttrack=False, + shutdown_latch=False, ) feedback_in_overlap = set() @@ -154,6 +160,8 @@ def get_feedback(self) -> Interface: fb_out.set(**fb_in) if timeout: fb_out.update(fault=True, fault_desc=timeout) + if self.command_out.get("shutdown_latch"): + fb_out.update(shutdown_complete=True) # Higher levels may correct return fb_out def log_goal_reached(self): @@ -204,7 +212,12 @@ def set_command(self, **kwargs) -> Interface: cmd_out = self._interfaces["command_out"] cmd_in.set(**kwargs) cmd_out.set() - if cmd_in.get("reset_fault"): + if cmd_in.get("shutdown") or cmd_out.get("shutdown_latch"): + # Incoming shutdown command latches + cmd_out.update(shutdown_latch=True) + if cmd_out.rising_edge("shutdown_latch"): + self.logger.info("Commanding drive shutdown") + elif cmd_in.get("reset_fault"): if cmd_in.rising_edge("reset_fault"): self.logger.info("Reset fault command") return cmd_out diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 0f16faa1..90366cc9 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -22,6 +22,7 @@ def device_model_id(cls): STATE_STOP = 1 STATE_START = 2 STATE_FAULT = 4 + STATE_SHUTDOWN = 5 feedback_out_defaults = dict( enabled=False, @@ -132,8 +133,9 @@ def scan_devices(cls, **kwargs): "position_cmd", "position_fb", }, - # - Don't expose device `state` or `reset_fault`, controlled by manager - command_in={"state", "reset_fault"}, + # - Don't expose device `state`, `reset_fault`, `shutdown`, + # controlled by manager + command_in={"state", "reset_fault", "shutdown"}, ) @lru_cache @@ -167,6 +169,9 @@ def dev_prefix(self, dev, prefix="d", suffix=""): # - stop_complete: Done dict(name="stop_command", src="*", dst="stop_1"), dict(name="stop_complete", src="stop_1", dst="stop_complete"), + # Shutdown state: From any state + dict(name="shutdown_command", src="*", dst="shutdown_1"), + dict(name="shutdown_complete", src="shutdown_1", dst="shutdown_complete"), ], state_field="state", ) @@ -263,6 +268,21 @@ def on_before_stop_complete(self, e): def on_enter_stop_complete(self, e): self.fsm_finalize_command(e) + # + # Shutdown command + # + def on_before_shutdown_command(self, e): + return True # Always can shutdown + + def on_enter_shutdown_1(self, e): + self.fsm_set_drive_state_cmd(e, "SHUTDOWN") + + def on_before_shutdown_complete(self, e): + return self.fsm_check_drive_goal_state(e) + + def on_enter_shutdown_complete(self, e): + self.fsm_finalize_command(e) + # # All states # @@ -446,6 +466,10 @@ def read_update_write(self): fault_1="fault_complete", fault_complete=None, ), + shutdown=dict( + shutdown_1="shutdown_complete", + shutdown_complete=None, + ), ) def read(self): @@ -561,10 +585,17 @@ def set_command(self, **cmd_in_kwargs): # clobber parent class updates for regular device classes, but this # isn't a regular device and it inherits directly from `Device` old_cmd_out = self.command_out.get().copy() + cmd_in_shutdown = cmd_in_kwargs.get("shutdown", False) + if cmd_in_shutdown or old_cmd_out.get("shutdown_latch"): + # Incoming shutdown command latches + old_cmd_out.update(shutdown_latch=True) cmd_out = super().set_command(**cmd_in_kwargs) cmd_out.update(**old_cmd_out) cmd_in = self.command_in + if cmd_in.rising_edge("shutdown"): + self.logger.info("Commanding drive shutdown") + # Check for new command if self.command_in.rising_edge("state_set"): # state_set went high; log it @@ -660,22 +691,26 @@ def set_drive_command(self): mgr_vals = self.command_in.get() skip = self.device_translated_interfaces.get("command_in", set()) reset = self.command_out.get("reset_fault_cmd") + shutdown=self.command_in.get("shutdown") for dev in self.devices: if "command_in" in self.device_translated_interfaces: # Copy mgr command_out to matching device command_in dev_command_in = dev.interface("command_in") prefix = self.dev_prefix(dev, suffix=dev.slug_separator) - dev.set_command( - state=self.command_out.get("drive_state"), - reset_fault=reset, - **{ - k: mgr_vals[f"{prefix}{k}"] + kwargs = { + k: mgr_vals[f"{prefix}{k}"] for k in dev_command_in.keys() if k not in skip - }, + } + kwargs.update( + shutdown=shutdown, + state=self.command_out.get("drive_state"), + reset_fault=reset, ) + dev.set_command(**kwargs) else: dev.set_command( + shutdown=shutdown, state=self.command_out.get("drive_state"), reset_fault=reset, ) diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index ca8a1a51..18ab9abd 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -25,7 +25,9 @@ goal_reason: Offline ({all_drives}) fault: False fault_desc: "" + shutdown_complete: False # Drives + d.x.shutdown_complete: False # - CiA 301 d.x.online: False d.x.oper: False @@ -51,6 +53,7 @@ d.x.error_code: 0x00000000 d.x.description: No error command_in: + shutdown: False # Mgr state_cmd: 0 # init state_set: 0 # don't latch in state_cmd @@ -62,6 +65,7 @@ d.x.move_request: False d.x.relative_target: False command_out: + shutdown_latch: False # Mgr state: 0 # init state_log: Automatic transition to init_command from init_command state @@ -71,6 +75,7 @@ reset_fault_cmd: False fasttrack: False # Drives + d.x.shutdown_latch: False # - CiA 402 d.x.control_word: 0x0000 # SWITCH ON DISABLED d.x.control_mode: 8 # MODE_CSP diff --git a/hw_device_mgr/mgr/tests/test_mgr.py b/hw_device_mgr/mgr/tests/test_mgr.py index 18945017..8932ad59 100644 --- a/hw_device_mgr/mgr/tests/test_mgr.py +++ b/hw_device_mgr/mgr/tests/test_mgr.py @@ -34,7 +34,7 @@ def test_state_values(self, obj): assert val in obj.cmd_int_to_name_map assert obj.cmd_int_to_name_map[val] == key values[key] = val - assert len(values) == 4 + assert len(values) == 5 def test_init(self, obj): super().test_init(obj) From 1c911c2dd76559cd58c9009de4f85f199c7a4c83 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 12 Nov 2024 15:45:27 -0600 Subject: [PATCH 069/121] cia_301, cia_402: Log more information about state changes In cia_301, log when device comes online and again when operational. All other changes are in cia_402: Log when STO goes active, and log status word changes, even when not yet operational. The latter allows more 402-level state calculations than before, but stops before looking at higher-level functions like HM or PP, and stops before logging faults. When fault is active, be clear why goal is reached but errors apparently exist, with "Goal reached: Fault state reached; [...]" log message. In `set_command()`, log 402 state command changes. --- hw_device_mgr/cia_301/device.py | 6 +++ hw_device_mgr/cia_402/device.py | 76 +++++++++++++++++++-------------- 2 files changed, 50 insertions(+), 32 deletions(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 9ef77644..93a5bc74 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -109,6 +109,9 @@ def get_feedback(self): # Stop param init return fb_out # Nothing more to do + if self.feedback_in.changed("online"): + self.logger.info("Drive came online") + # Device online; update CiA301 feedback goal_reached, goal_reasons = True, list() @@ -155,6 +158,9 @@ def get_feedback(self): fb_out.update( fault=True, fault_desc=fb_out.get_old("fault_desc") ) + else: # operational + if self.feedback_in.changed("oper"): + self.logger.info("Drive came online/operational") # Update feedback and return goal_reason = "Reached" if goal_reached else ", ".join(goal_reasons) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 60545760..f7b86f1d 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -274,6 +274,12 @@ def get_feedback_sto(self): if self.feedback_in.changed("sto"): # Log once self.logger.info("STO input inactive") return True, None + else: + if self.feedback_in.changed("sto"): # Log once + self.logger.info("STO input active") + + if not self.feedback_in.get("oper"): + return True, None # STO active (high) state_cmd = self.command_in.get("state") @@ -310,11 +316,6 @@ def get_feedback(self): fb_out = super().get_feedback() fb_in = self.feedback_in - # Set default "START" state in these cases: - if not fb_out.get("oper"): - # Device not yet operational - return fb_out - # Don't clobber lower layer's feedback, but continue managing CiA 402 # states even while param init continues goal_reached = fb_out.get("goal_reached") @@ -367,13 +368,12 @@ def get_feedback(self): ) and not self.test_sw_bit(sw, "VOLTAGE_ENABLED"): fault = True fault_desc = "Enable command while no voltage at motor" - goal_reasons.append(fault_desc) # Handle `FOLLOWING_ERROR` active ferror = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_2") fb_out.update(following_error=ferror) - # Raise fault if device unexpectedly goes offline + # Raise fault if device unexpectedly disabled if self.command_in.get( "state" ) == "OPERATION ENABLED" and not self.test_sw_bit( @@ -381,7 +381,6 @@ def get_feedback(self): ): fault = True fault_desc = "Enabled drive unexpectedly disabled" - goal_reasons.append(fault_desc) # Calculate 'transition' feedback new_st, old_st = fb_out.changed("state", return_vals=True) @@ -396,6 +395,34 @@ def get_feedback(self): else: fb_out.update(transition=-1) + # Handle STO + if self.have_sto: + sto_success, sto_reason = self.get_feedback_sto() + if not sto_success: + goal_reached = False + goal_reasons.append(sto_reason) + + # Log status word changes + if self.log_status_word_changes and fb_out.changed("status_word"): + self.logger.info(f"status_word: {self.sw_to_str(sw)}") + + # If device not yet operational, don't do any more, incl. log faults, + # etc. + if not fb_out.get("oper"): + return fb_out + + # Fault reported by drive + if self.test_sw_bit(sw, "FAULT"): + fault = True + fault_desc = "Drive status word FAULT bit set" + if fb_out.get("error_code"): + error_code = fb_out.get("error_code") + fault_desc += f", code {error_code}" + if (error_desc := fb_out.get("description")): + fault_desc += f" '{error_desc}'" + else: + fault_desc += " (no error code)" + # Mode-specific functions if cm == self.MODE_HM: # Calculate homing status @@ -422,24 +449,6 @@ def get_feedback(self): goal_reached = False goal_reasons.append(pt_reason) - # Handle STO - if self.have_sto: - sto_success, sto_reason = self.get_feedback_sto() - if not sto_success: - goal_reached = False - goal_reasons.append(sto_reason) - - # Fault reported by drive - if self.test_sw_bit(sw, "FAULT"): - fault = True - if fb_out.get("error_code"): - error_code = fb_out.get("error_code") - error_desc = fb_out.get("description") - fault_desc = f"{error_code} {error_desc}" - else: - fault_desc = "Fault (no error code)" - goal_reasons.append(fault_desc) - # If in CiA402 FAULT state, set device fault if self.command_in.get("state") == "FAULT": fault = True @@ -449,18 +458,18 @@ def get_feedback(self): # If FAULT is commanded & no device fault, this will be an empty # string if not fault_desc: - fault_desc = f"FAULT command from controller (was {old_st})" - goal_reasons.append(fault_desc) + fault_desc = "FAULT command from controller" + fault_desc += f" (from state {old_st})" # Update feedback to controller if fault: fb_out.update(fault=True, fault_desc=fault_desc) - if self.log_status_word_changes and fb_out.changed("status_word"): - self.logger.info(f"status_word: {self.sw_to_str(sw)}") - if not goal_reached: - goal_reached = fault # If fault active, nothing to do, goal reached + if fault: + # If fault active, nothing to do, goal reached + goal_reasons.insert(0, "Fault state reached") + goal_reached = True goal_reason = "; ".join(goal_reasons) fb_out.update(goal_reached=goal_reached, goal_reason=goal_reason) return fb_out @@ -603,6 +612,9 @@ def sw_to_str(cls, sw): def set_command(self, **kwargs): cmd_out = super().set_command(**kwargs) + if self.command_in.changed("state"): + state_cmd = self.command_in.get("state") + self.logger.info(f"CiA 402 state command: {state_cmd}") if not self.feedback_out.get("oper"): return cmd_out self._get_next_control_mode(cmd_out) From 71023ddf1bf2bf3571b0bfe3a2fa97cc5b81f4ab Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 14 Nov 2024 13:27:03 -0600 Subject: [PATCH 070/121] cia_402: Don't attempt state transitions until params are written --- hw_device_mgr/cia_402/device.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index f7b86f1d..bf49eb52 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -617,6 +617,9 @@ def set_command(self, **kwargs): self.logger.info(f"CiA 402 state command: {state_cmd}") if not self.feedback_out.get("oper"): return cmd_out + complete = CiA301Device.PARAM_STATE_COMPLETE + if self.feedback_out.get("param_state") != complete: + return cmd_out self._get_next_control_mode(cmd_out) self._get_next_control_word(cmd_out) return cmd_out From a8ef41d02409c76a3f640999c78d5c0126eb4772 Mon Sep 17 00:00:00 2001 From: John Morris Date: Fri, 22 Nov 2024 16:20:14 -0600 Subject: [PATCH 071/121] Revert "PP-4619 - ignore ecat alias 9999" This reverts commit 07d63b65f190c9d69e5a3b4d47fd3f9f51906399. Application-specific change moved out of general code --- hw_device_mgr/cia_301/command.py | 2 -- hw_device_mgr/lcec/command.py | 2 -- 2 files changed, 4 deletions(-) diff --git a/hw_device_mgr/cia_301/command.py b/hw_device_mgr/cia_301/command.py index 234c881f..94de971e 100644 --- a/hw_device_mgr/cia_301/command.py +++ b/hw_device_mgr/cia_301/command.py @@ -112,8 +112,6 @@ def scan_bus(self, bus=0): for dd in self.sim_device_data.values(): if dd["address"][0] != bus: continue - if dd["address"][2] == 9999: - continue res.append([dd["address"], dd["model_id"]]) return res diff --git a/hw_device_mgr/lcec/command.py b/hw_device_mgr/lcec/command.py index a108716a..519d295f 100644 --- a/hw_device_mgr/lcec/command.py +++ b/hw_device_mgr/lcec/command.py @@ -62,8 +62,6 @@ def scan_bus(self, bus=None, **kwargs): alias = int(line.split(":", 1)[1].strip()) addr = device[-1][0:2] + (alias,) device[0] = addr - if alias == 9999: - del devices[-1] elif line.startswith("Vendor Id:"): # Vendor Id: 0x00100000 vi = line.split(":", 1)[1].strip() From a2722dbae5e3035e08b7b5863ce7c600eba251d5 Mon Sep 17 00:00:00 2001 From: John Morris Date: Fri, 22 Nov 2024 16:49:17 -0600 Subject: [PATCH 072/121] Clean up & dedup SV670 configs --- .../devices/device_err/inovance_sv670n.yaml | 566 - .../device_xml/SV660_EOE_1Axis_V9.12.xml | 2 +- .../SV670_EOE_1Axis_05003_220801.xml | 34798 ++++++++-------- hw_device_mgr/devices/inovance_sv670.py | 2 +- 4 files changed, 17401 insertions(+), 17967 deletions(-) delete mode 100644 hw_device_mgr/devices/device_err/inovance_sv670n.yaml diff --git a/hw_device_mgr/devices/device_err/inovance_sv670n.yaml b/hw_device_mgr/devices/device_err/inovance_sv670n.yaml deleted file mode 100644 index 7384f3f3..00000000 --- a/hw_device_mgr/devices/device_err/inovance_sv670n.yaml +++ /dev/null @@ -1,566 +0,0 @@ -# From Inovance SV660N "Advanced User Guide" 2020-10-20, table 10.2 -# "Communication Faults and Warning Codes" -# -# Parameter 603Fh shows the basic error code, but the -# manufacturer-specific SV660N parameter 203Fh "Manufacturer fault -# code" shows an extended error value. The manual's table 10.2 shows -# e.g. "fault" E101, with "display" broken down into E101.0 and E101.1 -# with different "name" and occasional differences in "fault range" -# column ("type" and "resettable or not" columns appear not to -# change). -# -# key: "Auxiliary Code" column most significant word -# display: "Display" column; code displayed on drive LED panel -# description: "Name" column -# type: "Type" column; indicates severity, with 1 most severe -# resettable: "Resettable" column; indicates whether resettable -# without power cycle - -# -# List of fault codes -# -'0x0101': - display: E101.0 - description: System parameter error - type: 1 - resettable: false -'0x1101': - display: E101.1 - description: 2000h/2001h parameter error - type: 1 - resettable: false -'0x0102': - display: E102.0 - description: FPGA communication initialization error - type: 1 - resettable: false -'0x8102': - display: E102.8 - description: Software version mismatch - type: 1 - resettable: false -'0x1104': - display: E104.1 - description: MCU operation timeout - type: 1 - resettable: false -'0x2104': - display: E104.2 - description: Current loop operation timeout - type: 1 - resettable: false -'0x4104': - display: E104.4 - description: MCU reference update timeout - type: 1 - resettable: false -'0x0108': - display: E108.0 - description: Parameter write error - type: 1 - resettable: true -'0x1108': - display: E108.1 - description: Parameter read error - type: 1 - resettable: true -'0x2108': - display: E108.2 - description: Invalid check on data written in EEPROM - type: 1 - resettable: true -'0x3108': - display: E108.3 - description: Invalid check on data read in EEPROM - type: 1 - resettable: true -'0x0120': - display: E120.0 - description: Unknown encoder type - type: 1 - resettable: false -'0x1120': - display: E120.1 - description: Unknown motor model - type: 1 - resettable: false -'0x2120': - display: E120.2 - description: Unknown drive model - type: 1 - resettable: false -'0x5120': - display: E120.5 - description: Motor current and drive current mismatch - type: 1 - resettable: false -'0x6120': - display: E120.6 - description: FPGA and motor model mismatch - type: 1 - resettable: false -'0x0122': - display: E122.0 - description: Multi-turn absolute encoder setting error - type: 2 - resettable: true -'0x1122': - display: E122.1 - description: Different DIs allocated with the same function - type: 2 - resettable: true -'0x3122': - display: E122.3 - description: Upper limit invalid - type: 2 - resettable: true -'0x0136': - display: E136.0 - description: Encoder parameter error - type: 1 - resettable: false -'0x1136': - display: E136.1 - description: Encoder communication error - type: 1 - resettable: false -'0x0140': - display: E140.0 - description: Encryption chip check error - type: 1 - resettable: false -'0x1140': - display: E140.1 - description: Encryption chip check failure - type: 1 - resettable: false -'0x0150': - display: E150.0 - description: STO signal input protection activated - type: 1 - resettable: true -'0x1150': - display: E150.1 - description: STO signal input error - type: 1 - resettable: true -'0x2150': - display: E150.2 - description: Abnormal voltage detected - type: 1 - resettable: true -'0x3150': - display: E150.3 - description: STO upstream optocoupler detection failure - type: 1 - resettable: true -'0x4150': - display: E150.4 - description: PWM Buffer detection failure - type: 1 - resettable: true -'0x0201': - display: E201.0 - description: Phase-P overcurrent - type: 1 - resettable: false -'0x1201': - display: E201.1 - description: Phase-U overcurrent - type: 1 - resettable: false -'0x2201': - display: E201.2 - description: Phase-V overcurrent - type: 1 - resettable: false -'0x4201': - display: E201.4 - description: Phase-N overcurrent - type: 1 - resettable: false -'0x0208': - display: E208.0 - description: MCU position reference updated frequently - type: 1 - resettable: true -'0x2208': - display: E208.2 - description: Encoder communication timeout - type: 1 - resettable: true -'0x3208': - display: E208.3 - description: Current sampling fault - type: 1 - resettable: true -'0x4208': - display: E208.4 - description: FPGA current loop operation timeout - type: 1 - resettable: true -'0x0210': - display: E210.0 - description: Output shorted to ground - type: 1 - resettable: false -'0x0234': - display: E234.0 - description: Runaway protection - type: 1 - resettable: false -'0x0400': - display: E400.0 - description: Main circuit overvoltage - type: 1 - resettable: true -'0x0410': - display: E410.0 - description: Main circuit undervoltage - type: 1 - resettable: true -'0x0420': - display: E420.0 - description: Phase loss fault - type: 2 - resettable: true -'0x0430': - display: E430.0 - description: Control circuit undervoltage - type: 2 - resettable: true -'0x0500': - display: E500.0 - description: Motor overspeed - type: 1 - resettable: true -'0x1500': - display: E500.1 - description: Speed feedback overflow - type: 1 - resettable: true -'0x2500': - display: E500.2 - description: FPGA position feedback pulse overspeed - type: 1 - resettable: true -'0x0602': - display: E602.0 - description: Angle auto-tuning error - type: 1 - resettable: true -'0x2602': - display: E602.2 - description: Wrong UVW phase sequence detected during angle auto-tuning - type: 1 - resettable: true -'0x0605': - display: E605.0 - description: Speed upon S-ON too high - type: 1 - resettable: true -'0x0620': - display: E620.0 - description: Motor overload - type: 1 - resettable: true -'0x0630': - display: E630.0 - description: Motor stall - type: 1 - resettable: true -'0x0640': - display: E640.0 - description: IGBT over-temperature - type: 1 - resettable: true -'0x1640': - display: E640.1 - description: Flywheel diode over-temperature - type: 1 - resettable: true -'0x0650': - display: E650.0 - description: Heatsink over-temperature - type: 1 - resettable: true -'0x0660': - display: E660.0 - description: Air-cooled motor over-temperature - type: 1 - resettable: true -'0x0661': - display: E661.0 - description: Auto-tuned gain values too low - type: 2 - resettable: true -'0x0731': - display: E731.0 - description: Encoder battery failure - type: 2 - resettable: true -'0x0733': - display: E733.0 - description: Encoder multi-turn counting error - type: 2 - resettable: true -'0x0735': - display: E735.0 - description: Encoder multi-turn counting overflow - type: 2 - resettable: true -'0x2740': - display: E740.2 - description: Absolute encoder error - type: 1 - resettable: false -'0x3740': - display: E740.3 - description: Absolute encoder single-turn calculation error - type: 1 - resettable: false -'0x6740': - display: E740.6 - description: Encoder write error - type: 1 - resettable: false -'0x0755': - display: E755.0 - description: Nikon encoder communication failure - type: 1 - resettable: false -'0x0760': - display: E760.0 - description: Encoder over-temperature - type: 2 - resettable: true -'0x0765': - display: E765.0 - description: Nikon encoder beyond the limit - type: 1 - resettable: false -'0x0B00': - display: EB00.0 - description: Position deviation too large - type: 2 - resettable: true -'0x1B00': - display: EB00.1 - description: Position deviation overflow - type: 2 - resettable: true -# (Note: out of numerical order in manual) -'0x0A33': - display: EA33.0 - description: Encoder read/write check error - type: 1 - resettable: false -'0x1B01': - display: EB01.1 - description: Position reference increment too large for once - type: 2 - resettable: true -'0x2B01': - display: EB01.2 - description: Position reference increment too large continuously - type: 2 - resettable: true -'0x3B01': - display: EB01.3 - description: Reference overflow - type: 2 - resettable: true -'0x4B01': - display: EB01.4 - description: Target position beyond upper/lower limit - type: 2 - resettable: true -'0x0E09': - display: EE09.0 - description: Software position limit setting error - type: 2 - resettable: true -'0x1E09': - display: EE09.1 - description: Home setting error - type: 2 - resettable: true -'0x2E09': - display: EE09.2 - description: Gear ratio beyond the limit - type: 2 - resettable: true -'0x3E09': - display: EE09.3 - description: No synchronization signal - type: 2 - resettable: true -'0x5E09': - display: EE09.5 - description: PDO mapping beyond the limit - type: 2 - resettable: true -# (Note: EE08.0 out of order in manual) -'0x0E08': - display: EE08.0 - description: Synchronization loss - type: 2 - resettable: true -'0x1E08': - display: EE08.1 - description: Network status switchover error - type: 2 - resettable: true -'0x2E08': - display: EE08.2 - description: IRQ loss - type: 2 - resettable: true -'0x3E08': - display: EE08.3 - description: LAN cable connected improperly - type: 2 - resettable: true -'0x4E08': - display: EE08.4 - description: Data frame loss protection error - type: 2 - resettable: true -'0x5E08': - display: EE08.5 - description: Data frame transfer error - type: 2 - resettable: true -'0x6E08': - display: EE08.6 - description: Data update timeout - type: 2 - resettable: true -'0x0E11': - display: EE11.0 - description: ESI check error - type: 2 - resettable: true -'0x1E11': - display: EE11.1 - description: EEPROM read failure - type: 2 - resettable: true -'0x2E11': - display: EE11.2 - description: EEPROM update failure - type: 2 - resettable: true -'0x0E12': - display: EE12.0 - description: EtherCAT external device error - type: 1 - resettable: false -'0x0E13': - display: EE13.0 - description: Synchronization cycle setting error - type: 2 - resettable: true -'0x0E15': - display: EE15.0 - description: Number of synchronization cycle errors too large - type: 2 - resettable: true -# -# List of warning codes -# -'0x0121': - display: E121.0 - description: Invalid S-ON command - type: 3 - resettable: true -'0x0600': - display: E600.0 - description: Inertia auto-tuning failure - type: 3 - resettable: true -'0x0601': - display: E601.0 - description: Homing timeout - type: 3 - resettable: true -'0x1601': - display: E601.1 - description: Home switch error - type: 3 - resettable: true -'0x2601': - display: E601.2 - description: Homing mode setting error - type: 3 - resettable: true -'0x0730': - display: E730.0 - description: Encoder battery warning - type: 3 - resettable: true -'0x0900': - display: E900.0 - description: Emergency stop - type: 3 - resettable: true -'0x0902': - display: E902.0 - description: Invalid DI setting - type: 3 - resettable: true -'0x1902': - display: E902.1 - description: Invalid DO setting - type: 3 - resettable: true -'0x0908': - display: E908.0 - description: Model identification check byte invalid - type: 3 - resettable: true -'0x0909': - display: E909.0 - description: Motor overload warning - type: 3 - resettable: true -'0x0920': - display: E920.0 - description: Regenerative resistor overload - type: 3 - resettable: true -'0x0922': - display: E922.0 - description: Resistance of external regenerative resistor too small - type: 3 - resettable: true -'0x0924': - display: E924.0 - description: Braking transistor over-temperature - type: 3 - resettable: true -'0x0941': - display: E941.0 - description: Parameter modifications not activated - type: 3 - resettable: true -'0x0942': - display: E942.0 - description: Parameter saved frequently - type: 3 - resettable: true -'0x0950': - display: E950.0 - description: Forward overtravel warning - type: 3 - resettable: true -'0x0952': - display: E952.0 - description: Reverse overtravel warning - type: 3 - resettable: true -'0x0A41': - display: EA41.0 - description: Torque ripple compensation failure - type: 3 - resettable: true diff --git a/hw_device_mgr/devices/device_xml/SV660_EOE_1Axis_V9.12.xml b/hw_device_mgr/devices/device_xml/SV660_EOE_1Axis_V9.12.xml index 648b9f3f..0e1dc5d4 100644 --- a/hw_device_mgr/devices/device_xml/SV660_EOE_1Axis_V9.12.xml +++ b/hw_device_mgr/devices/device_xml/SV660_EOE_1Axis_V9.12.xml @@ -7387,7 +7387,7 @@ 7 1 - + ro diff --git a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml index ba6b927e..55ceb5dd 100644 --- a/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml +++ b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml @@ -1,17403 +1,17403 @@ - - #x00100000 - Inovance - 汇川技术 - 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 - - - - - InoServo - Servo Drives - 伺服驱动器 - 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 - - - - - InoSV670N - SV670_1Axis_05003 - ServoDrive - http://www.inovance.cn - - - - 3000 - 9000 - 5000 - 200 - - - - - 100 - 2000 - - - - InoServo - - - 402 - - - - - - BIT2 - 2 - - - - BOOL - 1 - - - - DINT - 32 - - - - INT - 16 - - - - UDINT - 32 - - - - UINT - 16 - - - - USINT - 8 - - - - SINT - 8 - - - - STRING(10) - 80 - - - - STRING(4) - 32 - - - DT1018 - 144 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Vendor ID - UDINT - 32 - 16 - - ro - - - - 2 - Product Code - UDINT - 32 - 48 - - ro - - - - 3 - Revision - UDINT - 32 - 80 - - ro - - - - 4 - Serial number - UDINT - 32 - 112 - - ro - - - - - DT1600 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - rw - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - rw - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - rw - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - rw - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - rw - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - rw - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - rw - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - rw - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - rw - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - rw - - - - - DT1601 - 368 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - rw - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - rw - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - rw - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - rw - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - rw - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - rw - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - rw - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - rw - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - rw - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - rw - - - - 11 - 11th Output Object to be mapped - UDINT - 32 - 336 - - rw - - - - - DT1701 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1702 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1703 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1704 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1705 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Output Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Output Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Output Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Output Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Output Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Output Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Output Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Output Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Output Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Output Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1A00 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - rw - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - rw - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - rw - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - rw - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - rw - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - rw - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - rw - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - rw - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - rw - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - rw - - - - - DT1A01 - 368 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - rw - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - rw - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - rw - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - rw - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - rw - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - rw - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - rw - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - rw - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - rw - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - rw - - - - 11 - 11th Input Object to be mapped - UDINT - 32 - 336 - - rw - - - - - DT1B01 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1B02 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1B03 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1B04 - 336 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Input Object to be mapped - UDINT - 32 - 16 - - ro - - - - 2 - 2nd Input Object to be mapped - UDINT - 32 - 48 - - ro - - - - 3 - 3rd Input Object to be mapped - UDINT - 32 - 80 - - ro - - - - 4 - 4th Input Object to be mapped - UDINT - 32 - 112 - - ro - - - - 5 - 5th Input Object to be mapped - UDINT - 32 - 144 - - ro - - - - 6 - 6th Input Object to be mapped - UDINT - 32 - 176 - - ro - - - - 7 - 7th Input Object to be mapped - UDINT - 32 - 208 - - ro - - - - 8 - 8th Input Object to be mapped - UDINT - 32 - 240 - - ro - - - - 9 - 9th Input Object to be mapped - UDINT - 32 - 272 - - ro - - - - 10 - 10th Input Object to be mapped - UDINT - 32 - 304 - - ro - - - - - DT1C00ARR - USINT - 32 - - 1 - 4 - - - - DT1C00 - 48 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - o - - - - Elements - DT1C00ARR - 32 - 16 - - ro - o - - - - - - DT1C32 - 488 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - m - - - - 1 - Sync mode - UINT - 16 - 16 - - rw - - - - 2 - Cycle time - UDINT - 32 - 32 - - ro - o - - - - 4 - Sync modes supported - UINT - 16 - 96 - - ro - o - - - - 5 - Minimum cycle time - UDINT - 32 - 112 - - ro - o - - - - 6 - Calc and copy time - UDINT - 32 - 144 - - ro - o - - - - 8 - Get Cycle Time - UINT - 16 - 208 - - rw - c - - - - 9 - Delay Time - UDINT - 32 - 224 - - ro - c - - - - 10 - Sync0 Cycle Time - UDINT - 32 - 256 - - rw - o - - - - 11 - SM-Event Missed - UINT - 16 - 288 - - ro - c - - - - 12 - Cycle Time Too Small - UINT - 16 - 304 - - ro - c - - - - 32 - Sync Error - BOOL - 1 - 480 - - ro - c - - - - - - DT1C33 - 488 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - o - - - - 1 - Sync mode - UINT - 16 - 16 - - rw - - - - 2 - Cycle time - UDINT - 32 - 32 - - ro - o - - - - 4 - Sync modes supported - UINT - 16 - 96 - - ro - o - - - - 5 - Minimum cycle time - UDINT - 32 - 112 - - ro - o - - - - 6 - Calc and copy time - UDINT - 32 - 144 - - ro - o - - - - 8 - Get Cycle Time - UINT - 16 - 208 - - rw - c - - - - 9 - Delay Time - UDINT - 32 - 224 - - ro - c - - - - 10 - Sync0 Cycle Time - UDINT - 32 - 256 - - rw - o - - - - 11 - SM-Event Missed - UINT - 16 - 288 - - ro - c - - - - 12 - Cycle Time Too Small - UINT - 16 - 304 - - ro - c - - - - 32 - Sync Error - BOOL - 1 - 480 - - ro - c - - - - - DT1C12ARR - UINT - 16 - - 1 - 1 - - - - DT1C12 - 32 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - Elements - DT1C12ARR - 16 - 16 - - rw - o - - - - - DT1C13ARR - UINT - 16 - - 1 - 1 - - - - DT1C13 - 32 - - 0 - SubIndex 000 - USINT - 8 - 0 - - rw - - - - Elements - DT1C13ARR - 16 - 16 - - rw - o - - - - - - DT2000 - 128 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Motor SN - UINT - 16 - 16 - - rw - - - - 3 - Customized firmware version - UDINT - 32 - 48 - - ro - - - - 5 - Encoder Version - UINT - 16 - 96 - - ro - - - - 6 - Serial encoder motor SN - UINT - 16 - 112 - - ro - - - - - - DT2001 - 672 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - MCU firmware Version - UINT - 16 - 16 - - ro - - - - 2 - Fpga firmware Version - UINT - 16 - 32 - - ro - - - - 11 - Drive serial number - UINT - 16 - 176 - - rw - - - - 12 - Drive voltage class - UINT - 16 - 192 - - ro - - - - 13 - Drive rated power - UDINT - 32 - 208 - - ro - - - - 15 - Drive maximum output power - UDINT - 32 - 240 - - ro - - - - 17 - Drive rated output current - UDINT - 32 - 272 - - ro - - - - 19 - Drive maximum output current - UDINT - 32 - 304 - - ro - - - - 41 - DC bus overvoltage protective point - UINT - 16 - 656 - - rw - - - - - - DT2002 - 688 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Control mode selection - UINT - 16 - 16 - - rw - - - - 2 - Absolute system selection - UINT - 16 - 32 - - rw - - - - 3 - Rotating direction - UINT - 16 - 48 - - rw - - - - 4 - Output pulse phase - UINT - 16 - 64 - - rw - - - - 6 - Disable operation option Code - INT - 16 - 96 - - rw - - - - 7 - NO2 Fault Reaction option Code - INT - 16 - 112 - - rw - - - - 8 - Stop mode at limit switch signal - UINT - 16 - 128 - - rw - - - - 9 - Stop mode at NO.1 fault - UINT - 16 - 144 - - rw - - - - 10 - Delay from brake output on to command received - UINT - 16 - 160 - - rw - - - - 11 - Delay from brake output off to motor de-energized - UINT - 16 - 176 - - rw - - - - 12 - Motor speed threshold at brake output off in rotating state - UINT - 16 - 192 - - rw - - - - 13 - Delay from servo off to brake output off in the rotating state - UINT - 16 - 208 - - rw - - - - 16 - LED warning display selection - UINT - 16 - 256 - - rw - - - - 18 - MainPower Cutoff Reaction Option Code - UINT - 16 - 288 - - rw - - - - 19 - QuickStop Reaction Option Code - UINT - 16 - 304 - - rw - - - - 22 - Allowed minimum braking resistance - UINT - 16 - 352 - - ro - - - - 23 - Power of built-in braking resistor - UINT - 16 - 368 - - ro - - - - 24 - Resistance of built-in braking resistor - UINT - 16 - 384 - - ro - - - - 25 - Resistor heat dissipation coefficient - UINT - 16 - 400 - - rw - - - - 26 - braking resistor type - UINT - 16 - 416 - - rw - - - - 27 - Power of external dynamic resistor - UINT - 16 - 432 - - rw - - - - 28 - Resistance of external braking resistor - UINT - 16 - 448 - - rw - - - - 31 - User password - UINT - 16 - 496 - - wo - - - - 32 - Parameter initialization - UINT - 16 - 512 - - rw - - - - 33 - Default keypad display - UINT - 16 - 528 - - rw - - - - 36 - Panel data refresh rate - UINT - 16 - 576 - - rw - - - - 42 - OEM password - UINT - 16 - 672 - - wo - - - - - DT2003 - 1056 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 3 - DI1 function selection - UINT - 16 - 48 - - rw - - - - 4 - DI1 logic selection - UINT - 16 - 64 - - rw - - - - 5 - DI2 function selection - UINT - 16 - 80 - - rw - - - - 6 - DI2 logic selection - UINT - 16 - 96 - - rw - - - - 7 - DI3 function selection - UINT - 16 - 112 - - rw - - - - 8 - DI3 logic selection - UINT - 16 - 128 - - rw - - - - 9 - DI4 function selection - UINT - 16 - 144 - - rw - - - - 10 - DI4 logic selection - UINT - 16 - 160 - - rw - - - - 11 - DI5 function selection - UINT - 16 - 176 - - rw - - - - 12 - DI5 logic selection - UINT - 16 - 192 - - rw - - - - 51 - AI1 Offset - INT - 16 - 816 - - rw - - - - 52 - AI1 Filter - UINT - 16 - 832 - - rw - - - - 54 - AI1 Dead Zone - UINT - 16 - 864 - - rw - - - - 55 - AI1 Zero Drifting - INT - 16 - 880 - - rw - - - - 61 - DI1 filtertime constant - UINT - 16 - 976 - - rw - - - - 62 - DI2 filtertime constant - UINT - 16 - 992 - - rw - - - - 63 - DI3 filtertime constant - UINT - 16 - 1008 - - rw - - - - 64 - DI4 filtertime constant - UINT - 16 - 1024 - - rw - - - - 65 - DI5 filtertime constant - UINT - 16 - 1040 - - rw - - - - - DT2004 - 864 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - DO1 Function Selection - UINT - 16 - 16 - - rw - - - - 2 - DO1 Logic Level Selection - UINT - 16 - 32 - - rw - - - - 3 - DO2 Function Selection - UINT - 16 - 48 - - rw - - - - 4 - DO2 Logic Level Selection - UINT - 16 - 64 - - rw - - - - 5 - DO3 Function Selection - UINT - 16 - 80 - - rw - - - - 6 - DO3 Logic Level Selection - UINT - 16 - 96 - - rw - - - - 23 - DO OutPut Source Select - UINT - 16 - 368 - - rw - - - - 24 - ECAT Lost Force DO OutPut Logic - UINT - 16 - 384 - - rw - - - - 51 - AO1 Source Select - UINT - 16 - 816 - - rw - - - - 52 - AO1 Offset - INT - 16 - 832 - - rw - - - - 53 - AO1 Multiplying - INT - 16 - 848 - - rw - - - - - DT2005 - 1152 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 5 - Time constant of first-order low-pass filter - UINT - 16 - 80 - - rw - - - - 7 - Time constant of moving average filter 1 - UINT - 16 - 112 - - rw - - - - 8 - Numerator of electronic gear ratio - UDINT - 32 - 128 - - rw - - - - 10 - Denominator of electronic gear ratio - UDINT - 32 - 160 - - rw - - - - 18 - Encoder frequency division pulses - UDINT - 32 - 288 - - rw - - - - 20 - Speed feedforward control selection - UINT - 16 - 320 - - rw - - - - 31 - Local home mode - UINT - 16 - 496 - - rw - - - - 36 - Time of home searching - UINT - 16 - 576 - - rw - - - - 37 - Local home position offset - DINT - 32 - 592 - - rw - - - - 39 - Servo pulse output source - UINT - 16 - 624 - - rw - - - - 42 - Output polarity of Z pulse - UINT - 16 - 672 - - rw - - - - 51 - Mechanical Gear ratio numerator of absolute encode mode 2 - UINT - 16 - 816 - - rw - - - - 52 - Mechanical Gear ratio denominator of absolute encode mode 2 - UINT - 16 - 832 - - rw - - - - 53 - Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) - UDINT - 32 - 848 - - rw - - - - 55 - Max value of mechanical absolute position(inc) of absolute encode mode 2(High) - UDINT - 32 - 880 - - rw - - - - 59 - Trq Reference of Mechanical Homing - UINT - 16 - 944 - - rw - - - - 61 - Position Coin Hold Time - UINT - 16 - 976 - - rw - - - - 67 - Time Unit of Homing - UINT - 16 - 1072 - - rw - - - - 71 - Time constant of moving average filter 2 - UINT - 16 - 1136 - - rw - - - - - DT2006 - 896 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 4 - Keypad setting value of speed reference - INT - 16 - 64 - - rw - - - - 5 - DI Jog speed reference - UINT - 16 - 80 - - rw - - - - 6 - Acceleration ramp time constant of speed reference - UINT - 16 - 96 - - rw - - - - 7 - Deceleration ramp time constant of speed reference - UINT - 16 - 112 - - rw - - - - 8 - Maximum speed limit - UINT - 16 - 128 - - rw - - - - 9 - Forward speed threshold - UINT - 16 - 144 - - rw - - - - 10 - Reverse speed threshold - UINT - 16 - 160 - - rw - - - - 11 - Quick decelaration coefficient - UINT - 16 - 176 - - rw - - - - 12 - Torque feedforward selection - UINT - 16 - 192 - - rw - - - - 13 - Acceleration/Deceleration ramp time constant of jog speed reference - UINT - 16 - 208 - - rw - - - - 14 - Speed feedforward filter time constant - UINT - 16 - 224 - - rw - - - - 16 - Speed threshold of Zero Hold signal - UINT - 16 - 256 - - rw - - - - 17 - Speed threshold of motor rotation signal - UINT - 16 - 272 - - rw - - - - 18 - Speed threshold of Spd Reach signal - UINT - 16 - 288 - - rw - - - - 19 - Speed threshold of Spd Arrive signal - UINT - 16 - 304 - - rw - - - - 20 - Speed threshold of Zero Spd signal - UINT - 16 - 320 - - rw - - - - 51 - Spd SCurve Enable - UINT - 16 - 816 - - rw - - - - 52 - Spd SCurve Acceleration UP - UINT - 16 - 832 - - rw - - - - 53 - Spd SCurve Acceleration Down - UINT - 16 - 848 - - rw - - - - 54 - Spd SCurve Deceleration UP - UINT - 16 - 864 - - rw - - - - 55 - Spd SCurve Deceleration Down - UINT - 16 - 880 - - rw - - - - - DT2007 - 640 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 4 - Keypad setting value of torque reference - INT - 16 - 64 - - rw - - - - 6 - Torque reference filter time 1 - UINT - 16 - 96 - - rw - - - - 7 - Torque reference filter time 2 - UINT - 16 - 112 - - rw - - - - 10 - Internal forward torque limit - UINT - 16 - 160 - - rw - - - - 11 - Internal reverse torque limit - UINT - 16 - 176 - - rw - - - - 16 - Emergency stop torque - UINT - 16 - 256 - - rw - - - - 20 - Forward speed limit/Speed limit 1 in local torque control - UINT - 16 - 320 - - rw - - - - 21 - Reverse speed limit/Speed limit 2 in local torque control - UINT - 16 - 336 - - rw - - - - 22 - Base value for torque reached - UINT - 16 - 352 - - rw - - - - 23 - Threshold of torque reached valid - UINT - 16 - 368 - - rw - - - - 24 - Threshold of torque reached invalid - UINT - 16 - 384 - - rw - - - - 25 - Depth of field-weakening - UINT - 16 - 400 - - rw - - - - 26 - Maximum field-weakening current - UINT - 16 - 416 - - rw - - - - 27 - Field-weakening enable - UINT - 16 - 432 - - rw - - - - 28 - Field-weakening gain - UINT - 16 - 448 - - rw - - - - 29 - Field-weakening point speed - UINT - 16 - 464 - - ro - - - - 36 - Motor output calibration enable - UINT - 16 - 576 - - rw - - - - 37 - The second-stage torque reference filter time - UINT - 16 - 592 - - rw - - - - 38 - Torque reference filter type select - UINT - 16 - 608 - - rw - - - - 39 - Biquad low pass filter damping - UINT - 16 - 624 - - rw - - - - - DT2008 - 1056 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Speed-loop Gain - UINT - 16 - 16 - - rw - - - - 2 - Speed-loop integral time constant - UINT - 16 - 32 - - rw - - - - 3 - Position-loop Gain - UINT - 16 - 48 - - rw - - - - 4 - The second speed loop gain - UINT - 16 - 64 - - rw - - - - 5 - The second speed loop integral time constant - UINT - 16 - 80 - - rw - - - - 6 - The second position loop gain - UINT - 16 - 96 - - rw - - - - 9 - Second gain mode setting - UINT - 16 - 144 - - rw - - - - 10 - Gain switchover condition - UINT - 16 - 160 - - rw - - - - 11 - Gain switchover delay - UINT - 16 - 176 - - rw - - - - 12 - Gain switchover level - UINT - 16 - 192 - - rw - - - - 13 - Gain switchover hysteresis - UINT - 16 - 208 - - rw - - - - 14 - Position gain switchover time - UINT - 16 - 224 - - rw - - - - 16 - Average value of load inertia ratio - UINT - 16 - 256 - - rw - - - - 18 - Zero-Phase delay time - UINT - 16 - 288 - - rw - - - - 19 - Speed feedforward filter time constant - UINT - 16 - 304 - - rw - - - - 20 - Speed feedforward gain - UINT - 16 - 320 - - rw - - - - 21 - Torque feedforward filter time constant - UINT - 16 - 336 - - rw - - - - 22 - Torque feedforward gain - UINT - 16 - 352 - - rw - - - - 23 - Speed feedback filter - UINT - 16 - 368 - - rw - - - - 24 - Cut-off frequency of speed feedback low-pass filter - UINT - 16 - 384 - - rw - - - - 25 - Pseudo-differential forward feedback control coefficient - UINT - 16 - 400 - - rw - - - - 28 - Cut-off frequency of speed observer - UINT - 16 - 448 - - rw - - - - 29 - Modified inertia coefficient of speed observer - UINT - 16 - 464 - - rw - - - - 30 - Filter time of speed observer - UINT - 16 - 480 - - rw - - - - 32 - Cut-off frequency of torque disturbance observer - UINT - 16 - 512 - - rw - - - - 33 - Compensation gain of torque disturbance observer - UINT - 16 - 528 - - rw - - - - 34 - Modified inertia coefficient of torque disturbance observer - UINT - 16 - 544 - - rw - - - - 41 - Speed observer enable - UINT - 16 - 656 - - rw - - - - 43 - Module control enable - UINT - 16 - 688 - - rw - - - - 44 - Module control gain - UINT - 16 - 704 - - rw - - - - 47 - Module feedforward value - UINT - 16 - 752 - - rw - - - - 54 - 3rd medium and low-frequency vibration suppression frequency - UINT - 16 - 864 - - rw - - - - 55 - 3rd compensation gain of medium and low-frequency vibration suppression frequency - UINT - 16 - 880 - - rw - - - - 57 - 3rd phase modulation of medium and low-frequency vibration suppression frequency - UINT - 16 - 912 - - rw - - - - 60 - 4th medium and low-frequency vibration suppression frequency - UINT - 16 - 960 - - rw - - - - 61 - 4th compensation gain of medium and low-frequency vibration suppression frequency - UINT - 16 - 976 - - rw - - - - 62 - 4th phase modulation of medium and low-frequency vibration suppression frequency - UINT - 16 - 992 - - rw - - - - 63 - Time constant of position loop integration - UINT - 16 - 1008 - - rw - - - - 64 - 2nd time constant of position loop integration - UINT - 16 - 1024 - - rw - - - - 65 - Speed observation feedback source selection - UINT - 16 - 1040 - - rw - - - - - DT2009 - 848 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Auto-adjusting mode - UINT - 16 - 16 - - rw - - - - 2 - Rigidity level selection - UINT - 16 - 32 - - rw - - - - 3 - Working mode of self-adaptive notch - UINT - 16 - 48 - - rw - - - - 4 - Online inertia auto-tuning mode - UINT - 16 - 64 - - rw - - - - 6 - Offline inertia auto-tuning mode - UINT - 16 - 96 - - rw - - - - 7 - Maximum speed for inertia autotuning - UINT - 16 - 112 - - rw - - - - 8 - Acceleration/Deceleration time for inertia autotuning - UINT - 16 - 128 - - rw - - - - 9 - Interval after an inertia autotuning - UINT - 16 - 144 - - rw - - - - 10 - Motor revolutions for an inertia auto-tuning - UINT - 16 - 160 - - rw - - - - 12 - Vibration threshold setting - UINT - 16 - 192 - - rw - - - - 13 - 1st notch frequency - UINT - 16 - 208 - - rw - - - - 14 - 1st notch width level - UINT - 16 - 224 - - rw - - - - 15 - 1st notch attenuation level - UINT - 16 - 240 - - rw - - - - 16 - 2nd notch frequency - UINT - 16 - 256 - - rw - - - - 17 - 2nd notch width level - UINT - 16 - 272 - - rw - - - - 18 - 2nd notch attenuation level - UINT - 16 - 288 - - rw - - - - 19 - 3rd notch frequency - UINT - 16 - 304 - - rw - - - - 20 - 3rd notch width level - UINT - 16 - 320 - - rw - - - - 21 - 3rd notch attenuation level - UINT - 16 - 336 - - rw - - - - 22 - 4th notch frequency - UINT - 16 - 352 - - rw - - - - 23 - 4th notch width level - UINT - 16 - 368 - - rw - - - - 24 - 4th notch attenuation level - UINT - 16 - 384 - - rw - - - - 25 - Obtained resonance frequency - UINT - 16 - 400 - - ro - - - - 26 - 1st anti-resonance point frequency - UINT - 16 - 416 - - rw - - - - 27 - 2nd anti-resonance point frequency - UINT - 16 - 432 - - rw - - - - 33 - Gravity compensation value - INT - 16 - 528 - - rw - - - - 34 - Forward friction compensation - INT - 16 - 544 - - rw - - - - 35 - Reverse friction compensation - INT - 16 - 560 - - rw - - - - 36 - Friction compensation speed - UINT - 16 - 576 - - rw - - - - 37 - Friction compensation speed selection - UINT - 16 - 592 - - rw - - - - 38 - Vibration monitor time - UINT - 16 - 608 - - rw - - - - 39 - 1st terminal low-frequency vibration suppression frequency - UINT - 16 - 624 - - rw - - - - 40 - 1st filter order of low-frequency vibration suppression frequency - UINT - 16 - 640 - - rw - - - - 42 - 5th notch frequency - UINT - 16 - 672 - - rw - - - - 43 - 5th notch width level - UINT - 16 - 688 - - rw - - - - 44 - 5th notch attenuation level - UINT - 16 - 704 - - rw - - - - 45 - 2nd terminal low-frequency vibration suppression frequency - UINT - 16 - 720 - - rw - - - - 46 - 2nd damping frequency ratio of low-frequency vibration suppression frequency - UINT - 16 - 736 - - rw - - - - 48 - 2nd damping coefficient of low-frequency vibration suppression frequency - UINT - 16 - 768 - - rw - - - - 50 - 3rd terminal low-frequency vibration suppression frequency - UINT - 16 - 800 - - rw - - - - 51 - 3rd damping frequency ratio of low-frequency vibration suppression frequency - UINT - 16 - 816 - - rw - - - - 53 - 3rd damping coefficient of low-frequency vibration suppression frequency - UINT - 16 - 832 - - rw - - - - - DT200A - 1536 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Power inputphase loss protection disable - UINT - 16 - 16 - - rw - - - - 2 - Absolute position limit set - UINT - 16 - 32 - - rw - - - - 5 - Motor overload protection gain - UINT - 16 - 80 - - rw - - - - 9 - Overspeed threshold - UINT - 16 - 144 - - rw - - - - 11 - Local following error window - UDINT - 32 - 176 - - rw - - - - 13 - Runaway protection enable - UINT - 16 - 208 - - rw - - - - 19 - Over Temperature value of IPM - UINT - 16 - 304 - - rw - - - - 20 - Touch Probe 1 filter time constant - UINT - 16 - 320 - - rw - - - - 21 - Touch Probe 2 filter time constant - UINT - 16 - 336 - - rw - - - - 22 - STO Display Function Selection - UINT - 16 - 352 - - rw - - - - 24 - Filter time constant of TZ signal - UINT - 16 - 384 - - rw - - - - 26 - Filter time of speed feedback display - UINT - 16 - 416 - - rw - - - - 27 - Motor overload shielding - UINT - 16 - 432 - - rw - - - - 28 - Speed DO Filter time constant - UINT - 16 - 448 - - rw - - - - 30 - Full Closed-loop(ABZ) Filter time constant - UINT - 16 - 480 - - rw - - - - 33 - Overheat protection time duration for locked rotor - UINT - 16 - 528 - - rw - - - - 34 - Overheat protection for locked rotor enable - UINT - 16 - 544 - - rw - - - - 37 - Absolute Encode multi-turns error forbidden - UINT - 16 - 592 - - rw - - - - 41 - Compensation Function - UINT - 16 - 656 - - rw - - - - 50 - Over Temperature value of discharge tube - UINT - 16 - 800 - - rw - - - - 51 - Encoder communiction error threshold - UINT - 16 - 816 - - rw - - - - 52 - Phase lack threshold - UINT - 16 - 832 - - rw - - - - 53 - Over Temperature value of Encoder - UINT - 16 - 848 - - rw - - - - 54 - TouchProbe DI Turn-on Compensation Time - INT - 16 - 864 - - rw - - - - 55 - TouchProbe DI Turn-off Compensation Time - INT - 16 - 880 - - rw - - - - 56 - Runaway current threshold - UINT - 16 - 896 - - rw - - - - 57 - Fault reset delay time - UINT - 16 - 912 - - rw - - - - 58 - Runaway speed threshold - UINT - 16 - 928 - - rw - - - - 59 - Runaway speed filter time constant - UINT - 16 - 944 - - rw - - - - 60 - Runaway protection time window - UINT - 16 - 960 - - rw - - - - 61 - BlackBox Mode Select - UINT - 16 - 976 - - rw - - - - 62 - BlackBox Selected Error Code - UINT - 16 - 992 - - rw - - - - 63 - BlackBox Trig Source - UINT - 16 - 1008 - - rw - - - - 64 - BlackBox Trig Level - DINT - 32 - 1024 - - rw - - - - 66 - BlackBox Trig Level Select - UINT - 16 - 1056 - - rw - - - - 67 - BlackBox Trig Position - UINT - 16 - 1072 - - rw - - - - 68 - BlackBox Trig Frequency Select - UINT - 16 - 1088 - - rw - - - - 71 - The 2nd over speed threshold - UINT - 16 - 1136 - - rw - - - - 72 - Motor over load monitor switch - UINT - 16 - 1152 - - rw - - - - 73 - Maximum ramp stop time - UINT - 16 - 1168 - - rw - - - - 74 - STO Disconnect filter time - UINT - 16 - 1184 - - rw - - - - 75 - STO Mismatch filter time - UINT - 16 - 1200 - - rw - - - - 76 - STO Servo off filter time - UINT - 16 - 1216 - - rw - - - - 86 - Motor Offline Trq Limit - UINT - 16 - 1376 - - rw - - - - 87 - Motor Offline Filter Time - UINT - 16 - 1392 - - rw - - - - 91 - Filter Time Constant of Spd Display - UINT - 16 - 1456 - - rw - - - - 92 - Filter Time Constant of Trq Display - INT - 16 - 1472 - - rw - - - - 93 - Filter Time Constant of Position Display - UINT - 16 - 1488 - - rw - - - - 94 - Filter Time Constant of Voltage Display - UINT - 16 - 1504 - - rw - - - - 95 - Filter Time Constant of Temp Display - UINT - 16 - 1520 - - rw - - - - - DT200B - 1584 - - 0 - Number of Entries - USINT - 8 - 0 - - ro - - - - 1 - Actual motor rotational speed - INT - 16 - 16 - - ro - T - - - - 2 - Speed reference - INT - 16 - 32 - - ro - T - - - - 3 - Internal torque reference - INT - 16 - 48 - - ro - T - - - - 4 - Monitored DI states - UINT - 16 - 64 - - ro - T - - - - 6 - Monitored DO states - UINT - 16 - 96 - - ro - T - - - - 8 - Absolute position counter - DINT - 32 - 128 - - ro - T - - - - 10 - Mechanical angle - UINT - 16 - 160 - - ro - T - - - - 11 - Electrical angle - UINT - 16 - 176 - - ro - T - - - - 13 - Average load rate - UINT - 16 - 208 - - ro - T - - - - 16 - Encoder position deviation counter - DINT - 32 - 256 - - ro - T - - - - 18 - Feedback pulse counter - DINT - 32 - 288 - - ro - T - - - - 20 - Total power-on time - UDINT - 32 - 320 - - ro - T - - - - 22 - AI1 Voltage DisPlay - INT - 16 - 352 - - ro - T - - - - 25 - Phase current valid value - UINT - 16 - 400 - - ro - T - - - - 27 - Bus voltage - UINT - 16 - 432 - - ro - T - - - - 28 - Module temperature - UINT - 16 - 448 - - ro - T - - - - 29 - Absolute encoder fault info. from FPGA - UINT - 16 - 464 - - ro - - - - 30 - Axis state from FPGA - UINT - 16 - 480 - - ro - - - - 31 - Axis fault info. from FPGA - UINT - 16 - 496 - - ro - - - - 32 - Encoder internal fault info. - UINT - 16 - 512 - - rw - - - - 34 - Displayed fault record - UINT - 16 - 544 - - rw - - - - 35 - Fault code - UINT - 16 - 560 - - ro - - - - 36 - Time stamp upon displayed fault - UDINT - 32 - 576 - - ro - - - - 38 - Current rotational speed upon displayed fault - INT - 16 - 608 - - ro - - - - 39 - Current U upon displayed fault - INT - 16 - 624 - - ro - - - - 40 - Current V upon displayed fault - INT - 16 - 640 - - ro - - - - 41 - Bus voltage upon displayed fault - UINT - 16 - 656 - - ro - - - - 42 - Input terminal state upon displayed fault - UINT - 16 - 672 - - ro - - - - 44 - Output terminal state upon displayed fault - UINT - 16 - 704 - - ro - - - - 46 - Inner error code - UINT - 16 - 736 - - ro - - - - 47 - Fault message of absolute encode from Fpga upon displayed - UINT - 16 - 752 - - ro - - - - 48 - System state from Fpga upon displayed fault - UINT - 16 - 768 - - ro - - - - 49 - System fault message from Fpga upon displayed fault - UINT - 16 - 784 - - ro - - - - 50 - Encode state 1 upon displayed fault - UINT - 16 - 800 - - ro - - - - 52 - Inner error code upon displayed fault - UINT - 16 - 832 - - ro - - - - 53 - Fpga overtime state upon displayed fault - UINT - 16 - 848 - - ro - - - - 54 - Reference position deviation - DINT - 32 - 864 - - ro - T - - - - 56 - Actual motor rotational speed(0.1rpm) - DINT - 32 - 896 - - ro - T - - - - 58 - Control bus voltage - UINT - 16 - 928 - - ro - T - - - - 59 - Mechanical absolute position inc(Low) - UDINT - 32 - 944 - - ro - T - - - - 61 - Mechanical absolute position inc(High) - DINT - 32 - 976 - - ro - T - - - - 64 - Not ready reason - UINT - 16 - 1024 - - ro - - - - 67 - Encoder temperature - UINT - 16 - 1072 - - ro - - - - 68 - Discharge load rate - UINT - 16 - 1088 - - ro - T - - - - 69 - Fpga over time state - UINT - 16 - 1104 - - ro - - - - 71 - Number of turns of absolute encode - UINT - 16 - 1136 - - ro - T - - - - 72 - Single feedback postion of absolute encode - UDINT - 32 - 1152 - - ro - T - - - - 75 - System Error - UINT - 16 - 1200 - - ro - - - - 78 - feedback postion of absolute encode(Low) - UDINT - 32 - 1248 - - ro - T - - - - 80 - feedback postion of absolute encode(High) - DINT - 32 - 1280 - - ro - T - - - - 82 - feedback postion inc of rotating load(Low) - UDINT - 32 - 1312 - - ro - T - - - - 84 - feedback postion inc of rotating load(High) - UDINT - 32 - 1344 - - ro - T - - - - 86 - Single feedback postion of rotating load - UDINT - 32 - 1376 - - ro - T - - - - 88 - IGBT Temperature - UINT - 16 - 1408 - - ro - - - - 91 - Group of unusual function code - UINT - 16 - 1456 - - ro - - - - 92 - Offset of unusual function code - UINT - 16 - 1472 - - ro - - - - 95 - Single Power-On Time - UDINT - 32 - 1520 - - ro - T - - - - 97 - Single Power-On Time upon displayed fault - UDINT - 32 - 1552 - - ro - - - - - DT200D - 400 - - 0 - Number of Entries - USINT - 8 - 0 - - ro - - - - 1 - Software reset - UINT - 16 - 16 - - rw - - - - 2 - Fault reset - UINT - 16 - 32 - - rw - - - - 3 - Offline inertia autotuning selection - UINT - 16 - 48 - - rw - - - - 5 - Encoder ROM reading/writing - UINT - 16 - 80 - - rw - - - - 6 - Emergency stop - UINT - 16 - 96 - - rw - - - - 11 - AI1 Self-Adjust of Voltage Offset - UINT - 16 - 176 - - rw - - - - 13 - UV phase current auto-tuning - UINT - 16 - 208 - - rw - - - - 18 - Forced DI/DO setting - UINT - 16 - 288 - - rw - - - - 19 - Forced DI level - UINT - 16 - 304 - - rw - - - - 20 - Forced DO setting - UINT - 16 - 320 - - rw - - - - 21 - Absolute Encode Fault Reset - UINT - 16 - 336 - - rw - - - - 24 - Cogging torque self-learning - UINT - 16 - 384 - - rw - - - - - DT200E - 1568 - - 0 - Number of Entries - USINT - 8 - 0 - - ro - - - - 1 - Node address - UINT - 16 - 16 - - rw - - - - 2 - Update function code values written via communication to EEPROM - UINT - 16 - 32 - - rw - - - - 21 - station auto inc address - UINT - 16 - 336 - - ro - - - - 22 - station alias - UINT - 16 - 352 - - rw - - - - 23 - Sync lost window - UINT - 16 - 368 - - rw - - - - 25 - Sync lost counter - UINT - 16 - 400 - - ro - - - - 26 - Port 0 invalid frame counter - UINT - 16 - 416 - - ro - - - - 27 - Port 1 invalid frame counter - UINT - 16 - 432 - - ro - - - - 28 - Port 0/1 transfer error counter - UINT - 16 - 448 - - ro - - - - 29 - process unit and PDI error counter - UINT - 16 - 464 - - ro - - - - 30 - Port 0/1 lost counter - UINT - 16 - 480 - - ro - - - - 32 - Sync mode set - UINT - 16 - 512 - - rw - - - - 33 - Sync error window - UINT - 16 - 528 - - rw - - - - 34 - EtherCAT network state and link state - UINT - 16 - 544 - - ro - - - - 35 - CSP postion increment over counter - UINT - 16 - 560 - - rw - - - - 36 - ECAT AL Error Code - UINT - 16 - 576 - - ro - - - - 37 - Enhanced link detection enable - UINT - 16 - 592 - - rw - - - - 38 - Reset EtherCAT xml file - UINT - 16 - 608 - - rw - - - - 74 - EtherCAT port control mode and state display - UINT - 16 - 1184 - - ro - - - - 94 - EtherCAT COE version number - UINT - 16 - 1504 - - ro - - - - 97 - EtherCAT xml file version number - UINT - 16 - 1552 - - ro - - - - - DT200F - 720 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Encoder feedback mode - UINT - 16 - 16 - - rw - - - - 2 - Running mode of external encoder - UINT - 16 - 32 - - rw - - - - 3 - SecEncoder Absolute system selection - UINT - 16 - 48 - - rw - - - - 4 - SecEncoder Type selection - UINT - 16 - 64 - - rw - - - - 5 - External encoder pulses per motor revolution - UDINT - 32 - 80 - - rw - - - - 9 - Hybrid deviation excess setting - UDINT - 32 - 144 - - rw - - - - 11 - Hybrid deviation clear setting - UINT - 16 - 176 - - rw - - - - 14 - First-order lowpass filter time of external/internal deviation - UINT - 16 - 224 - - rw - - - - 17 - Hybrid deviation counter - DINT - 32 - 272 - - ro - T - - - - 19 - Pulse feedback display of internal encoder - DINT - 32 - 304 - - ro - T - - - - 21 - Pulse feedback display of external encoder - DINT - 32 - 336 - - ro - T - - - - 23 - SecEncoder Pulse ZPhase Ignore - UINT - 16 - 368 - - rw - - - - 26 - SecEncoder Pulse Z-TouchProbe Selection - UINT - 16 - 416 - - rw - - - - - DT2012 - 1104 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - MultiSpd Function Select - UINT - 16 - 16 - - rw - R - - - - 2 - MultiSpd Final Part Select - UINT - 16 - 32 - - rw - R - - - - 3 - Time Uint of Runing - UINT - 16 - 48 - - rw - R - - - - 4 - AccTime1 - UINT - 16 - 64 - - rw - R - - - - 5 - DecTime1 - UINT - 16 - 80 - - rw - R - - - - 6 - AccTime2 - UINT - 16 - 96 - - rw - R - - - - 7 - DecTime2 - UINT - 16 - 112 - - rw - R - - - - 8 - AccTime3 - UINT - 16 - 128 - - rw - R - - - - 9 - DecTime3 - UINT - 16 - 144 - - rw - R - - - - 10 - AccTime4 - UINT - 16 - 160 - - rw - R - - - - 11 - DecTime4 - UINT - 16 - 176 - - rw - R - - - - 21 - 1st Part Spd Cmd - INT - 16 - 336 - - rw - R - - - - 22 - 1st Part Spd Runing Time - UINT - 16 - 352 - - rw - R - - - - 23 - 1st Part AccDec Time Select - UINT - 16 - 368 - - rw - R - - - - 24 - 2nd Part Spd Cmd - INT - 16 - 384 - - rw - R - - - - 25 - 2nd Part Spd Runing Time - UINT - 16 - 400 - - rw - R - - - - 26 - 2nd Part AccDec Time Select - UINT - 16 - 416 - - rw - R - - - - 27 - 3rd Part Spd Cmd - INT - 16 - 432 - - rw - R - - - - 28 - 3rd Part Spd Runing Time - UINT - 16 - 448 - - rw - R - - - - 29 - 3rd Part AccDec Time Select - UINT - 16 - 464 - - rw - R - - - - 30 - 4th Part Spd Cmd - INT - 16 - 480 - - rw - R - - - - 31 - 4th Part Spd Runing Time - UINT - 16 - 496 - - rw - R - - - - 32 - 4th Part AccDec Time Select - UINT - 16 - 512 - - rw - R - - - - 33 - 5th Part Spd Cmd - INT - 16 - 528 - - rw - R - - - - 34 - 5th Part Spd Runing Time - UINT - 16 - 544 - - rw - R - - - - 35 - 5th Part AccDec Time Select - UINT - 16 - 560 - - rw - R - - - - 36 - 6th Part Spd Cmd - INT - 16 - 576 - - rw - R - - - - 37 - 6th Part Spd Runing Time - UINT - 16 - 592 - - rw - R - - - - 38 - 6th Part AccDec Time Select - UINT - 16 - 608 - - rw - R - - - - 39 - 7th Part Spd Cmd - INT - 16 - 624 - - rw - R - - - - 40 - 7th Part Spd Runing Time - UINT - 16 - 640 - - rw - R - - - - 41 - 7th Part AccDec Time Select - UINT - 16 - 656 - - rw - R - - - - 42 - 8th Part Spd Cmd - INT - 16 - 672 - - rw - R - - - - 43 - 8th Part Spd Runing Time - UINT - 16 - 688 - - rw - R - - - - 44 - 8th Part AccDec Time Select - UINT - 16 - 704 - - rw - R - - - - 45 - 9th Part Spd Cmd - INT - 16 - 720 - - rw - R - - - - 46 - 9th Part Spd Runing Time - UINT - 16 - 736 - - rw - R - - - - 47 - 9th Part AccDec Time Select - UINT - 16 - 752 - - rw - R - - - - 48 - 10th Part Spd Cmd - INT - 16 - 768 - - rw - R - - - - 49 - 10th Part Spd Runing Time - UINT - 16 - 784 - - rw - R - - - - 50 - 10th Part AccDec Time Select - UINT - 16 - 800 - - rw - R - - - - 51 - 11th Part Spd Cmd - INT - 16 - 816 - - rw - R - - - - 52 - 11th Part Spd Runing Time - UINT - 16 - 832 - - rw - R - - - - 53 - 11th Part AccDec Time Select - UINT - 16 - 848 - - rw - R - - - - 54 - 12th Part Spd Cmd - INT - 16 - 864 - - rw - R - - - - 55 - 12th Part Spd Runing Time - UINT - 16 - 880 - - rw - R - - - - 56 - 12th Part AccDec Time Select - UINT - 16 - 896 - - rw - R - - - - 57 - 13th Part Spd Cmd - INT - 16 - 912 - - rw - R - - - - 58 - 13th Part Spd Runing Time - UINT - 16 - 928 - - rw - R - - - - 59 - 13th Part AccDec Time Select - UINT - 16 - 944 - - rw - R - - - - 60 - 14th Part Spd Cmd - INT - 16 - 960 - - rw - R - - - - 61 - 14th Part Spd Runing Time - UINT - 16 - 976 - - rw - R - - - - 62 - 14th Part AccDec Time Select - UINT - 16 - 992 - - rw - R - - - - 63 - 15th Part Spd Cmd - INT - 16 - 1008 - - rw - R - - - - 64 - 15th Part Spd Runing Time - UINT - 16 - 1024 - - rw - R - - - - 65 - 15th Part AccDec Time Select - UINT - 16 - 1040 - - rw - R - - - - 66 - 16th Part Spd Cmd - INT - 16 - 1056 - - rw - R - - - - 67 - 16th Part Spd Runing Time - UINT - 16 - 1072 - - rw - R - - - - 68 - 16th Part AccDec Time Select - UINT - 16 - 1088 - - rw - R - - - - - DT2017 - 1520 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - VDI1 Terminal Function Selection - UINT - 16 - 16 - - rw - - - - 2 - VDI1 Terminal Logic Selection - UINT - 16 - 32 - - rw - - - - 3 - VDI2 Terminal Function Selection - UINT - 16 - 48 - - rw - - - - 4 - VDI2 Terminal Logic Selection - UINT - 16 - 64 - - rw - - - - 5 - VDI3 Terminal Function Selection - UINT - 16 - 80 - - rw - - - - 6 - VDI3 Terminal Logic Selection - UINT - 16 - 96 - - rw - - - - 7 - VDI4 Terminal Function Selection - UINT - 16 - 112 - - rw - - - - 8 - VDI4 Terminal Logic Selection - UINT - 16 - 128 - - rw - - - - 9 - VDI5 Terminal Function Selection - UINT - 16 - 144 - - rw - - - - 10 - VDI5 Terminal Logic Selection - UINT - 16 - 160 - - rw - - - - 11 - VDI6 Terminal Function Selection - UINT - 16 - 176 - - rw - - - - 12 - VDI6 Terminal Logic Selection - UINT - 16 - 192 - - rw - - - - 13 - VDI7 Terminal Function Selection - UINT - 16 - 208 - - rw - - - - 14 - VDI7 Terminal Logic Selection - UINT - 16 - 224 - - rw - - - - 15 - VDI8 Terminal Function Selection - UINT - 16 - 240 - - rw - - - - 16 - VDI8 Terminal Logic Selection - UINT - 16 - 256 - - rw - - - - 17 - VDI9 Terminal Function Selection - UINT - 16 - 272 - - rw - - - - 18 - VDI9 Terminal Logic Selection - UINT - 16 - 288 - - rw - - - - 19 - VDI10 Terminal Function Selection - UINT - 16 - 304 - - rw - - - - 20 - VDI10 Terminal Logic Selection - UINT - 16 - 320 - - rw - - - - 21 - VDI11 Terminal Function Selection - UINT - 16 - 336 - - rw - - - - 22 - VDI11 Terminal Logic Selection - UINT - 16 - 352 - - rw - - - - 23 - VDI12 Terminal Function Selection - UINT - 16 - 368 - - rw - - - - 24 - VDI12 Terminal Logic Selection - UINT - 16 - 384 - - rw - - - - 25 - VDI13 Terminal Function Selection - UINT - 16 - 400 - - rw - - - - 26 - VDI13 Terminal Logic Selection - UINT - 16 - 416 - - rw - - - - 27 - VDI14 Terminal Function Selection - UINT - 16 - 432 - - rw - - - - 28 - VDI14 Terminal Logic Selection - UINT - 16 - 448 - - rw - - - - 29 - VDI15 Terminal Function Selection - UINT - 16 - 464 - - rw - - - - 30 - VDI15 Terminal Logic Selection - UINT - 16 - 480 - - rw - - - - 31 - VDI16 Terminal Function Selection - UINT - 16 - 496 - - rw - - - - 32 - VDI16 Terminal Logic Selection - UINT - 16 - 512 - - rw - - - - 33 - VDO virtual level - UINT - 16 - 528 - - ro - - - - 34 - VDO1 Terminal Function Selection - UINT - 16 - 544 - - rw - - - - 35 - VDO1 Terminal Logic Level Selection - UINT - 16 - 560 - - rw - - - - 36 - VDO2 Terminal Function Selection - UINT - 16 - 576 - - rw - - - - 37 - VDO2 Terminal Logic Level Selection - UINT - 16 - 592 - - rw - - - - 38 - VDO3 Terminal Function Selection - UINT - 16 - 608 - - rw - - - - 39 - VDO3 Terminal Logic Level Selection - UINT - 16 - 624 - - rw - - - - 40 - VDO4 Terminal Function Selection - UINT - 16 - 640 - - rw - - - - 41 - VDO4 Terminal Logic Level Selection - UINT - 16 - 656 - - rw - - - - 42 - VDO5 Terminal Function Selection - UINT - 16 - 672 - - rw - - - - 43 - VDO5 Terminal Logic Level Selection - UINT - 16 - 688 - - rw - - - - 44 - VDO6 Terminal Function Selection - UINT - 16 - 704 - - rw - - - - 45 - VDO6 Terminal Logic Level Selection - UINT - 16 - 720 - - rw - - - - 46 - VDO7 Terminal Function Selection - UINT - 16 - 736 - - rw - - - - 47 - VDO7 Terminal Logic Level Selection - UINT - 16 - 752 - - rw - - - - 48 - VDO8 Terminal Function Selection - UINT - 16 - 768 - - rw - - - - 49 - VDO8 Terminal Logic Level Selection - UINT - 16 - 784 - - rw - - - - 50 - VDO9 Terminal Function Selection - UINT - 16 - 800 - - rw - - - - 51 - VDO9 Terminal Logic Level Selection - UINT - 16 - 816 - - rw - - - - 52 - VDO10 Terminal Function Selection - UINT - 16 - 832 - - rw - - - - 53 - VDO10 Terminal Logic Level Selection - UINT - 16 - 848 - - rw - - - - 54 - VDO11 Terminal Function Selection - UINT - 16 - 864 - - rw - - - - 55 - VDO11 Terminal Logic Level Selection - UINT - 16 - 880 - - rw - - - - 56 - VDO12 Terminal Function Selection - UINT - 16 - 896 - - rw - - - - 57 - VDO12 Terminal Logic Level Selection - UINT - 16 - 912 - - rw - - - - 58 - VDO13 Terminal Function Selection - UINT - 16 - 928 - - rw - - - - 59 - VDO13 Terminal Logic Level Selection - UINT - 16 - 944 - - rw - - - - 60 - VDO14 Terminal Function Selection - UINT - 16 - 960 - - rw - - - - 61 - VDO14 Terminal Logic Level Selection - UINT - 16 - 976 - - rw - - - - 62 - VDO15 Terminal Function Selection - UINT - 16 - 992 - - rw - - - - 63 - VDO15 Terminal Logic Level Selection - UINT - 16 - 1008 - - rw - - - - 64 - VDO16 Terminal Function Selection - UINT - 16 - 1024 - - rw - - - - 65 - VDO16 Terminal Logic Level Selection - UINT - 16 - 1040 - - rw - - - - 91 - VDI Enable - UINT - 16 - 1456 - - rw - R - - - - 92 - VDI Default Value - UINT - 16 - 1472 - - rw - R - - - - 93 - VDO Enable - UINT - 16 - 1488 - - rw - R - - - - 94 - VDO Default Value - UINT - 16 - 1504 - - rw - R - - - - - DT2018 - 288 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Enable Comparison - UINT - 16 - 16 - - rw - R - - - - 2 - Comparison PosFdb Source Select - UINT - 16 - 32 - - rw - R - - - - 3 - Encoder Resolution - UINT - 16 - 48 - - rw - R - - - - 4 - Mode Of Comparison - UINT - 16 - 64 - - rw - R - - - - 5 - Current Position As Zero - UINT - 16 - 80 - - rw - R - - - - 6 - Output Duration - UINT - 16 - 96 - - rw - R - - - - 7 - Comparison ABZ OutPut Logic - UINT - 16 - 112 - - rw - R - - - - 8 - Starting Point Number - UINT - 16 - 128 - - rw - R - - - - 9 - Ending Point Number - UINT - 16 - 144 - - rw - R - - - - 10 - Comparison Status - UINT - 16 - 160 - - ro - T - - - - 11 - Current Position - DINT - 32 - 176 - - ro - T - - - - 13 - Position Offset - DINT - 32 - 208 - - rw - R - - - - 15 - Comparison OutPut Delay Compensation - INT - 16 - 240 - - rw - R - - - - 16 - Lilited number of Comparison Cycle Times - UINT - 16 - 256 - - rw - R - - - - 17 - Comparison ABZ OutPut Function - UINT - 16 - 272 - - rw - R - - - - - DT2019 - 1936 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - 1st Comparing Position - DINT - 32 - 16 - - rw - R - - - - 3 - 1st Point Property - UINT - 16 - 48 - - rw - R - - - - 4 - 2nd Comparing Position - DINT - 32 - 64 - - rw - R - - - - 6 - 2nd Point Property - UINT - 16 - 96 - - rw - R - - - - 7 - 3rd Comparing Position - DINT - 32 - 112 - - rw - R - - - - 9 - 3rd Point Property - UINT - 16 - 144 - - rw - R - - - - 10 - 4th Comparing Position - DINT - 32 - 160 - - rw - R - - - - 12 - 4th Point Property - UINT - 16 - 192 - - rw - R - - - - 13 - 5th Comparing Position - DINT - 32 - 208 - - rw - R - - - - 15 - 5th Point Property - UINT - 16 - 240 - - rw - R - - - - 16 - 6th Comparing Position - DINT - 32 - 256 - - rw - R - - - - 18 - 6th Point Property - UINT - 16 - 288 - - rw - R - - - - 19 - 7th Comparing Position - DINT - 32 - 304 - - rw - R - - - - 21 - 7th Point Property - UINT - 16 - 336 - - rw - R - - - - 22 - 8th Comparing Position - DINT - 32 - 352 - - rw - R - - - - 24 - 8th Point Property - UINT - 16 - 384 - - rw - R - - - - 25 - 9th Comparing Position - DINT - 32 - 400 - - rw - R - - - - 27 - 9th Point Property - UINT - 16 - 432 - - rw - R - - - - 28 - 10th Comparing Position - DINT - 32 - 448 - - rw - R - - - - 30 - 10th Point Property - UINT - 16 - 480 - - rw - R - - - - 31 - 11th Comparing Position - DINT - 32 - 496 - - rw - R - - - - 33 - 11th Point Property - UINT - 16 - 528 - - rw - R - - - - 34 - 12th Comparing Position - DINT - 32 - 544 - - rw - R - - - - 36 - 12th Point Property - UINT - 16 - 576 - - rw - R - - - - 37 - 13th Comparing Position - DINT - 32 - 592 - - rw - R - - - - 39 - 13th Point Property - UINT - 16 - 624 - - rw - R - - - - 40 - 14th Comparing Position - DINT - 32 - 640 - - rw - R - - - - 42 - 14th Point Property - UINT - 16 - 672 - - rw - R - - - - 43 - 15th Comparing Position - DINT - 32 - 688 - - rw - R - - - - 45 - 15th Point Property - UINT - 16 - 720 - - rw - R - - - - 46 - 16th Comparing Position - DINT - 32 - 736 - - rw - R - - - - 48 - 16th Point Property - UINT - 16 - 768 - - rw - R - - - - 49 - 17th Comparing Position - DINT - 32 - 784 - - rw - R - - - - 51 - 17th Point Property - UINT - 16 - 816 - - rw - R - - - - 52 - 18th Comparing Position - DINT - 32 - 832 - - rw - R - - - - 54 - 18th Point Property - UINT - 16 - 864 - - rw - R - - - - 55 - 19th Comparing Position - DINT - 32 - 880 - - rw - R - - - - 57 - 19th Point Property - UINT - 16 - 912 - - rw - R - - - - 58 - 20th Comparing Position - DINT - 32 - 928 - - rw - R - - - - 60 - 20th Point Property - UINT - 16 - 960 - - rw - R - - - - 61 - 21st Comparing Position - DINT - 32 - 976 - - rw - R - - - - 63 - 21st Point Property - UINT - 16 - 1008 - - rw - R - - - - 64 - 22nd Comparing Position - DINT - 32 - 1024 - - rw - R - - - - 66 - 22nd Point Property - UINT - 16 - 1056 - - rw - R - - - - 67 - 23rd Comparing Position - DINT - 32 - 1072 - - rw - R - - - - 69 - 23rd Point Property - UINT - 16 - 1104 - - rw - R - - - - 70 - 24th Comparing Position - DINT - 32 - 1120 - - rw - R - - - - 72 - 24th Point Property - UINT - 16 - 1152 - - rw - R - - - - 73 - 25th Comparing Position - DINT - 32 - 1168 - - rw - R - - - - 75 - 25th Point Property - UINT - 16 - 1200 - - rw - R - - - - 76 - 26th Comparing Position - DINT - 32 - 1216 - - rw - R - - - - 78 - 26th Point Property - UINT - 16 - 1248 - - rw - R - - - - 79 - 27th Comparing Position - DINT - 32 - 1264 - - rw - R - - - - 81 - 27th Point Property - UINT - 16 - 1296 - - rw - R - - - - 82 - 28th Comparing Position - DINT - 32 - 1312 - - rw - R - - - - 84 - 28th Point Property - UINT - 16 - 1344 - - rw - R - - - - 85 - 29th Comparing Position - DINT - 32 - 1360 - - rw - R - - - - 87 - 29th Point Property - UINT - 16 - 1392 - - rw - R - - - - 88 - 30th Comparing Position - DINT - 32 - 1408 - - rw - R - - - - 90 - 30th Point Property - UINT - 16 - 1440 - - rw - R - - - - 91 - 31st Comparing Position - DINT - 32 - 1456 - - rw - R - - - - 93 - 31st Point Property - UINT - 16 - 1488 - - rw - R - - - - 94 - 32nd Comparing Position - DINT - 32 - 1504 - - rw - R - - - - 96 - 32nd Point Property - UINT - 16 - 1536 - - rw - R - - - - 97 - 33rd Comparing Position - DINT - 32 - 1552 - - rw - R - - - - 99 - 33rd Point Property - UINT - 16 - 1584 - - rw - R - - - - 100 - 34th Comparing Position - DINT - 32 - 1600 - - rw - R - - - - 102 - 34th Point Property - UINT - 16 - 1632 - - rw - R - - - - 103 - 35th Comparing Position - DINT - 32 - 1648 - - rw - R - - - - 105 - 35th Point Property - UINT - 16 - 1680 - - rw - R - - - - 106 - 36th Comparing Position - DINT - 32 - 1696 - - rw - R - - - - 108 - 36th Point Property - UINT - 16 - 1728 - - rw - R - - - - 109 - 37th Comparing Position - DINT - 32 - 1744 - - rw - R - - - - 111 - 37th Point Property - UINT - 16 - 1776 - - rw - R - - - - 112 - 38th Comparing Position - DINT - 32 - 1792 - - rw - R - - - - 114 - 38th Point Property - UINT - 16 - 1824 - - rw - R - - - - 115 - 39th Comparing Position - DINT - 32 - 1840 - - rw - R - - - - 117 - 39th Point Property - UINT - 16 - 1872 - - rw - R - - - - 118 - 40th Comparing Position - DINT - 32 - 1888 - - rw - R - - - - 120 - 40th Point Property - UINT - 16 - 1920 - - rw - R - - - - - DT2030 - 64 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Servo Status - UINT - 16 - 16 - - ro - T - - - - 2 - DO Function1 - UINT - 16 - 32 - - ro - T - - - - 3 - DO Function2 - UINT - 16 - 48 - - ro - T - - - - - DT2031 - 224 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Comm Set VDI - UINT - 16 - 16 - - rw - R - - - - 5 - Comm Set DO - UINT - 16 - 80 - - rw - R - - - - 6 - Comm Set AO - INT - 16 - 96 - - rw - R - - - - 10 - Comm Set Local SpdRef - DINT - 32 - 160 - - rw - R - - - - 12 - Comm Set Local TrqRef - DINT - 32 - 192 - - rw - R - - - - - DT607D - 80 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Min position limit - DINT - 32 - 16 - - rw - R - - - - 2 - Max position limit - DINT - 32 - 48 - - rw - R - - - - - DT6091 - 80 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Motor revolutions - UDINT - 32 - 16 - - rw - R - - - - 2 - Shaft revolutions - UDINT - 32 - 48 - - rw - R - - - - - DT6099 - 80 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Speed during search for switch - UDINT - 32 - 16 - - rw - R - - - - 2 - Speed during search for zero - UDINT - 32 - 48 - - rw - R - - - - - DT60FE - 80 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Physical outputs - UDINT - 32 - 16 - - rw - R - - - - 2 - Bit Mask - UDINT - 32 - 48 - - rw - R - - - - - DT60E3 - 544 - - 0 - SubIndex 000 - USINT - 8 - 0 - - ro - - - - 1 - Support homing method 1 - INT - 16 - 16 - - ro - - - - 2 - Support homing method 2 - INT - 16 - 32 - - ro - - - - 3 - Support homing method 3 - INT - 16 - 48 - - ro - - - - 4 - Support homing method 4 - INT - 16 - 64 - - ro - - - - 5 - Support homing method 5 - INT - 16 - 80 - - ro - - - - 6 - Support homing method 6 - INT - 16 - 96 - - ro - - - - 7 - Support homing method 7 - INT - 16 - 112 - - ro - - - - 8 - Support homing method 8 - INT - 16 - 128 - - ro - - - - 9 - Support homing method 9 - INT - 16 - 144 - - ro - - - - 10 - Support homing method 10 - INT - 16 - 160 - - ro - - - - 11 - Support homing method 11 - INT - 16 - 176 - - ro - - - - 12 - Support homing method 12 - INT - 16 - 192 - - ro - - - - 13 - Support homing method 13 - INT - 16 - 208 - - ro - - - - 14 - Support homing method 14 - INT - 16 - 224 - - ro - - - - 15 - Support homing method 15 - INT - 16 - 240 - - ro - - - - 16 - Support homing method 16 - INT - 16 - 256 - - ro - - - - 17 - Support homing method 17 - INT - 16 - 272 - - ro - - - - 18 - Support homing method 18 - INT - 16 - 288 - - ro - - - - 19 - Support homing method 19 - INT - 16 - 304 - - ro - - - - 20 - Support homing method 20 - INT - 16 - 320 - - ro - - - - 21 - Support homing method 21 - INT - 16 - 336 - - ro - - - - 22 - Support homing method 22 - INT - 16 - 352 - - ro - - - - 23 - Support homing method 23 - INT - 16 - 368 - - ro - - - - 24 - Support homing method 24 - INT - 16 - 384 - - ro - - - - 25 - Support homing method 25 - INT - 16 - 400 - - ro - - - - 26 - Support homing method 26 - INT - 16 - 416 - - ro - - - - 27 - Support homing method 27 - INT - 16 - 432 - - ro - - - - 28 - Support homing method 28 - INT - 16 - 448 - - ro - - - - 29 - Support homing method 29 - INT - 16 - 464 - - ro - - - - 30 - Support homing method 30 - INT - 16 - 480 - - ro - - - - 31 - Support homing method 31 - INT - 16 - 496 - - ro - - - - 32 - Support homing method 32 - INT - 16 - 512 - - ro - - - - 33 - Support homing method 33 - INT - 16 - 528 - - ro - - - - - - - #x1000 - Device type - UDINT - 32 - - #x00020192 - - - ro - o - - - - #x1001 - Error Register - USINT - 8 - - 00 - - - ro - o - - - - #x1008 - Device name - STRING(10) - 80 - - SV670_ECAT - - - ro - - - - #x1009 - Hardware version - STRING(4) - 32 - - V1.0 - - - ro - - - - #x100a - Software version - STRING(4) - 32 - - V1.0 - - - ro - o - - - - #x1c00 - Sync manager type - DT1C00 - 48 - - - SubIndex 000 - - 04 - - - - SubIndex 001 - - 01 - - - - SubIndex 002 - - 02 - - - - SubIndex 003 - - 03 - - - - SubIndex 004 - - 04 - - - - - ro - o - - - - #x1018 - Identity - DT1018 - 144 - - - SubIndex 000 - - 04 - - - - Vendor ID - - #x00100000 - - - - Product Code - - #x000C011E - - - - Revision - - #x00010000 - - - - Serial number - - 00000000 - - - - - ro - o - - - - #x1600 - Outputs - DT1600 - 336 - - - SubIndex 000 - - 00 - 10 - #x03 - - - - 1st Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60400010 - - - - 2nd Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x607A0020 - - - - 3rd Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60B80010 - - - - 4th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 5th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 6th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 7th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 8th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 9th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 10th Output Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - - rw - - - - #x1601 - Outputs - DT1601 - 368 - - - SubIndex 000 - - #x0B - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x60600008 - - - - 3rd Output Object to be mapped - - #x60710010 - - - - 4th Output Object to be mapped - - #x607A0020 - - - - 5th Output Object to be mapped - - #x607F0020 - - - - 6th Output Object to be mapped - - #x60810020 - - - - 7th Output Object to be mapped - - #x60830020 - - - - 8th Output Object to be mapped - - #x60840020 - - - - 9th Output Object to be mapped - - #x60870020 - - - - 10th Output Object to be mapped - - #x60B80010 - - - - 11th Output Object to be mapped - - #x60FF0020 - - - - - rw - - - - #x1701 - Outputs - DT1701 - 336 - - - SubIndex 000 - - #x04 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60B80010 - - - - 4th Output Object to be mapped - - #x60FE0120 - - - - - ro - - - - #x1702 - Outputs - DT1702 - 336 - - - SubIndex 000 - - #x07 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60B80010 - - - - 4th Output Object to be mapped - - #x60710010 - - - - 5th Output Object to be mapped - - #x60600008 - - - - 6th Output Object to be mapped - - #x60B80010 - - - - 7th Output Object to be mapped - - #x607F0020 - - - - - ro - - - - #x1703 - Outputs - DT1702 - 336 - - - SubIndex 000 - - #x07 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60FF0020 - - - - 4th Output Object to be mapped - - #x60600008 - - - - 5th Output Object to be mapped - - #x60B80010 - - - - 6th Output Object to be mapped - - #x60E00010 - - - - 7th Output Object to be mapped - - #x60E10010 - - - - - ro - - - - #x1704 - Outputs - DT1704 - 336 - - - SubIndex 000 - - #x09 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60FF0020 - - - - 4th Output Object to be mapped - - #x60710010 - - - - 5th Output Object to be mapped - - #x60600008 - - - - 6th Output Object to be mapped - - #x60B80010 - - - - 7th Output Object to be mapped - - #x607F0020 - - - - 8th Output Object to be mapped - - #x60E00010 - - - - 9th Output Object to be mapped - - #x60E10010 - - - - - ro - - - - #x1705 - Outputs - DT1705 - 336 - - - SubIndex 000 - - #x08 - - - - 1st Output Object to be mapped - - #x60400010 - - - - 2nd Output Object to be mapped - - #x607A0020 - - - - 3rd Output Object to be mapped - - #x60FF0020 - - - - 4th Output Object to be mapped - - #x60600008 - - - - 5th Output Object to be mapped - - #x60B80010 - - - - 6th Output Object to be mapped - - #x60E00010 - - - - 7th Output Object to be mapped - - #x60E10010 - - - - 8th Output Object to be mapped - - #x60B20010 - - - - - ro - - - - #x1A00 - Inputs - DT1A00 - 336 - - - SubIndex 000 - - 00 - 10 - #x07 - - - - 1st Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60410010 - - - - 2nd Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60640020 - - - - 3rd Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60B90010 - - - - 4th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60BA0020 - - - - 5th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60BC0020 - - - - 6th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x603F0010 - - - - 7th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x60FD0020 - - - - 8th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 9th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - 10th Input Object to be mapped - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - - rw - - - - #x1A01 - Inputs - DT1A01 - 368 - - - SubIndex 000 - - #x0B - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60610008 - - - - 4th Input Object to be mapped - - #x60640020 - - - - 5th Input Object to be mapped - - #x606C0020 - - - - 6th Input Object to be mapped - - #x60770010 - - - - 7th Input Object to be mapped - - #x60B90010 - - - - 8th Input Object to be mapped - - #x60BA0020 - - - - 9th Input Object to be mapped - - #x60BC0020 - - - - 10th Input Object to be mapped - - #x60F40020 - - - - 11th Input Object to be mapped - - #x60FD0020 - - - - - rw - - - - #x1B01 - Inputs - DT1B01 - 336 - - - SubIndex 000 - - #x09 - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60640020 - - - - 4th Input Object to be mapped - - #x60770010 - - - - 5th Input Object to be mapped - - #x60F40020 - - - - 6th Input Object to be mapped - - #x60B90010 - - - - 7th Input Object to be mapped - - #x60BA0020 - - - - 8th Input Object to be mapped - - #x60BC0020 - - - - 9th Input Object to be mapped - - #x60FD0020 - - - - - ro - - - - #x1B02 - Inputs - DT1B01 - 336 - - - SubIndex 000 - - #x09 - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60640020 - - - - 4th Input Object to be mapped - - #x60770010 - - - - 5th Input Object to be mapped - - #x60610008 - - - - 6th Input Object to be mapped - - #x60B90010 - - - - 7th Input Object to be mapped - - #x60BA0020 - - - - 8th Input Object to be mapped - - #x60BC0020 - - - - 9th Input Object to be mapped - - #x60FD0020 - - - - - ro - - - - #x1B03 - Inputs - DT1B03 - 336 - - - SubIndex 000 - - #x0A - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60640020 - - - - 4th Input Object to be mapped - - #x60770010 - - - - 5th Input Object to be mapped - - #x60F40020 - - - - 6th Input Object to be mapped - - #x60610008 - - - - 7th Input Object to be mapped - - #x60B90010 - - - - 8th Input Object to be mapped - - #x60BA0020 - - - - 9th Input Object to be mapped - - #x60BC0020 - - - - 10th Input Object to be mapped - - #x60FD0020 - - - - - ro - - - - #x1B04 - Inputs - DT1B04 - 336 - - - SubIndex 000 - - #x0A - - - - 1st Input Object to be mapped - - #x603F0010 - - - - 2nd Input Object to be mapped - - #x60410010 - - - - 3rd Input Object to be mapped - - #x60640020 - - - - 4th Input Object to be mapped - - #x60770010 - - - - 5th Input Object to be mapped - - #x60610008 - - - - 6th Input Object to be mapped - - #x60B90010 - - - - 7th Input Object to be mapped - - #x60BA0020 - - - - 8th Input Object to be mapped - - #x60BC0020 - - - - 9th Input Object to be mapped - - #x60FD0020 - - - - 10th Input Object to be mapped - - #x606C0020 - - - - - ro - - - - #x1c32 - SM output parameter - DT1C32 - 488 - - - SubIndex 000 - - 20 - - - - Sync mode - - 0200 - - - - Cycle time - - 00000000 - - - - Sync modes supported - - 0004 - - - - Minimum cycle time - - 00000000 - - - - Calc and copy time - - #x0003d090 - - - - Get Cycle Time - - 0000 - - - - Delay Time - - 00000000 - - - - Sync0 Cycle Time - - 00000000 - - - - SM-Event Missed - - 0000 - - - - Cycle Time Too Small - - 0000 - - - - Sync Error - - 00 - - - - - ro - o - - - - #x1c33 - SM input parameter - DT1C33 - 488 - - - SubIndex 000 - - 20 - - - - Sync mode - - 0002 - - - - Cycle time - - 00000000 - - - - Sync modes supported - - 4 - - - - Minimum cycle time - - 00000000 - - - - Calc and copy time - - 00000000 - - - - Get Cycle Time - - 0000 - - - - Delay Time - - 00000000 - - - - Sync0 Cycle Time - - 00000000 - - - - SM-Event Missed - - 0000 - - - - Cycle Time Too Small - - 0000 - - - - Sync Error - - 00 - - - - - ro - o - - - - #x1c12 - RxPDO assign - DT1C12 - 32 - - - SubIndex 000 - - 00 - - - - SubIndex 001 - - 0000 - - - - - ro - - - - #x1c13 - TxPDO assign - DT1C13 - 32 - - - SubIndex 000 - - 00 - - - - SubIndex 001 - - 0000 - - - - - ro - - - - #x2000 - Servo Motor Parameters - 伺服电机参数 - DT2000 - 128 - - - SubIndex 000 - - 6 - - - - Motor SN - - 0 - 65535 - 14101 - - - - Customized firmware version - - 0 - 65535 - 0 - - - - Encoder Version - - 0 - 65535 - 0 - - - - Serial encoder motor SN - - 0 - 65535 - 0 - - - - - ro - - - - #x2001 - Servo Drive Parameters - 伺服驱动器参数 - DT2001 - 672 - - - SubIndex 000 - - 41 - - - - MCU firmware Version - - 0 - 65535 - 0 - - - - Fpga firmware Version - - 0 - 65535 - 0 - - - - Drive serial number - - 0 - 65535 - 3 - - - - Drive voltage class - - 0 - 65535 - 220 - - - - Drive rated power - - 0 - 1073741824 - 400 - - - - Drive maximum output power - - 0 - 1073741824 - 400 - - - - Drive rated output current - - 0 - 1073741824 - 280 - - - - Drive maximum output current - - 0 - 1073741824 - 1010 - - - - DC bus overvoltage protective point - - 0 - 2000 - 420 - - - - - ro - - - - #x2002 - Basic control - 基本控制参数 - DT2002 - 688 - - - SubIndex 000 - - 36 - - - - Control mode selection - - 0 - 9 - 9 - - - - Absolute system selection - - 0 - 4 - 0 - - - - Rotating direction - - 0 - 1 - 0 - - - - Output pulse phase - - 0 - 1 - 0 - - - - Disable operation option Code - - -4 - 2 - 0 - - - - NO2 Fault Reaction option Code - - -5 - 4 - 2 - - - - Stop mode at limit switch signal - - 0 - 7 - 1 - - - - Stop mode at NO.1 fault - - 0 - 2 - 2 - - - - Delay from brake output on to command received - - 0 - 500 - 250 - - - - Delay from brake output off to motor de-energized - - 50 - 1000 - 150 - - - - Motor speed threshold at brake output off in rotating state - - 20 - 3000 - 30 - - - - Delay from servo off to brake output off in the rotating state - - 1 - 65535 - 500 - - - - LED warning display selection - - 0 - 1 - 0 - - - - MainPower Cutoff Reaction Option Code - - 0 - 3 - 2 - - - - QuickStop Reaction Option Code - - 0 - 7 - 2 - - - - Allowed minimum braking resistance - - 1 - 1000 - 40 - - - - Power of built-in braking resistor - - 0 - 65535 - 50 - - - - Resistance of built-in braking resistor - - 0 - 65535 - 50 - - - - Resistor heat dissipation coefficient - - 10 - 100 - 30 - - - - braking resistor type - - 0 - 3 - 3 - - - - Power of external dynamic resistor - - 1 - 65535 - 40 - - - - Resistance of external braking resistor - - 15 - 1000 - 50 - - - - User password - - 0 - 65535 - 0 - - - - Parameter initialization - - 0 - 2 - 0 - - - - Default keypad display - - 0 - 99 - 50 - - - - Panel data refresh rate - - 0 - 20 - 0 - - - - OEM password - - 0 - 65535 - 0 - - - - - ro - - - - #x2003 - Input Terminal Parameters - 端子输入参数 - DT2003 - 1056 - - - SubIndex 000 - - 65 - - - - DI1 function selection - - 0 - 40 - 14 - - - - DI1 logic selection - - 0 - 1 - 0 - - - - DI2 function selection - - 0 - 40 - 15 - - - - DI2 logic selection - - 0 - 1 - 0 - - - - DI3 function selection - - 0 - 40 - 31 - - - - DI3 logic selection - - 0 - 1 - 0 - - - - DI4 function selection - - 0 - 40 - 34 - - - - DI4 logic selection - - 0 - 1 - 0 - - - - DI5 function selection - - 0 - 40 - 38 - - - - DI5 logic selection - - 0 - 1 - 0 - - - - AI1 Offset - - -5000 - 5000 - 0 - - - - AI1 Filter - - 0 - 65535 - 200 - - - - AI1 Dead Zone - - 0 - 10000 - 100 - - - - AI1 Zero Drifting - - -5000 - 5000 - 0 - - - - DI1 filtertime constant - - 0 - 50000 - 300 - - - - DI2 filtertime constant - - 0 - 50000 - 300 - - - - DI3 filtertime constant - - 0 - 50000 - 300 - - - - DI4 filtertime constant - - 0 - 50000 - 300 - - - - DI5 filtertime constant - - 0 - 50000 - 300 - - - - - ro - - - - #x2004 - Output terminal Parameters - 端子输出参数 - DT2004 - 864 - - - SubIndex 000 - - 53 - - - - DO1 Function Selection - - 0 - 65535 - 1 - - - - DO1 Logic Level Selection - - 0 - 1 - 0 - - - - DO2 Function Selection - - 0 - 65535 - 9 - - - - DO2 Logic Level Selection - - 0 - 1 - 0 - - - - DO3 Function Selection - - 0 - 65535 - 9 - - - - DO3 Logic Level Selection - - 0 - 1 - 0 - - - - DO OutPut Source Select - - 0 - 3 - 0 - - - - ECAT Lost Force DO OutPut Logic - - 0 - 3 - 0 - - - - AO1 Source Select - - 0 - 10 - 0 - - - - AO1 Offset - - -10000 - 10000 - 0 - - - - AO1 Multiplying - - -10000 - 10000 - 100 - - - - - ro - - - - #x2005 - Position Control Parameters - 位置控制参数组 - DT2005 - 1152 - - - SubIndex 000 - - 55 - - - - Time constant of first-order low-pass filter - - 0 - 65535 - 0 - - - - Time constant of moving average filter 1 - - 0 - 1280 - 0 - - - - Numerator of electronic gear ratio - - 1 - 1073741824 - 1 - - - - Denominator of electronic gear ratio - - 1 - 1073741824 - 1 - - - - Encoder frequency division pulses - - 0 - 4194303 - 2500 - - - - Speed feedforward control selection - - 0 - 3 - 1 - - - - Local home mode - - 0 - 8 - 0 - - - - Time of home searching - - 0 - 65535 - 10000 - - - - Local home position offset - - -2147483648 - 2147483647 - 0 - - - - Servo pulse output source - - 0 - 3 - 0 - - - - Output polarity of Z pulse - - 0 - 65535 - 1 - - - - Mechanical Gear ratio numerator of absolute encode mode 2 - - 1 - 65535 - 1 - - - - Mechanical Gear ratio denominator of absolute encode mode 2 - - 1 - 65535 - 1 - - - - Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) - - 0 - 4294967295 - 0 - - - - Max value of mechanical absolute position(inc) of absolute encode mode 2(High) - - 0 - 4294967295 - 0 - - - - Trq Reference of Mechanical Homing - - 0 - 4000 - 1000 - - - - Position Coin Hold Time - - 0 - 30000 - 0 - - - - Time Unit of Homing - - 0 - 2 - 2 - - - - Time constant of moving average filter 2 - - 0 - 10000 - 0 - - - - - ro - - - - #x2006 - Speed control - 速度控制 - DT2006 - 896 - - - SubIndex 000 - - 16 - - - - Keypad setting value of speed reference - - -10000 - 10000 - 200 - - - - DI Jog speed reference - - 0 - 10000 - 150 - - - - Acceleration ramp time constant of speed reference - - 0 - 65535 - 0 - - - - Deceleration ramp time constant of speed reference - - 0 - 65535 - 0 - - - - Maximum speed limit - - 0 - 10000 - 7000 - - - - Forward speed threshold - - 0 - 10000 - 7000 - - - - Reverse speed threshold - - 0 - 10000 - 7000 - - - - Quick decelaration coefficient - - 0 - 2 - 0 - - - - Torque feedforward selection - - 0 - 2 - 1 - - - - Acceleration/Deceleration ramp time constant of jog speed reference - - 0 - 65535 - 10 - - - - Speed feedforward filter time constant - - 0 - 65535 - 0 - - - - Speed threshold of Zero Hold signal - - 0 - 10000 - 10 - - - - Speed threshold of motor rotation signal - - 0 - 1000 - 20 - - - - Speed threshold of Spd Reach signal - - 0 - 100 - 10 - - - - Speed threshold of Spd Arrive signal - - 20 - 10000 - 1000 - - - - Speed threshold of Zero Spd signal - - 1 - 10000 - 10 - - - - Spd SCurve Enable - - 0 - 1 - 1 - - - - Spd SCurve Acceleration UP - - 0 - 1000 - 500 - - - - Spd SCurve Acceleration Down - - 0 - 1000 - 500 - - - - Spd SCurve Deceleration UP - - 0 - 1000 - 500 - - - - Spd SCurve Deceleration Down - - 0 - 1000 - 500 - - - - - ro - - - - #x2007 - Torque control - 转矩控制参数 - DT2007 - 640 - - - SubIndex 000 - - 40 - - - - Keypad setting value of torque reference - - -4000 - 4000 - 0 - - - - Torque reference filter time 1 - - 0 - 3000 - 50 - - - - Torque reference filter time 2 - - 0 - 3000 - 27 - - - - Internal forward torque limit - - 0 - 4000 - 3500 - - - - Internal reverse torque limit - - 0 - 4000 - 3500 - - - - Emergency stop torque - - 0 - 4000 - 1000 - - - - Forward speed limit/Speed limit 1 in local torque control - - 0 - 6000 - 3000 - - - - Reverse speed limit/Speed limit 2 in local torque control - - 0 - 6000 - 3000 - - - - Base value for torque reached - - 0 - 4000 - 0 - - - - Threshold of torque reached valid - - 0 - 4000 - 200 - - - - Threshold of torque reached invalid - - 0 - 4000 - 100 - - - - Depth of field-weakening - - 60 - 115 - 115 - - - - Maximum field-weakening current - - 0 - 300 - 100 - - - - Field-weakening enable - - 0 - 1 - 0 - - - - Field-weakening gain - - 1 - 1000 - 30 - - - - Field-weakening point speed - - 0 - 65535 - 0 - - - - Motor output calibration enable - - 0 - 1 - 0 - - - - The second-stage torque reference filter time - - 0 - 1000 - 0 - - - - Torque reference filter type select - - 0 - 1 - 0 - - - - Biquad low pass filter damping - - 0 - 50 - 16 - - - - - ro - - - - #x2008 - Gain Parameters - 增益参数 - DT2008 - 1056 - - - SubIndex 000 - - 65 - - - - Speed-loop Gain - - 1 - 20000 - 400 - - - - Speed-loop integral time constant - - 15 - 51200 - 1989 - - - - Position-loop Gain - - 1 - 20000 - 640 - - - - The second speed loop gain - - 1 - 20000 - 750 - - - - The second speed loop integral time constant - - 15 - 51200 - 1061 - - - - The second position loop gain - - 1 - 20000 - 1200 - - - - Second gain mode setting - - 0 - 1 - 1 - - - - Gain switchover condition - - 0 - 10 - 0 - - - - Gain switchover delay - - 0 - 10000 - 50 - - - - Gain switchover level - - 0 - 20000 - 50 - - - - Gain switchover hysteresis - - 0 - 20000 - 30 - - - - Position gain switchover time - - 0 - 10000 - 30 - - - - Average value of load inertia ratio - - 0 - 12000 - 100 - - - - Zero-Phase delay time - - 0 - 40 - 0 - - - - Speed feedforward filter time constant - - 0 - 6400 - 50 - - - - Speed feedforward gain - - 0 - 1000 - 0 - - - - Torque feedforward filter time constant - - 0 - 6400 - 50 - - - - Torque feedforward gain - - 0 - 3000 - 0 - - - - Speed feedback filter - - 0 - 4 - 0 - - - - Cut-off frequency of speed feedback low-pass filter - - 100 - 8000 - 8000 - - - - Pseudo-differential forward feedback control coefficient - - 0 - 2000 - 1000 - - - - Cut-off frequency of speed observer - - 50 - 600 - 170 - - - - Modified inertia coefficient of speed observer - - 1 - 1600 - 100 - - - - Filter time of speed observer - - 0 - 1000 - 80 - - - - Cut-off frequency of torque disturbance observer - - 10 - 4000 - 600 - - - - Compensation gain of torque disturbance observer - - 0 - 100 - 0 - - - - Modified inertia coefficient of torque disturbance observer - - 1 - 1600 - 100 - - - - Speed observer enable - - 0 - 1 - 0 - - - - Module control enable - - 0 - 2 - 0 - - - - Module control gain - - 1 - 20000 - 400 - - - - Module feedforward value - - 0 - 1024 - 950 - - - - 3rd medium and low-frequency vibration suppression frequency - - 0 - 3000 - 0 - - - - 3rd compensation gain of medium and low-frequency vibration suppression frequency - - 0 - 200 - 0 - - - - 3rd phase modulation of medium and low-frequency vibration suppression frequency - - 0 - 600 - 100 - - - - 4th medium and low-frequency vibration suppression frequency - - 0 - 3000 - 0 - - - - 4th compensation gain of medium and low-frequency vibration suppression frequency - - 0 - 200 - 0 - - - - 4th phase modulation of medium and low-frequency vibration suppression frequency - - 0 - 600 - 100 - - - - Time constant of position loop integration - - 15 - 51200 - 51200 - - - - 2nd time constant of position loop integration - - 15 - 51200 - 51200 - - - - Speed observation feedback source selection - - 0 - 1 - 0 - - - - - ro - - - - #x2009 - Auto-adjusting Parameters - 自整定参数 - DT2009 - 848 - - - SubIndex 000 - - 60 - - - - Auto-adjusting mode - - 0 - 7 - 4 - - - - Rigidity level selection - - 0 - 41 - 15 - - - - Working mode of self-adaptive notch - - 0 - 4 - 0 - - - - Online inertia auto-tuning mode - - 0 - 3 - 0 - - - - Offline inertia auto-tuning mode - - 0 - 1 - 0 - - - - Maximum speed for inertia autotuning - - 100 - 1000 - 500 - - - - Acceleration/Deceleration time for inertia autotuning - - 20 - 800 - 125 - - - - Interval after an inertia autotuning - - 50 - 10000 - 800 - - - - Motor revolutions for an inertia auto-tuning - - 0 - 10000 - 100 - - - - Vibration threshold setting - - 0 - 1000 - 50 - - - - 1st notch frequency - - 50 - 8000 - 8000 - - - - 1st notch width level - - 0 - 20 - 2 - - - - 1st notch attenuation level - - 0 - 99 - 0 - - - - 2nd notch frequency - - 50 - 8000 - 8000 - - - - 2nd notch width level - - 0 - 20 - 2 - - - - 2nd notch attenuation level - - 0 - 99 - 0 - - - - 3rd notch frequency - - 50 - 8000 - 8000 - - - - 3rd notch width level - - 0 - 20 - 2 - - - - 3rd notch attenuation level - - 0 - 99 - 0 - - - - 4th notch frequency - - 50 - 8000 - 8000 - - - - 4th notch width level - - 0 - 20 - 2 - - - - 4th notch attenuation level - - 0 - 99 - 0 - - - - Obtained resonance frequency - - 0 - 5000 - 0 - - - - 1st anti-resonance point frequency - - 0 - 5000 - 0 - - - - 2nd anti-resonance point frequency - - 0 - 5000 - 0 - - - - Gravity compensation value - - 0 - 1000 - 0 - - - - Forward friction compensation - - 0 - 1000 - 0 - - - - Reverse friction compensation - - -1000 - 0 - 0 - - - - Friction compensation speed - - 0 - 200 - 20 - - - - Friction compensation speed selection - - 0 - 19 - 0 - - - - Vibration monitor time - - 0 - 65535 - 300 - - - - 1st terminal low-frequency vibration suppression frequency - - 10 - 1000 - 1000 - - - - 1st filter order of low-frequency vibration suppression frequency - - 0 - 3 - 2 - - - - 5th notch frequency - - 50 - 8000 - 8000 - - - - 5th notch width level - - 0 - 20 - 2 - - - - 5th notch attenuation level - - 0 - 99 - 0 - - - - 2nd terminal low-frequency vibration suppression frequency - - 0 - 2000 - 0 - - - - 2nd damping frequency ratio of low-frequency vibration suppression frequency - - 1 - 1000 - 100 - - - - 2nd damping coefficient of low-frequency vibration suppression frequency - - 0 - 200 - 100 - - - - 3rd terminal low-frequency vibration suppression frequency - - 0 - 2000 - 0 - - - - 3rd damping frequency ratio of low-frequency vibration suppression frequency - - 1 - 1000 - 100 - - - - 3rd damping coefficient of low-frequency vibration suppression frequency - - 0 - 200 - 100 - - - - - ro - - - - #x200A - Error and Protection Parameter - 故障与保护参数 - DT200A - 1536 - - - SubIndex 000 - - 60 - - - - Power inputphase loss protection disable - - 0 - 1 - 0 - - - - Absolute position limit set - - 0 - 2 - 0 - - - - Motor overload protection gain - - 50 - 300 - 100 - - - - Overspeed threshold - - 0 - 20000 - 0 - - - - Local following error window - - 0 - 4294967295 - 27486951 - - - - Runaway protection enable - - 0 - 1 - 1 - - - - Over Temperature value of IPM - - 120 - 175 - 140 - - - - Touch Probe 1 filter time constant - - 0 - 630 - 200 - - - - Touch Probe 2 filter time constant - - 0 - 630 - 200 - - - - STO Display Function Selection - - 0 - 1 - 0 - - - - Filter time constant of TZ signal - - 0 - 31 - 15 - - - - Filter time of speed feedback display - - 0 - 5000 - 50 - - - - Motor overload shielding - - 0 - 1 - 0 - - - - Speed DO Filter time constant - - 0 - 5000 - 50 - - - - Full Closed-loop(ABZ) Filter time constant - - 0 - 255 - 15 - - - - Overheat protection time duration for locked rotor - - 10 - 65535 - 200 - - - - Overheat protection for locked rotor enable - - 0 - 1 - 1 - - - - Absolute Encode multi-turns error forbidden - - 0 - 1 - 0 - - - - Compensation Function - - 0 - 15 - 6 - - - - Over Temperature value of discharge tube - - 100 - 175 - 115 - - - - Encoder communiction error threshold - - 0 - 31 - 5 - - - - Phase lack threshold - - 3 - 36 - 20 - - - - Over Temperature value of Encoder - - 0 - 175 - 125 - - - - TouchProbe DI Turn-on Compensation Time - - -3000 - 3000 - 200 - - - - TouchProbe DI Turn-off Compensation Time - - -3000 - 3000 - 1512 - - - - Runaway current threshold - - 1000 - 4000 - 2000 - - - - Fault reset delay time - - 0 - 60000 - 10000 - - - - Runaway speed threshold - - 1 - 1000 - 50 - - - - Runaway speed filter time constant - - 1 - 1000 - 20 - - - - Runaway protection time window - - 10 - 1000 - 30 - - - - BlackBox Mode Select - - 0 - 3 - 1 - - - - BlackBox Selected Error Code - - 0 - 65535 - 0 - - - - BlackBox Trig Source - - 0 - 25 - 0 - - - - BlackBox Trig Level - - -2147483648 - 2147483647 - 0 - - - - BlackBox Trig Level Select - - 0 - 3 - 0 - - - - BlackBox Trig Position - - 0 - 100 - 75 - - - - BlackBox Trig Frequency Select - - 0 - 2 - 0 - - - - The 2nd over speed threshold - - 0 - 20000 - 0 - - - - Motor over load monitor switch - - 0 - 65535 - 4098 - - - - Maximum ramp stop time - - 0 - 65535 - 10000 - - - - STO Disconnect filter time - - 1 - 5 - 5 - - - - STO Mismatch filter time - - 1 - 1000 - 100 - - - - STO Servo off filter time - - 0 - 25 - 20 - - - - Motor Offline Trq Limit - - 40 - 4000 - 50 - - - - Motor Offline Filter Time - - 5 - 1000 - 30 - - - - Filter Time Constant of Spd Display - - 0 - 100 - 0 - - - - Filter Time Constant of Trq Display - - 0 - 100 - 0 - - - - Filter Time Constant of Position Display - - 0 - 100 - 0 - - - - Filter Time Constant of Voltage Display - - 0 - 250 - 0 - - - - Filter Time Constant of Temp Display - - 0 - 250 - 0 - - - - - ro - - - - #x200B - Display Parameters - 显示参数 - DT200B - 1584 - - - Number of Entries - - 92 - - - - Actual motor rotational speed - - 0 - - - - Speed reference - - 0 - - - - Internal torque reference - - 0 - - - - Monitored DI states - - 0 - - - - Monitored DO states - - 0 - - - - Absolute position counter - - 0 - - - - Mechanical angle - - 0 - - - - Electrical angle - - 0 - - - - Average load rate - - 0 - - - - Encoder position deviation counter - - 0 - - - - Feedback pulse counter - - 0 - - - - Total power-on time - - 0 - - - - AI1 Voltage DisPlay - - 0 - - - - Phase current valid value - - 0 - - - - Bus voltage - - 0 - - - - Module temperature - - 0 - - - - Absolute encoder fault info. from FPGA - - 0 - - - - Axis state from FPGA - - 0 - - - - Axis fault info. from FPGA - - 0 - - - - Encoder internal fault info. - - 0 - - - - Displayed fault record - - 0 - 19 - 0 - - - - Fault code - - 0 - - - - Time stamp upon displayed fault - - 0 - - - - Current rotational speed upon displayed fault - - 0 - - - - Current U upon displayed fault - - 0 - - - - Current V upon displayed fault - - 0 - - - - Bus voltage upon displayed fault - - 0 - - - - Input terminal state upon displayed fault - - 0 - - - - Output terminal state upon displayed fault - - 0 - - - - Inner error code - - 0 - - - - Fault message of absolute encode from Fpga upon displayed - - 0 - - - - System state from Fpga upon displayed fault - - 0 - - - - System fault message from Fpga upon displayed fault - - 0 - - - - Encode state 1 upon displayed fault - - 0 - - - - Inner error code upon displayed fault - - 0 - - - - Fpga overtime state upon displayed fault - - 0 - - - - Reference position deviation - - 0 - - - - Actual motor rotational speed(0.1rpm) - - 0 - - - - Control bus voltage - - 0 - - - - Mechanical absolute position inc(Low) - - 0 - - - - Mechanical absolute position inc(High) - - 0 - - - - Not ready reason - - 0 - - - - Encoder temperature - - 0 - - - - Discharge load rate - - 0 - - - - Fpga over time state - - 0 - - - - Number of turns of absolute encode - - 0 - - - - Single feedback postion of absolute encode - - 0 - - - - System Error - - 0 - - - - feedback postion of absolute encode(Low) - - 0 - - - - feedback postion of absolute encode(High) - - 0 - - - - feedback postion inc of rotating load(Low) - - 0 - - - - feedback postion inc of rotating load(High) - - 0 - - - - Single feedback postion of rotating load - - 0 - - - - IGBT Temperature - - 0 - - - - Group of unusual function code - - 0 - - - - Offset of unusual function code - - 0 - - - - Single Power-On Time - - 0 - - - - Single Power-On Time upon displayed fault - - 0 - - - - - ro - - - - #x200D - Auxiliary Function Parameters - 辅助功能参数 - DT200D - 400 - - - Number of Entries - - 21 - - - - Software reset - - 0 - 1 - 0 - - - - Fault reset - - 0 - 1 - 0 - - - - Offline inertia autotuning selection - - 0 - 1 - 0 - - - - Encoder ROM reading/writing - - 0 - 3 - 0 - - - - Emergency stop - - 0 - 1 - 0 - - - - AI1 Self-Adjust of Voltage Offset - - 0 - 1 - 0 - - - - UV phase current auto-tuning - - 0 - 1 - 0 - - - - Forced DI/DO setting - - 0 - 3 - 0 - - - - Forced DI level - - 0 - 31 - 31 - - - - Forced DO setting - - 0 - 3 - 0 - - - - Absolute Encode Fault Reset - - 0 - 2 - 0 - - - - Cogging torque self-learning - - 0 - 1 - 0 - - - - - ro - - - - #x200E - Communication parameters - 通信参数 - DT200E - 1568 - - - Number of Entries - - 97 - - - - Node address - - 1 - 127 - 1 - - - - Update function code values written via communication to EEPROM - - 0 - 4 - 4 - - - - station auto inc address - - 0 - 65535 - 0 - - - - station alias - - 0 - 65535 - 0 - - - - Sync lost window - - 1 - 20 - 8 - - - - Sync lost counter - - 0 - 65535 - 0 - - - - Port 0 invalid frame counter - - 0 - 65535 - 0 - - - - Port 1 invalid frame counter - - 0 - 65535 - 0 - - - - Port 0/1 transfer error counter - - 0 - 65535 - 0 - - - - process unit and PDI error counter - - 0 - 255 - 0 - - - - Port 0/1 lost counter - - 0 - 65535 - 0 - - - - Sync mode set - - 0 - 2 - 2 - - - - Sync error window - - 100 - 4000 - 4000 - - - - EtherCAT network state and link state - - 0 - 65535 - 0 - - - - CSP postion increment over counter - - 1 - 30 - 20 - - - - ECAT AL Error Code - - 0 - 65535 - 0 - - - - Enhanced link detection enable - - 0 - 1 - 0 - - - - Reset EtherCAT xml file - - 0 - 1 - 0 - - - - EtherCAT port control mode and state display - - 0 - 65535 - 0 - - - - EtherCAT COE version number - - 0 - 65535 - 0 - - - - EtherCAT xml file version number - - 0 - 65535 - 0 - - - - - ro - - - - #x200F - Closed Loop Function - 全闭环功能 - DT200F - 720 - - - SubIndex 000 - - 26 - - - - Encoder feedback mode - - 0 - 2 - 0 - - - - Running mode of external encoder - - 0 - 1 - 0 - - - - SecEncoder Absolute system selection - - 0 - 1 - 0 - - - - SecEncoder Type selection - - 0 - 2 - 0 - - - - External encoder pulses per motor revolution - - 0 - 2147483647 - 100000 - - - - Hybrid deviation excess setting - - 0 - 2147483647 - 10000 - - - - Hybrid deviation clear setting - - 0 - 100 - 1 - - - - First-order lowpass filter time of external/internal deviation - - 0 - 65535 - 0 - - - - Hybrid deviation counter - - -2147483648 - 2147483647 - 0 - - - - Pulse feedback display of internal encoder - - -2147483648 - 2147483647 - 0 - - - - Pulse feedback display of external encoder - - -2147483648 - 2147483647 - 0 - - - - SecEncoder Pulse ZPhase Ignore - - 0 - 1 - 0 - - - - SecEncoder Pulse Z-TouchProbe Selection - - 0 - 1 - 0 - - - - - ro - - - - #x2012 - MultiSpd Function - 多段速功能 - DT2012 - 1104 - - - SubIndex 000 - - 59 - - - - MultiSpd Function Select - - 0 - 2 - 1 - - - - MultiSpd Final Part Select - - 1 - 16 - 16 - - - - Time Uint of Runing - - 0 - 1 - 0 - - - - AccTime1 - - 0 - 65535 - 10 - - - - DecTime1 - - 0 - 65535 - 10 - - - - AccTime2 - - 0 - 65535 - 50 - - - - DecTime2 - - 0 - 65535 - 50 - - - - AccTime3 - - 0 - 65535 - 100 - - - - DecTime3 - - 0 - 65535 - 100 - - - - AccTime4 - - 0 - 65535 - 150 - - - - DecTime4 - - 0 - 65535 - 150 - - - - 1st Part Spd Cmd - - -10000 - 10000 - 0 - - - - 1st Part Spd Runing Time - - 0 - 65535 - 50 - - - - 1st Part AccDec Time Select - - 0 - 4 - 0 - - - - 2nd Part Spd Cmd - - -10000 - 10000 - 100 - - - - 2nd Part Spd Runing Time - - 0 - 65535 - 50 - - - - 2nd Part AccDec Time Select - - 0 - 4 - 0 - - - - 3rd Part Spd Cmd - - -10000 - 10000 - 300 - - - - 3rd Part Spd Runing Time - - 0 - 65535 - 50 - - - - 3rd Part AccDec Time Select - - 0 - 4 - 0 - - - - 4th Part Spd Cmd - - -10000 - 10000 - 500 - - - - 4th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 4th Part AccDec Time Select - - 0 - 4 - 0 - - - - 5th Part Spd Cmd - - -10000 - 10000 - 700 - - - - 5th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 5th Part AccDec Time Select - - 0 - 4 - 0 - - - - 6th Part Spd Cmd - - -10000 - 10000 - 900 - - - - 6th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 6th Part AccDec Time Select - - 0 - 4 - 0 - - - - 7th Part Spd Cmd - - -10000 - 10000 - 600 - - - - 7th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 7th Part AccDec Time Select - - 0 - 4 - 0 - - - - 8th Part Spd Cmd - - -10000 - 10000 - 300 - - - - 8th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 8th Part AccDec Time Select - - 0 - 4 - 0 - - - - 9th Part Spd Cmd - - -10000 - 10000 - 100 - - - - 9th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 9th Part AccDec Time Select - - 0 - 4 - 0 - - - - 10th Part Spd Cmd - - -10000 - 10000 - -100 - - - - 10th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 10th Part AccDec Time Select - - 0 - 4 - 0 - - - - 11th Part Spd Cmd - - -10000 - 10000 - -300 - - - - 11th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 11th Part AccDec Time Select - - 0 - 4 - 0 - - - - 12th Part Spd Cmd - - -10000 - 10000 - -500 - - - - 12th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 12th Part AccDec Time Select - - 0 - 4 - 0 - - - - 13th Part Spd Cmd - - -10000 - 10000 - -700 - - - - 13th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 13th Part AccDec Time Select - - 0 - 4 - 0 - - - - 14th Part Spd Cmd - - -10000 - 10000 - -900 - - - - 14th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 14th Part AccDec Time Select - - 0 - 4 - 0 - - - - 15th Part Spd Cmd - - -10000 - 10000 - -600 - - - - 15th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 15th Part AccDec Time Select - - 0 - 4 - 0 - - - - 16th Part Spd Cmd - - -10000 - 10000 - -300 - - - - 16th Part Spd Runing Time - - 0 - 65535 - 50 - - - - 16th Part AccDec Time Select - - 0 - 4 - 0 - - - - - ro - - - - #x2017 - VDI VDO - 虚拟DI、DO - DT2017 - 1520 - - - SubIndex 000 - - 68 - - - - VDI1 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI1 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI2 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI2 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI3 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI3 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI4 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI4 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI5 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI5 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI6 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI6 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI7 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI7 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI8 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI8 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI9 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI9 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI10 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI10 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI11 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI11 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI12 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI12 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI13 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI13 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI14 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI14 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI15 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI15 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDI16 Terminal Function Selection - - 0 - 40 - 0 - - - - VDI16 Terminal Logic Selection - - 0 - 1 - 0 - - - - VDO virtual level - - 0 - 65535 - 0 - - - - VDO1 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO1 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO2 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO2 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO3 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO3 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO4 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO4 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO5 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO5 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO6 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO6 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO7 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO7 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO8 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO8 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO9 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO9 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO10 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO10 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO11 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO11 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO12 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO12 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO13 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO13 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO14 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO14 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO15 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO15 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDO16 Terminal Function Selection - - 0 - 32 - 0 - - - - VDO16 Terminal Logic Level Selection - - 0 - 1 - 0 - - - - VDI Enable - - 0 - 1 - 0 - - - - VDI Default Value - - 0 - 65535 - 0 - - - - VDO Enable - - 0 - 1 - 0 - - - - VDO Default Value - - 0 - 65535 - 0 - - - - - ro - - - - #x2018 - Position Comparison - 位置比较参数 - DT2018 - 288 - - - SubIndex 000 - - 17 - - - - Enable Comparison - - 0 - - - - Comparison PosFdb Source Select - - 0 - 1 - 0 - - - - Encoder Resolution - - 0 - 7 - 1 - - - - Mode Of Comparison - - 0 - 2 - 0 - - - - Current Position As Zero - - 0 - 1 - 0 - - - - Output Duration - - 1 - 2047 - 1 - - - - Comparison ABZ OutPut Logic - - 0 - 65535 - 0 - - - - Starting Point Number - - 0 - 40 - 0 - - - - Ending Point Number - - 0 - 40 - 0 - - - - Comparison Status - - 0 - 1024 - 0 - - - - Current Position - - -2147483648 - 2147483647 - 0 - - - - Position Offset - - -2147483648 - 2147483647 - 0 - - - - Comparison OutPut Delay Compensation - - -1200 - 1200 - 0 - - - - Lilited number of Comparison Cycle Times - - 1 - 65535 - 1 - - - - Comparison ABZ OutPut Function - - 0 - 65535 - 0 - - - - - ro - - - - #x2019 - Comparing Points - 位置比较点 - DT2019 - 1936 - - - SubIndex 000 - - 120 - - - - 1st Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 1st Point Property - - 0 - - - - 2nd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 2nd Point Property - - 0 - - - - 3rd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 3rd Point Property - - 0 - - - - 4th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 4th Point Property - - 0 - - - - 5th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 5th Point Property - - 0 - - - - 6th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 6th Point Property - - 0 - - - - 7th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 7th Point Property - - 0 - - - - 8th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 8th Point Property - - 0 - - - - 9th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 9th Point Property - - 0 - - - - 10th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 10th Point Property - - 0 - - - - 11th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 11th Point Property - - 0 - - - - 12th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 12th Point Property - - 0 - - - - 13th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 13th Point Property - - 0 - - - - 14th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 14th Point Property - - 0 - - - - 15th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 15th Point Property - - 0 - - - - 16th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 16th Point Property - - 0 - - - - 17th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 17th Point Property - - 0 - - - - 18th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 18th Point Property - - 0 - - - - 19th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 19th Point Property - - 0 - - - - 20th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 20th Point Property - - 0 - - - - 21st Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 21st Point Property - - 0 - - - - 22nd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 22nd Point Property - - 0 - - - - 23rd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 23rd Point Property - - 0 - - - - 24th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 24th Point Property - - 0 - - - - 25th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 25th Point Property - - 0 - - - - 26th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 26th Point Property - - 0 - - - - 27th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 27th Point Property - - 0 - - - - 28th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 28th Point Property - - 0 - - - - 29th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 29th Point Property - - 0 - - - - 30th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 30th Point Property - - 0 - - - - 31st Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 31st Point Property - - 0 - - - - 32nd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 32nd Point Property - - 0 - - - - 33rd Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 33rd Point Property - - 0 - - - - 34th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 34th Point Property - - 0 - - - - 35th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 35th Point Property - - 0 - - - - 36th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 36th Point Property - - 0 - - - - 37th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 37th Point Property - - 0 - - - - 38th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 38th Point Property - - 0 - - - - 39th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 39th Point Property - - 0 - - - - 40th Comparing Position - - -2147483648 - 2147483647 - 0 - - - - 40th Point Property - - 0 - - - - - ro - - - - #x2030 - Comm Read Servo Variable - 通讯读取相关变量 - DT2030 - 64 - - - SubIndex 000 - - 3 - - - - Servo Status - - 0 - 65535 - 0 - - - - DO Function1 - - 0 - 65535 - 0 - - - - DO Function2 - - 0 - 65535 - 0 - - - - - ro - - - - #x2031 - Comm Set Servo Variable - 通讯给定相关变量 - DT2031 - 224 - - - SubIndex 000 - - 5 - - - - Comm Set VDI - - 0 - 65535 - 0 - - - - Comm Set DO - - 0 - 65535 - 0 - - - - Comm Set AO - - -10000 - 10000 - 0 - - - - Comm Set Local SpdRef - - -9000000 - 9000000 - 0 - - - - Comm Set Local TrqRef - - -100000 - 100000 - 0 - - - - - ro - - - - #x203F - Manufacturor Error code - 伺服故障码 - UDINT - 32 - - #x00000000 - #xFFFFFFFF - #x00000000 - - - ro - T - - - - #x603F - Error code - UINT - 16 - - #x0000 - #xFFFF - #x0000 - - - ro - T - - - - #x6040 - Control word - UINT - 16 - - #x0000 - #xFFFF - #x0000 - - - rw - R - - - - #x6041 - Status word - UINT - 16 - - #x0000 - #xFFFF - #x0000 - - - ro - T - - - - #x605A - Quick stop option code - INT - 16 - - #x0000 - #x0007 - #x0002 - - - rw - - - - #x605C - Disable operation option code - INT - 16 - - #xFFFC - #x0002 - #x0000 - - - rw - - - - #x605D - Halt option Code - INT - 16 - - #x0001 - #x0003 - #x0001 - - - rw - - - - #x605E - Fault Reaction option Code - INT - 16 - - #xFFFB - #x0004 - #x0002 - - - rw - - - - #x6060 - Modes of operation - SINT - 8 - - 0 - 10 - 0 - - - rw - R - - - - #x6061 - Modes of operation display - SINT - 8 - - 0 - 10 - 0 - - - ro - T - - - - #x6062 - Position demand value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x6063 - Position actual internal value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x6064 - Position actual value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x6065 - Following error window - UDINT - 32 - - #x0 - #xFFFFFFFF - #x1A36AE7 - - - rw - R - - - - #x6066 - Following error time out - UINT - 16 - - #x0 - #xFFFF - #x0 - - - rw - R - - - - #x6067 - Position window - UDINT - 32 - - #x0 - #xFFFFFFFF - #x16F0 - - - rw - R - - - - #x6068 - Position window time - UINT - 16 - - #x0 - #xFFFF - #x0 - - - rw - R - - - - #x606C - Velocity actual value - DINT - 32 - - #x80000000 - #x7FFFFFFF - 0 - - - ro - T - - - - #x606D - Velocity window - UINT - 16 - - #x0000 - #xFFFF - #xA - - - rw - R - - - - #x606E - Velocity window time - UINT - 16 - - #x0000 - #xFFFF - #x0 - - - rw - - - - #x606F - Velocity threshold - UINT - 16 - - #x0000 - #xFFFF - #xA - - - rw - R - - - - #x6070 - Velocity threshold time - UINT - 16 - - #x0000 - #xFFFF - #x0 - - - rw - - - - #x6071 - Target torque - INT - 16 - - #xF060 - #x0FA0 - #x0 - - - rw - R - - - - #x6072 - Max Torque - UINT - 16 - - #x0 - #x0FA0 - #x0DAC - - - rw - R - - - - #x6074 - Torque demand - INT - 16 - - #xF060 - #x0FA0 - #x0 - - - ro - T - - - - #x6077 - Torque actual value - INT - 16 - - #xF060 - #x0FA0 - #x0 - - - ro - T - - - - #x607A - Target position - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x607C - Home offset - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x607D - Software position limit - DT607D - 80 - - - SubIndex 000 - - #x02 - - - - Min position limit - - #x80000000 - #x7FFFFFFF - #x80000000 - - - - Max position limit - - #x80000000 - #x7FFFFFFF - #x7FFFFFFF - - - - - ro - - - - #x607E - Polarity - USINT - 8 - - #x0 - #xFF - #x0 - - - rw - R - - - - #x607F - Max profile velocity - UDINT - 32 - - #x0 - #xFFFFFFFF - #x32000000 - - - rw - R - - - - #x6081 - Profile velocity - UDINT - 32 - - #x0 - #xFFFFFFFF - #xD55555 - - - rw - R - - - - #x6083 - Profile acceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #x53555555 - - - rw - R - - - - #x6084 - Profile deceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #x53555555 - - - rw - R - - - - #x6085 - Quick stop deceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #x7FFFFFFF - - - rw - R - - - - #x6086 - Motion profile type - INT - 16 - - #x8000 - #x7FFF - #x0 - - - rw - R - - - - #x6087 - Torque slope - UDINT - 32 - - #x0 - #xFFFFFFFF - #xFFFFFFFF - - - rw - R - - - - #x6091 - Gear ratio - DT6091 - 80 - - - SubIndex 000 - - #x02 - - - - Motor revolutions - - #x1 - #xFFFFFFFF - #x1 - - - - Shaft revolutions - - #x1 - #xFFFFFFFF - #x1 - - - - - ro - - - - #x6098 - Homing method - SINT - 8 - - #xFD - #x23 - 1 - - - rw - R - - - - #x6099 - Homing speeds - DT6099 - 80 - - - SubIndex 000 - - #x02 - - - - Speed during search for switch - - 0 - #xFFFFFFFF - #xD55555 - - - - Speed during search for zero - - 0 - #xFFFFFFFF - #x155555 - - - - - ro - - - - #x609A - Homing acceleration - UDINT - 32 - - 0 - #xFFFFFFFF - #x53555555 - - - rw - R - - - - #x60B0 - Position offset - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x60B1 - Velocity offset - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x60B2 - Torque offset - INT - 16 - - #xF060 - #x0FA0 - #x0 - - - rw - R - - - - #x60B8 - Touch probe function - UINT - 16 - - #x0 - #xFFFF - #x0 - - - rw - R - - - - #x60B9 - Touch Probe Status - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60BA - Touch probe 1 positive edge - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60BB - Touch probe 1 negative edge - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60BC - Touch probe 2 positive edge - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60BD - Touch probe 2 negative edge - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60C5 - Max Acceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #xFFFFFFFF - - - rw - R - - - - #x60C6 - Max Deceleration - UDINT - 32 - - #x0 - #xFFFFFFFF - #xFFFFFFFF - - - rw - R - - - - #x60D5 - Touch probe 1 positive edge counter - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60D6 - Touch probe 1 negative edge counter - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60D7 - Touch probe 2 positive edge counter - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60D8 - Touch probe 2 negative edge counter - UINT - 16 - - #x0 - #xFFFF - #x0 - - - ro - T - - - - #x60E0 - Positive torque limit value - UINT - 16 - - #x0 - #x0FA0 - #x0DAC - - - rw - R - - - - #x60E1 - Negative torque limit value - UINT - 16 - - #x0 - #x0FA0 - #x0DAC - - - rw - R - - - - #x60E3 - Supported homing methods - DT60E3 - 544 - - - SubIndex 000 - - #x0 - #x22 - 33 - - - - Support homing method 1 - - #x01 - - - - Support homing method 2 - - #x02 - - - - Support homing method 3 - - #x03 - - - - Support homing method 4 - - #x04 - - - - Support homing method 5 - - #x05 - - - - Support homing method 6 - - #x06 - - - - Support homing method 7 - - #x07 - - - - Support homing method 8 - - #x08 - - - - Support homing method 9 - - #x09 - - - - Support homing method 10 - - #x0A - - - - Support homing method 11 - - #x0B - - - - Support homing method 12 - - #x0C - - - - Support homing method 13 - - #x0D - - - - Support homing method 14 - - #x0E - - - - Support homing method 15 - - #x11 - - - - Support homing method 16 - - #x12 - - - - Support homing method 17 - - #x13 - - - - Support homing method 18 - - #x14 - - - - Support homing method 19 - - #x15 - - - - Support homing method 20 - - #x16 - - - - Support homing method 21 - - #x17 - - - - Support homing method 22 - - #x18 - - - - Support homing method 23 - - #x19 - - - - Support homing method 24 - - #x1A - - - - Support homing method 25 - - #x1B - - - - Support homing method 26 - - #x1C - - - - Support homing method 27 - - #x1D - - - - Support homing method 28 - - #x1E - - - - Support homing method 29 - - #x21 - - - - Support homing method 30 - - #x22 - - - - Support homing method 31 - - #x23 - - - - Support homing method 32 - - #xFF - - - - Support homing method 33 - - #xFE - - - - - ro - - - - #x60F4 - Following error actual value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60FC - Position demand internal value - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - ro - T - - - - #x60FD - Digital inputs - UDINT - 32 - - #x0 - #xFFFFFFFF - #x0 - - - ro - T - - - - #x60FE - Digital outputs - DT60FE - 80 - - - SubIndex 000 - - #x02 - - - - Physical outputs - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - Bit Mask - - #x00000000 - #xFFFFFFFF - #x00000000 - - - - - ro - - - - #x60FF - Target velocity - DINT - 32 - - #x80000000 - #x7FFFFFFF - #x0 - - - rw - R - - - - #x6502 - Supported drive modes - UDINT - 32 - - #x00000000 - #xFFFFFFFF - #x000003AD - - - ro - - - - - - Outputs - Inputs - MBoxState - MBoxOut - MBoxIn - Outputs - Inputs - - #x1600 - Outputs - #x1601 - #x1701 - #x1702 - #x1703 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - - #x1601 - Outputs - #x1600 - #x1701 - #x1702 - #x1703 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x6071 - 0 - 16 - Target torque - INT - - - #x607A - 0 - 32 - Target position - DINT - - - #x607F - 0 - 32 - Max profile velocity - UDINT - - - #x6081 - 0 - 32 - profile velocity - UDINT - - - #x6083 - 0 - 32 - profile acceleration - UDINT - - - #x6084 - 0 - 32 - profile deceleration - UDINT - - - #x6087 - 0 - 32 - Torque Slope - UDINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - - #x1701 - Outputs - #x1600 - #x1601 - #x1702 - #x1703 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x60FE - 1 - 32 - Physical outputs - UDINT - - - - #x1702 - Outputs - #x1600 - #x1601 - #x1701 - #x1703 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - #x6071 - 0 - 16 - Target torque - INT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x607F - 0 - 32 - Max profile velocity - UDINT - - - - #x1703 - Outputs - #x1600 - #x1601 - #x1701 - #x1702 - #x1704 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x60E0 - 0 - 16 - Positive torque limit value - UINT - - - #x60E1 - 0 - 16 - Negative torque limit value - UINT - - - - #x1704 - Outputs - #x1600 - #x1601 - #x1701 - #x1702 - #x1703 - #x1705 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - #x6071 - 0 - 16 - Target torque - INT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x607F - 0 - 32 - Max profile velocity - UDINT - - - #x60E0 - 0 - 16 - Positive torque limit value - UINT - - - #x60E1 - 0 - 16 - Negative torque limit value - UINT - - - - #x1705 - Outputs - #x1600 - #x1601 - #x1701 - #x1702 - #x1703 - #x1704 - - #x6040 - 0 - 16 - Controlword - UINT - - - #x607A - 0 - 32 - Target position - DINT - - - #x60FF - 0 - 32 - Target velocity - DINT - - - #x6060 - 0 - 8 - Modes of operation - SINT - - - #x60B8 - 0 - 16 - Touch probe function - UINT - - - #x60E0 - 0 - 16 - Positive torque limit value - UINT - - - #x60E1 - 0 - 16 - Negative torque limit value - UINT - - - #x60B2 - 0 - 16 - Torque offset - INT - - - - #x1A00 - Inputs - #x1A01 - #x1B01 - #x1B02 - #x1B03 - #x1B04 - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x603F - 0 - 16 - Error code - UINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1A01 - Inputs - #x1A00 - #x1B01 - #x1B02 - #x1B03 - #x1B04 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6061 - 0 - 8 - Modes of operation display - SINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x606C - 0 - 32 - Velocity actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x60F4 - 0 - 32 - Following error actual value - DINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1B01 - Inputs - #x1A00 - #x1A01 - #x1B02 - #x1B03 - #x1B04 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x60F4 - 0 - 32 - Following error actual value - DINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1B02 - Inputs - #x1A00 - #x1A01 - #x1B01 - #x1B03 - #x1B04 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x6061 - 0 - 8 - Modes of operation display - SINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1B03 - Inputs - #x1A00 - #x1A01 - #x1B01 - #x1B02 - #x1B04 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x60F4 - 0 - 32 - Following error actual value - DINT - - - #x6061 - 0 - 8 - Modes of operation display - SINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x60FD - 0 - 32 - Digital inputs - UDINT - - - - #x1B04 - Inputs - #x1A00 - #x1A01 - #x1B01 - #x1B02 - #x1B03 - - #x603F - 0 - 16 - Error code - UINT - - - #x6041 - 0 - 16 - Statusword - UINT - - - #x6064 - 0 - 32 - Position actual value - DINT - - - #x6077 - 0 - 16 - Torque actual value - INT - - - #x6061 - 0 - 8 - Modes of operation display - SINT - - - #x60F4 - 0 - 32 - Following error actual value - DINT - - - #x60B9 - 0 - 16 - Touch probe status - UINT - - - #x60BA - 0 - 32 - Touch probe pos1 pos value - DINT - - - #x60BC - 0 - 32 - Touch probe pos2 pos value - DINT - - - #x606C - 0 - 32 - Velocity actual value - DINT - - - - - - - PS - #x6060 - 0 - 08 - Modes of operation - - - - - - DC - DC-Sync - #x300 - 0 - 0 - 0 - - - Synchron - FreeRun - #x0 - - - - 2048 - 080C0004640000000000 - - 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 - - - + + #x00100000 + Inovance + 汇川技术 + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + + InoServo + Servo Drives + 伺服驱动器 + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + + InoSV670N + SV670_1Axis_05003 + ServoDrive + http://www.inovance.cn + + + + 3000 + 9000 + 5000 + 200 + + + + + 100 + 2000 + + + + InoServo + + + 402 + + + + + + BIT2 + 2 + + + + BOOL + 1 + + + + DINT + 32 + + + + INT + 16 + + + + UDINT + 32 + + + + UINT + 16 + + + + USINT + 8 + + + + SINT + 8 + + + + STRING(10) + 80 + + + + STRING(4) + 32 + + + DT1018 + 144 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Vendor ID + UDINT + 32 + 16 + + ro + + + + 2 + Product Code + UDINT + 32 + 48 + + ro + + + + 3 + Revision + UDINT + 32 + 80 + + ro + + + + 4 + Serial number + UDINT + 32 + 112 + + ro + + + + + DT1600 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + + DT1601 + 368 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + + DT1701 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1702 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1703 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1704 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1705 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1A00 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + + DT1A01 + 368 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + + DT1B01 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B02 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B03 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1B04 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + ro + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + ro + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + ro + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + ro + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + ro + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + ro + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + ro + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + ro + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + ro + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + ro + + + + + DT1C00ARR + USINT + 32 + + 1 + 4 + + + + DT1C00 + 48 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + o + + + + Elements + DT1C00ARR + 32 + 16 + + ro + o + + + + + + DT1C32 + 488 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + m + + + + 1 + Sync mode + UINT + 16 + 16 + + rw + + + + 2 + Cycle time + UDINT + 32 + 32 + + ro + o + + + + 4 + Sync modes supported + UINT + 16 + 96 + + ro + o + + + + 5 + Minimum cycle time + UDINT + 32 + 112 + + ro + o + + + + 6 + Calc and copy time + UDINT + 32 + 144 + + ro + o + + + + 8 + Get Cycle Time + UINT + 16 + 208 + + rw + c + + + + 9 + Delay Time + UDINT + 32 + 224 + + ro + c + + + + 10 + Sync0 Cycle Time + UDINT + 32 + 256 + + rw + o + + + + 11 + SM-Event Missed + UINT + 16 + 288 + + ro + c + + + + 12 + Cycle Time Too Small + UINT + 16 + 304 + + ro + c + + + + 32 + Sync Error + BOOL + 1 + 480 + + ro + c + + + + + + DT1C33 + 488 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + o + + + + 1 + Sync mode + UINT + 16 + 16 + + rw + + + + 2 + Cycle time + UDINT + 32 + 32 + + ro + o + + + + 4 + Sync modes supported + UINT + 16 + 96 + + ro + o + + + + 5 + Minimum cycle time + UDINT + 32 + 112 + + ro + o + + + + 6 + Calc and copy time + UDINT + 32 + 144 + + ro + o + + + + 8 + Get Cycle Time + UINT + 16 + 208 + + rw + c + + + + 9 + Delay Time + UDINT + 32 + 224 + + ro + c + + + + 10 + Sync0 Cycle Time + UDINT + 32 + 256 + + rw + o + + + + 11 + SM-Event Missed + UINT + 16 + 288 + + ro + c + + + + 12 + Cycle Time Too Small + UINT + 16 + 304 + + ro + c + + + + 32 + Sync Error + BOOL + 1 + 480 + + ro + c + + + + + DT1C12ARR + UINT + 16 + + 1 + 1 + + + + DT1C12 + 32 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + Elements + DT1C12ARR + 16 + 16 + + rw + o + + + + + DT1C13ARR + UINT + 16 + + 1 + 1 + + + + DT1C13 + 32 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + Elements + DT1C13ARR + 16 + 16 + + rw + o + + + + + + DT2000 + 128 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Motor SN + UINT + 16 + 16 + + rw + + + + 3 + Customized firmware version + UDINT + 32 + 48 + + ro + + + + 5 + Encoder Version + UINT + 16 + 96 + + ro + + + + 6 + Serial encoder motor SN + UINT + 16 + 112 + + ro + + + + + + DT2001 + 672 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + MCU firmware Version + UINT + 16 + 16 + + ro + + + + 2 + Fpga firmware Version + UINT + 16 + 32 + + ro + + + + 11 + Drive serial number + UINT + 16 + 176 + + rw + + + + 12 + Drive voltage class + UINT + 16 + 192 + + ro + + + + 13 + Drive rated power + UDINT + 32 + 208 + + ro + + + + 15 + Drive maximum output power + UDINT + 32 + 240 + + ro + + + + 17 + Drive rated output current + UDINT + 32 + 272 + + ro + + + + 19 + Drive maximum output current + UDINT + 32 + 304 + + ro + + + + 41 + DC bus overvoltage protective point + UINT + 16 + 656 + + rw + + + + + + DT2002 + 688 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Control mode selection + UINT + 16 + 16 + + rw + + + + 2 + Absolute system selection + UINT + 16 + 32 + + rw + + + + 3 + Rotating direction + UINT + 16 + 48 + + rw + + + + 4 + Output pulse phase + UINT + 16 + 64 + + rw + + + + 6 + Disable operation option Code + INT + 16 + 96 + + rw + + + + 7 + NO2 Fault Reaction option Code + INT + 16 + 112 + + rw + + + + 8 + Stop mode at limit switch signal + UINT + 16 + 128 + + rw + + + + 9 + Stop mode at NO.1 fault + UINT + 16 + 144 + + rw + + + + 10 + Delay from brake output on to command received + UINT + 16 + 160 + + rw + + + + 11 + Delay from brake output off to motor de-energized + UINT + 16 + 176 + + rw + + + + 12 + Motor speed threshold at brake output off in rotating state + UINT + 16 + 192 + + rw + + + + 13 + Delay from servo off to brake output off in the rotating state + UINT + 16 + 208 + + rw + + + + 16 + LED warning display selection + UINT + 16 + 256 + + rw + + + + 18 + MainPower Cutoff Reaction Option Code + UINT + 16 + 288 + + rw + + + + 19 + QuickStop Reaction Option Code + UINT + 16 + 304 + + rw + + + + 22 + Allowed minimum braking resistance + UINT + 16 + 352 + + ro + + + + 23 + Power of built-in braking resistor + UINT + 16 + 368 + + ro + + + + 24 + Resistance of built-in braking resistor + UINT + 16 + 384 + + ro + + + + 25 + Resistor heat dissipation coefficient + UINT + 16 + 400 + + rw + + + + 26 + braking resistor type + UINT + 16 + 416 + + rw + + + + 27 + Power of external dynamic resistor + UINT + 16 + 432 + + rw + + + + 28 + Resistance of external braking resistor + UINT + 16 + 448 + + rw + + + + 31 + User password + UINT + 16 + 496 + + wo + + + + 32 + Parameter initialization + UINT + 16 + 512 + + rw + + + + 33 + Default keypad display + UINT + 16 + 528 + + rw + + + + 36 + Panel data refresh rate + UINT + 16 + 576 + + rw + + + + 42 + OEM password + UINT + 16 + 672 + + wo + + + + + DT2003 + 1056 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 3 + DI1 function selection + UINT + 16 + 48 + + rw + + + + 4 + DI1 logic selection + UINT + 16 + 64 + + rw + + + + 5 + DI2 function selection + UINT + 16 + 80 + + rw + + + + 6 + DI2 logic selection + UINT + 16 + 96 + + rw + + + + 7 + DI3 function selection + UINT + 16 + 112 + + rw + + + + 8 + DI3 logic selection + UINT + 16 + 128 + + rw + + + + 9 + DI4 function selection + UINT + 16 + 144 + + rw + + + + 10 + DI4 logic selection + UINT + 16 + 160 + + rw + + + + 11 + DI5 function selection + UINT + 16 + 176 + + rw + + + + 12 + DI5 logic selection + UINT + 16 + 192 + + rw + + + + 51 + AI1 Offset + INT + 16 + 816 + + rw + + + + 52 + AI1 Filter + UINT + 16 + 832 + + rw + + + + 54 + AI1 Dead Zone + UINT + 16 + 864 + + rw + + + + 55 + AI1 Zero Drifting + INT + 16 + 880 + + rw + + + + 61 + DI1 filtertime constant + UINT + 16 + 976 + + rw + + + + 62 + DI2 filtertime constant + UINT + 16 + 992 + + rw + + + + 63 + DI3 filtertime constant + UINT + 16 + 1008 + + rw + + + + 64 + DI4 filtertime constant + UINT + 16 + 1024 + + rw + + + + 65 + DI5 filtertime constant + UINT + 16 + 1040 + + rw + + + + + DT2004 + 864 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + DO1 Function Selection + UINT + 16 + 16 + + rw + + + + 2 + DO1 Logic Level Selection + UINT + 16 + 32 + + rw + + + + 3 + DO2 Function Selection + UINT + 16 + 48 + + rw + + + + 4 + DO2 Logic Level Selection + UINT + 16 + 64 + + rw + + + + 5 + DO3 Function Selection + UINT + 16 + 80 + + rw + + + + 6 + DO3 Logic Level Selection + UINT + 16 + 96 + + rw + + + + 23 + DO OutPut Source Select + UINT + 16 + 368 + + rw + + + + 24 + ECAT Lost Force DO OutPut Logic + UINT + 16 + 384 + + rw + + + + 51 + AO1 Source Select + UINT + 16 + 816 + + rw + + + + 52 + AO1 Offset + INT + 16 + 832 + + rw + + + + 53 + AO1 Multiplying + INT + 16 + 848 + + rw + + + + + DT2005 + 1152 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 5 + Time constant of first-order low-pass filter + UINT + 16 + 80 + + rw + + + + 7 + Time constant of moving average filter 1 + UINT + 16 + 112 + + rw + + + + 8 + Numerator of electronic gear ratio + UDINT + 32 + 128 + + rw + + + + 10 + Denominator of electronic gear ratio + UDINT + 32 + 160 + + rw + + + + 18 + Encoder frequency division pulses + UDINT + 32 + 288 + + rw + + + + 20 + Speed feedforward control selection + UINT + 16 + 320 + + rw + + + + 31 + Local home mode + UINT + 16 + 496 + + rw + + + + 36 + Time of home searching + UINT + 16 + 576 + + rw + + + + 37 + Local home position offset + DINT + 32 + 592 + + rw + + + + 39 + Servo pulse output source + UINT + 16 + 624 + + rw + + + + 42 + Output polarity of Z pulse + UINT + 16 + 672 + + rw + + + + 51 + Mechanical Gear ratio numerator of absolute encode mode 2 + UINT + 16 + 816 + + rw + + + + 52 + Mechanical Gear ratio denominator of absolute encode mode 2 + UINT + 16 + 832 + + rw + + + + 53 + Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) + UDINT + 32 + 848 + + rw + + + + 55 + Max value of mechanical absolute position(inc) of absolute encode mode 2(High) + UDINT + 32 + 880 + + rw + + + + 59 + Trq Reference of Mechanical Homing + UINT + 16 + 944 + + rw + + + + 61 + Position Coin Hold Time + UINT + 16 + 976 + + rw + + + + 67 + Time Unit of Homing + UINT + 16 + 1072 + + rw + + + + 71 + Time constant of moving average filter 2 + UINT + 16 + 1136 + + rw + + + + + DT2006 + 896 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 4 + Keypad setting value of speed reference + INT + 16 + 64 + + rw + + + + 5 + DI Jog speed reference + UINT + 16 + 80 + + rw + + + + 6 + Acceleration ramp time constant of speed reference + UINT + 16 + 96 + + rw + + + + 7 + Deceleration ramp time constant of speed reference + UINT + 16 + 112 + + rw + + + + 8 + Maximum speed limit + UINT + 16 + 128 + + rw + + + + 9 + Forward speed threshold + UINT + 16 + 144 + + rw + + + + 10 + Reverse speed threshold + UINT + 16 + 160 + + rw + + + + 11 + Quick decelaration coefficient + UINT + 16 + 176 + + rw + + + + 12 + Torque feedforward selection + UINT + 16 + 192 + + rw + + + + 13 + Acceleration/Deceleration ramp time constant of jog speed reference + UINT + 16 + 208 + + rw + + + + 14 + Speed feedforward filter time constant + UINT + 16 + 224 + + rw + + + + 16 + Speed threshold of Zero Hold signal + UINT + 16 + 256 + + rw + + + + 17 + Speed threshold of motor rotation signal + UINT + 16 + 272 + + rw + + + + 18 + Speed threshold of Spd Reach signal + UINT + 16 + 288 + + rw + + + + 19 + Speed threshold of Spd Arrive signal + UINT + 16 + 304 + + rw + + + + 20 + Speed threshold of Zero Spd signal + UINT + 16 + 320 + + rw + + + + 51 + Spd SCurve Enable + UINT + 16 + 816 + + rw + + + + 52 + Spd SCurve Acceleration UP + UINT + 16 + 832 + + rw + + + + 53 + Spd SCurve Acceleration Down + UINT + 16 + 848 + + rw + + + + 54 + Spd SCurve Deceleration UP + UINT + 16 + 864 + + rw + + + + 55 + Spd SCurve Deceleration Down + UINT + 16 + 880 + + rw + + + + + DT2007 + 640 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 4 + Keypad setting value of torque reference + INT + 16 + 64 + + rw + + + + 6 + Torque reference filter time 1 + UINT + 16 + 96 + + rw + + + + 7 + Torque reference filter time 2 + UINT + 16 + 112 + + rw + + + + 10 + Internal forward torque limit + UINT + 16 + 160 + + rw + + + + 11 + Internal reverse torque limit + UINT + 16 + 176 + + rw + + + + 16 + Emergency stop torque + UINT + 16 + 256 + + rw + + + + 20 + Forward speed limit/Speed limit 1 in local torque control + UINT + 16 + 320 + + rw + + + + 21 + Reverse speed limit/Speed limit 2 in local torque control + UINT + 16 + 336 + + rw + + + + 22 + Base value for torque reached + UINT + 16 + 352 + + rw + + + + 23 + Threshold of torque reached valid + UINT + 16 + 368 + + rw + + + + 24 + Threshold of torque reached invalid + UINT + 16 + 384 + + rw + + + + 25 + Depth of field-weakening + UINT + 16 + 400 + + rw + + + + 26 + Maximum field-weakening current + UINT + 16 + 416 + + rw + + + + 27 + Field-weakening enable + UINT + 16 + 432 + + rw + + + + 28 + Field-weakening gain + UINT + 16 + 448 + + rw + + + + 29 + Field-weakening point speed + UINT + 16 + 464 + + ro + + + + 36 + Motor output calibration enable + UINT + 16 + 576 + + rw + + + + 37 + The second-stage torque reference filter time + UINT + 16 + 592 + + rw + + + + 38 + Torque reference filter type select + UINT + 16 + 608 + + rw + + + + 39 + Biquad low pass filter damping + UINT + 16 + 624 + + rw + + + + + DT2008 + 1056 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Speed-loop Gain + UINT + 16 + 16 + + rw + + + + 2 + Speed-loop integral time constant + UINT + 16 + 32 + + rw + + + + 3 + Position-loop Gain + UINT + 16 + 48 + + rw + + + + 4 + The second speed loop gain + UINT + 16 + 64 + + rw + + + + 5 + The second speed loop integral time constant + UINT + 16 + 80 + + rw + + + + 6 + The second position loop gain + UINT + 16 + 96 + + rw + + + + 9 + Second gain mode setting + UINT + 16 + 144 + + rw + + + + 10 + Gain switchover condition + UINT + 16 + 160 + + rw + + + + 11 + Gain switchover delay + UINT + 16 + 176 + + rw + + + + 12 + Gain switchover level + UINT + 16 + 192 + + rw + + + + 13 + Gain switchover hysteresis + UINT + 16 + 208 + + rw + + + + 14 + Position gain switchover time + UINT + 16 + 224 + + rw + + + + 16 + Average value of load inertia ratio + UINT + 16 + 256 + + rw + + + + 18 + Zero-Phase delay time + UINT + 16 + 288 + + rw + + + + 19 + Speed feedforward filter time constant + UINT + 16 + 304 + + rw + + + + 20 + Speed feedforward gain + UINT + 16 + 320 + + rw + + + + 21 + Torque feedforward filter time constant + UINT + 16 + 336 + + rw + + + + 22 + Torque feedforward gain + UINT + 16 + 352 + + rw + + + + 23 + Speed feedback filter + UINT + 16 + 368 + + rw + + + + 24 + Cut-off frequency of speed feedback low-pass filter + UINT + 16 + 384 + + rw + + + + 25 + Pseudo-differential forward feedback control coefficient + UINT + 16 + 400 + + rw + + + + 28 + Cut-off frequency of speed observer + UINT + 16 + 448 + + rw + + + + 29 + Modified inertia coefficient of speed observer + UINT + 16 + 464 + + rw + + + + 30 + Filter time of speed observer + UINT + 16 + 480 + + rw + + + + 32 + Cut-off frequency of torque disturbance observer + UINT + 16 + 512 + + rw + + + + 33 + Compensation gain of torque disturbance observer + UINT + 16 + 528 + + rw + + + + 34 + Modified inertia coefficient of torque disturbance observer + UINT + 16 + 544 + + rw + + + + 41 + Speed observer enable + UINT + 16 + 656 + + rw + + + + 43 + Module control enable + UINT + 16 + 688 + + rw + + + + 44 + Module control gain + UINT + 16 + 704 + + rw + + + + 47 + Module feedforward value + UINT + 16 + 752 + + rw + + + + 54 + 3rd medium and low-frequency vibration suppression frequency + UINT + 16 + 864 + + rw + + + + 55 + 3rd compensation gain of medium and low-frequency vibration suppression frequency + UINT + 16 + 880 + + rw + + + + 57 + 3rd phase modulation of medium and low-frequency vibration suppression frequency + UINT + 16 + 912 + + rw + + + + 60 + 4th medium and low-frequency vibration suppression frequency + UINT + 16 + 960 + + rw + + + + 61 + 4th compensation gain of medium and low-frequency vibration suppression frequency + UINT + 16 + 976 + + rw + + + + 62 + 4th phase modulation of medium and low-frequency vibration suppression frequency + UINT + 16 + 992 + + rw + + + + 63 + Time constant of position loop integration + UINT + 16 + 1008 + + rw + + + + 64 + 2nd time constant of position loop integration + UINT + 16 + 1024 + + rw + + + + 65 + Speed observation feedback source selection + UINT + 16 + 1040 + + rw + + + + + DT2009 + 848 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Auto-adjusting mode + UINT + 16 + 16 + + rw + + + + 2 + Rigidity level selection + UINT + 16 + 32 + + rw + + + + 3 + Working mode of self-adaptive notch + UINT + 16 + 48 + + rw + + + + 4 + Online inertia auto-tuning mode + UINT + 16 + 64 + + rw + + + + 6 + Offline inertia auto-tuning mode + UINT + 16 + 96 + + rw + + + + 7 + Maximum speed for inertia autotuning + UINT + 16 + 112 + + rw + + + + 8 + Acceleration/Deceleration time for inertia autotuning + UINT + 16 + 128 + + rw + + + + 9 + Interval after an inertia autotuning + UINT + 16 + 144 + + rw + + + + 10 + Motor revolutions for an inertia auto-tuning + UINT + 16 + 160 + + rw + + + + 12 + Vibration threshold setting + UINT + 16 + 192 + + rw + + + + 13 + 1st notch frequency + UINT + 16 + 208 + + rw + + + + 14 + 1st notch width level + UINT + 16 + 224 + + rw + + + + 15 + 1st notch attenuation level + UINT + 16 + 240 + + rw + + + + 16 + 2nd notch frequency + UINT + 16 + 256 + + rw + + + + 17 + 2nd notch width level + UINT + 16 + 272 + + rw + + + + 18 + 2nd notch attenuation level + UINT + 16 + 288 + + rw + + + + 19 + 3rd notch frequency + UINT + 16 + 304 + + rw + + + + 20 + 3rd notch width level + UINT + 16 + 320 + + rw + + + + 21 + 3rd notch attenuation level + UINT + 16 + 336 + + rw + + + + 22 + 4th notch frequency + UINT + 16 + 352 + + rw + + + + 23 + 4th notch width level + UINT + 16 + 368 + + rw + + + + 24 + 4th notch attenuation level + UINT + 16 + 384 + + rw + + + + 25 + Obtained resonance frequency + UINT + 16 + 400 + + ro + + + + 26 + 1st anti-resonance point frequency + UINT + 16 + 416 + + rw + + + + 27 + 2nd anti-resonance point frequency + UINT + 16 + 432 + + rw + + + + 33 + Gravity compensation value + INT + 16 + 528 + + rw + + + + 34 + Forward friction compensation + INT + 16 + 544 + + rw + + + + 35 + Reverse friction compensation + INT + 16 + 560 + + rw + + + + 36 + Friction compensation speed + UINT + 16 + 576 + + rw + + + + 37 + Friction compensation speed selection + UINT + 16 + 592 + + rw + + + + 38 + Vibration monitor time + UINT + 16 + 608 + + rw + + + + 39 + 1st terminal low-frequency vibration suppression frequency + UINT + 16 + 624 + + rw + + + + 40 + 1st filter order of low-frequency vibration suppression frequency + UINT + 16 + 640 + + rw + + + + 42 + 5th notch frequency + UINT + 16 + 672 + + rw + + + + 43 + 5th notch width level + UINT + 16 + 688 + + rw + + + + 44 + 5th notch attenuation level + UINT + 16 + 704 + + rw + + + + 45 + 2nd terminal low-frequency vibration suppression frequency + UINT + 16 + 720 + + rw + + + + 46 + 2nd damping frequency ratio of low-frequency vibration suppression frequency + UINT + 16 + 736 + + rw + + + + 48 + 2nd damping coefficient of low-frequency vibration suppression frequency + UINT + 16 + 768 + + rw + + + + 50 + 3rd terminal low-frequency vibration suppression frequency + UINT + 16 + 800 + + rw + + + + 51 + 3rd damping frequency ratio of low-frequency vibration suppression frequency + UINT + 16 + 816 + + rw + + + + 53 + 3rd damping coefficient of low-frequency vibration suppression frequency + UINT + 16 + 832 + + rw + + + + + DT200A + 1536 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Power inputphase loss protection disable + UINT + 16 + 16 + + rw + + + + 2 + Absolute position limit set + UINT + 16 + 32 + + rw + + + + 5 + Motor overload protection gain + UINT + 16 + 80 + + rw + + + + 9 + Overspeed threshold + UINT + 16 + 144 + + rw + + + + 11 + Local following error window + UDINT + 32 + 176 + + rw + + + + 13 + Runaway protection enable + UINT + 16 + 208 + + rw + + + + 19 + Over Temperature value of IPM + UINT + 16 + 304 + + rw + + + + 20 + Touch Probe 1 filter time constant + UINT + 16 + 320 + + rw + + + + 21 + Touch Probe 2 filter time constant + UINT + 16 + 336 + + rw + + + + 22 + STO Display Function Selection + UINT + 16 + 352 + + rw + + + + 24 + Filter time constant of TZ signal + UINT + 16 + 384 + + rw + + + + 26 + Filter time of speed feedback display + UINT + 16 + 416 + + rw + + + + 27 + Motor overload shielding + UINT + 16 + 432 + + rw + + + + 28 + Speed DO Filter time constant + UINT + 16 + 448 + + rw + + + + 30 + Full Closed-loop(ABZ) Filter time constant + UINT + 16 + 480 + + rw + + + + 33 + Overheat protection time duration for locked rotor + UINT + 16 + 528 + + rw + + + + 34 + Overheat protection for locked rotor enable + UINT + 16 + 544 + + rw + + + + 37 + Absolute Encode multi-turns error forbidden + UINT + 16 + 592 + + rw + + + + 41 + Compensation Function + UINT + 16 + 656 + + rw + + + + 50 + Over Temperature value of discharge tube + UINT + 16 + 800 + + rw + + + + 51 + Encoder communiction error threshold + UINT + 16 + 816 + + rw + + + + 52 + Phase lack threshold + UINT + 16 + 832 + + rw + + + + 53 + Over Temperature value of Encoder + UINT + 16 + 848 + + rw + + + + 54 + TouchProbe DI Turn-on Compensation Time + INT + 16 + 864 + + rw + + + + 55 + TouchProbe DI Turn-off Compensation Time + INT + 16 + 880 + + rw + + + + 56 + Runaway current threshold + UINT + 16 + 896 + + rw + + + + 57 + Fault reset delay time + UINT + 16 + 912 + + rw + + + + 58 + Runaway speed threshold + UINT + 16 + 928 + + rw + + + + 59 + Runaway speed filter time constant + UINT + 16 + 944 + + rw + + + + 60 + Runaway protection time window + UINT + 16 + 960 + + rw + + + + 61 + BlackBox Mode Select + UINT + 16 + 976 + + rw + + + + 62 + BlackBox Selected Error Code + UINT + 16 + 992 + + rw + + + + 63 + BlackBox Trig Source + UINT + 16 + 1008 + + rw + + + + 64 + BlackBox Trig Level + DINT + 32 + 1024 + + rw + + + + 66 + BlackBox Trig Level Select + UINT + 16 + 1056 + + rw + + + + 67 + BlackBox Trig Position + UINT + 16 + 1072 + + rw + + + + 68 + BlackBox Trig Frequency Select + UINT + 16 + 1088 + + rw + + + + 71 + The 2nd over speed threshold + UINT + 16 + 1136 + + rw + + + + 72 + Motor over load monitor switch + UINT + 16 + 1152 + + rw + + + + 73 + Maximum ramp stop time + UINT + 16 + 1168 + + rw + + + + 74 + STO Disconnect filter time + UINT + 16 + 1184 + + rw + + + + 75 + STO Mismatch filter time + UINT + 16 + 1200 + + rw + + + + 76 + STO Servo off filter time + UINT + 16 + 1216 + + rw + + + + 86 + Motor Offline Trq Limit + UINT + 16 + 1376 + + rw + + + + 87 + Motor Offline Filter Time + UINT + 16 + 1392 + + rw + + + + 91 + Filter Time Constant of Spd Display + UINT + 16 + 1456 + + rw + + + + 92 + Filter Time Constant of Trq Display + INT + 16 + 1472 + + rw + + + + 93 + Filter Time Constant of Position Display + UINT + 16 + 1488 + + rw + + + + 94 + Filter Time Constant of Voltage Display + UINT + 16 + 1504 + + rw + + + + 95 + Filter Time Constant of Temp Display + UINT + 16 + 1520 + + rw + + + + + DT200B + 1584 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Actual motor rotational speed + INT + 16 + 16 + + ro + T + + + + 2 + Speed reference + INT + 16 + 32 + + ro + T + + + + 3 + Internal torque reference + INT + 16 + 48 + + ro + T + + + + 4 + Monitored DI states + UINT + 16 + 64 + + ro + T + + + + 6 + Monitored DO states + UINT + 16 + 96 + + ro + T + + + + 8 + Absolute position counter + DINT + 32 + 128 + + ro + T + + + + 10 + Mechanical angle + UINT + 16 + 160 + + ro + T + + + + 11 + Electrical angle + UINT + 16 + 176 + + ro + T + + + + 13 + Average load rate + UINT + 16 + 208 + + ro + T + + + + 16 + Encoder position deviation counter + DINT + 32 + 256 + + ro + T + + + + 18 + Feedback pulse counter + DINT + 32 + 288 + + ro + T + + + + 20 + Total power-on time + UDINT + 32 + 320 + + ro + T + + + + 22 + AI1 Voltage DisPlay + INT + 16 + 352 + + ro + T + + + + 25 + Phase current valid value + UINT + 16 + 400 + + ro + T + + + + 27 + Bus voltage + UINT + 16 + 432 + + ro + T + + + + 28 + Module temperature + UINT + 16 + 448 + + ro + T + + + + 29 + Absolute encoder fault info. from FPGA + UINT + 16 + 464 + + ro + + + + 30 + Axis state from FPGA + UINT + 16 + 480 + + ro + + + + 31 + Axis fault info. from FPGA + UINT + 16 + 496 + + ro + + + + 32 + Encoder internal fault info. + UINT + 16 + 512 + + rw + + + + 34 + Displayed fault record + UINT + 16 + 544 + + rw + + + + 35 + Fault code + UINT + 16 + 560 + + ro + + + + 36 + Time stamp upon displayed fault + UDINT + 32 + 576 + + ro + + + + 38 + Current rotational speed upon displayed fault + INT + 16 + 608 + + ro + + + + 39 + Current U upon displayed fault + INT + 16 + 624 + + ro + + + + 40 + Current V upon displayed fault + INT + 16 + 640 + + ro + + + + 41 + Bus voltage upon displayed fault + UINT + 16 + 656 + + ro + + + + 42 + Input terminal state upon displayed fault + UINT + 16 + 672 + + ro + + + + 44 + Output terminal state upon displayed fault + UINT + 16 + 704 + + ro + + + + 46 + Inner error code + UINT + 16 + 736 + + ro + + + + 47 + Fault message of absolute encode from Fpga upon displayed + UINT + 16 + 752 + + ro + + + + 48 + System state from Fpga upon displayed fault + UINT + 16 + 768 + + ro + + + + 49 + System fault message from Fpga upon displayed fault + UINT + 16 + 784 + + ro + + + + 50 + Encode state 1 upon displayed fault + UINT + 16 + 800 + + ro + + + + 52 + Inner error code upon displayed fault + UINT + 16 + 832 + + ro + + + + 53 + Fpga overtime state upon displayed fault + UINT + 16 + 848 + + ro + + + + 54 + Reference position deviation + DINT + 32 + 864 + + ro + T + + + + 56 + Actual motor rotational speed(0.1rpm) + DINT + 32 + 896 + + ro + T + + + + 58 + Control bus voltage + UINT + 16 + 928 + + ro + T + + + + 59 + Mechanical absolute position inc(Low) + UDINT + 32 + 944 + + ro + T + + + + 61 + Mechanical absolute position inc(High) + DINT + 32 + 976 + + ro + T + + + + 64 + Not ready reason + UINT + 16 + 1024 + + ro + + + + 67 + Encoder temperature + UINT + 16 + 1072 + + ro + + + + 68 + Discharge load rate + UINT + 16 + 1088 + + ro + T + + + + 69 + Fpga over time state + UINT + 16 + 1104 + + ro + + + + 71 + Number of turns of absolute encode + UINT + 16 + 1136 + + ro + T + + + + 72 + Single feedback postion of absolute encode + UDINT + 32 + 1152 + + ro + T + + + + 75 + System Error + UINT + 16 + 1200 + + ro + + + + 78 + feedback postion of absolute encode(Low) + UDINT + 32 + 1248 + + ro + T + + + + 80 + feedback postion of absolute encode(High) + DINT + 32 + 1280 + + ro + T + + + + 82 + feedback postion inc of rotating load(Low) + UDINT + 32 + 1312 + + ro + T + + + + 84 + feedback postion inc of rotating load(High) + UDINT + 32 + 1344 + + ro + T + + + + 86 + Single feedback postion of rotating load + UDINT + 32 + 1376 + + ro + T + + + + 88 + IGBT Temperature + UINT + 16 + 1408 + + ro + + + + 91 + Group of unusual function code + UINT + 16 + 1456 + + ro + + + + 92 + Offset of unusual function code + UINT + 16 + 1472 + + ro + + + + 95 + Single Power-On Time + UDINT + 32 + 1520 + + ro + T + + + + 97 + Single Power-On Time upon displayed fault + UDINT + 32 + 1552 + + ro + + + + + DT200D + 400 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Software reset + UINT + 16 + 16 + + rw + + + + 2 + Fault reset + UINT + 16 + 32 + + rw + + + + 3 + Offline inertia autotuning selection + UINT + 16 + 48 + + rw + + + + 5 + Encoder ROM reading/writing + UINT + 16 + 80 + + rw + + + + 6 + Emergency stop + UINT + 16 + 96 + + rw + + + + 11 + AI1 Self-Adjust of Voltage Offset + UINT + 16 + 176 + + rw + + + + 13 + UV phase current auto-tuning + UINT + 16 + 208 + + rw + + + + 18 + Forced DI/DO setting + UINT + 16 + 288 + + rw + + + + 19 + Forced DI level + UINT + 16 + 304 + + rw + + + + 20 + Forced DO setting + UINT + 16 + 320 + + rw + + + + 21 + Absolute Encode Fault Reset + UINT + 16 + 336 + + rw + + + + 24 + Cogging torque self-learning + UINT + 16 + 384 + + rw + + + + + DT200E + 1568 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Node address + UINT + 16 + 16 + + rw + + + + 2 + Update function code values written via communication to EEPROM + UINT + 16 + 32 + + rw + + + + 21 + station auto inc address + UINT + 16 + 336 + + ro + + + + 22 + station alias + UINT + 16 + 352 + + rw + + + + 23 + Sync lost window + UINT + 16 + 368 + + rw + + + + 25 + Sync lost counter + UINT + 16 + 400 + + ro + + + + 26 + Port 0 invalid frame counter + UINT + 16 + 416 + + ro + + + + 27 + Port 1 invalid frame counter + UINT + 16 + 432 + + ro + + + + 28 + Port 0/1 transfer error counter + UINT + 16 + 448 + + ro + + + + 29 + process unit and PDI error counter + UINT + 16 + 464 + + ro + + + + 30 + Port 0/1 lost counter + UINT + 16 + 480 + + ro + + + + 32 + Sync mode set + UINT + 16 + 512 + + rw + + + + 33 + Sync error window + UINT + 16 + 528 + + rw + + + + 34 + EtherCAT network state and link state + UINT + 16 + 544 + + ro + + + + 35 + CSP postion increment over counter + UINT + 16 + 560 + + rw + + + + 36 + ECAT AL Error Code + UINT + 16 + 576 + + ro + + + + 37 + Enhanced link detection enable + UINT + 16 + 592 + + rw + + + + 38 + Reset EtherCAT xml file + UINT + 16 + 608 + + rw + + + + 74 + EtherCAT port control mode and state display + UINT + 16 + 1184 + + ro + + + + 94 + EtherCAT COE version number + UINT + 16 + 1504 + + ro + + + + 97 + EtherCAT xml file version number + UINT + 16 + 1552 + + ro + + + + + DT200F + 720 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Encoder feedback mode + UINT + 16 + 16 + + rw + + + + 2 + Running mode of external encoder + UINT + 16 + 32 + + rw + + + + 3 + SecEncoder Absolute system selection + UINT + 16 + 48 + + rw + + + + 4 + SecEncoder Type selection + UINT + 16 + 64 + + rw + + + + 5 + External encoder pulses per motor revolution + UDINT + 32 + 80 + + rw + + + + 9 + Hybrid deviation excess setting + UDINT + 32 + 144 + + rw + + + + 11 + Hybrid deviation clear setting + UINT + 16 + 176 + + rw + + + + 14 + First-order lowpass filter time of external/internal deviation + UINT + 16 + 224 + + rw + + + + 17 + Hybrid deviation counter + DINT + 32 + 272 + + ro + T + + + + 19 + Pulse feedback display of internal encoder + DINT + 32 + 304 + + ro + T + + + + 21 + Pulse feedback display of external encoder + DINT + 32 + 336 + + ro + T + + + + 23 + SecEncoder Pulse ZPhase Ignore + UINT + 16 + 368 + + rw + + + + 26 + SecEncoder Pulse Z-TouchProbe Selection + UINT + 16 + 416 + + rw + + + + + DT2012 + 1104 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + MultiSpd Function Select + UINT + 16 + 16 + + rw + R + + + + 2 + MultiSpd Final Part Select + UINT + 16 + 32 + + rw + R + + + + 3 + Time Uint of Runing + UINT + 16 + 48 + + rw + R + + + + 4 + AccTime1 + UINT + 16 + 64 + + rw + R + + + + 5 + DecTime1 + UINT + 16 + 80 + + rw + R + + + + 6 + AccTime2 + UINT + 16 + 96 + + rw + R + + + + 7 + DecTime2 + UINT + 16 + 112 + + rw + R + + + + 8 + AccTime3 + UINT + 16 + 128 + + rw + R + + + + 9 + DecTime3 + UINT + 16 + 144 + + rw + R + + + + 10 + AccTime4 + UINT + 16 + 160 + + rw + R + + + + 11 + DecTime4 + UINT + 16 + 176 + + rw + R + + + + 21 + 1st Part Spd Cmd + INT + 16 + 336 + + rw + R + + + + 22 + 1st Part Spd Runing Time + UINT + 16 + 352 + + rw + R + + + + 23 + 1st Part AccDec Time Select + UINT + 16 + 368 + + rw + R + + + + 24 + 2nd Part Spd Cmd + INT + 16 + 384 + + rw + R + + + + 25 + 2nd Part Spd Runing Time + UINT + 16 + 400 + + rw + R + + + + 26 + 2nd Part AccDec Time Select + UINT + 16 + 416 + + rw + R + + + + 27 + 3rd Part Spd Cmd + INT + 16 + 432 + + rw + R + + + + 28 + 3rd Part Spd Runing Time + UINT + 16 + 448 + + rw + R + + + + 29 + 3rd Part AccDec Time Select + UINT + 16 + 464 + + rw + R + + + + 30 + 4th Part Spd Cmd + INT + 16 + 480 + + rw + R + + + + 31 + 4th Part Spd Runing Time + UINT + 16 + 496 + + rw + R + + + + 32 + 4th Part AccDec Time Select + UINT + 16 + 512 + + rw + R + + + + 33 + 5th Part Spd Cmd + INT + 16 + 528 + + rw + R + + + + 34 + 5th Part Spd Runing Time + UINT + 16 + 544 + + rw + R + + + + 35 + 5th Part AccDec Time Select + UINT + 16 + 560 + + rw + R + + + + 36 + 6th Part Spd Cmd + INT + 16 + 576 + + rw + R + + + + 37 + 6th Part Spd Runing Time + UINT + 16 + 592 + + rw + R + + + + 38 + 6th Part AccDec Time Select + UINT + 16 + 608 + + rw + R + + + + 39 + 7th Part Spd Cmd + INT + 16 + 624 + + rw + R + + + + 40 + 7th Part Spd Runing Time + UINT + 16 + 640 + + rw + R + + + + 41 + 7th Part AccDec Time Select + UINT + 16 + 656 + + rw + R + + + + 42 + 8th Part Spd Cmd + INT + 16 + 672 + + rw + R + + + + 43 + 8th Part Spd Runing Time + UINT + 16 + 688 + + rw + R + + + + 44 + 8th Part AccDec Time Select + UINT + 16 + 704 + + rw + R + + + + 45 + 9th Part Spd Cmd + INT + 16 + 720 + + rw + R + + + + 46 + 9th Part Spd Runing Time + UINT + 16 + 736 + + rw + R + + + + 47 + 9th Part AccDec Time Select + UINT + 16 + 752 + + rw + R + + + + 48 + 10th Part Spd Cmd + INT + 16 + 768 + + rw + R + + + + 49 + 10th Part Spd Runing Time + UINT + 16 + 784 + + rw + R + + + + 50 + 10th Part AccDec Time Select + UINT + 16 + 800 + + rw + R + + + + 51 + 11th Part Spd Cmd + INT + 16 + 816 + + rw + R + + + + 52 + 11th Part Spd Runing Time + UINT + 16 + 832 + + rw + R + + + + 53 + 11th Part AccDec Time Select + UINT + 16 + 848 + + rw + R + + + + 54 + 12th Part Spd Cmd + INT + 16 + 864 + + rw + R + + + + 55 + 12th Part Spd Runing Time + UINT + 16 + 880 + + rw + R + + + + 56 + 12th Part AccDec Time Select + UINT + 16 + 896 + + rw + R + + + + 57 + 13th Part Spd Cmd + INT + 16 + 912 + + rw + R + + + + 58 + 13th Part Spd Runing Time + UINT + 16 + 928 + + rw + R + + + + 59 + 13th Part AccDec Time Select + UINT + 16 + 944 + + rw + R + + + + 60 + 14th Part Spd Cmd + INT + 16 + 960 + + rw + R + + + + 61 + 14th Part Spd Runing Time + UINT + 16 + 976 + + rw + R + + + + 62 + 14th Part AccDec Time Select + UINT + 16 + 992 + + rw + R + + + + 63 + 15th Part Spd Cmd + INT + 16 + 1008 + + rw + R + + + + 64 + 15th Part Spd Runing Time + UINT + 16 + 1024 + + rw + R + + + + 65 + 15th Part AccDec Time Select + UINT + 16 + 1040 + + rw + R + + + + 66 + 16th Part Spd Cmd + INT + 16 + 1056 + + rw + R + + + + 67 + 16th Part Spd Runing Time + UINT + 16 + 1072 + + rw + R + + + + 68 + 16th Part AccDec Time Select + UINT + 16 + 1088 + + rw + R + + + + + DT2017 + 1520 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + VDI1 Terminal Function Selection + UINT + 16 + 16 + + rw + + + + 2 + VDI1 Terminal Logic Selection + UINT + 16 + 32 + + rw + + + + 3 + VDI2 Terminal Function Selection + UINT + 16 + 48 + + rw + + + + 4 + VDI2 Terminal Logic Selection + UINT + 16 + 64 + + rw + + + + 5 + VDI3 Terminal Function Selection + UINT + 16 + 80 + + rw + + + + 6 + VDI3 Terminal Logic Selection + UINT + 16 + 96 + + rw + + + + 7 + VDI4 Terminal Function Selection + UINT + 16 + 112 + + rw + + + + 8 + VDI4 Terminal Logic Selection + UINT + 16 + 128 + + rw + + + + 9 + VDI5 Terminal Function Selection + UINT + 16 + 144 + + rw + + + + 10 + VDI5 Terminal Logic Selection + UINT + 16 + 160 + + rw + + + + 11 + VDI6 Terminal Function Selection + UINT + 16 + 176 + + rw + + + + 12 + VDI6 Terminal Logic Selection + UINT + 16 + 192 + + rw + + + + 13 + VDI7 Terminal Function Selection + UINT + 16 + 208 + + rw + + + + 14 + VDI7 Terminal Logic Selection + UINT + 16 + 224 + + rw + + + + 15 + VDI8 Terminal Function Selection + UINT + 16 + 240 + + rw + + + + 16 + VDI8 Terminal Logic Selection + UINT + 16 + 256 + + rw + + + + 17 + VDI9 Terminal Function Selection + UINT + 16 + 272 + + rw + + + + 18 + VDI9 Terminal Logic Selection + UINT + 16 + 288 + + rw + + + + 19 + VDI10 Terminal Function Selection + UINT + 16 + 304 + + rw + + + + 20 + VDI10 Terminal Logic Selection + UINT + 16 + 320 + + rw + + + + 21 + VDI11 Terminal Function Selection + UINT + 16 + 336 + + rw + + + + 22 + VDI11 Terminal Logic Selection + UINT + 16 + 352 + + rw + + + + 23 + VDI12 Terminal Function Selection + UINT + 16 + 368 + + rw + + + + 24 + VDI12 Terminal Logic Selection + UINT + 16 + 384 + + rw + + + + 25 + VDI13 Terminal Function Selection + UINT + 16 + 400 + + rw + + + + 26 + VDI13 Terminal Logic Selection + UINT + 16 + 416 + + rw + + + + 27 + VDI14 Terminal Function Selection + UINT + 16 + 432 + + rw + + + + 28 + VDI14 Terminal Logic Selection + UINT + 16 + 448 + + rw + + + + 29 + VDI15 Terminal Function Selection + UINT + 16 + 464 + + rw + + + + 30 + VDI15 Terminal Logic Selection + UINT + 16 + 480 + + rw + + + + 31 + VDI16 Terminal Function Selection + UINT + 16 + 496 + + rw + + + + 32 + VDI16 Terminal Logic Selection + UINT + 16 + 512 + + rw + + + + 33 + VDO virtual level + UINT + 16 + 528 + + ro + + + + 34 + VDO1 Terminal Function Selection + UINT + 16 + 544 + + rw + + + + 35 + VDO1 Terminal Logic Level Selection + UINT + 16 + 560 + + rw + + + + 36 + VDO2 Terminal Function Selection + UINT + 16 + 576 + + rw + + + + 37 + VDO2 Terminal Logic Level Selection + UINT + 16 + 592 + + rw + + + + 38 + VDO3 Terminal Function Selection + UINT + 16 + 608 + + rw + + + + 39 + VDO3 Terminal Logic Level Selection + UINT + 16 + 624 + + rw + + + + 40 + VDO4 Terminal Function Selection + UINT + 16 + 640 + + rw + + + + 41 + VDO4 Terminal Logic Level Selection + UINT + 16 + 656 + + rw + + + + 42 + VDO5 Terminal Function Selection + UINT + 16 + 672 + + rw + + + + 43 + VDO5 Terminal Logic Level Selection + UINT + 16 + 688 + + rw + + + + 44 + VDO6 Terminal Function Selection + UINT + 16 + 704 + + rw + + + + 45 + VDO6 Terminal Logic Level Selection + UINT + 16 + 720 + + rw + + + + 46 + VDO7 Terminal Function Selection + UINT + 16 + 736 + + rw + + + + 47 + VDO7 Terminal Logic Level Selection + UINT + 16 + 752 + + rw + + + + 48 + VDO8 Terminal Function Selection + UINT + 16 + 768 + + rw + + + + 49 + VDO8 Terminal Logic Level Selection + UINT + 16 + 784 + + rw + + + + 50 + VDO9 Terminal Function Selection + UINT + 16 + 800 + + rw + + + + 51 + VDO9 Terminal Logic Level Selection + UINT + 16 + 816 + + rw + + + + 52 + VDO10 Terminal Function Selection + UINT + 16 + 832 + + rw + + + + 53 + VDO10 Terminal Logic Level Selection + UINT + 16 + 848 + + rw + + + + 54 + VDO11 Terminal Function Selection + UINT + 16 + 864 + + rw + + + + 55 + VDO11 Terminal Logic Level Selection + UINT + 16 + 880 + + rw + + + + 56 + VDO12 Terminal Function Selection + UINT + 16 + 896 + + rw + + + + 57 + VDO12 Terminal Logic Level Selection + UINT + 16 + 912 + + rw + + + + 58 + VDO13 Terminal Function Selection + UINT + 16 + 928 + + rw + + + + 59 + VDO13 Terminal Logic Level Selection + UINT + 16 + 944 + + rw + + + + 60 + VDO14 Terminal Function Selection + UINT + 16 + 960 + + rw + + + + 61 + VDO14 Terminal Logic Level Selection + UINT + 16 + 976 + + rw + + + + 62 + VDO15 Terminal Function Selection + UINT + 16 + 992 + + rw + + + + 63 + VDO15 Terminal Logic Level Selection + UINT + 16 + 1008 + + rw + + + + 64 + VDO16 Terminal Function Selection + UINT + 16 + 1024 + + rw + + + + 65 + VDO16 Terminal Logic Level Selection + UINT + 16 + 1040 + + rw + + + + 91 + VDI Enable + UINT + 16 + 1456 + + rw + R + + + + 92 + VDI Default Value + UINT + 16 + 1472 + + rw + R + + + + 93 + VDO Enable + UINT + 16 + 1488 + + rw + R + + + + 94 + VDO Default Value + UINT + 16 + 1504 + + rw + R + + + + + DT2018 + 288 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Enable Comparison + UINT + 16 + 16 + + rw + R + + + + 2 + Comparison PosFdb Source Select + UINT + 16 + 32 + + rw + R + + + + 3 + Encoder Resolution + UINT + 16 + 48 + + rw + R + + + + 4 + Mode Of Comparison + UINT + 16 + 64 + + rw + R + + + + 5 + Current Position As Zero + UINT + 16 + 80 + + rw + R + + + + 6 + Output Duration + UINT + 16 + 96 + + rw + R + + + + 7 + Comparison ABZ OutPut Logic + UINT + 16 + 112 + + rw + R + + + + 8 + Starting Point Number + UINT + 16 + 128 + + rw + R + + + + 9 + Ending Point Number + UINT + 16 + 144 + + rw + R + + + + 10 + Comparison Status + UINT + 16 + 160 + + ro + T + + + + 11 + Current Position + DINT + 32 + 176 + + ro + T + + + + 13 + Position Offset + DINT + 32 + 208 + + rw + R + + + + 15 + Comparison OutPut Delay Compensation + INT + 16 + 240 + + rw + R + + + + 16 + Lilited number of Comparison Cycle Times + UINT + 16 + 256 + + rw + R + + + + 17 + Comparison ABZ OutPut Function + UINT + 16 + 272 + + rw + R + + + + + DT2019 + 1936 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + 1st Comparing Position + DINT + 32 + 16 + + rw + R + + + + 3 + 1st Point Property + UINT + 16 + 48 + + rw + R + + + + 4 + 2nd Comparing Position + DINT + 32 + 64 + + rw + R + + + + 6 + 2nd Point Property + UINT + 16 + 96 + + rw + R + + + + 7 + 3rd Comparing Position + DINT + 32 + 112 + + rw + R + + + + 9 + 3rd Point Property + UINT + 16 + 144 + + rw + R + + + + 10 + 4th Comparing Position + DINT + 32 + 160 + + rw + R + + + + 12 + 4th Point Property + UINT + 16 + 192 + + rw + R + + + + 13 + 5th Comparing Position + DINT + 32 + 208 + + rw + R + + + + 15 + 5th Point Property + UINT + 16 + 240 + + rw + R + + + + 16 + 6th Comparing Position + DINT + 32 + 256 + + rw + R + + + + 18 + 6th Point Property + UINT + 16 + 288 + + rw + R + + + + 19 + 7th Comparing Position + DINT + 32 + 304 + + rw + R + + + + 21 + 7th Point Property + UINT + 16 + 336 + + rw + R + + + + 22 + 8th Comparing Position + DINT + 32 + 352 + + rw + R + + + + 24 + 8th Point Property + UINT + 16 + 384 + + rw + R + + + + 25 + 9th Comparing Position + DINT + 32 + 400 + + rw + R + + + + 27 + 9th Point Property + UINT + 16 + 432 + + rw + R + + + + 28 + 10th Comparing Position + DINT + 32 + 448 + + rw + R + + + + 30 + 10th Point Property + UINT + 16 + 480 + + rw + R + + + + 31 + 11th Comparing Position + DINT + 32 + 496 + + rw + R + + + + 33 + 11th Point Property + UINT + 16 + 528 + + rw + R + + + + 34 + 12th Comparing Position + DINT + 32 + 544 + + rw + R + + + + 36 + 12th Point Property + UINT + 16 + 576 + + rw + R + + + + 37 + 13th Comparing Position + DINT + 32 + 592 + + rw + R + + + + 39 + 13th Point Property + UINT + 16 + 624 + + rw + R + + + + 40 + 14th Comparing Position + DINT + 32 + 640 + + rw + R + + + + 42 + 14th Point Property + UINT + 16 + 672 + + rw + R + + + + 43 + 15th Comparing Position + DINT + 32 + 688 + + rw + R + + + + 45 + 15th Point Property + UINT + 16 + 720 + + rw + R + + + + 46 + 16th Comparing Position + DINT + 32 + 736 + + rw + R + + + + 48 + 16th Point Property + UINT + 16 + 768 + + rw + R + + + + 49 + 17th Comparing Position + DINT + 32 + 784 + + rw + R + + + + 51 + 17th Point Property + UINT + 16 + 816 + + rw + R + + + + 52 + 18th Comparing Position + DINT + 32 + 832 + + rw + R + + + + 54 + 18th Point Property + UINT + 16 + 864 + + rw + R + + + + 55 + 19th Comparing Position + DINT + 32 + 880 + + rw + R + + + + 57 + 19th Point Property + UINT + 16 + 912 + + rw + R + + + + 58 + 20th Comparing Position + DINT + 32 + 928 + + rw + R + + + + 60 + 20th Point Property + UINT + 16 + 960 + + rw + R + + + + 61 + 21st Comparing Position + DINT + 32 + 976 + + rw + R + + + + 63 + 21st Point Property + UINT + 16 + 1008 + + rw + R + + + + 64 + 22nd Comparing Position + DINT + 32 + 1024 + + rw + R + + + + 66 + 22nd Point Property + UINT + 16 + 1056 + + rw + R + + + + 67 + 23rd Comparing Position + DINT + 32 + 1072 + + rw + R + + + + 69 + 23rd Point Property + UINT + 16 + 1104 + + rw + R + + + + 70 + 24th Comparing Position + DINT + 32 + 1120 + + rw + R + + + + 72 + 24th Point Property + UINT + 16 + 1152 + + rw + R + + + + 73 + 25th Comparing Position + DINT + 32 + 1168 + + rw + R + + + + 75 + 25th Point Property + UINT + 16 + 1200 + + rw + R + + + + 76 + 26th Comparing Position + DINT + 32 + 1216 + + rw + R + + + + 78 + 26th Point Property + UINT + 16 + 1248 + + rw + R + + + + 79 + 27th Comparing Position + DINT + 32 + 1264 + + rw + R + + + + 81 + 27th Point Property + UINT + 16 + 1296 + + rw + R + + + + 82 + 28th Comparing Position + DINT + 32 + 1312 + + rw + R + + + + 84 + 28th Point Property + UINT + 16 + 1344 + + rw + R + + + + 85 + 29th Comparing Position + DINT + 32 + 1360 + + rw + R + + + + 87 + 29th Point Property + UINT + 16 + 1392 + + rw + R + + + + 88 + 30th Comparing Position + DINT + 32 + 1408 + + rw + R + + + + 90 + 30th Point Property + UINT + 16 + 1440 + + rw + R + + + + 91 + 31st Comparing Position + DINT + 32 + 1456 + + rw + R + + + + 93 + 31st Point Property + UINT + 16 + 1488 + + rw + R + + + + 94 + 32nd Comparing Position + DINT + 32 + 1504 + + rw + R + + + + 96 + 32nd Point Property + UINT + 16 + 1536 + + rw + R + + + + 97 + 33rd Comparing Position + DINT + 32 + 1552 + + rw + R + + + + 99 + 33rd Point Property + UINT + 16 + 1584 + + rw + R + + + + 100 + 34th Comparing Position + DINT + 32 + 1600 + + rw + R + + + + 102 + 34th Point Property + UINT + 16 + 1632 + + rw + R + + + + 103 + 35th Comparing Position + DINT + 32 + 1648 + + rw + R + + + + 105 + 35th Point Property + UINT + 16 + 1680 + + rw + R + + + + 106 + 36th Comparing Position + DINT + 32 + 1696 + + rw + R + + + + 108 + 36th Point Property + UINT + 16 + 1728 + + rw + R + + + + 109 + 37th Comparing Position + DINT + 32 + 1744 + + rw + R + + + + 111 + 37th Point Property + UINT + 16 + 1776 + + rw + R + + + + 112 + 38th Comparing Position + DINT + 32 + 1792 + + rw + R + + + + 114 + 38th Point Property + UINT + 16 + 1824 + + rw + R + + + + 115 + 39th Comparing Position + DINT + 32 + 1840 + + rw + R + + + + 117 + 39th Point Property + UINT + 16 + 1872 + + rw + R + + + + 118 + 40th Comparing Position + DINT + 32 + 1888 + + rw + R + + + + 120 + 40th Point Property + UINT + 16 + 1920 + + rw + R + + + + + DT2030 + 64 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Servo Status + UINT + 16 + 16 + + ro + T + + + + 2 + DO Function1 + UINT + 16 + 32 + + ro + T + + + + 3 + DO Function2 + UINT + 16 + 48 + + ro + T + + + + + DT2031 + 224 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Comm Set VDI + UINT + 16 + 16 + + rw + R + + + + 5 + Comm Set DO + UINT + 16 + 80 + + rw + R + + + + 6 + Comm Set AO + INT + 16 + 96 + + rw + R + + + + 10 + Comm Set Local SpdRef + DINT + 32 + 160 + + rw + R + + + + 12 + Comm Set Local TrqRef + DINT + 32 + 192 + + rw + R + + + + + DT607D + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Min position limit + DINT + 32 + 16 + + rw + R + + + + 2 + Max position limit + DINT + 32 + 48 + + rw + R + + + + + DT6091 + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Motor revolutions + UDINT + 32 + 16 + + rw + R + + + + 2 + Shaft revolutions + UDINT + 32 + 48 + + rw + R + + + + + DT6099 + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Speed during search for switch + UDINT + 32 + 16 + + rw + R + + + + 2 + Speed during search for zero + UDINT + 32 + 48 + + rw + R + + + + + DT60FE + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Physical outputs + UDINT + 32 + 16 + + rw + R + + + + 2 + Bit Mask + UDINT + 32 + 48 + + rw + R + + + + + DT60E3 + 544 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Support homing method 1 + INT + 16 + 16 + + ro + + + + 2 + Support homing method 2 + INT + 16 + 32 + + ro + + + + 3 + Support homing method 3 + INT + 16 + 48 + + ro + + + + 4 + Support homing method 4 + INT + 16 + 64 + + ro + + + + 5 + Support homing method 5 + INT + 16 + 80 + + ro + + + + 6 + Support homing method 6 + INT + 16 + 96 + + ro + + + + 7 + Support homing method 7 + INT + 16 + 112 + + ro + + + + 8 + Support homing method 8 + INT + 16 + 128 + + ro + + + + 9 + Support homing method 9 + INT + 16 + 144 + + ro + + + + 10 + Support homing method 10 + INT + 16 + 160 + + ro + + + + 11 + Support homing method 11 + INT + 16 + 176 + + ro + + + + 12 + Support homing method 12 + INT + 16 + 192 + + ro + + + + 13 + Support homing method 13 + INT + 16 + 208 + + ro + + + + 14 + Support homing method 14 + INT + 16 + 224 + + ro + + + + 15 + Support homing method 15 + INT + 16 + 240 + + ro + + + + 16 + Support homing method 16 + INT + 16 + 256 + + ro + + + + 17 + Support homing method 17 + INT + 16 + 272 + + ro + + + + 18 + Support homing method 18 + INT + 16 + 288 + + ro + + + + 19 + Support homing method 19 + INT + 16 + 304 + + ro + + + + 20 + Support homing method 20 + INT + 16 + 320 + + ro + + + + 21 + Support homing method 21 + INT + 16 + 336 + + ro + + + + 22 + Support homing method 22 + INT + 16 + 352 + + ro + + + + 23 + Support homing method 23 + INT + 16 + 368 + + ro + + + + 24 + Support homing method 24 + INT + 16 + 384 + + ro + + + + 25 + Support homing method 25 + INT + 16 + 400 + + ro + + + + 26 + Support homing method 26 + INT + 16 + 416 + + ro + + + + 27 + Support homing method 27 + INT + 16 + 432 + + ro + + + + 28 + Support homing method 28 + INT + 16 + 448 + + ro + + + + 29 + Support homing method 29 + INT + 16 + 464 + + ro + + + + 30 + Support homing method 30 + INT + 16 + 480 + + ro + + + + 31 + Support homing method 31 + INT + 16 + 496 + + ro + + + + 32 + Support homing method 32 + INT + 16 + 512 + + ro + + + + 33 + Support homing method 33 + INT + 16 + 528 + + ro + + + + + + + #x1000 + Device type + UDINT + 32 + + #x00020192 + + + ro + o + + + + #x1001 + Error Register + USINT + 8 + + 00 + + + ro + o + + + + #x1008 + Device name + STRING(10) + 80 + + SV670_ECAT + + + ro + + + + #x1009 + Hardware version + STRING(4) + 32 + + V1.0 + + + ro + + + + #x100a + Software version + STRING(4) + 32 + + V1.0 + + + ro + o + + + + #x1c00 + Sync manager type + DT1C00 + 48 + + + SubIndex 000 + + 04 + + + + SubIndex 001 + + 01 + + + + SubIndex 002 + + 02 + + + + SubIndex 003 + + 03 + + + + SubIndex 004 + + 04 + + + + + ro + o + + + + #x1018 + Identity + DT1018 + 144 + + + SubIndex 000 + + 04 + + + + Vendor ID + + #x00100000 + + + + Product Code + + #x000C011E + + + + Revision + + #x00010000 + + + + Serial number + + 00000000 + + + + + ro + o + + + + #x1600 + Outputs + DT1600 + 336 + + + SubIndex 000 + + 00 + 10 + #x03 + + + + 1st Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60400010 + + + + 2nd Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x607A0020 + + + + 3rd Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60B80010 + + + + 4th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 5th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 6th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 7th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 8th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 9th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 10th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + rw + + + + #x1601 + Outputs + DT1601 + 368 + + + SubIndex 000 + + #x0B + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x60600008 + + + + 3rd Output Object to be mapped + + #x60710010 + + + + 4th Output Object to be mapped + + #x607A0020 + + + + 5th Output Object to be mapped + + #x607F0020 + + + + 6th Output Object to be mapped + + #x60810020 + + + + 7th Output Object to be mapped + + #x60830020 + + + + 8th Output Object to be mapped + + #x60840020 + + + + 9th Output Object to be mapped + + #x60870020 + + + + 10th Output Object to be mapped + + #x60B80010 + + + + 11th Output Object to be mapped + + #x60FF0020 + + + + + rw + + + + #x1701 + Outputs + DT1701 + 336 + + + SubIndex 000 + + #x04 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60B80010 + + + + 4th Output Object to be mapped + + #x60FE0120 + + + + + ro + + + + #x1702 + Outputs + DT1702 + 336 + + + SubIndex 000 + + #x07 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60B80010 + + + + 4th Output Object to be mapped + + #x60710010 + + + + 5th Output Object to be mapped + + #x60600008 + + + + 6th Output Object to be mapped + + #x60B80010 + + + + 7th Output Object to be mapped + + #x607F0020 + + + + + ro + + + + #x1703 + Outputs + DT1702 + 336 + + + SubIndex 000 + + #x07 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60600008 + + + + 5th Output Object to be mapped + + #x60B80010 + + + + 6th Output Object to be mapped + + #x60E00010 + + + + 7th Output Object to be mapped + + #x60E10010 + + + + + ro + + + + #x1704 + Outputs + DT1704 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60710010 + + + + 5th Output Object to be mapped + + #x60600008 + + + + 6th Output Object to be mapped + + #x60B80010 + + + + 7th Output Object to be mapped + + #x607F0020 + + + + 8th Output Object to be mapped + + #x60E00010 + + + + 9th Output Object to be mapped + + #x60E10010 + + + + + ro + + + + #x1705 + Outputs + DT1705 + 336 + + + SubIndex 000 + + #x08 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x607A0020 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60600008 + + + + 5th Output Object to be mapped + + #x60B80010 + + + + 6th Output Object to be mapped + + #x60E00010 + + + + 7th Output Object to be mapped + + #x60E10010 + + + + 8th Output Object to be mapped + + #x60B20010 + + + + + ro + + + + #x1A00 + Inputs + DT1A00 + 336 + + + SubIndex 000 + + 00 + 10 + #x07 + + + + 1st Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60410010 + + + + 2nd Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60640020 + + + + 3rd Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60B90010 + + + + 4th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60BA0020 + + + + 5th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60BC0020 + + + + 6th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x603F0010 + + + + 7th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60FD0020 + + + + 8th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 9th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 10th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + rw + + + + #x1A01 + Inputs + DT1A01 + 368 + + + SubIndex 000 + + #x0B + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60610008 + + + + 4th Input Object to be mapped + + #x60640020 + + + + 5th Input Object to be mapped + + #x606C0020 + + + + 6th Input Object to be mapped + + #x60770010 + + + + 7th Input Object to be mapped + + #x60B90010 + + + + 8th Input Object to be mapped + + #x60BA0020 + + + + 9th Input Object to be mapped + + #x60BC0020 + + + + 10th Input Object to be mapped + + #x60F40020 + + + + 11th Input Object to be mapped + + #x60FD0020 + + + + + rw + + + + #x1B01 + Inputs + DT1B01 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60F40020 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B02 + Inputs + DT1B01 + 336 + + + SubIndex 000 + + #x09 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60610008 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B03 + Inputs + DT1B03 + 336 + + + SubIndex 000 + + #x0A + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60F40020 + + + + 6th Input Object to be mapped + + #x60610008 + + + + 7th Input Object to be mapped + + #x60B90010 + + + + 8th Input Object to be mapped + + #x60BA0020 + + + + 9th Input Object to be mapped + + #x60BC0020 + + + + 10th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B04 + Inputs + DT1B04 + 336 + + + SubIndex 000 + + #x0A + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60640020 + + + + 4th Input Object to be mapped + + #x60770010 + + + + 5th Input Object to be mapped + + #x60610008 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + 10th Input Object to be mapped + + #x606C0020 + + + + + ro + + + + #x1c32 + SM output parameter + DT1C32 + 488 + + + SubIndex 000 + + 20 + + + + Sync mode + + 0200 + + + + Cycle time + + 00000000 + + + + Sync modes supported + + 0004 + + + + Minimum cycle time + + 00000000 + + + + Calc and copy time + + #x0003d090 + + + + Get Cycle Time + + 0000 + + + + Delay Time + + 00000000 + + + + Sync0 Cycle Time + + 00000000 + + + + SM-Event Missed + + 0000 + + + + Cycle Time Too Small + + 0000 + + + + Sync Error + + 00 + + + + + ro + o + + + + #x1c33 + SM input parameter + DT1C33 + 488 + + + SubIndex 000 + + 20 + + + + Sync mode + + 0002 + + + + Cycle time + + 00000000 + + + + Sync modes supported + + 4 + + + + Minimum cycle time + + 00000000 + + + + Calc and copy time + + 00000000 + + + + Get Cycle Time + + 0000 + + + + Delay Time + + 00000000 + + + + Sync0 Cycle Time + + 00000000 + + + + SM-Event Missed + + 0000 + + + + Cycle Time Too Small + + 0000 + + + + Sync Error + + 00 + + + + + ro + o + + + + #x1c12 + RxPDO assign + DT1C12 + 32 + + + SubIndex 000 + + 00 + + + + SubIndex 001 + + 0000 + + + + + ro + + + + #x1c13 + TxPDO assign + DT1C13 + 32 + + + SubIndex 000 + + 00 + + + + SubIndex 001 + + 0000 + + + + + ro + + + + #x2000 + Servo Motor Parameters + 伺服电机参数 + DT2000 + 128 + + + SubIndex 000 + + 6 + + + + Motor SN + + 0 + 65535 + 14101 + + + + Customized firmware version + + 0 + 65535 + 0 + + + + Encoder Version + + 0 + 65535 + 0 + + + + Serial encoder motor SN + + 0 + 65535 + 0 + + + + + ro + + + + #x2001 + Servo Drive Parameters + 伺服驱动器参数 + DT2001 + 672 + + + SubIndex 000 + + 41 + + + + MCU firmware Version + + 0 + 65535 + 0 + + + + Fpga firmware Version + + 0 + 65535 + 0 + + + + Drive serial number + + 0 + 65535 + 3 + + + + Drive voltage class + + 0 + 65535 + 220 + + + + Drive rated power + + 0 + 1073741824 + 400 + + + + Drive maximum output power + + 0 + 1073741824 + 400 + + + + Drive rated output current + + 0 + 1073741824 + 280 + + + + Drive maximum output current + + 0 + 1073741824 + 1010 + + + + DC bus overvoltage protective point + + 0 + 2000 + 420 + + + + + ro + + + + #x2002 + Basic control + 基本控制参数 + DT2002 + 688 + + + SubIndex 000 + + 36 + + + + Control mode selection + + 0 + 9 + 9 + + + + Absolute system selection + + 0 + 4 + 0 + + + + Rotating direction + + 0 + 1 + 0 + + + + Output pulse phase + + 0 + 1 + 0 + + + + Disable operation option Code + + -4 + 2 + 0 + + + + NO2 Fault Reaction option Code + + -5 + 4 + 2 + + + + Stop mode at limit switch signal + + 0 + 7 + 1 + + + + Stop mode at NO.1 fault + + 0 + 2 + 2 + + + + Delay from brake output on to command received + + 0 + 500 + 250 + + + + Delay from brake output off to motor de-energized + + 50 + 1000 + 150 + + + + Motor speed threshold at brake output off in rotating state + + 20 + 3000 + 30 + + + + Delay from servo off to brake output off in the rotating state + + 1 + 65535 + 500 + + + + LED warning display selection + + 0 + 1 + 0 + + + + MainPower Cutoff Reaction Option Code + + 0 + 3 + 2 + + + + QuickStop Reaction Option Code + + 0 + 7 + 2 + + + + Allowed minimum braking resistance + + 1 + 1000 + 40 + + + + Power of built-in braking resistor + + 0 + 65535 + 50 + + + + Resistance of built-in braking resistor + + 0 + 65535 + 50 + + + + Resistor heat dissipation coefficient + + 10 + 100 + 30 + + + + braking resistor type + + 0 + 3 + 3 + + + + Power of external dynamic resistor + + 1 + 65535 + 40 + + + + Resistance of external braking resistor + + 15 + 1000 + 50 + + + + User password + + 0 + 65535 + 0 + + + + Parameter initialization + + 0 + 2 + 0 + + + + Default keypad display + + 0 + 99 + 50 + + + + Panel data refresh rate + + 0 + 20 + 0 + + + + OEM password + + 0 + 65535 + 0 + + + + + ro + + + + #x2003 + Input Terminal Parameters + 端子输入参数 + DT2003 + 1056 + + + SubIndex 000 + + 65 + + + + DI1 function selection + + 0 + 40 + 14 + + + + DI1 logic selection + + 0 + 1 + 0 + + + + DI2 function selection + + 0 + 40 + 15 + + + + DI2 logic selection + + 0 + 1 + 0 + + + + DI3 function selection + + 0 + 40 + 31 + + + + DI3 logic selection + + 0 + 1 + 0 + + + + DI4 function selection + + 0 + 40 + 34 + + + + DI4 logic selection + + 0 + 1 + 0 + + + + DI5 function selection + + 0 + 40 + 38 + + + + DI5 logic selection + + 0 + 1 + 0 + + + + AI1 Offset + + -5000 + 5000 + 0 + + + + AI1 Filter + + 0 + 65535 + 200 + + + + AI1 Dead Zone + + 0 + 10000 + 100 + + + + AI1 Zero Drifting + + -5000 + 5000 + 0 + + + + DI1 filtertime constant + + 0 + 50000 + 300 + + + + DI2 filtertime constant + + 0 + 50000 + 300 + + + + DI3 filtertime constant + + 0 + 50000 + 300 + + + + DI4 filtertime constant + + 0 + 50000 + 300 + + + + DI5 filtertime constant + + 0 + 50000 + 300 + + + + + ro + + + + #x2004 + Output terminal Parameters + 端子输出参数 + DT2004 + 864 + + + SubIndex 000 + + 53 + + + + DO1 Function Selection + + 0 + 65535 + 1 + + + + DO1 Logic Level Selection + + 0 + 1 + 0 + + + + DO2 Function Selection + + 0 + 65535 + 9 + + + + DO2 Logic Level Selection + + 0 + 1 + 0 + + + + DO3 Function Selection + + 0 + 65535 + 9 + + + + DO3 Logic Level Selection + + 0 + 1 + 0 + + + + DO OutPut Source Select + + 0 + 3 + 0 + + + + ECAT Lost Force DO OutPut Logic + + 0 + 3 + 0 + + + + AO1 Source Select + + 0 + 10 + 0 + + + + AO1 Offset + + -10000 + 10000 + 0 + + + + AO1 Multiplying + + -10000 + 10000 + 100 + + + + + ro + + + + #x2005 + Position Control Parameters + 位置控制参数组 + DT2005 + 1152 + + + SubIndex 000 + + 55 + + + + Time constant of first-order low-pass filter + + 0 + 65535 + 0 + + + + Time constant of moving average filter 1 + + 0 + 1280 + 0 + + + + Numerator of electronic gear ratio + + 1 + 1073741824 + 1 + + + + Denominator of electronic gear ratio + + 1 + 1073741824 + 1 + + + + Encoder frequency division pulses + + 0 + 4194303 + 2500 + + + + Speed feedforward control selection + + 0 + 3 + 1 + + + + Local home mode + + 0 + 8 + 0 + + + + Time of home searching + + 0 + 65535 + 10000 + + + + Local home position offset + + -2147483648 + 2147483647 + 0 + + + + Servo pulse output source + + 0 + 3 + 0 + + + + Output polarity of Z pulse + + 0 + 65535 + 1 + + + + Mechanical Gear ratio numerator of absolute encode mode 2 + + 1 + 65535 + 1 + + + + Mechanical Gear ratio denominator of absolute encode mode 2 + + 1 + 65535 + 1 + + + + Max value of mechanical absolute position(inc) of absolute encode mode 2(Low) + + 0 + 4294967295 + 0 + + + + Max value of mechanical absolute position(inc) of absolute encode mode 2(High) + + 0 + 4294967295 + 0 + + + + Trq Reference of Mechanical Homing + + 0 + 4000 + 1000 + + + + Position Coin Hold Time + + 0 + 30000 + 0 + + + + Time Unit of Homing + + 0 + 2 + 2 + + + + Time constant of moving average filter 2 + + 0 + 10000 + 0 + + + + + ro + + + + #x2006 + Speed control + 速度控制 + DT2006 + 896 + + + SubIndex 000 + + 16 + + + + Keypad setting value of speed reference + + -10000 + 10000 + 200 + + + + DI Jog speed reference + + 0 + 10000 + 150 + + + + Acceleration ramp time constant of speed reference + + 0 + 65535 + 0 + + + + Deceleration ramp time constant of speed reference + + 0 + 65535 + 0 + + + + Maximum speed limit + + 0 + 10000 + 7000 + + + + Forward speed threshold + + 0 + 10000 + 7000 + + + + Reverse speed threshold + + 0 + 10000 + 7000 + + + + Quick decelaration coefficient + + 0 + 2 + 0 + + + + Torque feedforward selection + + 0 + 2 + 1 + + + + Acceleration/Deceleration ramp time constant of jog speed reference + + 0 + 65535 + 10 + + + + Speed feedforward filter time constant + + 0 + 65535 + 0 + + + + Speed threshold of Zero Hold signal + + 0 + 10000 + 10 + + + + Speed threshold of motor rotation signal + + 0 + 1000 + 20 + + + + Speed threshold of Spd Reach signal + + 0 + 100 + 10 + + + + Speed threshold of Spd Arrive signal + + 20 + 10000 + 1000 + + + + Speed threshold of Zero Spd signal + + 1 + 10000 + 10 + + + + Spd SCurve Enable + + 0 + 1 + 1 + + + + Spd SCurve Acceleration UP + + 0 + 1000 + 500 + + + + Spd SCurve Acceleration Down + + 0 + 1000 + 500 + + + + Spd SCurve Deceleration UP + + 0 + 1000 + 500 + + + + Spd SCurve Deceleration Down + + 0 + 1000 + 500 + + + + + ro + + + + #x2007 + Torque control + 转矩控制参数 + DT2007 + 640 + + + SubIndex 000 + + 40 + + + + Keypad setting value of torque reference + + -4000 + 4000 + 0 + + + + Torque reference filter time 1 + + 0 + 3000 + 50 + + + + Torque reference filter time 2 + + 0 + 3000 + 27 + + + + Internal forward torque limit + + 0 + 4000 + 3500 + + + + Internal reverse torque limit + + 0 + 4000 + 3500 + + + + Emergency stop torque + + 0 + 4000 + 1000 + + + + Forward speed limit/Speed limit 1 in local torque control + + 0 + 6000 + 3000 + + + + Reverse speed limit/Speed limit 2 in local torque control + + 0 + 6000 + 3000 + + + + Base value for torque reached + + 0 + 4000 + 0 + + + + Threshold of torque reached valid + + 0 + 4000 + 200 + + + + Threshold of torque reached invalid + + 0 + 4000 + 100 + + + + Depth of field-weakening + + 60 + 115 + 115 + + + + Maximum field-weakening current + + 0 + 300 + 100 + + + + Field-weakening enable + + 0 + 1 + 0 + + + + Field-weakening gain + + 1 + 1000 + 30 + + + + Field-weakening point speed + + 0 + 65535 + 0 + + + + Motor output calibration enable + + 0 + 1 + 0 + + + + The second-stage torque reference filter time + + 0 + 1000 + 0 + + + + Torque reference filter type select + + 0 + 1 + 0 + + + + Biquad low pass filter damping + + 0 + 50 + 16 + + + + + ro + + + + #x2008 + Gain Parameters + 增益参数 + DT2008 + 1056 + + + SubIndex 000 + + 65 + + + + Speed-loop Gain + + 1 + 20000 + 400 + + + + Speed-loop integral time constant + + 15 + 51200 + 1989 + + + + Position-loop Gain + + 1 + 20000 + 640 + + + + The second speed loop gain + + 1 + 20000 + 750 + + + + The second speed loop integral time constant + + 15 + 51200 + 1061 + + + + The second position loop gain + + 1 + 20000 + 1200 + + + + Second gain mode setting + + 0 + 1 + 1 + + + + Gain switchover condition + + 0 + 10 + 0 + + + + Gain switchover delay + + 0 + 10000 + 50 + + + + Gain switchover level + + 0 + 20000 + 50 + + + + Gain switchover hysteresis + + 0 + 20000 + 30 + + + + Position gain switchover time + + 0 + 10000 + 30 + + + + Average value of load inertia ratio + + 0 + 12000 + 100 + + + + Zero-Phase delay time + + 0 + 40 + 0 + + + + Speed feedforward filter time constant + + 0 + 6400 + 50 + + + + Speed feedforward gain + + 0 + 1000 + 0 + + + + Torque feedforward filter time constant + + 0 + 6400 + 50 + + + + Torque feedforward gain + + 0 + 3000 + 0 + + + + Speed feedback filter + + 0 + 4 + 0 + + + + Cut-off frequency of speed feedback low-pass filter + + 100 + 8000 + 8000 + + + + Pseudo-differential forward feedback control coefficient + + 0 + 2000 + 1000 + + + + Cut-off frequency of speed observer + + 50 + 600 + 170 + + + + Modified inertia coefficient of speed observer + + 1 + 1600 + 100 + + + + Filter time of speed observer + + 0 + 1000 + 80 + + + + Cut-off frequency of torque disturbance observer + + 10 + 4000 + 600 + + + + Compensation gain of torque disturbance observer + + 0 + 100 + 0 + + + + Modified inertia coefficient of torque disturbance observer + + 1 + 1600 + 100 + + + + Speed observer enable + + 0 + 1 + 0 + + + + Module control enable + + 0 + 2 + 0 + + + + Module control gain + + 1 + 20000 + 400 + + + + Module feedforward value + + 0 + 1024 + 950 + + + + 3rd medium and low-frequency vibration suppression frequency + + 0 + 3000 + 0 + + + + 3rd compensation gain of medium and low-frequency vibration suppression frequency + + 0 + 200 + 0 + + + + 3rd phase modulation of medium and low-frequency vibration suppression frequency + + 0 + 600 + 100 + + + + 4th medium and low-frequency vibration suppression frequency + + 0 + 3000 + 0 + + + + 4th compensation gain of medium and low-frequency vibration suppression frequency + + 0 + 200 + 0 + + + + 4th phase modulation of medium and low-frequency vibration suppression frequency + + 0 + 600 + 100 + + + + Time constant of position loop integration + + 15 + 51200 + 51200 + + + + 2nd time constant of position loop integration + + 15 + 51200 + 51200 + + + + Speed observation feedback source selection + + 0 + 1 + 0 + + + + + ro + + + + #x2009 + Auto-adjusting Parameters + 自整定参数 + DT2009 + 848 + + + SubIndex 000 + + 60 + + + + Auto-adjusting mode + + 0 + 7 + 4 + + + + Rigidity level selection + + 0 + 41 + 15 + + + + Working mode of self-adaptive notch + + 0 + 4 + 0 + + + + Online inertia auto-tuning mode + + 0 + 3 + 0 + + + + Offline inertia auto-tuning mode + + 0 + 1 + 0 + + + + Maximum speed for inertia autotuning + + 100 + 1000 + 500 + + + + Acceleration/Deceleration time for inertia autotuning + + 20 + 800 + 125 + + + + Interval after an inertia autotuning + + 50 + 10000 + 800 + + + + Motor revolutions for an inertia auto-tuning + + 0 + 10000 + 100 + + + + Vibration threshold setting + + 0 + 1000 + 50 + + + + 1st notch frequency + + 50 + 8000 + 8000 + + + + 1st notch width level + + 0 + 20 + 2 + + + + 1st notch attenuation level + + 0 + 99 + 0 + + + + 2nd notch frequency + + 50 + 8000 + 8000 + + + + 2nd notch width level + + 0 + 20 + 2 + + + + 2nd notch attenuation level + + 0 + 99 + 0 + + + + 3rd notch frequency + + 50 + 8000 + 8000 + + + + 3rd notch width level + + 0 + 20 + 2 + + + + 3rd notch attenuation level + + 0 + 99 + 0 + + + + 4th notch frequency + + 50 + 8000 + 8000 + + + + 4th notch width level + + 0 + 20 + 2 + + + + 4th notch attenuation level + + 0 + 99 + 0 + + + + Obtained resonance frequency + + 0 + 5000 + 0 + + + + 1st anti-resonance point frequency + + 0 + 5000 + 0 + + + + 2nd anti-resonance point frequency + + 0 + 5000 + 0 + + + + Gravity compensation value + + 0 + 1000 + 0 + + + + Forward friction compensation + + 0 + 1000 + 0 + + + + Reverse friction compensation + + -1000 + 0 + 0 + + + + Friction compensation speed + + 0 + 200 + 20 + + + + Friction compensation speed selection + + 0 + 19 + 0 + + + + Vibration monitor time + + 0 + 65535 + 300 + + + + 1st terminal low-frequency vibration suppression frequency + + 10 + 1000 + 1000 + + + + 1st filter order of low-frequency vibration suppression frequency + + 0 + 3 + 2 + + + + 5th notch frequency + + 50 + 8000 + 8000 + + + + 5th notch width level + + 0 + 20 + 2 + + + + 5th notch attenuation level + + 0 + 99 + 0 + + + + 2nd terminal low-frequency vibration suppression frequency + + 0 + 2000 + 0 + + + + 2nd damping frequency ratio of low-frequency vibration suppression frequency + + 1 + 1000 + 100 + + + + 2nd damping coefficient of low-frequency vibration suppression frequency + + 0 + 200 + 100 + + + + 3rd terminal low-frequency vibration suppression frequency + + 0 + 2000 + 0 + + + + 3rd damping frequency ratio of low-frequency vibration suppression frequency + + 1 + 1000 + 100 + + + + 3rd damping coefficient of low-frequency vibration suppression frequency + + 0 + 200 + 100 + + + + + ro + + + + #x200A + Error and Protection Parameter + 故障与保护参数 + DT200A + 1536 + + + SubIndex 000 + + 60 + + + + Power inputphase loss protection disable + + 0 + 1 + 0 + + + + Absolute position limit set + + 0 + 2 + 0 + + + + Motor overload protection gain + + 50 + 300 + 100 + + + + Overspeed threshold + + 0 + 20000 + 0 + + + + Local following error window + + 0 + 4294967295 + 27486951 + + + + Runaway protection enable + + 0 + 1 + 1 + + + + Over Temperature value of IPM + + 120 + 175 + 140 + + + + Touch Probe 1 filter time constant + + 0 + 630 + 200 + + + + Touch Probe 2 filter time constant + + 0 + 630 + 200 + + + + STO Display Function Selection + + 0 + 1 + 0 + + + + Filter time constant of TZ signal + + 0 + 31 + 15 + + + + Filter time of speed feedback display + + 0 + 5000 + 50 + + + + Motor overload shielding + + 0 + 1 + 0 + + + + Speed DO Filter time constant + + 0 + 5000 + 50 + + + + Full Closed-loop(ABZ) Filter time constant + + 0 + 255 + 15 + + + + Overheat protection time duration for locked rotor + + 10 + 65535 + 200 + + + + Overheat protection for locked rotor enable + + 0 + 1 + 1 + + + + Absolute Encode multi-turns error forbidden + + 0 + 1 + 0 + + + + Compensation Function + + 0 + 15 + 6 + + + + Over Temperature value of discharge tube + + 100 + 175 + 115 + + + + Encoder communiction error threshold + + 0 + 31 + 5 + + + + Phase lack threshold + + 3 + 36 + 20 + + + + Over Temperature value of Encoder + + 0 + 175 + 125 + + + + TouchProbe DI Turn-on Compensation Time + + -3000 + 3000 + 200 + + + + TouchProbe DI Turn-off Compensation Time + + -3000 + 3000 + 1512 + + + + Runaway current threshold + + 1000 + 4000 + 2000 + + + + Fault reset delay time + + 0 + 60000 + 10000 + + + + Runaway speed threshold + + 1 + 1000 + 50 + + + + Runaway speed filter time constant + + 1 + 1000 + 20 + + + + Runaway protection time window + + 10 + 1000 + 30 + + + + BlackBox Mode Select + + 0 + 3 + 1 + + + + BlackBox Selected Error Code + + 0 + 65535 + 0 + + + + BlackBox Trig Source + + 0 + 25 + 0 + + + + BlackBox Trig Level + + -2147483648 + 2147483647 + 0 + + + + BlackBox Trig Level Select + + 0 + 3 + 0 + + + + BlackBox Trig Position + + 0 + 100 + 75 + + + + BlackBox Trig Frequency Select + + 0 + 2 + 0 + + + + The 2nd over speed threshold + + 0 + 20000 + 0 + + + + Motor over load monitor switch + + 0 + 65535 + 4098 + + + + Maximum ramp stop time + + 0 + 65535 + 10000 + + + + STO Disconnect filter time + + 1 + 5 + 5 + + + + STO Mismatch filter time + + 1 + 1000 + 100 + + + + STO Servo off filter time + + 0 + 25 + 20 + + + + Motor Offline Trq Limit + + 40 + 4000 + 50 + + + + Motor Offline Filter Time + + 5 + 1000 + 30 + + + + Filter Time Constant of Spd Display + + 0 + 100 + 0 + + + + Filter Time Constant of Trq Display + + 0 + 100 + 0 + + + + Filter Time Constant of Position Display + + 0 + 100 + 0 + + + + Filter Time Constant of Voltage Display + + 0 + 250 + 0 + + + + Filter Time Constant of Temp Display + + 0 + 250 + 0 + + + + + ro + + + + #x200B + Display Parameters + 显示参数 + DT200B + 1584 + + + Number of Entries + + 92 + + + + Actual motor rotational speed + + 0 + + + + Speed reference + + 0 + + + + Internal torque reference + + 0 + + + + Monitored DI states + + 0 + + + + Monitored DO states + + 0 + + + + Absolute position counter + + 0 + + + + Mechanical angle + + 0 + + + + Electrical angle + + 0 + + + + Average load rate + + 0 + + + + Encoder position deviation counter + + 0 + + + + Feedback pulse counter + + 0 + + + + Total power-on time + + 0 + + + + AI1 Voltage DisPlay + + 0 + + + + Phase current valid value + + 0 + + + + Bus voltage + + 0 + + + + Module temperature + + 0 + + + + Absolute encoder fault info. from FPGA + + 0 + + + + Axis state from FPGA + + 0 + + + + Axis fault info. from FPGA + + 0 + + + + Encoder internal fault info. + + 0 + + + + Displayed fault record + + 0 + 19 + 0 + + + + Fault code + + 0 + + + + Time stamp upon displayed fault + + 0 + + + + Current rotational speed upon displayed fault + + 0 + + + + Current U upon displayed fault + + 0 + + + + Current V upon displayed fault + + 0 + + + + Bus voltage upon displayed fault + + 0 + + + + Input terminal state upon displayed fault + + 0 + + + + Output terminal state upon displayed fault + + 0 + + + + Inner error code + + 0 + + + + Fault message of absolute encode from Fpga upon displayed + + 0 + + + + System state from Fpga upon displayed fault + + 0 + + + + System fault message from Fpga upon displayed fault + + 0 + + + + Encode state 1 upon displayed fault + + 0 + + + + Inner error code upon displayed fault + + 0 + + + + Fpga overtime state upon displayed fault + + 0 + + + + Reference position deviation + + 0 + + + + Actual motor rotational speed(0.1rpm) + + 0 + + + + Control bus voltage + + 0 + + + + Mechanical absolute position inc(Low) + + 0 + + + + Mechanical absolute position inc(High) + + 0 + + + + Not ready reason + + 0 + + + + Encoder temperature + + 0 + + + + Discharge load rate + + 0 + + + + Fpga over time state + + 0 + + + + Number of turns of absolute encode + + 0 + + + + Single feedback postion of absolute encode + + 0 + + + + System Error + + 0 + + + + feedback postion of absolute encode(Low) + + 0 + + + + feedback postion of absolute encode(High) + + 0 + + + + feedback postion inc of rotating load(Low) + + 0 + + + + feedback postion inc of rotating load(High) + + 0 + + + + Single feedback postion of rotating load + + 0 + + + + IGBT Temperature + + 0 + + + + Group of unusual function code + + 0 + + + + Offset of unusual function code + + 0 + + + + Single Power-On Time + + 0 + + + + Single Power-On Time upon displayed fault + + 0 + + + + + ro + + + + #x200D + Auxiliary Function Parameters + 辅助功能参数 + DT200D + 400 + + + Number of Entries + + 21 + + + + Software reset + + 0 + 1 + 0 + + + + Fault reset + + 0 + 1 + 0 + + + + Offline inertia autotuning selection + + 0 + 1 + 0 + + + + Encoder ROM reading/writing + + 0 + 3 + 0 + + + + Emergency stop + + 0 + 1 + 0 + + + + AI1 Self-Adjust of Voltage Offset + + 0 + 1 + 0 + + + + UV phase current auto-tuning + + 0 + 1 + 0 + + + + Forced DI/DO setting + + 0 + 3 + 0 + + + + Forced DI level + + 0 + 31 + 31 + + + + Forced DO setting + + 0 + 3 + 0 + + + + Absolute Encode Fault Reset + + 0 + 2 + 0 + + + + Cogging torque self-learning + + 0 + 1 + 0 + + + + + ro + + + + #x200E + Communication parameters + 通信参数 + DT200E + 1568 + + + Number of Entries + + 97 + + + + Node address + + 1 + 127 + 1 + + + + Update function code values written via communication to EEPROM + + 0 + 4 + 4 + + + + station auto inc address + + 0 + 65535 + 0 + + + + station alias + + 0 + 65535 + 0 + + + + Sync lost window + + 1 + 20 + 8 + + + + Sync lost counter + + 0 + 65535 + 0 + + + + Port 0 invalid frame counter + + 0 + 65535 + 0 + + + + Port 1 invalid frame counter + + 0 + 65535 + 0 + + + + Port 0/1 transfer error counter + + 0 + 65535 + 0 + + + + process unit and PDI error counter + + 0 + 255 + 0 + + + + Port 0/1 lost counter + + 0 + 65535 + 0 + + + + Sync mode set + + 0 + 2 + 2 + + + + Sync error window + + 100 + 4000 + 4000 + + + + EtherCAT network state and link state + + 0 + 65535 + 0 + + + + CSP postion increment over counter + + 1 + 30 + 20 + + + + ECAT AL Error Code + + 0 + 65535 + 0 + + + + Enhanced link detection enable + + 0 + 1 + 0 + + + + Reset EtherCAT xml file + + 0 + 1 + 0 + + + + EtherCAT port control mode and state display + + 0 + 65535 + 0 + + + + EtherCAT COE version number + + 0 + 65535 + 0 + + + + EtherCAT xml file version number + + 0 + 65535 + 0 + + + + + ro + + + + #x200F + Closed Loop Function + 全闭环功能 + DT200F + 720 + + + SubIndex 000 + + 26 + + + + Encoder feedback mode + + 0 + 2 + 0 + + + + Running mode of external encoder + + 0 + 1 + 0 + + + + SecEncoder Absolute system selection + + 0 + 1 + 0 + + + + SecEncoder Type selection + + 0 + 2 + 0 + + + + External encoder pulses per motor revolution + + 0 + 2147483647 + 100000 + + + + Hybrid deviation excess setting + + 0 + 2147483647 + 10000 + + + + Hybrid deviation clear setting + + 0 + 100 + 1 + + + + First-order lowpass filter time of external/internal deviation + + 0 + 65535 + 0 + + + + Hybrid deviation counter + + -2147483648 + 2147483647 + 0 + + + + Pulse feedback display of internal encoder + + -2147483648 + 2147483647 + 0 + + + + Pulse feedback display of external encoder + + -2147483648 + 2147483647 + 0 + + + + SecEncoder Pulse ZPhase Ignore + + 0 + 1 + 0 + + + + SecEncoder Pulse Z-TouchProbe Selection + + 0 + 1 + 0 + + + + + ro + + + + #x2012 + MultiSpd Function + 多段速功能 + DT2012 + 1104 + + + SubIndex 000 + + 59 + + + + MultiSpd Function Select + + 0 + 2 + 1 + + + + MultiSpd Final Part Select + + 1 + 16 + 16 + + + + Time Uint of Runing + + 0 + 1 + 0 + + + + AccTime1 + + 0 + 65535 + 10 + + + + DecTime1 + + 0 + 65535 + 10 + + + + AccTime2 + + 0 + 65535 + 50 + + + + DecTime2 + + 0 + 65535 + 50 + + + + AccTime3 + + 0 + 65535 + 100 + + + + DecTime3 + + 0 + 65535 + 100 + + + + AccTime4 + + 0 + 65535 + 150 + + + + DecTime4 + + 0 + 65535 + 150 + + + + 1st Part Spd Cmd + + -10000 + 10000 + 0 + + + + 1st Part Spd Runing Time + + 0 + 65535 + 50 + + + + 1st Part AccDec Time Select + + 0 + 4 + 0 + + + + 2nd Part Spd Cmd + + -10000 + 10000 + 100 + + + + 2nd Part Spd Runing Time + + 0 + 65535 + 50 + + + + 2nd Part AccDec Time Select + + 0 + 4 + 0 + + + + 3rd Part Spd Cmd + + -10000 + 10000 + 300 + + + + 3rd Part Spd Runing Time + + 0 + 65535 + 50 + + + + 3rd Part AccDec Time Select + + 0 + 4 + 0 + + + + 4th Part Spd Cmd + + -10000 + 10000 + 500 + + + + 4th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 4th Part AccDec Time Select + + 0 + 4 + 0 + + + + 5th Part Spd Cmd + + -10000 + 10000 + 700 + + + + 5th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 5th Part AccDec Time Select + + 0 + 4 + 0 + + + + 6th Part Spd Cmd + + -10000 + 10000 + 900 + + + + 6th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 6th Part AccDec Time Select + + 0 + 4 + 0 + + + + 7th Part Spd Cmd + + -10000 + 10000 + 600 + + + + 7th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 7th Part AccDec Time Select + + 0 + 4 + 0 + + + + 8th Part Spd Cmd + + -10000 + 10000 + 300 + + + + 8th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 8th Part AccDec Time Select + + 0 + 4 + 0 + + + + 9th Part Spd Cmd + + -10000 + 10000 + 100 + + + + 9th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 9th Part AccDec Time Select + + 0 + 4 + 0 + + + + 10th Part Spd Cmd + + -10000 + 10000 + -100 + + + + 10th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 10th Part AccDec Time Select + + 0 + 4 + 0 + + + + 11th Part Spd Cmd + + -10000 + 10000 + -300 + + + + 11th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 11th Part AccDec Time Select + + 0 + 4 + 0 + + + + 12th Part Spd Cmd + + -10000 + 10000 + -500 + + + + 12th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 12th Part AccDec Time Select + + 0 + 4 + 0 + + + + 13th Part Spd Cmd + + -10000 + 10000 + -700 + + + + 13th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 13th Part AccDec Time Select + + 0 + 4 + 0 + + + + 14th Part Spd Cmd + + -10000 + 10000 + -900 + + + + 14th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 14th Part AccDec Time Select + + 0 + 4 + 0 + + + + 15th Part Spd Cmd + + -10000 + 10000 + -600 + + + + 15th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 15th Part AccDec Time Select + + 0 + 4 + 0 + + + + 16th Part Spd Cmd + + -10000 + 10000 + -300 + + + + 16th Part Spd Runing Time + + 0 + 65535 + 50 + + + + 16th Part AccDec Time Select + + 0 + 4 + 0 + + + + + ro + + + + #x2017 + VDI VDO + 虚拟DI、DO + DT2017 + 1520 + + + SubIndex 000 + + 68 + + + + VDI1 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI1 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI2 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI2 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI3 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI3 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI4 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI4 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI5 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI5 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI6 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI6 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI7 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI7 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI8 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI8 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI9 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI9 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI10 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI10 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI11 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI11 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI12 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI12 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI13 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI13 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI14 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI14 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI15 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI15 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDI16 Terminal Function Selection + + 0 + 40 + 0 + + + + VDI16 Terminal Logic Selection + + 0 + 1 + 0 + + + + VDO virtual level + + 0 + 65535 + 0 + + + + VDO1 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO1 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO2 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO2 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO3 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO3 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO4 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO4 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO5 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO5 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO6 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO6 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO7 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO7 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO8 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO8 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO9 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO9 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO10 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO10 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO11 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO11 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO12 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO12 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO13 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO13 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO14 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO14 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO15 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO15 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDO16 Terminal Function Selection + + 0 + 32 + 0 + + + + VDO16 Terminal Logic Level Selection + + 0 + 1 + 0 + + + + VDI Enable + + 0 + 1 + 0 + + + + VDI Default Value + + 0 + 65535 + 0 + + + + VDO Enable + + 0 + 1 + 0 + + + + VDO Default Value + + 0 + 65535 + 0 + + + + + ro + + + + #x2018 + Position Comparison + 位置比较参数 + DT2018 + 288 + + + SubIndex 000 + + 17 + + + + Enable Comparison + + 0 + + + + Comparison PosFdb Source Select + + 0 + 1 + 0 + + + + Encoder Resolution + + 0 + 7 + 1 + + + + Mode Of Comparison + + 0 + 2 + 0 + + + + Current Position As Zero + + 0 + 1 + 0 + + + + Output Duration + + 1 + 2047 + 1 + + + + Comparison ABZ OutPut Logic + + 0 + 65535 + 0 + + + + Starting Point Number + + 0 + 40 + 0 + + + + Ending Point Number + + 0 + 40 + 0 + + + + Comparison Status + + 0 + 1024 + 0 + + + + Current Position + + -2147483648 + 2147483647 + 0 + + + + Position Offset + + -2147483648 + 2147483647 + 0 + + + + Comparison OutPut Delay Compensation + + -1200 + 1200 + 0 + + + + Lilited number of Comparison Cycle Times + + 1 + 65535 + 1 + + + + Comparison ABZ OutPut Function + + 0 + 65535 + 0 + + + + + ro + + + + #x2019 + Comparing Points + 位置比较点 + DT2019 + 1936 + + + SubIndex 000 + + 120 + + + + 1st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 1st Point Property + + 0 + + + + 2nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 2nd Point Property + + 0 + + + + 3rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 3rd Point Property + + 0 + + + + 4th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 4th Point Property + + 0 + + + + 5th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 5th Point Property + + 0 + + + + 6th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 6th Point Property + + 0 + + + + 7th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 7th Point Property + + 0 + + + + 8th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 8th Point Property + + 0 + + + + 9th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 9th Point Property + + 0 + + + + 10th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 10th Point Property + + 0 + + + + 11th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 11th Point Property + + 0 + + + + 12th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 12th Point Property + + 0 + + + + 13th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 13th Point Property + + 0 + + + + 14th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 14th Point Property + + 0 + + + + 15th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 15th Point Property + + 0 + + + + 16th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 16th Point Property + + 0 + + + + 17th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 17th Point Property + + 0 + + + + 18th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 18th Point Property + + 0 + + + + 19th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 19th Point Property + + 0 + + + + 20th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 20th Point Property + + 0 + + + + 21st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 21st Point Property + + 0 + + + + 22nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 22nd Point Property + + 0 + + + + 23rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 23rd Point Property + + 0 + + + + 24th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 24th Point Property + + 0 + + + + 25th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 25th Point Property + + 0 + + + + 26th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 26th Point Property + + 0 + + + + 27th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 27th Point Property + + 0 + + + + 28th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 28th Point Property + + 0 + + + + 29th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 29th Point Property + + 0 + + + + 30th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 30th Point Property + + 0 + + + + 31st Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 31st Point Property + + 0 + + + + 32nd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 32nd Point Property + + 0 + + + + 33rd Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 33rd Point Property + + 0 + + + + 34th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 34th Point Property + + 0 + + + + 35th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 35th Point Property + + 0 + + + + 36th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 36th Point Property + + 0 + + + + 37th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 37th Point Property + + 0 + + + + 38th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 38th Point Property + + 0 + + + + 39th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 39th Point Property + + 0 + + + + 40th Comparing Position + + -2147483648 + 2147483647 + 0 + + + + 40th Point Property + + 0 + + + + + ro + + + + #x2030 + Comm Read Servo Variable + 通讯读取相关变量 + DT2030 + 64 + + + SubIndex 000 + + 3 + + + + Servo Status + + 0 + 65535 + 0 + + + + DO Function1 + + 0 + 65535 + 0 + + + + DO Function2 + + 0 + 65535 + 0 + + + + + ro + + + + #x2031 + Comm Set Servo Variable + 通讯给定相关变量 + DT2031 + 224 + + + SubIndex 000 + + 5 + + + + Comm Set VDI + + 0 + 65535 + 0 + + + + Comm Set DO + + 0 + 65535 + 0 + + + + Comm Set AO + + -10000 + 10000 + 0 + + + + Comm Set Local SpdRef + + -9000000 + 9000000 + 0 + + + + Comm Set Local TrqRef + + -100000 + 100000 + 0 + + + + + ro + + + + #x203F + Manufacturor Error code + 伺服故障码 + UDINT + 32 + + #x00000000 + #xFFFFFFFF + #x00000000 + + + ro + T + + + + #x603F + Error code + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + ro + T + + + + #x6040 + Control word + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + rw + R + + + + #x6041 + Status word + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + ro + T + + + + #x605A + Quick stop option code + INT + 16 + + #x0000 + #x0007 + #x0002 + + + rw + + + + #x605C + Disable operation option code + INT + 16 + + #xFFFC + #x0002 + #x0000 + + + rw + + + + #x605D + Halt option Code + INT + 16 + + #x0001 + #x0003 + #x0001 + + + rw + + + + #x605E + Fault Reaction option Code + INT + 16 + + #xFFFB + #x0004 + #x0002 + + + rw + + + + #x6060 + Modes of operation + SINT + 8 + + 0 + 10 + 0 + + + rw + R + + + + #x6061 + Modes of operation display + SINT + 8 + + 0 + 10 + 0 + + + ro + T + + + + #x6062 + Position demand value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6063 + Position actual internal value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6064 + Position actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6065 + Following error window + UDINT + 32 + + #x0 + #xFFFFFFFF + #x1A36AE7 + + + rw + R + + + + #x6066 + Following error time out + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x6067 + Position window + UDINT + 32 + + #x0 + #xFFFFFFFF + #x16F0 + + + rw + R + + + + #x6068 + Position window time + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x606C + Velocity actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + 0 + + + ro + T + + + + #x606D + Velocity window + UINT + 16 + + #x0000 + #xFFFF + #xA + + + rw + R + + + + #x606E + Velocity window time + UINT + 16 + + #x0000 + #xFFFF + #x0 + + + rw + + + + #x606F + Velocity threshold + UINT + 16 + + #x0000 + #xFFFF + #xA + + + rw + R + + + + #x6070 + Velocity threshold time + UINT + 16 + + #x0000 + #xFFFF + #x0 + + + rw + + + + #x6071 + Target torque + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + rw + R + + + + #x6072 + Max Torque + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x6074 + Torque demand + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + ro + T + + + + #x6077 + Torque actual value + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + ro + T + + + + #x607A + Target position + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x607C + Home offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x607D + Software position limit + DT607D + 80 + + + SubIndex 000 + + #x02 + + + + Min position limit + + #x80000000 + #x7FFFFFFF + #x80000000 + + + + Max position limit + + #x80000000 + #x7FFFFFFF + #x7FFFFFFF + + + + + ro + + + + #x607E + Polarity + USINT + 8 + + #x0 + #xFF + #x0 + + + rw + R + + + + #x607F + Max profile velocity + UDINT + 32 + + #x0 + #xFFFFFFFF + #x32000000 + + + rw + R + + + + #x6081 + Profile velocity + UDINT + 32 + + #x0 + #xFFFFFFFF + #xD55555 + + + rw + R + + + + #x6083 + Profile acceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x6084 + Profile deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x6085 + Quick stop deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x7FFFFFFF + + + rw + R + + + + #x6086 + Motion profile type + INT + 16 + + #x8000 + #x7FFF + #x0 + + + rw + R + + + + #x6087 + Torque slope + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x6091 + Gear ratio + DT6091 + 80 + + + SubIndex 000 + + #x02 + + + + Motor revolutions + + #x1 + #xFFFFFFFF + #x1 + + + + Shaft revolutions + + #x1 + #xFFFFFFFF + #x1 + + + + + ro + + + + #x6098 + Homing method + SINT + 8 + + #xFD + #x23 + 1 + + + rw + R + + + + #x6099 + Homing speeds + DT6099 + 80 + + + SubIndex 000 + + #x02 + + + + Speed during search for switch + + 0 + #xFFFFFFFF + #xD55555 + + + + Speed during search for zero + + 0 + #xFFFFFFFF + #x155555 + + + + + ro + + + + #x609A + Homing acceleration + UDINT + 32 + + 0 + #xFFFFFFFF + #x53555555 + + + rw + R + + + + #x60B0 + Position offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x60B1 + Velocity offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x60B2 + Torque offset + INT + 16 + + #xF060 + #x0FA0 + #x0 + + + rw + R + + + + #x60B8 + Touch probe function + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x60B9 + Touch Probe Status + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60BA + Touch probe 1 positive edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BB + Touch probe 1 negative edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BC + Touch probe 2 positive edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BD + Touch probe 2 negative edge + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60C5 + Max Acceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x60C6 + Max Deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #xFFFFFFFF + + + rw + R + + + + #x60D5 + Touch probe 1 positive edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D6 + Touch probe 1 negative edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D7 + Touch probe 2 positive edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D8 + Touch probe 2 negative edge counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60E0 + Positive torque limit value + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x60E1 + Negative torque limit value + UINT + 16 + + #x0 + #x0FA0 + #x0DAC + + + rw + R + + + + #x60E3 + Supported homing methods + DT60E3 + 544 + + + SubIndex 000 + + #x0 + #x22 + 33 + + + + Support homing method 1 + + #x01 + + + + Support homing method 2 + + #x02 + + + + Support homing method 3 + + #x03 + + + + Support homing method 4 + + #x04 + + + + Support homing method 5 + + #x05 + + + + Support homing method 6 + + #x06 + + + + Support homing method 7 + + #x07 + + + + Support homing method 8 + + #x08 + + + + Support homing method 9 + + #x09 + + + + Support homing method 10 + + #x0A + + + + Support homing method 11 + + #x0B + + + + Support homing method 12 + + #x0C + + + + Support homing method 13 + + #x0D + + + + Support homing method 14 + + #x0E + + + + Support homing method 15 + + #x11 + + + + Support homing method 16 + + #x12 + + + + Support homing method 17 + + #x13 + + + + Support homing method 18 + + #x14 + + + + Support homing method 19 + + #x15 + + + + Support homing method 20 + + #x16 + + + + Support homing method 21 + + #x17 + + + + Support homing method 22 + + #x18 + + + + Support homing method 23 + + #x19 + + + + Support homing method 24 + + #x1A + + + + Support homing method 25 + + #x1B + + + + Support homing method 26 + + #x1C + + + + Support homing method 27 + + #x1D + + + + Support homing method 28 + + #x1E + + + + Support homing method 29 + + #x21 + + + + Support homing method 30 + + #x22 + + + + Support homing method 31 + + #x23 + + + + Support homing method 32 + + #xFF + + + + Support homing method 33 + + #xFE + + + + + ro + + + + #x60F4 + Following error actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60FC + Position demand internal value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60FD + Digital inputs + UDINT + 32 + + #x0 + #xFFFFFFFF + #x0 + + + ro + T + + + + #x60FE + Digital outputs + DT60FE + 80 + + + SubIndex 000 + + #x02 + + + + Physical outputs + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + Bit Mask + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + ro + + + + #x60FF + Target velocity + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x6502 + Supported drive modes + UDINT + 32 + + #x00000000 + #xFFFFFFFF + #x000003AD + + + ro + + + + + + Outputs + Inputs + MBoxState + MBoxOut + MBoxIn + Outputs + Inputs + + #x1600 + Outputs + #x1601 + #x1701 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + + #x1601 + Outputs + #x1600 + #x1701 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x607A + 0 + 32 + Target position + DINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + #x6081 + 0 + 32 + profile velocity + UDINT + + + #x6083 + 0 + 32 + profile acceleration + UDINT + + + #x6084 + 0 + 32 + profile deceleration + UDINT + + + #x6087 + 0 + 32 + Torque Slope + UDINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + + #x1701 + Outputs + #x1600 + #x1601 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60FE + 1 + 32 + Physical outputs + UDINT + + + + #x1702 + Outputs + #x1600 + #x1601 + #x1701 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + + #x1703 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + + #x1704 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1703 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6071 + 0 + 16 + Target torque + INT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x607F + 0 + 32 + Max profile velocity + UDINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + + #x1705 + Outputs + #x1600 + #x1601 + #x1701 + #x1702 + #x1703 + #x1704 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60E0 + 0 + 16 + Positive torque limit value + UINT + + + #x60E1 + 0 + 16 + Negative torque limit value + UINT + + + #x60B2 + 0 + 16 + Torque offset + INT + + + + #x1A00 + Inputs + #x1A01 + #x1B01 + #x1B02 + #x1B03 + #x1B04 + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x603F + 0 + 16 + Error code + UINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1A01 + Inputs + #x1A00 + #x1B01 + #x1B02 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x606C + 0 + 32 + Velocity actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B01 + Inputs + #x1A00 + #x1A01 + #x1B02 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B02 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B03 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B02 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B04 + Inputs + #x1A00 + #x1A01 + #x1B01 + #x1B02 + #x1B03 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x6077 + 0 + 16 + Torque actual value + INT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x60F4 + 0 + 32 + Following error actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x606C + 0 + 32 + Velocity actual value + DINT + + + + + + + PS + #x6060 + 0 + 08 + Modes of operation + + + + + + DC + DC-Sync + #x300 + 0 + 0 + 0 + + + Synchron + FreeRun + #x0 + + + + 2048 + 080C0004640000000000 + + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + diff --git a/hw_device_mgr/devices/inovance_sv670.py b/hw_device_mgr/devices/inovance_sv670.py index 0b07c5c4..bf8109f0 100644 --- a/hw_device_mgr/devices/inovance_sv670.py +++ b/hw_device_mgr/devices/inovance_sv670.py @@ -61,7 +61,7 @@ class InovanceSV670(EtherCATDevice, CiA402Device, ErrorDevice): xml_description_package = "hw_device_mgr.devices.device_xml" xml_description_fname = "SV670_EOE_1Axis_05003_220801.xml" device_error_package = "hw_device_mgr.devices.device_err" - device_error_yaml = "inovance_sv670n.yaml" + device_error_yaml = "inovance_sv660n.yaml" config_class = InovanceSV670Config have_sto = True From 71e720a1f28773d22a5032bb4f8077b1d76165cf Mon Sep 17 00:00:00 2001 From: John Morris Date: Fri, 22 Nov 2024 15:57:43 -0600 Subject: [PATCH 073/121] Implement drive "shutdown" command --- hw_device_mgr/cia_301/device.py | 13 ++++- .../tests/read_update_write.cases.yaml | 3 ++ hw_device_mgr/cia_402/device.py | 23 +++++---- .../cia_402/tests/hm_timeout.cases.yaml | 3 ++ .../cia_402/tests/pp_timeout.cases.yaml | 3 ++ .../tests/read_update_write.cases.yaml | 3 ++ hw_device_mgr/device.py | 15 +++++- hw_device_mgr/mgr/mgr.py | 51 ++++++++++++++++--- .../mgr/tests/read_update_write.cases.yaml | 5 ++ hw_device_mgr/mgr/tests/test_mgr.py | 2 +- 10 files changed, 101 insertions(+), 20 deletions(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 93a5bc74..004b4e86 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -146,6 +146,11 @@ def get_feedback(self): # Update operational status if not self.feedback_in.get("oper"): + if self.command_in.get("shutdown"): + if self.feedback_in.changed("oper"): + self.logger.info("Drive non-operational, shutdown complete") + fb_out.update(shutdown_complete=True) + return fb_out # goal reached goal_reached = False goal_reasons.insert(0, "Not operational") @@ -161,6 +166,10 @@ def get_feedback(self): else: # operational if self.feedback_in.changed("oper"): self.logger.info("Drive came online/operational") + if self.command_out.get("shutdown_latch"): + goal_reached = False + goal_reasons.insert(0, "Drive operational during shutdown") + fb_out.update(shutdown_complete=False) # Update feedback and return goal_reason = "Reached" if goal_reached else ", ".join(goal_reasons) @@ -323,7 +332,9 @@ def init_class(cls, **kwargs): def set_sim_feedback(self, **kwargs): # Automatically step through to online/oper sfb = super().set_sim_feedback(**kwargs) - if self.feedback_in.get("online"): + if self.command_in.get("shutdown"): + sfb.update(online=True, oper=False) + elif self.feedback_in.get("online"): sfb.update(online=True, oper=True) else: sfb.update(online=True, oper=False) diff --git a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml index ff7012db..ae3c1e3b 100644 --- a/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml @@ -14,11 +14,14 @@ fault: False fault_desc: "" param_state: 0x00 # PARAM_STATE_UNKNOWN + shutdown_complete: False command_in: reset_fault: False + shutdown: False command_out: init_params: False fasttrack: False + shutdown_latch: False sim_feedback: online: True oper: False diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index bf49eb52..9318b83f 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -316,6 +316,10 @@ def get_feedback(self): fb_out = super().get_feedback() fb_in = self.feedback_in + # If shutting down, there's nothing to do here + if self.command_out.get("shutdown_latch"): + return fb_out + # Don't clobber lower layer's feedback, but continue managing CiA 402 # states even while param init continues goal_reached = fb_out.get("goal_reached") @@ -357,9 +361,9 @@ def get_feedback(self): f"Unknown status word 0x{sw:X}; " f"state {fb_out.get('state')} unchanged" ) + state_cmd = self.command_in.get("state") if self._get_next_transition() >= 0: goal_reached = False - state_cmd = self.command_in.get("state") sw = fb_in.get("status_word") goal_reasons.append(f"state {state} != {state_cmd}") if state_cmd in ( @@ -374,13 +378,10 @@ def get_feedback(self): fb_out.update(following_error=ferror) # Raise fault if device unexpectedly disabled - if self.command_in.get( - "state" - ) == "OPERATION ENABLED" and not self.test_sw_bit( - sw, "READY_TO_SWITCH_ON" - ): - fault = True - fault_desc = "Enabled drive unexpectedly disabled" + if state_cmd == "OPERATION ENABLED": + if not self.test_sw_bit(sw, "READY_TO_SWITCH_ON"): + fault = True + fault_desc = "Enabled drive unexpectedly disabled" # Calculate 'transition' feedback new_st, old_st = fb_out.changed("state", return_vals=True) @@ -450,7 +451,7 @@ def get_feedback(self): goal_reasons.append(pt_reason) # If in CiA402 FAULT state, set device fault - if self.command_in.get("state") == "FAULT": + if state_cmd == "FAULT": fault = True if not fault_desc: # Recycle previous description if possible @@ -615,6 +616,8 @@ def set_command(self, **kwargs): if self.command_in.changed("state"): state_cmd = self.command_in.get("state") self.logger.info(f"CiA 402 state command: {state_cmd}") + if self.command_out.get("shutdown_latch"): + return cmd_out if not self.feedback_out.get("oper"): return cmd_out complete = CiA301Device.PARAM_STATE_COMPLETE @@ -854,6 +857,8 @@ def _get_transition_control_word(self): return cw def _get_next_transition(self, curr_state=None): + if not self.feedback_in.get("oper"): + return -1 return self._get_next_state(curr_state=curr_state, transition=True) def _get_next_state(self, curr_state=None, transition=False): diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index 5d4cac7c..901caa33 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -43,6 +43,7 @@ error_code: 0x00000000 description: No error fault_desc: "" + shutdown_complete: False command_in: state: OPERATION ENABLED control_mode: 8 @@ -50,11 +51,13 @@ home_request: True move_request: False relative_target: False + shutdown: False command_out: control_word: 0x000F control_mode: 6 init_params: False fasttrack: False + shutdown_latch: False sim_feedback: online: True oper: True diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index 89e45c81..d1ff905a 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -45,6 +45,7 @@ error_code: 0x00000000 description: No error fault_desc: "" + shutdown_complete: False command_in: state: OPERATION ENABLED control_mode: 1 # MODE_PP @@ -52,11 +53,13 @@ home_request: False move_request: True relative_target: False + shutdown: False command_out: control_word: 0x001F # Bit 4 NEW_SETPOINT set control_mode: 1 # MODE_PP init_params: False fasttrack: True + shutdown_latch: False sim_feedback: online: True oper: True diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index 2ec8c163..41495650 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -18,6 +18,7 @@ # errors error_code: 0x00000000 feedback_out: + shutdown_complete: False # CiA 301 online: False oper: False @@ -45,6 +46,7 @@ description: No error fault_desc: "" command_in: + shutdown: False # CiA 402 state: SWITCH ON DISABLED control_mode: 8 # MODE_CSP @@ -53,6 +55,7 @@ relative_target: False reset_fault: False command_out: + shutdown_latch: False # CiA 402 control_word: 0x0000 control_mode: 8 # MODE_CSP diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 5581c5f2..86adb432 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -22,12 +22,15 @@ class Device(LoggingMixin, abc.ABC): goal_reason="str", fault="bit", fault_desc="str", + shutdown_complete="bit", ) command_in_data_types = dict( reset_fault="bit", + shutdown="bit", ) command_out_data_types = dict( fasttrack="bit", + shutdown_latch="bit", ) feedback_in_defaults = dict() @@ -36,12 +39,15 @@ class Device(LoggingMixin, abc.ABC): goal_reason="Reached", fault=False, fault_desc="", + shutdown_complete=False, ) command_in_defaults = dict( reset_fault=False, + shutdown=False, ) command_out_defaults = dict( fasttrack=False, + shutdown_latch=False, ) feedback_in_overlap = set() @@ -154,6 +160,8 @@ def get_feedback(self) -> Interface: fb_out.set(**fb_in) if timeout: fb_out.update(fault=True, fault_desc=timeout) + if self.command_out.get("shutdown_latch"): + fb_out.update(shutdown_complete=True) # Higher levels may correct return fb_out def log_goal_reached(self): @@ -204,7 +212,12 @@ def set_command(self, **kwargs) -> Interface: cmd_out = self._interfaces["command_out"] cmd_in.set(**kwargs) cmd_out.set() - if cmd_in.get("reset_fault"): + if cmd_in.get("shutdown") or cmd_out.get("shutdown_latch"): + # Incoming shutdown command latches + cmd_out.update(shutdown_latch=True) + if cmd_out.rising_edge("shutdown_latch"): + self.logger.info("Commanding drive shutdown") + elif cmd_in.get("reset_fault"): if cmd_in.rising_edge("reset_fault"): self.logger.info("Reset fault command") return cmd_out diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index a7b390f2..0e38d40d 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -22,6 +22,7 @@ def device_model_id(cls): STATE_STOP = 1 STATE_START = 2 STATE_FAULT = 4 + STATE_SHUTDOWN = 5 feedback_out_defaults = dict( enabled=False, @@ -136,8 +137,9 @@ def scan_devices(cls, **kwargs): "torque_cmd", "torque_fb" }, - # - Don't expose device `state` or `reset_fault`, controlled by manager - command_in={"state", "reset_fault"}, + # - Don't expose device `state`, `reset_fault`, `shutdown`, + # controlled by manager + command_in={"state", "reset_fault", "shutdown"}, ) @lru_cache @@ -171,6 +173,9 @@ def dev_prefix(self, dev, prefix="d", suffix=""): # - stop_complete: Done dict(name="stop_command", src="*", dst="stop_1"), dict(name="stop_complete", src="stop_1", dst="stop_complete"), + # Shutdown state: From any state + dict(name="shutdown_command", src="*", dst="shutdown_1"), + dict(name="shutdown_complete", src="shutdown_1", dst="shutdown_complete"), ], state_field="state", ) @@ -267,6 +272,21 @@ def on_before_stop_complete(self, e): def on_enter_stop_complete(self, e): self.fsm_finalize_command(e) + # + # Shutdown command + # + def on_before_shutdown_command(self, e): + return True # Always can shutdown + + def on_enter_shutdown_1(self, e): + self.fsm_set_drive_state_cmd(e, "SHUTDOWN") + + def on_before_shutdown_complete(self, e): + return self.fsm_check_drive_goal_state(e) + + def on_enter_shutdown_complete(self, e): + self.fsm_finalize_command(e) + # # All states # @@ -450,6 +470,10 @@ def read_update_write(self): fault_1="fault_complete", fault_complete=None, ), + shutdown=dict( + shutdown_1="shutdown_complete", + shutdown_complete=None, + ), ) def read(self): @@ -565,10 +589,17 @@ def set_command(self, **cmd_in_kwargs): # clobber parent class updates for regular device classes, but this # isn't a regular device and it inherits directly from `Device` old_cmd_out = self.command_out.get().copy() + cmd_in_shutdown = cmd_in_kwargs.get("shutdown", False) + if cmd_in_shutdown or old_cmd_out.get("shutdown_latch"): + # Incoming shutdown command latches + old_cmd_out.update(shutdown_latch=True) cmd_out = super().set_command(**cmd_in_kwargs) cmd_out.update(**old_cmd_out) cmd_in = self.command_in + if cmd_in.rising_edge("shutdown"): + self.logger.info("Commanding drive shutdown") + # Check for new command if self.command_in.rising_edge("state_set"): # state_set went high; log it @@ -664,22 +695,26 @@ def set_drive_command(self): mgr_vals = self.command_in.get() skip = self.device_translated_interfaces.get("command_in", set()) reset = self.command_out.get("reset_fault_cmd") + shutdown=self.command_in.get("shutdown") for dev in self.devices: if "command_in" in self.device_translated_interfaces: # Copy mgr command_out to matching device command_in dev_command_in = dev.interface("command_in") prefix = self.dev_prefix(dev, suffix=dev.slug_separator) - dev.set_command( - state=self.command_out.get("drive_state"), - reset_fault=reset, - **{ - k: mgr_vals[f"{prefix}{k}"] + kwargs = { + k: mgr_vals[f"{prefix}{k}"] for k in dev_command_in.keys() if k not in skip - }, + } + kwargs.update( + shutdown=shutdown, + state=self.command_out.get("drive_state"), + reset_fault=reset, ) + dev.set_command(**kwargs) else: dev.set_command( + shutdown=shutdown, state=self.command_out.get("drive_state"), reset_fault=reset, ) diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index fac448c9..97d5d0b3 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -25,7 +25,9 @@ goal_reason: Offline ({all_drives}) fault: False fault_desc: "" + shutdown_complete: False # Drives + d.x.shutdown_complete: False # - CiA 301 d.x.online: False d.x.oper: False @@ -51,6 +53,7 @@ d.x.error_code: 0x00000000 d.x.description: No error command_in: + shutdown: False # Mgr state_cmd: 0 # init state_set: 0 # don't latch in state_cmd @@ -62,6 +65,7 @@ d.x.move_request: False d.x.relative_target: False command_out: + shutdown_latch: False # Mgr state: 0 # init state_log: Automatic transition to init_command from init_command state @@ -71,6 +75,7 @@ reset_fault_cmd: False fasttrack: False # Drives + d.x.shutdown_latch: False # - CiA 402 d.x.control_word: 0x0000 # SWITCH ON DISABLED d.x.control_mode: 8 # MODE_CSP diff --git a/hw_device_mgr/mgr/tests/test_mgr.py b/hw_device_mgr/mgr/tests/test_mgr.py index 18945017..8932ad59 100644 --- a/hw_device_mgr/mgr/tests/test_mgr.py +++ b/hw_device_mgr/mgr/tests/test_mgr.py @@ -34,7 +34,7 @@ def test_state_values(self, obj): assert val in obj.cmd_int_to_name_map assert obj.cmd_int_to_name_map[val] == key values[key] = val - assert len(values) == 4 + assert len(values) == 5 def test_init(self, obj): super().test_init(obj) From fbe57036e417e987c180d50872302d90bf098360 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 3 Feb 2025 15:24:40 -0600 Subject: [PATCH 074/121] fixup! Implement drive "shutdown" command --- hw_device_mgr/mgr/mgr.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 0e38d40d..f63f1461 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -597,9 +597,6 @@ def set_command(self, **cmd_in_kwargs): cmd_out.update(**old_cmd_out) cmd_in = self.command_in - if cmd_in.rising_edge("shutdown"): - self.logger.info("Commanding drive shutdown") - # Check for new command if self.command_in.rising_edge("state_set"): # state_set went high; log it From 88e7ac170781bd2b0a991fc7c8a46f9221b619f5 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 4 Mar 2025 17:52:04 -0600 Subject: [PATCH 075/121] Run formatters --- hw_device_mgr/async_task_queue.py | 6 +++--- hw_device_mgr/cia_301/config.py | 5 +++-- hw_device_mgr/cia_301/device.py | 4 ++-- hw_device_mgr/cia_402/device.py | 1 - hw_device_mgr/device.py | 2 +- hw_device_mgr/devices/inovance_sv660.py | 2 +- .../devices/tests/test_device_read_update_write.py | 4 +--- hw_device_mgr/devices/tests/test_devices.py | 4 +++- hw_device_mgr/ethercat/device.py | 6 +++--- hw_device_mgr/mgr/mgr.py | 2 +- hw_device_mgr/tests/fixtures.py | 8 +++++--- 11 files changed, 23 insertions(+), 21 deletions(-) diff --git a/hw_device_mgr/async_task_queue.py b/hw_device_mgr/async_task_queue.py index 86bb54bc..6baee8f7 100644 --- a/hw_device_mgr/async_task_queue.py +++ b/hw_device_mgr/async_task_queue.py @@ -1,6 +1,6 @@ import threading import queue -from functools import cached_property, lru_cache +from functools import lru_cache class AsyncTaskQueue: @@ -12,7 +12,7 @@ class AsyncTaskQueue: """ # Idle wait time - idle_wait = 0.1 # s + idle_wait = 0.1 # s # Class-level singleton queue data _queue_names = list() @@ -113,7 +113,7 @@ def empty(self): return self.queue.empty() def join_queue(self): - """Flush and stop queue""" + """Flush and stop queue.""" self.flush_queue_and_clear_error() self.queue.join() diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index 931fa79c..b2e400e0 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -385,7 +385,8 @@ def param_init_in_progress(self): @property def param_init_error(self): - """Return param init error status. + """ + Return param init error status. If no error, returns `None`. Otherwise, returns a tuple of `(exception, method, args, kwargs)` @@ -414,7 +415,7 @@ def scan_bus(cls, bus=0, skip_optional_config_values=True, **kwargs): @classmethod def init_class(cls): - """Initialize the config class""" + """Initialize the config class.""" pass diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 9ef77644..98878c09 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -119,8 +119,8 @@ def get_feedback(self): param_state = self.PARAM_STATE_COMPLETE elif p_init_err: try: - errstr = "{1}({2}, {3}): {0}".format(p_init_err) - except: + errstr = "{1}({2}, {3}): {0}".format(*p_init_err) + except Exception: errstr = str(p_init_err) fb_out.update(fault=True, fault_desc=f"param init failed: {errstr}") param_state = self.PARAM_STATE_ERROR diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index b80a1ffa..a1fc19a7 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -577,7 +577,6 @@ def _get_next_control_word(self, cmd_out): # Add flags and return next_cm = cmd_out.get("control_mode") cw_flags = dict(OPERATION_MODE_SPECIFIC_3=False) - operation_mode_specific_3 = False # operation mode specific 3 sets the target to relative position # when in PP mode if next_cm == self.MODE_HM: diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 5581c5f2..ac659513 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -317,7 +317,7 @@ def get_model_by_name(cls, name): @classmethod def init_class(cls): - """Initialize device classes""" + """Initialize device classes.""" pass ######################################## diff --git a/hw_device_mgr/devices/inovance_sv660.py b/hw_device_mgr/devices/inovance_sv660.py index 643c2b79..eb05567b 100644 --- a/hw_device_mgr/devices/inovance_sv660.py +++ b/hw_device_mgr/devices/inovance_sv660.py @@ -48,7 +48,7 @@ def soft_reset(self): time.sleep(2.0) # Give the drive time to react def reset_error_and_restart(self): - self.logger.info(f"Queueing fault reset and rebooting drive") + self.logger.info("Queueing fault reset and rebooting drive") self.enqueue_command(self.clear_fault) self.enqueue_command(self.soft_reset) diff --git a/hw_device_mgr/devices/tests/test_device_read_update_write.py b/hw_device_mgr/devices/tests/test_device_read_update_write.py index 2ed61e94..e4fc469e 100644 --- a/hw_device_mgr/devices/tests/test_device_read_update_write.py +++ b/hw_device_mgr/devices/tests/test_device_read_update_write.py @@ -9,9 +9,7 @@ class TestDevicesRUW(BaseDevicesTestClass, _TestEtherCATDeviceRUW): error_code_re = re.compile(r"0x([0-9A-F]{4})[0-9A-F]{4}") - expected_error_code_attrs = ( - 'fault_desc', 'description', 'goal_reason' - ) + expected_error_code_attrs = ("fault_desc", "description", "goal_reason") @classmethod @lru_cache diff --git a/hw_device_mgr/devices/tests/test_devices.py b/hw_device_mgr/devices/tests/test_devices.py index 6efda5f8..5040bf0c 100644 --- a/hw_device_mgr/devices/tests/test_devices.py +++ b/hw_device_mgr/devices/tests/test_devices.py @@ -16,4 +16,6 @@ def test_sv660_error_code_str(self, obj): return print(obj.feedback_out.data_types) assert obj.feedback_out_data_types["error_code"] == "uint16" - assert obj.feedback_out.get_data_type("error_code").shared_name == "uint16" + assert ( + obj.feedback_out.get_data_type("error_code").shared_name == "uint16" + ) diff --git a/hw_device_mgr/ethercat/device.py b/hw_device_mgr/ethercat/device.py index 6ca95eb0..ee18e017 100644 --- a/hw_device_mgr/ethercat/device.py +++ b/hw_device_mgr/ethercat/device.py @@ -110,9 +110,9 @@ def init_class(cls, LcId="1033", **kwargs): """ Configure device, config, command for EtherCAT devices. - Like parent `CiA301Device.init_class()`, but parse SDO data - from EtherCAT ESI description file and pass with other kwargs - to parent class's method. + Like parent `CiA301Device.init_class()`, but parse SDO data from + EtherCAT ESI description file and pass with other kwargs to + parent class's method. """ sdo_data = cls.read_device_sdos_from_esi(LcId=LcId) dcs_data = cls.read_device_dcs_from_esi(LcId=LcId) diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 0f16faa1..c7e36406 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -197,7 +197,7 @@ def on_enter_init_complete(self, e): state=self.STATE_FAULT, state_log="Automatic 'fault' command at init complete", ) - else: # Automatically return to SWITCH ON DISABLED after init + else: # Automatically return to SWITCH ON DISABLED after init self.logger.info("Devices all online; commanding stop state") self.command_out.update( state=self.STATE_STOP, diff --git a/hw_device_mgr/tests/fixtures.py b/hw_device_mgr/tests/fixtures.py index ffdbad5c..25878927 100644 --- a/hw_device_mgr/tests/fixtures.py +++ b/hw_device_mgr/tests/fixtures.py @@ -60,9 +60,11 @@ def _make_mock_obj(self): attr, # Use m as sentinel object to avoid 1 extra SLOC! PropertyMock( - side_effect=lambda x=m: getattr(self, attr) - if x is m - else setattr(self, attr, x) + side_effect=lambda x=m: ( + getattr(self, attr) + if x is m + else setattr(self, attr, x) + ) ), ) return m From 65c79408035fb69826e316e64322595f3637741c Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 4 Feb 2025 14:14:11 -0600 Subject: [PATCH 076/121] cia_301: Tweak bus scan log message --- hw_device_mgr/cia_301/config.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index b2e400e0..a81b371c 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -410,7 +410,7 @@ def scan_bus(cls, bus=0, skip_optional_config_values=True, **kwargs): **kwargs, ) res.append(config) - config.logger.info("Drive config created from bus scan") + config.logger.info(f"{config} created from bus scan") return res @classmethod From 7313276e3b5e64b4ef6836a395f041d96790b530 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 6 Feb 2025 11:48:42 -0600 Subject: [PATCH 077/121] logging: Add `get_logger()` convenience function --- hw_device_mgr/logging/__init__.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/hw_device_mgr/logging/__init__.py b/hw_device_mgr/logging/__init__.py index 92dba988..d5173645 100644 --- a/hw_device_mgr/logging/__init__.py +++ b/hw_device_mgr/logging/__init__.py @@ -51,6 +51,10 @@ class LoggingMixin: def logging_name(self): return str(self) + @classmethod + def get_logger(cls, name): + return cls.logging_class.getLogger(name) + @cached_property def logger(self): return self.logging_class.getLogger(self.logging_name) From 4bb8e2dce3c0b1418435969c82d754b7039f70d4 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 6 Feb 2025 12:20:55 -0600 Subject: [PATCH 078/121] cia_301.command: Add `format_address` convenience function --- hw_device_mgr/cia_301/command.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/hw_device_mgr/cia_301/command.py b/hw_device_mgr/cia_301/command.py index 94de971e..80259d37 100644 --- a/hw_device_mgr/cia_301/command.py +++ b/hw_device_mgr/cia_301/command.py @@ -53,6 +53,10 @@ def decode_address(cls, address): position = 0 return master, position, alias + @classmethod + def format_address(cls, address): + return str(address).replace(" ", "") + class CiA301SimCommand(CiA301Command): """Simulated CiA 301 device.""" From ee92d9e4d85e1fdda6dfcda4898738e5bd52f02c Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 6 Feb 2025 12:21:30 -0600 Subject: [PATCH 079/121] cia_301.config: Add `CiA301ConfigException` To be used by subclasses --- hw_device_mgr/cia_301/config.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index a81b371c..f7156abd 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -6,6 +6,10 @@ from functools import cached_property +class CiA301ConfigException(RuntimeError): + pass + + class CiA301Config(LoggingMixin): """ CiA 301 device configuration interface. From 2350f35284eede31a27fd314da3f8d1c0748a4b6 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 12 Feb 2025 13:56:33 -0600 Subject: [PATCH 080/121] Add `CachedAttrMixin` to help clear stale device info after changes The `clear_cached_properties()` method will clear all cached data that could change during run; first use case is when the alias of a device changes, and cached address, log name, etc. need to be reset. --- hw_device_mgr/cached_attr_mgr.py | 15 +++++++++++++++ hw_device_mgr/cia_301/config.py | 6 ++++-- hw_device_mgr/cia_301/device.py | 4 ++++ hw_device_mgr/device.py | 3 +++ hw_device_mgr/ethercat/config.py | 3 +++ hw_device_mgr/ethercat/device.py | 3 +++ hw_device_mgr/logging/__init__.py | 6 +++++- hw_device_mgr/tests/test_device.py | 1 + 8 files changed, 38 insertions(+), 3 deletions(-) create mode 100644 hw_device_mgr/cached_attr_mgr.py diff --git a/hw_device_mgr/cached_attr_mgr.py b/hw_device_mgr/cached_attr_mgr.py new file mode 100644 index 00000000..5aa7fe3e --- /dev/null +++ b/hw_device_mgr/cached_attr_mgr.py @@ -0,0 +1,15 @@ +class CachedAttrMixin: + + def clear_cached_properties(self, *args): + """ + Clear `cached_property` and `lru_func` values. + + Subclasses should remove cached values defined in their class by + overloading this function: + + def clear_cached_properties(self, *args): + super().clear_cached_properties("prop1", "prop2", *args) + """ + props = set(args) + for prop in props: + self.__dict__.pop(prop, None) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index f7156abd..58607bbc 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -89,8 +89,7 @@ def command(cls): def set_name(self, name): self.name = name - if "logging_name" in self.__dict__: - del self.logging_name # clear cached property + self.clear_cached_properties() # reset logging_name etc. def __str__(self): cname = self.__class__.__name__ @@ -99,6 +98,9 @@ def __str__(self): def __repr__(self): return f"<{self}>" + def clear_cached_properties(self, *args): + super().clear_cached_properties("sdos", "config", *args) + # # Object dictionary # diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 98878c09..276bd7d3 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -65,6 +65,10 @@ def __init__( self.config = config super().__init__(address=address, **kwargs) + def clear_cached_properties(self, *args): + super().clear_cached_properties(*args) + self.config.clear_cached_properties() + @classmethod @lru_cache def device_model_id(cls): diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index ac659513..43215a7d 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -58,6 +58,9 @@ class Device(LoggingMixin, abc.ABC): goal_reached_timeout = 10 # seconds + def clear_cached_properties(self, *args): + super().clear_cached_properties("addr_slug", *args) + @classmethod def canon_address(cls, address): """Canonicalize a device address.""" diff --git a/hw_device_mgr/ethercat/config.py b/hw_device_mgr/ethercat/config.py index f593f5a9..add45d30 100644 --- a/hw_device_mgr/ethercat/config.py +++ b/hw_device_mgr/ethercat/config.py @@ -38,6 +38,9 @@ def canon_address(cls, address): def alias(self): return self.address[2] + def clear_cached_properties(self, *args): + super().clear_cached_properties("alias", *args) + @classmethod def address_variants(cls, address): address = cls.canon_address(address) diff --git a/hw_device_mgr/ethercat/device.py b/hw_device_mgr/ethercat/device.py index ee18e017..1c1c70af 100644 --- a/hw_device_mgr/ethercat/device.py +++ b/hw_device_mgr/ethercat/device.py @@ -62,6 +62,9 @@ def addr_slug(self): addr_prefix = re.sub(r"[^0-9]+", self.slug_separator, str(address)) return addr_prefix.strip(self.slug_separator) + def clear_cached_properties(self, *args): + super().clear_cached_properties("alias", *args) + @classmethod def read_device_sdos_from_esi(cls, LcId="1033"): sdo_data = dict() diff --git a/hw_device_mgr/logging/__init__.py b/hw_device_mgr/logging/__init__.py index d5173645..f45c311a 100644 --- a/hw_device_mgr/logging/__init__.py +++ b/hw_device_mgr/logging/__init__.py @@ -1,5 +1,6 @@ import logging from functools import cached_property, lru_cache +from ..cached_attr_mgr import CachedAttrMixin class Logging: @@ -42,7 +43,7 @@ def getLogger(cls, name): return cls(name) -class LoggingMixin: +class LoggingMixin(CachedAttrMixin): """Mixin class that provides a `logger` attribute.""" logging_class = Logging @@ -58,3 +59,6 @@ def get_logger(cls, name): @cached_property def logger(self): return self.logging_class.getLogger(self.logging_name) + + def clear_cached_properties(self, *args): + super().clear_cached_properties("logging_name", "logger", *args) diff --git a/hw_device_mgr/tests/test_device.py b/hw_device_mgr/tests/test_device.py index 6c14a595..e6f08a1e 100644 --- a/hw_device_mgr/tests/test_device.py +++ b/hw_device_mgr/tests/test_device.py @@ -11,6 +11,7 @@ class TestDevice(BaseTestClass): "SimDevice", "Device", "LoggingMixin", + "CachedAttrMixin", "ABC", ] From 436a6643742556cc11b20c118fdb00df8a0ba0b9 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 5 Feb 2025 17:17:38 -0600 Subject: [PATCH 081/121] ethercat, lcec: Add routines to set EtherCAT device alias --- hw_device_mgr/ethercat/command.py | 40 +++++++++++++++++++++++++-- hw_device_mgr/ethercat/config.py | 46 ++++++++++++++++++++++++++++++- hw_device_mgr/lcec/command.py | 18 ++++++++++++ 3 files changed, 101 insertions(+), 3 deletions(-) diff --git a/hw_device_mgr/ethercat/command.py b/hw_device_mgr/ethercat/command.py index f3ef2726..1034abba 100644 --- a/hw_device_mgr/ethercat/command.py +++ b/hw_device_mgr/ethercat/command.py @@ -1,3 +1,4 @@ +import abc from ..cia_301.command import ( CiA301Command, CiA301SimCommand, @@ -10,8 +11,43 @@ class EtherCATCommandException(CiA301CommandException): class EtherCATCommand(CiA301Command): - pass + + @abc.abstractmethod + def alias( + self, + address=None, + alias=None, + **kwargs, + ): + """Set a device alias.""" class EtherCATSimCommand(EtherCATCommand, CiA301SimCommand): - pass + + def alias( + self, + address=None, + alias=None, + **kwargs, + ): + # Set device alias in sim_device_data for future bus_scan() calls + for dd in self.sim_device_data.values(): + if dd["address"][0] != address[0]: + continue + if address[2]: + if dd["address"][2] != address[2]: + continue + elif dd["address"][1] != address[1]: + continue + oldaddr, newaddr = dd["address"], dd["address"][:2] + (alias,) + dd["address"] = newaddr + addr_str = self.format_address(oldaddr) + newaddr_str = self.format_address(newaddr) + self.sim_sdo_data[newaddr] = self.sim_sdo_data.pop(oldaddr) + self.sim_sdo_values[newaddr] = self.sim_sdo_values.pop(oldaddr) + self.logger.info(f"Set sim device addr {addr_str} -> {newaddr_str}") + return + else: + raise EtherCATCommandException( + f"Failed to set device alias: No device at address {address}" + ) diff --git a/hw_device_mgr/ethercat/config.py b/hw_device_mgr/ethercat/config.py index add45d30..69eadc59 100644 --- a/hw_device_mgr/ethercat/config.py +++ b/hw_device_mgr/ethercat/config.py @@ -1,11 +1,20 @@ +import time from .sdo import EtherCATSDO -from ..cia_301.config import CiA301Config, CiA301SimConfig +from ..cia_301.config import ( + CiA301Config, + CiA301SimConfig, + CiA301ConfigException, +) from .data_types import EtherCATDataType from .xml_reader import EtherCATXMLReader from .command import EtherCATCommand, EtherCATSimCommand from functools import lru_cache, cached_property +class EtherCATConfigException(CiA301ConfigException): + pass + + class EtherCATConfig(CiA301Config): """ EtherCAT drive configuration interface. @@ -136,6 +145,41 @@ def get_device_dcs_from_esi(cls, package, fname, LcId="1033"): esi_reader = cls.read_esi(package, fname, LcId=LcId) return esi_reader.parse_dc_opmodes() + # Device commands + + def set_alias(self, alias, timeout=5.0, **kwargs): + if self.alias == alias: + self.logger.info( + f"Set device alias={alias}: already set; doing nothing" + ) + return + self.command().alias( + address=self.address, + alias=alias, + **kwargs, + ) + # Confirm alias change and update device config + while timeout > 0: + self.clear_cached_properties() + for dev in self.scan_bus(bus=self.bus): + if dev.position != self.position: + continue + if dev.alias != alias: + time.sleep(0.1) + timeout -= 0.1 + continue + self.address = dev.address + self.logger.info(f"Updated alias for device {self}") + return + else: + raise EtherCATConfigException( + f"Unable to see {self} in bus scan after alias change" + ) + else: + raise EtherCATConfigException( + f"Failed to set {self} alias={alias} within {timeout}s timeout" + ) + class EtherCATSimConfig(EtherCATConfig, CiA301SimConfig): command_class = EtherCATSimCommand diff --git a/hw_device_mgr/lcec/command.py b/hw_device_mgr/lcec/command.py index 519d295f..de059c89 100644 --- a/hw_device_mgr/lcec/command.py +++ b/hw_device_mgr/lcec/command.py @@ -139,6 +139,24 @@ def download( **kwargs, ) + def alias( + self, + address=None, + alias=None, + **kwargs, + ): + master, position, old_alias = self.decode_address(address) + self._ethercat( + "alias", + f"--master={master}", + f"--position={position}", + f"--alias={old_alias}", + "--", + str(alias), + log_lev="info", + **kwargs, + ) + class LCECSimCommand(LCECCommand, EtherCATSimCommand): """Simulated LCEC device.""" From 55486429716f0967881560cc963a7bde089dbf97 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 19 Feb 2025 15:21:05 -0600 Subject: [PATCH 082/121] cia_301: Unconfuse `get_device()` and `scan_bus()` kwargs --- hw_device_mgr/cia_301/device.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 276bd7d3..dafd9a6d 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -242,7 +242,7 @@ def get_device(cls, address=None, **kwargs): return device_obj @classmethod - def scan_devices(cls, bus=0, **kwargs): + def scan_devices(cls, bus=0, get_device_kwargs=dict(), **kwargs): """Scan bus and return a list of device objects.""" devices = list() config_cls = cls.config_class @@ -254,7 +254,7 @@ def scan_devices(cls, bus=0, **kwargs): raise NotImplementedError( f"Unknown model {config.model_id} at {config.address}" ) - dev = device_cls.get_device(config, **kwargs) + dev = device_cls.get_device(config, **get_device_kwargs) devices.append(dev) return devices From be39f447be2c2cb19bdb35d4cd8999183c823bd9 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 24 Feb 2025 17:55:41 -0600 Subject: [PATCH 083/121] lcec: Fix `ethercat` command problems when alias is zero IgH `ethercat slaves --position=5 --alias=0` doesn't match slave at pos. 5 if slave at pos. 4 has alias 4; `--alias=-` does the expected. --- hw_device_mgr/lcec/command.py | 28 ++++++++++++++++------------ 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/hw_device_mgr/lcec/command.py b/hw_device_mgr/lcec/command.py index de059c89..cc55b599 100644 --- a/hw_device_mgr/lcec/command.py +++ b/hw_device_mgr/lcec/command.py @@ -17,6 +17,19 @@ class LCECCommand(EtherCATCommand): def _parse_output(cls, resp, kwargs): return resp + @classmethod + def address_to_args(cls, address): + """Convert address to `ethercat` utility arguments.""" + # IgH `ethercat slaves --position=5 --alias=0` doesn't match slave at + # pos. 5 if slave at pos. 4 has alias 4; `--alias=-` does the expected + master, position, alias = cls.decode_address(address) + return ( + f"--master={master}", + f"--position={position}", + f"--alias={alias or '-'}", + ) + + def _ethercat( self, *args, log_lev="debug", dry_run=False, stderr_to_devnull=False ): @@ -97,12 +110,9 @@ def master_nic(self, bus=None): def upload( self, address=None, index=None, subindex=0, datatype=None, **kwargs ): - master, position, alias = self.decode_address(address) output = self._ethercat( "upload", - f"--master={master}", - f"--position={position}", - f"--alias={alias}", + *self.address_to_args(address), f"0x{index:04X}", f"0x{subindex:02X}", f"--type={datatype.igh_type}", @@ -124,12 +134,9 @@ def download( datatype=None, **kwargs, ): - master, position, alias = self.decode_address(address) self._ethercat( "download", - f"--master={master}", - f"--position={position}", - f"--alias={alias}", + *self.address_to_args(address), f"--type={datatype.igh_type}", "--", f"0x{index:04X}", @@ -145,12 +152,9 @@ def alias( alias=None, **kwargs, ): - master, position, old_alias = self.decode_address(address) self._ethercat( "alias", - f"--master={master}", - f"--position={position}", - f"--alias={old_alias}", + *self.address_to_args(address), "--", str(alias), log_lev="info", From 8b7d15f84481d79dde18a92acee010fe24fb7f49 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 25 Mar 2025 15:43:29 -0500 Subject: [PATCH 084/121] fixup! lcec: Fix `ethercat` command problems when alias is zero --- hw_device_mgr/lcec/tests/base_test_class.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/lcec/tests/base_test_class.py b/hw_device_mgr/lcec/tests/base_test_class.py index f8153e2e..e2bab906 100644 --- a/hw_device_mgr/lcec/tests/base_test_class.py +++ b/hw_device_mgr/lcec/tests/base_test_class.py @@ -75,7 +75,8 @@ def emulate_ethercat_command(args, **kwargs): index=ix[0], subindex=ix[1], data_type=dt.shared_name ) address = tuple( - int(kwargs[k]) for k in ("master", "position", "alias") + int(kwargs[k].replace("-", "0")) + for k in ("master", "position", "alias") ) sim_sdo_values = self.command_class.sim_sdo_values key = self.config_class.address_in_canon_addresses( From 244eae9f92e3baa845454212e9332948c50fd7d8 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 25 Mar 2025 15:43:40 -0500 Subject: [PATCH 085/121] cia_301: Stop param updates during shutdown --- hw_device_mgr/cia_301/config.py | 6 ++++++ hw_device_mgr/cia_301/device.py | 4 +++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index 58607bbc..41555be7 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -389,6 +389,12 @@ def param_init_in_progress(self): """Return `False` if params still queued for init.""" return not self.params_queue.empty + def param_init_stop(self): + """Stop any ongoing param initialization.""" + if self.param_init_in_progress: + self.logger.info("Stopping param updates") + self.params_queue.join() + @property def param_init_error(self): """ diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index 5ad542bc..1031978f 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -198,7 +198,9 @@ def set_command(self, **kwargs): cmd_out = super().set_command(**kwargs) cmd_in = self._interfaces["command_in"] init_params_cmd = False - if self.feedback_in.rising_edge("online"): + if cmd_out.get("shutdown_latch"): + self.config.param_init_stop() + elif self.feedback_in.rising_edge("online"): self.logger.info("Initializing params after coming online") init_params_cmd = True elif cmd_in.rising_edge("reset_fault") and self.config.param_init_error: From 8f1ce21b210d5b927d744e6341397bc4e3a81413 Mon Sep 17 00:00:00 2001 From: Daniel Solis Date: Sat, 12 Apr 2025 20:47:52 +0000 Subject: [PATCH 086/121] Merged in 770MXE_support_for_new_Inovance_STD60N_driver_for_microarc4 (pull request #8) 770MXE support for new Inovance STD60N driver for microarc4 * 770MXE: initial support for Inovance STD60N driver Approved-by: Jason VandeKieft --- .../devices/device_err/inovance_std60n.yaml | 297 + .../STD60_EOE_1Axis_06008_NEW_v1_0.xml | 11658 ++++++++++++++++ hw_device_mgr/devices/inovance_std60.py | 121 + 3 files changed, 12076 insertions(+) create mode 100644 hw_device_mgr/devices/device_err/inovance_std60n.yaml create mode 100755 hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml create mode 100644 hw_device_mgr/devices/inovance_std60.py diff --git a/hw_device_mgr/devices/device_err/inovance_std60n.yaml b/hw_device_mgr/devices/device_err/inovance_std60n.yaml new file mode 100644 index 00000000..fe91bab8 --- /dev/null +++ b/hw_device_mgr/devices/device_err/inovance_std60n.yaml @@ -0,0 +1,297 @@ +# From Inovance STD60N "STD60N Series Stepper System Manual Package" 2022-12, table 18-1, 18-2, 18-3, 18-4 +# "Communication Faults and Warning Codes" +# +# Parameter 603Fh shows the basic error code, but the +# manufacturer-specific STD60N parameter 203Fh "Manufacturer fault +# code" shows an extended error value. The manual's table 18-1 shows +# e.g. "fault" E101, with "display" broken down into E101.0, E101.1 and E101.2. +# +# key: "Auxiliary Code" column most significant word +# display: "Display" column; code displayed on drive LED panel +# description: "Name" column +# type: "Type" column; indicates severity, with 1 most severe +# resettable: "Resettable" column; indicates whether resettable +# without power cycle + +# +# List of fault codes +# + +'0x0101': + display: E101.0 + description: Abnormal parameters in groups H02 and above + type: 1 + resettable: false +'0x1101': + display: E101.1 + description: Parameter error in group H00/H01 + type: 1 + resettable: false +'0x2101': + display: E101.2 + description: Address error in read/write operation after the number of parameters changes + type: 1 + resettable: false +'0x8102': + display: E102.8 + description: FPGA and MCU version mismatch + type: 1 + resettable: false +'0x2120': + display: E120.2 + description: Unknown drive model + type: 1 + resettable: false +'0x1122': + display: E122.1 + description: Different DIs assigned with the same function + type: 2 + resettable: true +'0x4122': + display: E122.4 + description: Different VDIs assigned with the same function + type: 2 + resettable: true +'0x5122': + display: E122.5 + description: DI and VDI assigned with the same function + type: 2 + resettable: true +'0x0126': + display: E126.0 + description: Process segment number error + type: 2 + resettable: true +'0x1126': + display: E126.1 + description: Incorrect technology segment operation mode + type: 2 + resettable: true +'0x2126': + display: E126.2 + description: Incorrect technology segment instruction type + type: 2 + resettable: true +'0x0140': + display: E140.0 + description: Encrypted chip check error + type: 1 + resettable: false +'0x2140': + display: E140.2 + description: Inconsistent versions of encrypted chip + type: 1 + resettable: false +'0x3140': + display: E140.3 + description: Encrypted chip damaged + type: 1 + resettable: false +'0x0201': + display: E201.0 + description: Hardware overcurrent + type: 1 + resettable: false +'0x0400': + display: E400.0 + description: Main circuit overvoltage + type: 1 + resettable: true +'0x0650': + display: E650.0 + description: Heatsink overtemperature + type: 1 + resettable: true +'0x0938': + display: E938.0 + description: Wrong phase of motor power cable + type: 1 + resettable: true +'0x0939': + display: E939.0 + description: Motor power cables disconnected + type: 1 + resettable: true +'0x1939': + display: E939.1 + description: Phase A power cable breakage + type: 1 + resettable: true +'0x2939': + display: E939.2 + description: Phase B power cable breakage + type: 1 + resettable: true +'0x1B01': + display: EB01.1 + description: Individual position reference increment too large + type: 2 + resettable: true +'0x3B01': + display: EB01.3 + description: Reference overflow + type: 2 + resettable: true +'0x0E08': + display: EE08.0 + description: Synchronization signal loss + type: 2 + resettable: true +'0x1E08': + display: EE08.1 + description: Status switchover error + type: 2 + resettable: true +'0x3E08': + display: EE08.3 + description: Network cable connected improperly + type: 2 + resettable: true +'0x4E08': + display: EE08.4 + description: Data frame loss protection error + type: 2 + resettable: true +'0x5E08': + display: EE08.5 + description: Data frame transfer error + type: 2 + resettable: true +'0x6E08': + display: EE08.6 + description: Data update timeout + type: 2 + resettable: true +'0x0E09': + display: EE09.0 + description: Software position limit setting error + type: 2 + resettable: true +'0x1E09': + display: EE09.1 + description: Home setting error + type: 2 + resettable: true +'0x3E09': + display: EE09.3 + description: Homing method setting error + type: 2 + resettable: true +'0x5E09': + display: EE09.5 + description: PDO mapping beyond the limit + type: 2 + resettable: true +'0x0E11': + display: EE11.0 + description: ESI check error + type: 2 + resettable: true +'0x1E11': + display: EE11.1 + description: Failed to read e2prom by bus + type: 2 + resettable: true +'0x2E11': + display: EE11.2 + description: Failed to update e2prom by bus + type: 2 + resettable: true +'0x0E12': + display: EE12.0 + description: EtherCAT initialization failure + type: 1 + resettable: false +'0x0E13': + display: EE13.0 + description: Synchronization cycle setting error + type: 2 + resettable: true +# +# List of warning codes +# +'0x0108': + display: E108.0 + description: Parameter write error + type: 3 + resettable: true +'0x1108': + display: E108.1 + description: Parameter read error + type: 3 + resettable: true +'0x2108': + display: E108.2 + description: Check on data written in e2prom failed + type: 3 + resettable: true +'0x3108': + display: E108.3 + description: Check on data read in e2prom failed + type: 3 + resettable: true +'0x0121': + display: E121.0 + description: Invalid drive ON command + type: 3 + resettable: true +'0x0601': + display: E601.0 + description: Homing warning + type: 3 + resettable: true +'0x1601': + display: E601.1 + description: Homing switch error + type: 3 + resettable: true +'0x2601': + display: E601.2 + description: Homing mode setting error + type: 3 + resettable: true +'0x0900': + display: E900.0 + description: DI emergency braking + type: 3 + resettable: true +'0x0902': + display: E902.0 + description: DI setting invalid + type: 3 + resettable: true +'0x1902': + display: E902.1 + description: DO setting invalid + type: 3 + resettable: true +'0x0941': + display: E941.0 + description: Modified parameters activated at next power-on + type: 3 + resettable: true +'0x0942': + display: E942.0 + description: Parameters saved frequently + type: 3 + resettable: true +'0x0950': + display: E950.0 + description: Forward overtravel warning + type: 3 + resettable: true +'0x0952': + display: E952.0 + description: Reverse overtravel warning + type: 3 + resettable: true +'0x0956': + display: E956.0 + description: Forward position reference overtravel in process segment position mode + type: 3 + resettable: true +'0x0958': + display: E958.0 + description: Reverse position reference overtravel in process segment position mode + type: 3 + resettable: true diff --git a/hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml b/hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml new file mode 100755 index 00000000..1bc81a7d --- /dev/null +++ b/hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml @@ -0,0 +1,11658 @@ + + + + + #x00100000 + Inovance + 汇川技术 + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + + InoServo + Servo Drives + 伺服驱动器 + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + + InoSTD60N + STD60_1Axis_06008 + ServoDrive + http://www.inovance.cn + + + + 3000 + 9000 + 5000 + 200 + + + + + 100 + 2000 + + + + InoServo + + + 402 + + + + + + BIT2 + 2 + + + + BOOL + 1 + + + + DINT + 32 + + + + INT + 16 + + + + UDINT + 32 + + + + UINT + 16 + + + + USINT + 8 + + + + SINT + 8 + + + + STRING(10) + 80 + + + + STRING(4) + 32 + + + DT1018 + 144 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Vendor ID + UDINT + 32 + 16 + + ro + + + + 2 + Product Code + UDINT + 32 + 48 + + ro + + + + 3 + Revision + UDINT + 32 + 80 + + ro + + + + 4 + Serial number + UDINT + 32 + 112 + + ro + + + + + DT1600 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Output Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Output Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Output Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Output Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Output Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Output Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Output Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Output Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Output Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1701 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Output Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Output Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Output Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Output Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Output Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Output Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Output Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Output Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Output Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1702 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Output Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Output Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Output Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Output Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Output Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Output Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Output Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Output Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Output Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1703 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Output Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Output Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Output Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Output Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Output Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Output Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Output Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Output Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Output Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1704 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Output Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Output Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Output Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Output Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Output Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Output Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Output Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Output Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Output Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1705 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Output Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Output Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Output Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Output Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Output Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Output Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Output Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Output Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Output Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Output Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Output Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Output Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Output Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Output Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Output Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Output Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Output Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Output Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Output Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Output Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1A00 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Input Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Input Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Input Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Input Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Input Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Input Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Input Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Input Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Input Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1B01 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Input Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Input Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Input Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Input Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Input Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Input Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Input Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Input Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Input Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1B02 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Input Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Input Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Input Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Input Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Input Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Input Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Input Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Input Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Input Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1B03 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Input Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Input Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Input Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Input Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Input Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Input Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Input Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Input Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Input Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1B04 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Input Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Input Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Input Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Input Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Input Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Input Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Input Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Input Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Input Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1B05 + 656 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + 1 + 1st Input Object to be mapped + UDINT + 32 + 16 + + rw + + + + 2 + 2nd Input Object to be mapped + UDINT + 32 + 48 + + rw + + + + 3 + 3rd Input Object to be mapped + UDINT + 32 + 80 + + rw + + + + 4 + 4th Input Object to be mapped + UDINT + 32 + 112 + + rw + + + + 5 + 5th Input Object to be mapped + UDINT + 32 + 144 + + rw + + + + 6 + 6th Input Object to be mapped + UDINT + 32 + 176 + + rw + + + + 7 + 7th Input Object to be mapped + UDINT + 32 + 208 + + rw + + + + 8 + 8th Input Object to be mapped + UDINT + 32 + 240 + + rw + + + + 9 + 9th Input Object to be mapped + UDINT + 32 + 272 + + rw + + + + 10 + 10th Input Object to be mapped + UDINT + 32 + 304 + + rw + + + + 11 + 11th Input Object to be mapped + UDINT + 32 + 336 + + rw + + + + 12 + 12th Input Object to be mapped + UDINT + 32 + 368 + + rw + + + + 13 + 13th Input Object to be mapped + UDINT + 32 + 400 + + rw + + + + 14 + 14th Input Object to be mapped + UDINT + 32 + 432 + + rw + + + + 15 + 15th Input Object to be mapped + UDINT + 32 + 464 + + rw + + + + 16 + 16th Input Object to be mapped + UDINT + 32 + 496 + + rw + + + + 17 + 17th Input Object to be mapped + UDINT + 32 + 528 + + rw + + + + 18 + 18th Input Object to be mapped + UDINT + 32 + 560 + + rw + + + + 19 + 19th Input Object to be mapped + UDINT + 32 + 592 + + rw + + + + 20 + 20th Input Object to be mapped + UDINT + 32 + 624 + + rw + + + + + DT1C00ARR + USINT + 32 + + 1 + 4 + + + + DT1C00 + 48 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + o + + + + Elements + DT1C00ARR + 32 + 16 + + ro + o + + + + + + DT1C32 + 488 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + m + + + + 1 + Sync mode + UINT + 16 + 16 + + rw + + + + 2 + Cycle time + UDINT + 32 + 32 + + ro + o + + + + 4 + Sync modes supported + UINT + 16 + 96 + + ro + o + + + + 5 + Minimum cycle time + UDINT + 32 + 112 + + ro + o + + + + 6 + Calc and copy time + UDINT + 32 + 144 + + ro + o + + + + 8 + Get Cycle Time + UINT + 16 + 208 + + rw + c + + + + 9 + Delay Time + UDINT + 32 + 224 + + ro + c + + + + 10 + Sync0 Cycle Time + UDINT + 32 + 256 + + rw + o + + + + 11 + SM-Event Missed + UINT + 16 + 288 + + ro + c + + + + 12 + Cycle Time Too Small + UINT + 16 + 304 + + ro + c + + + + 32 + Sync Error + BOOL + 1 + 480 + + ro + c + + + + + + DT1C33 + 488 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + o + + + + 1 + Sync mode + UINT + 16 + 16 + + rw + + + + 2 + Cycle time + UDINT + 32 + 32 + + ro + o + + + + 4 + Sync modes supported + UINT + 16 + 96 + + ro + o + + + + 5 + Minimum cycle time + UDINT + 32 + 112 + + ro + o + + + + 6 + Calc and copy time + UDINT + 32 + 144 + + ro + o + + + + 8 + Get Cycle Time + UINT + 16 + 208 + + rw + c + + + + 9 + Delay Time + UDINT + 32 + 224 + + ro + c + + + + 10 + Sync0 Cycle Time + UDINT + 32 + 256 + + rw + o + + + + 11 + SM-Event Missed + UINT + 16 + 288 + + ro + c + + + + 12 + Cycle Time Too Small + UINT + 16 + 304 + + ro + c + + + + 32 + Sync Error + BOOL + 1 + 480 + + ro + c + + + + + DT1C12ARR + UINT + 16 + + 1 + 1 + + + + DT1C12 + 32 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + Elements + DT1C12ARR + 16 + 16 + + rw + o + + + + + DT1C13ARR + UINT + 16 + + 1 + 1 + + + + DT1C13 + 32 + + 0 + SubIndex 000 + USINT + 8 + 0 + + rw + + + + Elements + DT1C13ARR + 16 + 16 + + rw + o + + + + + + DT2000 + 352 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Motor SN + UINT + 16 + 16 + + rw + + + + 3 + Customized firmware version + UDINT + 32 + 48 + + ro + + + + + 12 + Rated current + UINT + 16 + 176 + + rw + + + + + 16 + Maximum speed + UINT + 16 + 240 + + rw + + + + + 20 + Stator resistance + UINT + 16 + 304 + + rw + + + + + 21 + Phase A stator inductance + UINT + 16 + 320 + + rw + + + + + 22 + Phase B stator inductance + UINT + 16 + 336 + + rw + + + + + + DT2001 + 736 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + MCU firmware Version + UINT + 16 + 16 + + ro + + + + 11 + Drive serial number + UINT + 16 + 176 + + rw + + + + 12 + Drive voltage class + UINT + 16 + 192 + + ro + + + + 14 + Given peak current + UINT + 16 + 224 + + rw + + + + 19 + Drive maximum output current + UDINT + 32 + 304 + + ro + + + + 25 + Locking current percentage + UINT + 16 + 400 + + rw + + + + 26 + Delay time of Locking current + UINT + 16 + 416 + + rw + + + + 35 + Upper temperature threshold + UINT + 16 + 560 + + rw + + + + 41 + DC bus overvoltage protective point + UINT + 16 + 656 + + ro + + + + 43 + DC bus undervoltage protective point + UINT + 16 + 688 + + ro + + + + 44 + Current compensation filtering + UINT + 16 + 704 + + rw + + + + 45 + Current compensation Enable + UINT + 16 + 720 + + rw + + + + + 47 + A-axis proportional gain + UINT + 16 + 752 + + rw + + + + + 48 + A-axis integral compensation factor + UINT + 16 + 768 + + rw + + + + + 50 + B-axis proportional gain + UINT + 16 + 800 + + rw + + + + + 51 + B-axis integral compensation factor + UINT + 16 + 816 + + rw + + + + + + DT2002 + 688 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Control mode selection + UINT + 16 + 16 + + rw + + + + 3 + Rotating direction + UINT + 16 + 48 + + rw + + + + 8 + Stop mode at limit switch signal + UINT + 16 + 128 + + rw + + + + 16 + LED warning display selection + UINT + 16 + 256 + + rw + + + + 31 + User password + UINT + 16 + 496 + + wo + + + + 32 + Parameter initialization + UINT + 16 + 512 + + rw + + + + 33 + Default keypad display + UINT + 16 + 528 + + rw + + + + 36 + Panel data refresh rate + UINT + 16 + 576 + + rw + + + + 42 + OEM password + UINT + 16 + 672 + + wo + + + + + DT2003 + 1040 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 3 + DI1 function selection + UINT + 16 + 48 + + rw + + + + 4 + DI1 logic selection + UINT + 16 + 64 + + rw + + + + 5 + DI2 function selection + UINT + 16 + 80 + + rw + + + + 6 + DI2 logic selection + UINT + 16 + 96 + + rw + + + + 7 + DI3 function selection + UINT + 16 + 112 + + rw + + + + 8 + DI3 logic selection + UINT + 16 + 128 + + rw + + + + 9 + DI4 function selection + UINT + 16 + 144 + + rw + + + + 10 + DI4 logic selection + UINT + 16 + 160 + + rw + + + + 61 + DI1 filtertime constant + UINT + 16 + 976 + + rw + + + + 62 + DI2 filtertime constant + UINT + 16 + 992 + + rw + + + + 63 + DI3 filtertime constant + UINT + 16 + 1008 + + rw + + + + 64 + DI4 filtertime constant + UINT + 16 + 1024 + + rw + + + + + DT2004 + 400 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + DO1 Function Selection + UINT + 16 + 16 + + rw + + + + 2 + DO1 Logic Level Selection + UINT + 16 + 32 + + rw + + + + 3 + DO2 function selection + UINT + 16 + 48 + + rw + + + + 4 + DO2 Logic Level Selection + UINT + 16 + 64 + + rw + + + + 23 + DO Source Selection + UINT + 16 + 368 + + rw + + + + 24 + ECAT DO Offline Logic + UINT + 16 + 384 + + rw + + + + + DT2005 + 1152 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 5 + Time constant of first-order low-pass filter + UINT + 16 + 80 + + rw + + + + 7 + Time constant of moving average filter 1 + UINT + 16 + 112 + + rw + + + + + 12 + Motor step resolution + UDINT + 32 + 192 + + rw + + + + 36 + Time of home searching + UINT + 16 + 576 + + rw + + + + + 41 + Home selection + UINT + 16 + 656 + + rw + + + + 67 + Time unit of home searching + UINT + 16 + 1072 + + rw + + + + 71 + Time constant of moving average filter 2 + UINT + 16 + 1136 + + rw + + + + + DT2006 + 336 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 17 + Speed threshold of motor rotation signal + UINT + 16 + 272 + + rw + + + + 18 + Speed threshold of speed-consistent signal + UINT + 16 + 288 + + rw + + + + 19 + Speed threshold of speed-arrive signal + UINT + 16 + 304 + + rw + + + + 20 + Speed threshold of speed-zero signal + UINT + 16 + 320 + + rw + + + + + DT200A + 1184 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 2 + Absolute position limit set + UINT + 16 + 32 + + rw + + + + 11 + Local following error window + UDINT + 32 + 176 + + rw + + + + 20 + Touch Probe 1 filter time constant + UINT + 16 + 320 + + rw + + + + 21 + Touch Probe 2 filter time constant + UINT + 16 + 336 + + rw + + + + 26 + Speed DO Filter time constant + UINT + 16 + 448 + + rw + + + + 41 + Over Travel Compensation + UINT + 16 + 656 + + rw + + + + 57 + Fault reset delay time + UINT + 16 + 912 + + rw + + + + 71 + The 2nd over speed threshold + UINT + 16 + 1136 + + rw + + + + 73 + Maximum ramp stop time + UINT + 16 + 1168 + + rw + + + + + DT200B + 1488 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Actual motor rotational speed + INT + 16 + 16 + + ro + T + + + + 3 + Dip-switch value + UINT + 16 + 48 + + ro + T + + + + 4 + Monitored DI states + UINT + 16 + 64 + + ro + T + + + + 6 + Monitored DO states + UINT + 16 + 96 + + ro + T + + + + 8 + Absolute position counter + DINT + 32 + 128 + + ro + T + + + + 20 + Total power-on time + UDINT + 32 + 320 + + ro + T + + + + 25 + Phase current valid value + UINT + 16 + 400 + + ro + T + + + + 27 + Bus voltage + UINT + 16 + 432 + + ro + T + + + + 28 + Module temperature + UINT + 16 + 448 + + ro + T + + + + 34 + Displayed fault record + UINT + 16 + 544 + + rw + + + + 35 + Fault code + UINT + 16 + 560 + + ro + + + + 36 + Time stamp upon displayed fault + UDINT + 32 + 576 + + ro + + + + 38 + Current rotational speed upon displayed fault + INT + 16 + 608 + + ro + + + + 39 + Current U upon displayed fault + INT + 16 + 624 + + ro + + + + 40 + Current V upon displayed fault + INT + 16 + 640 + + ro + + + + 41 + Bus voltage upon displayed fault + UINT + 16 + 656 + + ro + + + + 42 + Input terminal state upon displayed fault + UINT + 16 + 672 + + ro + + + + 44 + Output terminal state upon displayed fault + UINT + 16 + 704 + + ro + + + + 46 + Inner error code + UINT + 16 + 736 + + ro + + + + 52 + Inner error code upon displayed fault + UINT + 16 + 832 + + ro + + + + 58 + Control bus voltage + UINT + 16 + 928 + + ro + T + + + + 64 + Not ready reason + UINT + 16 + 1024 + + ro + + + + 91 + Group of unusual function code + UINT + 16 + 1456 + + ro + + + + 92 + Offset of unusual function code + UINT + 16 + 1472 + + ro + + + + + DT200D + 336 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Software reset + UINT + 16 + 16 + + rw + + + + 2 + Fault reset + UINT + 16 + 32 + + rw + + + + 6 + Emergency stop + UINT + 16 + 96 + + rw + + + + 13 + UV phase current auto-tuning + UINT + 16 + 208 + + rw + + + + 18 + Forced DI/DO setting + UINT + 16 + 288 + + rw + + + + 19 + Forced DI level + UINT + 16 + 304 + + rw + + + + 20 + Forced DO setting + UINT + 16 + 320 + + rw + + + + + DT200E + 1568 + + 0 + Number of Entries + USINT + 8 + 0 + + ro + + + + 1 + Node address + UINT + 16 + 16 + + rw + + + + 2 + Update function code values written via communication to EEPROM + UINT + 16 + 32 + + rw + + + + 9 + Alias source + UINT + 16 + 144 + + rw + + + + 21 + station auto inc address + UINT + 16 + 336 + + ro + + + + 22 + station alias + UINT + 16 + 352 + + rw + + + + 23 + Sync lost window + UINT + 16 + 368 + + rw + + + + 25 + Sync lost counter + UINT + 16 + 400 + + ro + + + + 26 + Port 0 invalid frame counter + UINT + 16 + 416 + + ro + + + + 27 + Port 1 invalid frame counter + UINT + 16 + 432 + + ro + + + + 28 + Port 0/1 transfer error counter + UINT + 16 + 448 + + ro + + + + 29 + process unit and PDI error counter + UINT + 16 + 464 + + ro + + + + 30 + Port 0/1 lost counter + UINT + 16 + 480 + + ro + + + + 32 + Sync mode set + UINT + 16 + 512 + + rw + + + + 33 + Sync error window + UINT + 16 + 528 + + rw + + + + 34 + EtherCAT network state and link state + UINT + 16 + 544 + + ro + + + + 35 + CSP postion increment over counter + UINT + 16 + 560 + + rw + + + + 36 + ALCode + UINT + 16 + 576 + + ro + + + + 37 + Enhanced link detection enable + UINT + 16 + 592 + + rw + + + + 38 + Reset EtherCAT xml file + UINT + 16 + 608 + + rw + + + + 94 + EtherCAT PHY version number + UINT + 16 + 1504 + + ro + + + + 97 + EtherCAT xml file version number + UINT + 16 + 1552 + + ro + + + + + DT2017 + 1520 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + VDI1 function selection + UINT + 16 + 16 + + rw + + + + 2 + VDI1 logic selection + UINT + 16 + 32 + + rw + + + + 3 + VDI2 function selection + UINT + 16 + 48 + + rw + + + + 4 + VDI2 logic selection + UINT + 16 + 64 + + rw + + + + 5 + VDI3 function selection + UINT + 16 + 80 + + rw + + + + 6 + VDI3 logic selection + UINT + 16 + 96 + + rw + + + + 7 + VDI4 function selection + UINT + 16 + 112 + + rw + + + + 8 + VDI4 logic selection + UINT + 16 + 128 + + rw + + + + 9 + VDI5 function selection + UINT + 16 + 144 + + rw + + + + 10 + VDI5 logic selection + UINT + 16 + 160 + + rw + + + + 11 + VDI6 function selection + UINT + 16 + 176 + + rw + + + + 12 + VDI6 logic selection + UINT + 16 + 192 + + rw + + + + 13 + VDI7 function selection + UINT + 16 + 208 + + rw + + + + 14 + VDI7 logic selection + UINT + 16 + 224 + + rw + + + + 15 + VDI8 function selection + UINT + 16 + 240 + + rw + + + + 16 + VDI8 logic selection + UINT + 16 + 256 + + rw + + + + 17 + VDI9 function selection + UINT + 16 + 272 + + rw + + + + 18 + VDI9 logic selection + UINT + 16 + 288 + + rw + + + + 19 + VDI10 function selection + UINT + 16 + 304 + + rw + + + + 20 + VDI10 logic selection + UINT + 16 + 320 + + rw + + + + 21 + VDI11 function selection + UINT + 16 + 336 + + rw + + + + 22 + VDI11 logic selection + UINT + 16 + 352 + + rw + + + + 23 + VDI12 function selection + UINT + 16 + 368 + + rw + + + + 24 + VDI12 logic selection + UINT + 16 + 384 + + rw + + + + 25 + VDI13 function selection + UINT + 16 + 400 + + rw + + + + 26 + VDI13 logic selection + UINT + 16 + 416 + + rw + + + + 27 + VDI14 function selection + UINT + 16 + 432 + + rw + + + + 28 + VDI14 logic selection + UINT + 16 + 448 + + rw + + + + 29 + VDI15 function selection + UINT + 16 + 464 + + rw + + + + 30 + VDI15 logic selection + UINT + 16 + 480 + + rw + + + + 31 + VDI16 function selection + UINT + 16 + 496 + + rw + + + + 32 + VDI16 logic selection + UINT + 16 + 512 + + rw + + + + 33 + Comm Set VDO + UINT + 16 + 528 + + rw + R + + + + 34 + VDO1 function selection + UINT + 16 + 544 + + rw + + + + 35 + VDO1 logic selection + UINT + 16 + 560 + + rw + + + + 36 + VDO2 function selection + UINT + 16 + 576 + + rw + + + + 37 + VDO2 logic selection + UINT + 16 + 592 + + rw + + + + 38 + VDO3 function selection + UINT + 16 + 608 + + rw + + + + 39 + VDO3 logic selection + UINT + 16 + 624 + + rw + + + + 40 + VDO4 function selection + UINT + 16 + 640 + + rw + + + + 41 + VDO4 logic selection + UINT + 16 + 656 + + rw + + + + 42 + VDO5 function selection + UINT + 16 + 672 + + rw + + + + 43 + VDO5 logic selection + UINT + 16 + 688 + + rw + + + + 44 + VDO6 function selection + UINT + 16 + 704 + + rw + + + + 45 + VDO6 logic selection + UINT + 16 + 720 + + rw + + + + 46 + VDO7 function selection + UINT + 16 + 736 + + rw + + + + 47 + VDO7 logic selection + UINT + 16 + 752 + + rw + + + + 48 + VDO8 function selection + UINT + 16 + 768 + + rw + + + + 49 + VDO8 logic selection + UINT + 16 + 784 + + rw + + + + 50 + VDO9 function selection + UINT + 16 + 800 + + rw + + + + 51 + VDO9 logic selection + UINT + 16 + 816 + + rw + + + + 52 + VDO10 function selection + UINT + 16 + 832 + + rw + + + + 53 + VDO10 logic selection + UINT + 16 + 848 + + rw + + + + 54 + VDO11 function selection + UINT + 16 + 864 + + rw + + + + 55 + VDO11 logic selection + UINT + 16 + 880 + + rw + + + + 56 + VDO12 function selection + UINT + 16 + 896 + + rw + + + + 57 + VDO12 logic selection + UINT + 16 + 912 + + rw + + + + 58 + VDO13 function selection + UINT + 16 + 928 + + rw + + + + 59 + VDO13 logic selection + UINT + 16 + 944 + + rw + + + + 60 + VDO14 function selection + UINT + 16 + 960 + + rw + + + + 61 + VDO14 logic selection + UINT + 16 + 976 + + rw + + + + 62 + VDO15 function selection + UINT + 16 + 992 + + rw + + + + 63 + VDO15 logic selection + UINT + 16 + 1008 + + rw + + + + 64 + VDO16 function selection + UINT + 16 + 1024 + + rw + + + + 65 + VDO16 logic selection + UINT + 16 + 1040 + + rw + + + + 91 + VDI Enable + UINT + 16 + 1456 + + rw + R + + + + 92 + VDI Default after power-on + UINT + 16 + 1472 + + rw + R + + + + 93 + VDO Enable + UINT + 16 + 1488 + + rw + R + + + + 94 + VDO Default after power-on + UINT + 16 + 1504 + + rw + R + + + + + DT2018 + 1296 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Command trigger + UINT + 16 + 16 + + rw + R + + + + 2 + Event-rising-edge trigger process period + UINT + 16 + 32 + + rw + + + + 4 + ACC-DEC-Time of Process period halt + UINT + 16 + 64 + + rw + + + + 5 + Forward soft limit + DINT + 32 + 80 + + rw + + + + 7 + Reverse soft limit + DINT + 32 + 112 + + rw + + + + 9 + Process period number + UINT + 16 + 144 + + ro + + + + 10 + PR Command State + UINT + 16 + 160 + + ro + T + + + + 11 + PR Command Update + UINT + 16 + 176 + + rw + R + + + + 20 + Target speed + UINT + 16 + 320 + + rw + + + + 21 + Target speed1 + UINT + 16 + 336 + + rw + + + + 22 + Target speed2 + UINT + 16 + 352 + + rw + + + + 23 + Target speed3 + UINT + 16 + 368 + + rw + + + + 24 + Target speed4 + UINT + 16 + 384 + + rw + + + + 25 + Target speed5 + UINT + 16 + 400 + + rw + + + + 26 + Target speed6 + UINT + 16 + 416 + + rw + + + + 27 + Target speed7 + UINT + 16 + 432 + + rw + + + + 36 + ACC-DEC Time + UINT + 16 + 576 + + rw + + + + 37 + ACC-DEC Time1 + UINT + 16 + 592 + + rw + + + + 38 + ACC-DEC Time2 + UINT + 16 + 608 + + rw + + + + 39 + ACC-DEC Time3 + UINT + 16 + 624 + + rw + + + + 40 + ACC-DEC Time4 + UINT + 16 + 640 + + rw + + + + 41 + ACC-DEC Time5 + UINT + 16 + 656 + + rw + + + + 42 + ACC-DEC Time6 + UINT + 16 + 672 + + rw + + + + 43 + ACC-DEC Time7 + UINT + 16 + 688 + + rw + + + + 52 + Delay Time + UINT + 16 + 832 + + rw + + + + 53 + Delay Time1 + UINT + 16 + 848 + + rw + + + + 54 + Delay Time2 + UINT + 16 + 864 + + rw + + + + 55 + Delay Time3 + UINT + 16 + 880 + + rw + + + + 56 + Delay Time4 + UINT + 16 + 896 + + rw + + + + 57 + Delay Time5 + UINT + 16 + 912 + + rw + + + + 58 + Delay Time6 + UINT + 16 + 928 + + rw + + + + 59 + Delay Time7 + UINT + 16 + 944 + + rw + + + + 71 + Homing mode + UINT + 16 + 1136 + + rw + + + + 72 + High-speed of homing + UINT + 16 + 1152 + + rw + + + + 73 + Low-speed of homing + UINT + 16 + 1168 + + rw + + + + 74 + ACC-DEC time of homing + UINT + 16 + 1184 + + rw + + + + 75 + limit time of homing + UINT + 16 + 1200 + + rw + + + + 76 + Homing offset + DINT + 32 + 1216 + + rw + + + + 80 + Relative/Absolute homing + UINT + 16 + 1280 + + rw + + + + + DT2019 + 1040 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Homing definition + UDINT + 32 + 16 + + rw + + + + 3 + Homing data + DINT + 32 + 48 + + rw + + + + 5 + Process period1 definition + UDINT + 32 + 80 + + rw + + + + 7 + Process period1 data + DINT + 32 + 112 + + rw + + + + 9 + Process period2 definition + UDINT + 32 + 144 + + rw + + + + 11 + Process period2 data + DINT + 32 + 176 + + rw + + + + 13 + Process period3 definition + UDINT + 32 + 208 + + rw + + + + 15 + Process period3 data + DINT + 32 + 240 + + rw + + + + 17 + Process period4 definition + UDINT + 32 + 272 + + rw + + + + 19 + Process period4 data + DINT + 32 + 304 + + rw + + + + 21 + Process period5 definition + UDINT + 32 + 336 + + rw + + + + 23 + Process period5 data + DINT + 32 + 368 + + rw + + + + 25 + Process period6 definition + UDINT + 32 + 400 + + rw + + + + 27 + Process period6 data + DINT + 32 + 432 + + rw + + + + 29 + Process period7 definition + UDINT + 32 + 464 + + rw + + + + 31 + Process period7 data + DINT + 32 + 496 + + rw + + + + 33 + Process period8 definition + UDINT + 32 + 528 + + rw + + + + 35 + Process period8 data + DINT + 32 + 560 + + rw + + + + 37 + Process period9 definition + UDINT + 32 + 592 + + rw + + + + 39 + Process period9 data + DINT + 32 + 624 + + rw + + + + 41 + Process period10 definition + UDINT + 32 + 656 + + rw + + + + 43 + Process period10 data + DINT + 32 + 688 + + rw + + + + 45 + Process period11 definition + UDINT + 32 + 720 + + rw + + + + 47 + Process period11 data + DINT + 32 + 752 + + rw + + + + 49 + Process period12 definition + UDINT + 32 + 784 + + rw + + + + 51 + Process period12 data + DINT + 32 + 816 + + rw + + + + 53 + Process period13 definition + UDINT + 32 + 848 + + rw + + + + 55 + Process period13 data + DINT + 32 + 880 + + rw + + + + 57 + Process period14 definition + UDINT + 32 + 912 + + rw + + + + 59 + Process period14 data + DINT + 32 + 944 + + rw + + + + 61 + Process period15 definition + UDINT + 32 + 976 + + rw + + + + 63 + Process period15 data + DINT + 32 + 1008 + + rw + + + + + DT201D + 320 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Comm Set VDI + UINT + 16 + 16 + + rw + R + + + + 5 + Comm Set DO + UINT + 16 + 80 + + rw + R + + + + 16 + Internal ServoOn + UINT + 16 + 256 + + rw + R + + + + 19 + Servo Status + UINT + 16 + 304 + + rw + T + + + + + DT607D + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Min position limit + DINT + 32 + 16 + + rw + R + + + + 2 + Max position limit + DINT + 32 + 48 + + rw + R + + + + + DT6091 + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Motor revolutions + UDINT + 32 + 16 + + rw + R + + + + 2 + Shaft revolutions + UDINT + 32 + 48 + + rw + R + + + + + DT6092 + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Feed + UDINT + 32 + 16 + + rw + R + + + + 2 + Shaft revolutions + UDINT + 32 + 48 + + rw + R + + + + + DT6099 + 80 + + 0 + Number of entries + USINT + 8 + 0 + + ro + + + + 1 + Speed during search for switch + UDINT + 32 + 16 + + rw + R + + + + 2 + Speed during search for zero + UDINT + 32 + 48 + + rw + R + + + + + DT60FE + 80 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Physical outputs + UDINT + 32 + 16 + + rw + R + + + + 2 + Bit Mask + UDINT + 32 + 48 + + rw + R + + + + + DT60E3 + 256 + + 0 + SubIndex 000 + USINT + 8 + 0 + + ro + + + + 1 + Support homing method 1 + UINT + 16 + 16 + + ro + + + + 2 + Support homing method 2 + UINT + 16 + 32 + + ro + + + + 3 + Support homing method 3 + UINT + 16 + 48 + + ro + + + + 4 + Support homing method 4 + UINT + 16 + 64 + + ro + + + + 5 + Support homing method 5 + UINT + 16 + 80 + + ro + + + + 6 + Support homing method 6 + UINT + 16 + 96 + + ro + + + + 7 + Support homing method 7 + UINT + 16 + 112 + + ro + + + + 8 + Support homing method 8 + UINT + 16 + 128 + + ro + + + + 9 + Support homing method 9 + UINT + 16 + 144 + + ro + + + + 10 + Support homing method 10 + UINT + 16 + 160 + + ro + + + + 11 + Support homing method 11 + UINT + 16 + 176 + + ro + + + + 12 + Support homing method 12 + UINT + 16 + 192 + + ro + + + + 13 + Support homing method 13 + UINT + 16 + 208 + + ro + + + + 14 + Support homing method 14 + UINT + 16 + 224 + + ro + + + + 15 + Support homing method 15 + UINT + 16 + 240 + + ro + + + + + + + #x1000 + Device type + UDINT + 32 + + #x00020192 + + + ro + o + + + + #x1001 + Error Register + USINT + 8 + + 00 + + + ro + o + + + + #x1008 + Device name + STRING(10) + 80 + + SV660-ECAT + + + ro + + + + #x1009 + Hardware version + STRING(4) + 32 + + V001 + + + ro + + + + #x100a + Software version + STRING(4) + 32 + + V001 + + + ro + o + + + + #x1c00 + Sync manager type + DT1C00 + 48 + + + SubIndex 000 + + 04 + + + + SubIndex 001 + + 01 + + + + SubIndex 002 + + 02 + + + + SubIndex 003 + + 03 + + + + SubIndex 004 + + 04 + + + + + ro + o + + + + #x1018 + Identity + DT1018 + 144 + + + SubIndex 000 + + 04 + + + + Vendor ID + + #x00100000 + + + + Product Code + + #x000C010D + + + + Revision + + #x00010001 + + + + Serial number + + 00000000 + + + + + ro + o + + + + #x1600 + Outputs + DT1600 + 656 + + + SubIndex 000 + + 00 + 20 + #x03 + + + + 1st Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60400010 + + + + 2nd Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x607A0020 + + + + 3rd Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60B80010 + + + + 4th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 5th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 6th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 7th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 8th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 9th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 10th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 11th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 12th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 13th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 14th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 15th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 16th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 17th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 18th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 19th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 20th Output Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + rw + + + + #x1701 + CSP Outputs + DT1701 + 656 + + + SubIndex 000 + + #x03 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x60600008 + + + + 3rd Output Object to be mapped + + #x607A0020 + + + + + ro + + + + #x1702 + PP Outputs + DT1702 + 656 + + + SubIndex 000 + + #x07 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x60600008 + + + + 3rd Output Object to be mapped + + #x607A0020 + + + + 4th Output Object to be mapped + + #x60810020 + + + + 5th Output Object to be mapped + + #x60830020 + + + + 6th Output Object to be mapped + + #x60840020 + + + + 7th Output Object to be mapped + + #x60B80010 + + + + + ro + + + + #x1703 + PV Outputs + DT1703 + 656 + + + SubIndex 000 + + #x05 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x60600008 + + + + 3rd Output Object to be mapped + + #x60FF0020 + + + + 4th Output Object to be mapped + + #x60830020 + + + + 5th Output Object to be mapped + + #x60840020 + + + + + ro + + + + #x1704 + CSP+TouchProbe+DO Outputs + DT1704 + 656 + + + SubIndex 000 + + #x06 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x60600008 + + + + 3rd Output Object to be mapped + + #x607A0020 + + + + 4th Output Object to be mapped + + #x60B80010 + + + + 5th Output Object to be mapped + + #x60FE0120 + + + + 6th Output Object to be mapped + + #x60FE0220 + + + + + ro + + + + #x1705 + HOME Outputs + DT1705 + 656 + + + SubIndex 000 + + #x06 + + + + 1st Output Object to be mapped + + #x60400010 + + + + 2nd Output Object to be mapped + + #x60600008 + + + + 3rd Output Object to be mapped + + #x60980008 + + + + 4th Output Object to be mapped + + #x60990120 + + + + 5th Output Object to be mapped + + #x60990220 + + + + 6th Output Object to be mapped + + #x609A0020 + + + + + ro + + + + #x1A00 + Inputs + DT1A00 + 656 + + + SubIndex 000 + + 00 + 10 + #x07 + + + + 1st Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60410010 + + + + 2nd Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60640020 + + + + 3rd Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60B90010 + + + + 4th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60BA0020 + + + + 5th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60BC0020 + + + + 6th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x603F0010 + + + + 7th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x60FD0020 + + + + 8th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 9th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 10th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 11th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 12th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 13th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 14th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 15th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 16th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 17th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 18th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 19th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + 20th Input Object to be mapped + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + rw + + + + #x1B01 + CSP Inputs + DT1B01 + 656 + + + SubIndex 000 + + #x05 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60610008 + + + + 4th Input Object to be mapped + + #x60640020 + + + + 5th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B02 + PP Inputs + DT1B02 + 656 + + + SubIndex 000 + + #x08 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60610008 + + + + 4th Input Object to be mapped + + #x60640020 + + + + 5th Input Object to be mapped + + #x60B90010 + + + + 6th Input Object to be mapped + + #x60BA0020 + + + + 7th Input Object to be mapped + + #x60BC0020 + + + + 8th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B03 + PV Inputs + DT1B03 + 656 + + + SubIndex 000 + + #x06 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60610008 + + + + 4th Input Object to be mapped + + #x60640020 + + + + 5th Input Object to be mapped + + #x606C0020 + + + + 6th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1B04 + CSP+TouchProbe+DI Inputs + DT1B04 + 656 + + + SubIndex 000 + + #x09 + + + + 1st Input Object to be mapped + + #x603F0010 + + + + 2nd Input Object to be mapped + + #x60410010 + + + + 3rd Input Object to be mapped + + #x60610008 + + + + 4th Input Object to be mapped + + #x60640020 + + + + 5th Input Object to be mapped + + #x606C0020 + + + + 6th Input Object to be mapped + + #x60B90010 + + + + 7th Input Object to be mapped + + #x60BA0020 + + + + 8th Input Object to be mapped + + #x60BC0020 + + + + 9th Input Object to be mapped + + #x60FD0020 + + + + + ro + + + + #x1c32 + SM output parameter + DT1C32 + 488 + + + SubIndex 000 + + 20 + + + + Sync mode + + 0200 + + + + Cycle time + + 00000000 + + + + Sync modes supported + + 0004 + + + + Minimum cycle time + + 00000000 + + + + Calc and copy time + + #x0003d090 + + + + Get Cycle Time + + 0000 + + + + Delay Time + + 00000000 + + + + Sync0 Cycle Time + + 00000000 + + + + SM-Event Missed + + 0000 + + + + Cycle Time Too Small + + 0000 + + + + Sync Error + + 00 + + + + + ro + o + + + + #x1c33 + SM input parameter + DT1C33 + 488 + + + SubIndex 000 + + 20 + + + + Sync mode + + 0002 + + + + Cycle time + + 00000000 + + + + Sync modes supported + + 4 + + + + Minimum cycle time + + 00000000 + + + + Calc and copy time + + 00000000 + + + + Get Cycle Time + + 0000 + + + + Delay Time + + 00000000 + + + + Sync0 Cycle Time + + 00000000 + + + + SM-Event Missed + + 0000 + + + + Cycle Time Too Small + + 0000 + + + + Sync Error + + 00 + + + + + ro + o + + + + #x1c12 + RxPDO assign + DT1C12 + 32 + + + SubIndex 000 + + 00 + + + + SubIndex 001 + + 0000 + + + + + ro + + + + #x1c13 + TxPDO assign + DT1C13 + 32 + + + SubIndex 000 + + 00 + + + + SubIndex 001 + + 0000 + + + + + ro + + + + #x2000 + Servo Motor Parameters + 伺服电机参数 + DT2000 + 80 + + + SubIndex 000 + + 3 + + + + Motor SN + + 0 + 65535 + 14101 + + + + Customized firmware version + + 0 + 65535 + 0 + + + + + Rated current + + 0 + 6554 + 40 + + + + + Maximum speed + + 0 + 1200 + 1200 + + + + + Stator resistance + + 0 + 65535 + 500 + + + + + Phase A stator inductance + + 0 + 65535 + 2000 + + + + + Phase B stator inductance + + 0 + 65535 + 2000 + + + + + ro + + + + #x2001 + Servo Drive Parameters + 伺服驱动器参数 + DT2001 + 736 + + + SubIndex 000 + + 45 + + + + MCU firmware Version + + 0 + 65535 + 0 + + + + Drive serial number + + 0 + 65535 + 0 + + + + Drive voltage class + + 0 + 65535 + 240 + + + + Given peak current + + 0 + 120 + 21 + + + + Drive maximum output current + + 0 + 120 + 56 + + + + Locking current percentage + + 1 + 100 + 100 + + + + Delay time of Locking current + + 1 + 65535 + 10 + + + + Upper temperature threshold + + 0 + 150 + 90 + + + + DC bus overvoltage protective point + + 0 + 1200 + 600 + + + + DC bus undervoltage protective point + + 0 + 1200 + 150 + + + + Current compensation filtering + + 0 + 65535 + 5 + + + + Current compensation Enable + + 0 + 1 + 1 + + + + + A-axis proportional gain + + 0 + 65535 + 1000 + + + + + A-axis integral compensation factor + + 0 + 65535 + 100 + + + + + B-axis proportional gain + + 0 + 65535 + 1000 + + + + + B-axis integral compensation factor + + 0 + 65535 + 100 + + + + + ro + + + + #x2002 + Basic control + 基本控制参数 + DT2002 + 688 + + + SubIndex 000 + + 36 + + + + Control mode selection + + 0 + 9 + 9 + + + + Rotating direction + + 0 + 1 + 0 + + + + Stop mode at limit switch signal + + 0 + 7 + 1 + + + + LED warning display selection + + 0 + 1 + 0 + + + + User password + + 0 + 65535 + 0 + + + + Parameter initialization + + 0 + 2 + 0 + + + + Default keypad display + + 0 + 99 + 50 + + + + Panel data refresh rate + + 0 + 20 + 0 + + + + OEM password + + 0 + 65535 + 0 + + + + + ro + + + + #x2003 + Input Terminal Parameters + 端子输入参数 + DT2003 + 1040 + + + SubIndex 000 + + 64 + + + + DI1 function selection + + 0 + 40 + 14 + + + + DI1 logic selection + + 0 + 1 + 0 + + + + DI2 function selection + + 0 + 40 + 15 + + + + DI2 logic selection + + 0 + 1 + 0 + + + + DI3 function selection + + 0 + 40 + 0 + + + + DI3 logic selection + + 0 + 1 + 0 + + + + DI4 function selection + + 0 + 40 + 38 + + + + DI4 logic selection + + 0 + 1 + 0 + + + + DI1 filtertime constant + + 0 + 50000 + 50 + + + + DI2 filtertime constant + + 0 + 50000 + 50 + + + + DI3 filtertime constant + + 0 + 50000 + 50 + + + + DI4 filtertime constant + + 0 + 50000 + 50 + + + + + ro + + + + #x2004 + Output terminal Parameters + 端子输出参数 + DT2004 + 400 + + + SubIndex 000 + + 24 + + + + DO1 Function Selection + + 0 + 32 + 1 + + + + DO1 Logic Level Selection + + 0 + 1 + 0 + + + + DO2 function selection + + 0 + 32 + 11 + + + + DO2 Logic Level Selection + + 0 + 1 + 0 + + + + DO Source Selection + + 0 + 3 + 0 + + + + ECAT DO Offline Logic + + 0 + 3 + 0 + + + + + ro + + + + #x2005 + Position Control Parameters + 位置控制参数组 + DT2005 + 1152 + + + SubIndex 000 + + 71 + + + + Time constant of first-order low-pass filter + + 0 + 65535 + 0 + + + + Time constant of moving average filter 1 + + 0 + 1280 + 0 + + + + + Motor step resolution + + 0 + 51200 + 50000 + + + + Time of home searching + + 0 + 65535 + 10000 + + + + + Home selection + + 0 + 3 + 0 + + + + Time unit of home searching + + 0 + 2 + 2 + + + + Time constant of moving average filter 2 + + 0 + 10000 + 0 + + + + + ro + + + + #x2006 + Speed control + 速度控制 + DT2006 + 336 + + + SubIndex 000 + + 20 + + + + Speed threshold of motor rotation signal + + 0 + 1000 + 20 + + + + Speed threshold of speed-consistent signal + + 0 + 100 + 10 + + + + Speed threshold of speed-arrive signal + + 20 + 10000 + 1000 + + + + Speed threshold of speed-zero signal + + 1 + 10000 + 10 + + + + + ro + + + + #x200A + Error and Protection Parameter + 故障与保护参数 + DT200A + 1184 + + + SubIndex 000 + + 73 + + + + Absolute position limit set + + 0 + 2 + 0 + + + + Local following error window + + 0 + 4294967295 + 27486951 + + + + Touch Probe 1 filter time constant + + 0 + 630 + 200 + + + + Touch Probe 2 filter time constant + + 0 + 630 + 200 + + + + Speed DO Filter time constant + + 0 + 5000 + 50 + + + + Over Travel Compensation + + 0 + 1 + 0 + + + + Fault reset delay time + + 1 + 60000 + 10000 + + + + The 2nd over speed threshold + + 0 + 20000 + 0 + + + + Maximum ramp stop time + + 0 + 65535 + 10000 + + + + + ro + + + + #x200B + Display Parameters + 显示参数 + DT200B + 1488 + + + Number of Entries + + 92 + + + + Actual motor rotational speed + + 0 + + + + Dip-switch value + + 0 + + + + Monitored DI states + + 0 + + + + Monitored DO states + + 0 + + + + Absolute position counter + + 0 + + + + Total power-on time + + 0 + + + + Phase current valid value + + 0 + + + + Bus voltage + + 0 + + + + Module temperature + + 0 + + + + Displayed fault record + + 0 + 9 + 0 + + + + Fault code + + 0 + + + + Time stamp upon displayed fault + + 0 + + + + Current rotational speed upon displayed fault + + 0 + + + + Current U upon displayed fault + + 0 + + + + Current V upon displayed fault + + 0 + + + + Bus voltage upon displayed fault + + 0 + + + + Input terminal state upon displayed fault + + 0 + + + + Output terminal state upon displayed fault + + 0 + + + + Inner error code + + 0 + + + + Inner error code upon displayed fault + + 0 + + + + Control bus voltage + + 0 + + + + Not ready reason + + 0 + + + + Group of unusual function code + + 0 + + + + Offset of unusual function code + + 0 + + + + + ro + + + + #x200D + Auxiliary Function Parameters + 辅助功能参数 + DT200D + 336 + + + Number of Entries + + 20 + + + + Software reset + + 0 + 1 + 0 + + + + Fault reset + + 0 + 1 + 0 + + + + Emergency stop + + 0 + 1 + 0 + + + + UV phase current auto-tuning + + 0 + 1 + 0 + + + + Forced DI/DO setting + + 0 + 4 + 0 + + + + Forced DI level + + 0 + 31 + 0 + + + + Forced DO setting + + 0 + 7 + 0 + + + + + ro + + + + #x200E + Communication parameters + 通信参数 + DT200E + 1568 + + + Number of Entries + + 97 + + + + Node address + + 1 + 127 + 1 + + + + Update function code values written via communication to EEPROM + + 0 + 3 + 3 + + + + Alias source + + 0 + 1 + 1 + + + + station auto inc address + + 0 + 65535 + 0 + + + + station alias + + 0 + 65535 + 0 + + + + Sync lost window + + 1 + 20 + 8 + + + + Sync lost counter + + 0 + 65535 + 0 + + + + Port 0 invalid frame counter + + 0 + 65535 + 0 + + + + Port 1 invalid frame counter + + 0 + 65535 + 0 + + + + Port 0/1 transfer error counter + + 0 + 65535 + 0 + + + + process unit and PDI error counter + + 0 + 65535 + 0 + + + + Port 0/1 lost counter + + 0 + 65535 + 0 + + + + Sync mode set + + 0 + 2 + 1 + + + + Sync error window + + 100 + 4000 + 3000 + + + + EtherCAT network state and link state + + 0 + 65535 + 0 + + + + CSP postion increment over counter + + 1 + 7 + 3 + + + + ALCode + + 0 + 65535 + 0 + + + + Enhanced link detection enable + + 0 + 1 + 0 + + + + Reset EtherCAT xml file + + 0 + 1 + 0 + + + + EtherCAT PHY version number + + 0 + 65535 + 0 + + + + EtherCAT xml file version number + + 0 + 65535 + 0 + + + + + ro + + + + #x2017 + Virtual DIDO + 虚拟DIDO + DT2017 + 1520 + + + SubIndex 000 + + 94 + + + + VDI1 function selection + + 0 + 55 + 0 + + + + VDI1 logic selection + + 0 + 1 + 0 + + + + VDI2 function selection + + 0 + 55 + 0 + + + + VDI2 logic selection + + 0 + 1 + 0 + + + + VDI3 function selection + + 0 + 55 + 0 + + + + VDI3 logic selection + + 0 + 1 + 0 + + + + VDI4 function selection + + 0 + 55 + 0 + + + + VDI4 logic selection + + 0 + 1 + 0 + + + + VDI5 function selection + + 0 + 55 + 0 + + + + VDI5 logic selection + + 0 + 1 + 0 + + + + VDI6 function selection + + 0 + 55 + 0 + + + + VDI6 logic selection + + 0 + 1 + 0 + + + + VDI7 function selection + + 0 + 55 + 0 + + + + VDI7 logic selection + + 0 + 1 + 0 + + + + VDI8 function selection + + 0 + 55 + 0 + + + + VDI8 logic selection + + 0 + 1 + 0 + + + + VDI9 function selection + + 0 + 55 + 0 + + + + VDI9 logic selection + + 0 + 1 + 0 + + + + VDI10 function selection + + 0 + 55 + 0 + + + + VDI10 logic selection + + 0 + 1 + 0 + + + + VDI11 function selection + + 0 + 55 + 0 + + + + VDI11 logic selection + + 0 + 1 + 0 + + + + VDI12 function selection + + 0 + 55 + 0 + + + + VDI12 logic selection + + 0 + 1 + 0 + + + + VDI13 function selection + + 0 + 55 + 0 + + + + VDI13 logic selection + + 0 + 1 + 0 + + + + VDI14 function selection + + 0 + 55 + 0 + + + + VDI14 logic selection + + 0 + 1 + 0 + + + + VDI15 function selection + + 0 + 55 + 0 + + + + VDI15 logic selection + + 0 + 1 + 0 + + + + VDI16 function selection + + 0 + 55 + 0 + + + + VDI16 logic selection + + 0 + 1 + 0 + + + + Comm Set VDO + + 0 + 65535 + 0 + + + + VDO1 function selection + + 0 + 32 + 0 + + + + VDO1 logic selection + + 0 + 1 + 0 + + + + VDO2 function selection + + 0 + 32 + 0 + + + + VDO2 logic selection + + 0 + 1 + 0 + + + + VDO3 function selection + + 0 + 32 + 0 + + + + VDO3 logic selection + + 0 + 1 + 0 + + + + VDO4 function selection + + 0 + 32 + 0 + + + + VDO4 logic selection + + 0 + 1 + 0 + + + + VDO5 function selection + + 0 + 32 + 0 + + + + VDO5 logic selection + + 0 + 1 + 0 + + + + VDO6 function selection + + 0 + 32 + 0 + + + + VDO6 logic selection + + 0 + 1 + 0 + + + + VDO7 function selection + + 0 + 32 + 0 + + + + VDO7 logic selection + + 0 + 1 + 0 + + + + VDO8 function selection + + 0 + 32 + 0 + + + + VDO8 logic selection + + 0 + 1 + 0 + + + + VDO9 function selection + + 0 + 32 + 0 + + + + VDO9 logic selection + + 0 + 1 + 0 + + + + VDO10 function selection + + 0 + 32 + 0 + + + + VDO10 logic selection + + 0 + 1 + 0 + + + + VDO11 function selection + + 0 + 32 + 0 + + + + VDO11 logic selection + + 0 + 1 + 0 + + + + VDO12 function selection + + 0 + 32 + 0 + + + + VDO12 logic selection + + 0 + 1 + 0 + + + + VDO13 function selection + + 0 + 32 + 0 + + + + VDO13 logic selection + + 0 + 1 + 0 + + + + VDO14 function selection + + 0 + 32 + 0 + + + + VDO14 logic selection + + 0 + 1 + 0 + + + + VDO15 function selection + + 0 + 32 + 0 + + + + VDO15 logic selection + + 0 + 1 + 0 + + + + VDO16 function selection + + 0 + 32 + 0 + + + + VDO16 logic selection + + 0 + 1 + 0 + + + + VDI Enable + + 0 + 1 + 0 + + + + VDI Default after power-on + + 0 + 65535 + 0 + + + + VDO Enable + + 0 + 1 + 0 + + + + VDO Default after power-on + + 0 + 65535 + 0 + + + + + ro + + + + #x2018 + PR Parameter1 + PR参数1 + DT2018 + 1296 + + + SubIndex 000 + + 80 + + + + Command trigger + + 0 + 1000 + 0 + + + + Event-rising-edge trigger process period + + 0 + 65535 + 65535 + + + + ACC-DEC-Time of Process period halt + + 0 + 7 + 0 + + + + Forward soft limit + + -2147483648 + 2147483647 + 2147483647 + + + + Reverse soft limit + + -2147483648 + 2147483647 + -2147483648 + + + + Process period number + + 0 + 65535 + 0 + + + + PR Command State + + 0 + 65535 + 0 + + + + PR Command Update + + 0 + 1 + 0 + + + + Target speed + + 1 + 60000 + 500 + + + + Target speed1 + + 1 + 60000 + 2000 + + + + Target speed2 + + 1 + 60000 + 5000 + + + + Target speed3 + + 1 + 60000 + 10000 + + + + Target speed4 + + 1 + 60000 + 15000 + + + + Target speed5 + + 1 + 60000 + 20000 + + + + Target speed6 + + 1 + 60000 + 25000 + + + + Target speed7 + + 1 + 60000 + 30000 + + + + ACC-DEC Time + + 0 + 65535 + 50 + + + + ACC-DEC Time1 + + 0 + 65535 + 200 + + + + ACC-DEC Time2 + + 0 + 65535 + 500 + + + + ACC-DEC Time3 + + 0 + 65535 + 1000 + + + + ACC-DEC Time4 + + 0 + 65535 + 1500 + + + + ACC-DEC Time5 + + 0 + 65535 + 2000 + + + + ACC-DEC Time6 + + 0 + 65535 + 2500 + + + + ACC-DEC Time7 + + 0 + 65535 + 3000 + + + + Delay Time + + 0 + 65535 + 0 + + + + Delay Time1 + + 0 + 65535 + 50 + + + + Delay Time2 + + 0 + 65535 + 200 + + + + Delay Time3 + + 0 + 65535 + 500 + + + + Delay Time4 + + 0 + 65535 + 1000 + + + + Delay Time5 + + 0 + 65535 + 1500 + + + + Delay Time6 + + 0 + 65535 + 2000 + + + + Delay Time7 + + 0 + 65535 + 3000 + + + + Homing mode + + 17 + 35 + 17 + + + + High-speed of homing + + 0 + 3000 + 100 + + + + Low-speed of homing + + 0 + 1000 + 10 + + + + ACC-DEC time of homing + + 0 + 1000 + 1000 + + + + limit time of homing + + 0 + 65535 + 10000 + + + + Homing offset + + -2147483648 + 2147483647 + 0 + + + + Relative/Absolute homing + + 0 + 65535 + 0 + + + + + ro + + + + #x2019 + PR Parameter2 + PR参数2 + DT2019 + 1040 + + + SubIndex 000 + + 63 + + + + Homing definition + + 0 + 4294967295 + 0 + + + + Homing data + + -2147483648 + 2147483647 + 0 + + + + Process period1 definition + + 0 + 4294967295 + 0 + + + + Process period1 data + + -2147483648 + 2147483647 + 0 + + + + Process period2 definition + + 0 + 4294967295 + 0 + + + + Process period2 data + + -2147483648 + 2147483647 + 0 + + + + Process period3 definition + + 0 + 4294967295 + 0 + + + + Process period3 data + + -2147483648 + 2147483647 + 0 + + + + Process period4 definition + + 0 + 4294967295 + 0 + + + + Process period4 data + + -2147483648 + 2147483647 + 0 + + + + Process period5 definition + + 0 + 4294967295 + 0 + + + + Process period5 data + + -2147483648 + 2147483647 + 0 + + + + Process period6 definition + + 0 + 4294967295 + 0 + + + + Process period6 data + + -2147483648 + 2147483647 + 0 + + + + Process period7 definition + + 0 + 4294967295 + 0 + + + + Process period7 data + + -2147483648 + 2147483647 + 0 + + + + Process period8 definition + + 0 + 4294967295 + 0 + + + + Process period8 data + + -2147483648 + 2147483647 + 0 + + + + Process period9 definition + + 0 + 4294967295 + 0 + + + + Process period9 data + + -2147483648 + 2147483647 + 0 + + + + Process period10 definition + + 0 + 4294967295 + 0 + + + + Process period10 data + + -2147483648 + 2147483647 + 0 + + + + Process period11 definition + + 0 + 4294967295 + 0 + + + + Process period11 data + + -2147483648 + 2147483647 + 0 + + + + Process period12 definition + + 0 + 4294967295 + 0 + + + + Process period12 data + + -2147483648 + 2147483647 + 0 + + + + Process period13 definition + + 0 + 4294967295 + 0 + + + + Process period13 data + + -2147483648 + 2147483647 + 0 + + + + Process period14 definition + + 0 + 4294967295 + 0 + + + + Process period14 data + + -2147483648 + 2147483647 + 0 + + + + Process period15 definition + + 0 + 4294967295 + 0 + + + + Process period15 data + + -2147483648 + 2147483647 + 0 + + + + + ro + + + + #x201D + Comm Set Servo Variable + 通讯给定相关变量 + DT201D + 320 + + + SubIndex 000 + + 19 + + + + Comm Set VDI + + 0 + 65535 + 0 + + + + Comm Set DO + + 0 + 65535 + 0 + + + + Internal ServoOn + + 0 + 1 + 0 + + + + Servo Status + + 0 + 65535 + 0 + + + + + ro + + + + #x203F + Manufacturor Error code + 伺服故障码 + UDINT + 32 + + #x00000000 + #xFFFFFFFF + #x00000000 + + + ro + T + + + + #x603F + Error code + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + ro + T + + + + #x6040 + Control word + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + rw + R + + + + #x6041 + Status word + UINT + 16 + + #x0000 + #xFFFF + #x0000 + + + ro + T + + + + #x605A + Quick stop option code + INT + 16 + + #x0000 + #x0006 + #x0002 + + + rw + + + + #x605C + Disable operation option Code + INT + 16 + + #x0000 + #x0001 + #x0000 + + + rw + + + + #x605D + Halt option Code + INT + 16 + + #x0001 + #x0002 + #x0001 + + + rw + + + + #x605E + Fault Reaction option Code + INT + 16 + + #x0000 + #x0002 + #x0002 + + + rw + + + + #x6060 + Modes of operation + SINT + 8 + + 0 + 8 + 0 + + + rw + R + + + + #x6061 + Modes of operation display + SINT + 8 + + 0 + 8 + 0 + + + ro + T + + + + #x6062 + Position demand value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6063 + Position actual value* + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6064 + Position actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x6065 + Following error window + UDINT + 32 + + #x0 + #xFFFFFFFF + #x1A36AE7 + + + rw + R + + + + #x6066 + Following error time out + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x6067 + Position window + UDINT + 32 + + #x0 + #xFFFFFFFF + #x16F0 + + + rw + R + + + + #x6068 + Position window time + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x606C + Velocity actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + 0 + + + ro + T + + + + #x606D + Velocity window + UINT + 16 + + #x0000 + #xFFFF + #xA + + + rw + R + + + + #x606E + Velocity window time + UINT + 16 + + #x0000 + #xFFFF + #x0 + + + rw + + + + #x606F + Velocity threshold + UINT + 16 + + #x0000 + #xFFFF + #xA + + + rw + R + + + + #x6070 + Velocity threshold time + UINT + 16 + + #x0000 + #xFFFF + #x0 + + + rw + + + + + #x607A + Target position + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x607C + Home offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x607D + Software position limit + DT607D + 80 + + + SubIndex 000 + + #x02 + + + + Min position limit + + #x80000000 + #x7FFFFFFF + #x80000000 + + + + Max position limit + + #x80000000 + #x7FFFFFFF + #x7FFFFFFF + + + + + ro + + + + #x607E + Polarity + USINT + 8 + + #x0 + #xFF + #x0 + + + rw + R + + + + #x607F + Max profile velocity + UDINT + 32 + + #x0 + #xFFFFFFFF + #x000F4240 + + + rw + R + + + + #x6081 + Profile velocity + UDINT + 32 + + #x0 + #xFFFFFFFF + #x0007A120 + + + rw + R + + + + #x6083 + Profile acceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x004C4B40 + + + rw + R + + + + #x6084 + Profile deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x004C4B40 + + + rw + R + + + + #x6085 + Quick stop deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x7FFFFFFF + + + rw + R + + + + #x6086 + Motion profile type + INT + 16 + + #x8000 + #x7FFF + #x0 + + + rw + R + + + + + #x6092 + Feed Constant + DT6092 + 80 + + + SubIndex 000 + + #x02 + + + + Feed + + #xC8 + #xC800 + #xC350 + + + + Shaft revolutions + + #x1 + #x1 + #x1 + + + + + ro + + + + #x6098 + Homing method + SINT + 8 + + #x11 + #x23 + #x11 + + + rw + R + + + + #x6099 + Homing speeds + DT6099 + 80 + + + Number of entries + + #x02 + + + + Speed during search for switch + + 0 + #xFFFFFFFF + #x000186A0 + + + + Speed during search for zero + + 0 + #xFFFFFFFF + #x0000C350 + + + + + ro + + + + #x609A + Homing acceleration + UDINT + 32 + + 0 + #xFFFFFFFF + #x000F4240 + + + rw + R + + + + #x60B0 + Position offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x60B1 + Velocity offset + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + + #x60B8 + Touch probe function + UINT + 16 + + #x0 + #xFFFF + #x0 + + + rw + R + + + + #x60B9 + Touch Probe Status + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60BA + Touch Probe pos 1 pos value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BB + Touch Probe pos 1 neg value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BC + Touch Probe pos 2 pos value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60BD + Touch Probe pos 2 neg value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60C5 + Max Acceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x7FFFFFFF + + + rw + R + + + + #x60C6 + Max Deceleration + UDINT + 32 + + #x0 + #xFFFFFFFF + #x7FFFFFFF + + + rw + R + + + + #x60D5 + Touch Probe 1 positive egde counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D6 + Touch Probe 1 negative egde counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D7 + Touch Probe 2 positive egde counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + #x60D8 + Touch Probe 2 negative egde counter + UINT + 16 + + #x0 + #xFFFF + #x0 + + + ro + T + + + + + #x60E3 + Support homing method + DT60E3 + 256 + + + SubIndex 000 + + #x0 + #x0F + 15 + + + + Support homing method 1 + + #x0011 + + + + Support homing method 2 + + #x0012 + + + + Support homing method 3 + + #x0013 + + + + Support homing method 4 + + #x0014 + + + + Support homing method 5 + + #x0015 + + + + Support homing method 6 + + #x0016 + + + + Support homing method 7 + + #x0017 + + + + Support homing method 8 + + #x0018 + + + + Support homing method 9 + + #x0019 + + + + Support homing method 10 + + #x001A + + + + Support homing method 11 + + #x001B + + + + Support homing method 12 + + #x001C + + + + Support homing method 13 + + #x001D + + + + Support homing method 14 + + #x001E + + + + Support homing method 15 + + #x0023 + + + + + ro + + + + #x60E6 + Actual Position Calucation Method + SINT + 8 + + 0 + 1 + 1 + + + rw + + + + #x60F4 + Following error actual value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60FC + Position demand internal value + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + ro + T + + + + #x60FD + Digital inputs + UDINT + 32 + + #x0 + #xFFFFFFFF + #x0 + + + ro + T + + + + #x60FE + Digital outputs + DT60FE + 80 + + + SubIndex 000 + + #x02 + + + + Physical outputs + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + Bit Mask + + #x00000000 + #xFFFFFFFF + #x00000000 + + + + + ro + + + + #x60FF + Target velocity + DINT + 32 + + #x80000000 + #x7FFFFFFF + #x0 + + + rw + R + + + + #x6502 + Supported drive modes + UDINT + 32 + + #x00000000 + #xFFFFFFFF + #x000000A5 + + + ro + + + + + + Outputs + Inputs + MBoxState + MBoxOut + MBoxIn + Outputs + Inputs + + #x1600 + Outputs + #x1701 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x607A + 0 + 32 + Target position + DINT + + + + #x1701 + CSP Outputs + #x1600 + #x1702 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x607A + 0 + 32 + Target position + DINT + + + + #x1702 + PP Outputs + #x1600 + #x1701 + #x1703 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x6081 + 0 + 32 + Profile velocity + UDINT + + + #x6083 + 0 + 32 + Profile acceleration + UDINT + + + #x6084 + 0 + 32 + Profile deceleration + UDINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + + #x1703 + PV Outputs + #x1600 + #x1701 + #x1702 + #x1704 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x60FF + 0 + 32 + Target velocity + DINT + + + #x6083 + 0 + 32 + Profile acceleration + UDINT + + + #x6084 + 0 + 32 + Profile deceleration + UDINT + + + + #x1704 + CSP+TouchProbe Outputs + #x1600 + #x1701 + #x1702 + #x1703 + #x1705 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x607A + 0 + 32 + Target position + DINT + + + #x60B8 + 0 + 16 + Touch probe function + UINT + + + #x60FE + 1 + 32 + Physical outputs + UDINT + + + #x60FE + 2 + 32 + Bit Mask + UDINT + + + + #x1705 + HOME Outputs + #x1600 + #x1701 + #x1702 + #x1703 + #x1704 + + #x6040 + 0 + 16 + Controlword + UINT + + + #x6060 + 0 + 8 + Modes of operation + SINT + + + #x6098 + 0 + 8 + Homing method + SINT + + + #x6099 + 1 + 32 + Speed during search for switch + UDINT + + + #x6099 + 2 + 32 + Speed during search for zero + UDINT + + + #x609A + 0 + 32 + Homing acceleration + UDINT + + + + #x1A00 + Inputs + #x1B01 + #x1B02 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + + #x1B01 + CSP Inputs + #x1A00 + #x1B02 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B02 + PP Inputs + #x1A00 + #x1B01 + #x1B03 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B03 + PV Inputs + #x1A00 + #x1B01 + #x1B02 + #x1B04 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x606C + 0 + 32 + Velocity actual value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + #x1B04 + CSP+TouchProbe Inputs + #x1A00 + #x1B01 + #x1B02 + #x1B03 + + #x603F + 0 + 16 + Error code + UINT + + + #x6041 + 0 + 16 + Statusword + UINT + + + #x6061 + 0 + 8 + Modes of operation display + SINT + + + #x6064 + 0 + 32 + Position actual value + DINT + + + #x606C + 0 + 32 + Velocity actual value + DINT + + + #x60B9 + 0 + 16 + Touch probe status + UINT + + + #x60BA + 0 + 32 + Touch probe pos1 pos value + DINT + + + #x60BC + 0 + 32 + Touch probe pos2 pos value + DINT + + + #x60FD + 0 + 32 + Digital inputs + UDINT + + + + + + + PS + #x6060 + 0 + 08 + Modes of operation + + + + + + DC + DC-Synchron + #x300 + 0 + 0 + 0 + + + Synchron + FreeRun + #x0 + + + + 2048 + 800C42EEC80000000000 + + 424DF8010000000000003600000028000000100000000E0000000100100000000000C2010000202E0000202E00000000000000000000590A590A5A0A3906390239065906390239023906590639063902590A59065A0E1902190219027A167A125A12F8017A169A163906390639065A12390219023906390239021802DB325D53DB32BE73DB2E1C433C4B9A1E3C4B5D53F80139023906390239021802FB327D5BFB36FF7FBB26390A7D5FDB329E63DB36F8013902390639023902F801DB2EDF777D5B9E675D5339027D5F9E679E675A16190239023906390239021802DB2EBE6FFC3ABE6FFB369A221C439E677D5FFB3618023902390639023902390219065A1A1806590E1902F801F8015A0E190239023902390239063902390219029B225912BB26FC36DB2EDB2A7A1A19027A169A1E39023902390639023902F8011C3F9E671C3FBB267A163C473C479A1E5D4F5D5319023902390639023902F801BB26DF73BB2EB701D801BB2A3C4BBB265D4F3C4F19023902390639023902F801DB2EDE6FBB2EB701D801BB2A3D4BBB265D4F5D4F19023902390639023902F801DB2E7E5F3D4B1C3FDB32DB2E1C43BB263D4B3D4B1902390239063902390239025A0E59069A16DB2EBB265A0A590659065A0A590A39023902390639023902390219021902190218021802190219023902190219023902390239060000 + + + + diff --git a/hw_device_mgr/devices/inovance_std60.py b/hw_device_mgr/devices/inovance_std60.py new file mode 100644 index 00000000..4f553364 --- /dev/null +++ b/hw_device_mgr/devices/inovance_std60.py @@ -0,0 +1,121 @@ +from ..ethercat.device import EtherCATDevice, EtherCATSimDevice +from ..ethercat.config import EtherCATConfig +from ..cia_402.device import CiA402Device, CiA402SimDevice +from ..errors.device import ErrorDevice +from functools import lru_cache +import time + + +class InovanceSTD60Config(EtherCATConfig): + """Inovance STD60 servo drive config.""" + + # Device params non-volatile setting in 200E-02h: + # 0: params not updated + # 1: 2000h series changed from serial or EtherCAT saved + # 2: 6000h series changed from EtherCAT (only) saved + # 3: 2000h and 6000h series changed from EtherCAT (only) saved + + def get_device_params_nv(self): + return self.config.upload("200E-02h") == 3 + + def set_device_params_nv(self, nv=True, dry_run=False): + curr_setting = self.get_device_params_nv() + if curr_setting != nv: + self.logger.info( + f"Setting params {'non' if nv else ''}volatile mode" + ) + self.config.download( + "200E-02h", (0, 3)[nv], force=True, dry_run=dry_run + ) + else: + self.logger.info( + f"Params already {'non' if nv else ''}volatile mode" + ) + + def clear_fault(self): + err_code = self.upload("203Fh") + self.logger.info(f"Resetting device fault; code: {err_code}") + time.sleep(0.5) # This may or may not be needed + self.download("200D-02h", 1) + time.sleep(0.5) # This may or may not be needed + err_code = self.upload("203Fh") + self.logger.info(f" After fault reset, code: {err_code}") + + def soft_reset(self): + self.logger.info("Performing soft reset on drive") + time.sleep(0.5) # This may or may not be needed + self.download("200D-01h", 1) + time.sleep(2.0) # Give the drive time to react + + def reset_error_and_restart(self): + self.logger.info(f"Queueing fault reset and rebooting drive") + self.enqueue_command(self.clear_fault) + self.enqueue_command(self.soft_reset) + + +class InovanceSTD60(EtherCATDevice, CiA402Device, ErrorDevice): + """Inovance STD60 servo drives.""" + + vendor_id = 0x00100000 + product_code = 0x000C011A + xml_description_package = "hw_device_mgr.devices.device_xml" + xml_description_fname = "STD60_EOE_1Axis_06008_NEW_v1_0.xml" + device_error_package = "hw_device_mgr.devices.device_err" + device_error_yaml = "inovance_std60n.yaml" + config_class = InovanceSTD60Config + have_sto = True + + feedback_out_data_types = dict( + home_found="bit", + error_code="uint16", # Override uint32 + ) + feedback_out_overlap = {"error_code"} # Override uint32 + + feedback_out_defaults = dict( + home_found=False, + ) + + @classmethod + @lru_cache + def to_error_code_data_type(cls, value): + # Ignore least significant word, "manufacturer external fault code" + dt = cls.data_type_class.by_shared_name("uint16") + return dt(value >> 16) + + def get_error_code(self): + error_code = self.interface("feedback_in").get("error_code") + return self.to_error_code_data_type(error_code) + + def get_feedback(self): + fb_out = super().get_feedback() + sw = self.interface("feedback_in").get("status_word") + if self.test_sw_bit(sw, "MANUFACTURER_SPECIFIC_3"): # "Home found" + fb_out.update(home_found=True) + return fb_out + + def set_command(self, **kwargs): + cmd_out = super().set_command(**kwargs) + cmd_in = self._interfaces["command_in"] + fb_in = self._interfaces["feedback_in"] + if cmd_in.rising_edge("reset_fault"): + if fb_in.get("error_code") == 0x07310731: + self.config.reset_error_and_restart() + return cmd_out + + +class SimInovanceSTD60(InovanceSTD60, EtherCATSimDevice, CiA402SimDevice): + def set_sim_feedback(self): + # Simulate home_found feedback + sfb = super().set_sim_feedback() + sw, old_sw = sfb.changed("status_word", return_vals=True) + # In MODE_HM, OPERATION_MODE_SPECIFIC_1 is "homing attained" + homing_attained = False + if sfb.get("control_mode_fb") == self.MODE_HM: + homing_attained = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") + # STD60: MANUFACTURER_SPECIFIC_3 (bit 15) is "Home found" + old_home_found = self.test_sw_bit(old_sw, "MANUFACTURER_SPECIFIC_3") + home_found = old_home_found or homing_attained + if home_found: + sw = self.add_status_word_flags(sw, MANUFACTURER_SPECIFIC_3=True) + sfb.update(status_word=sw) + return sfb From d7ae7872801f28d4d1a722f6cf6005e8c2decc8a Mon Sep 17 00:00:00 2001 From: Jason VandeKieft Date: Thu, 22 May 2025 17:37:38 +0000 Subject: [PATCH 087/121] Merged in PP-4678-deprecate-velocity-torque-requests (pull request #10) * PP-4678 - deprecate velocity_request, torque_request, et al. * Merged in zultron/2024-05-21-PP-4678-deprecate-velocity-torque-requests (pull request #11) Approved-by: John Morris Approved-by: Robert Ellenberg --- hw_device_mgr/cached_attr_mgr.py | 1 - hw_device_mgr/cia_402/device.py | 239 +++--------------- .../cia_402/tests/hm_timeout.cases.yaml | 13 + .../cia_402/tests/pp_timeout.cases.yaml | 13 + hw_device_mgr/cia_402/tests/pt.cases.yaml | 230 +++++++++++++++++ hw_device_mgr/cia_402/tests/pv.cases.yaml | 230 +++++++++++++++++ .../tests/read_update_write.cases.yaml | 13 + .../tests/test_device_read_update_write.py | 13 +- .../STD60_EOE_1Axis_06008_NEW_v1_0.xml | 20 +- hw_device_mgr/devices/inovance_std60.py | 2 +- hw_device_mgr/devices/inovance_sv670.py | 2 +- hw_device_mgr/ethercat/command.py | 2 - hw_device_mgr/lcec/command.py | 1 - hw_device_mgr/mgr/mgr.py | 14 +- .../mgr/tests/read_update_write.cases.yaml | 9 + 15 files changed, 574 insertions(+), 228 deletions(-) create mode 100644 hw_device_mgr/cia_402/tests/pt.cases.yaml create mode 100644 hw_device_mgr/cia_402/tests/pv.cases.yaml mode change 100755 => 100644 hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml diff --git a/hw_device_mgr/cached_attr_mgr.py b/hw_device_mgr/cached_attr_mgr.py index 5aa7fe3e..6361e4bb 100644 --- a/hw_device_mgr/cached_attr_mgr.py +++ b/hw_device_mgr/cached_attr_mgr.py @@ -1,5 +1,4 @@ class CachedAttrMixin: - def clear_cached_properties(self, *args): """ Clear `cached_property` and `lru_func` values. diff --git a/hw_device_mgr/cia_402/device.py b/hw_device_mgr/cia_402/device.py index 44a82f48..a92ec50d 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -21,8 +21,6 @@ class CiA402Device(CiA301Device, ErrorDevice): - `home_request`: Command homing operation (HM mode) - `move_request`: Command move operation (PP mode) - `relative_target`: Relative vs Absolute move operation (PP mode) - - `velocity_request`: Command move operation (PV mode) - - `torque_request`: Command move operation (PT mode) Feedback parameters: - `home_success`: Drive completed homing successfully @@ -30,9 +28,7 @@ class CiA402Device(CiA301Device, ErrorDevice): - `move_setpoint_ack`: Drive acknowledges PP-mode `move_request` - `move_success`: Drive reports PP-mode move succeeded - `following_error`: Drive reports following error in various modes - - `velocity_success`: Drive reports PV-mode velocity reached - `velocity_zero`: Drive reports zero speed in PV mode - - `torque_success`: Drive reports PT-mode torque reached """ data_types = CiA301DataType @@ -56,8 +52,8 @@ class CiA402Device(CiA301Device, ErrorDevice): home_timeout = 15 # seconds move_timeout = 15 # seconds - velocity_timeout = 15 # seconds - torque_timeout = 15 #seconds + velocity_timeout = 15 # seconds + torque_timeout = 15 # seconds @classmethod def control_mode_str(cls, mode): @@ -120,9 +116,7 @@ def control_mode_str(cls, mode): move_setpoint_ack="bit", move_success="bit", following_error="bit", - velocity_success="bit", velocity_zero="bit", - torque_success="bit" ) feedback_out_defaults = dict( **feedback_in_defaults, @@ -133,9 +127,7 @@ def control_mode_str(cls, mode): move_setpoint_ack=False, move_success=False, following_error=False, - velocity_success=False, velocity_zero=False, - torque_success=False ) log_status_word_changes = True @@ -211,61 +203,10 @@ def get_feedback_pp(self, sw): def get_feedback_pv(self, sw): # Control mode is PV - if not self.command_in.get("velocity_request"): - self.feedback_out.update( - velocity_success=False - ) - return True, None - if self.feedback_out.get("state") != "OPERATION ENABLED": - reason = "Velocity request while drive not enabled" - self.feedback_out.update( - velocity_success=False, - fault=True, - fault_desc=reason, - ) - return False, reason - - success, reason = False, None - zero_speed = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") - if self.test_sw_bit(sw, "TARGET_REACHED"): - # done bit set - success = True - else: - reason = "velocity not reached" - self.feedback_out.update( - velocity_success=success, - velocity_zero=zero_speed + velocity_zero=self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") ) - return success, reason - - def get_feedback_pt(self, sw): - # Control mode is PT - if not self.command_in.get("torque_request"): - self.feedback_out.update( - torque_success=False - ) - return True, None - if self.feedback_out.get("state") != "OPERATION ENABLED": - reason = "Torque request while drive not enabled" - self.feedback_out.update( - torque_success=False, - fault=True, - fault_desc=reason, - ) - return False, reason - - success, reason = False, None - if self.test_sw_bit(sw, "TARGET_REACHED"): - # done bit set - success = True - else: - reason = "torque not reached" - - self.feedback_out.update( - torque_success=success - ) - return success, reason + return True, None def get_feedback_sto(self): # Process active STO: Raise fault on OPERATION ENABLED command @@ -306,10 +247,6 @@ def goal_reached_timeout(self): return self.home_timeout if self.command_in.get("move_request"): return self.move_timeout - if self.command_in.get("velocity_request"): - return self.velocity_timeout - if self.command_in.get("torque_request"): - return self.torque_timeout return super().goal_reached_timeout def get_feedback(self): @@ -332,21 +269,18 @@ def get_feedback(self): cm = fb_in.get("control_mode_fb") fb_out.update(status_word=sw, control_mode_fb=cm) cm_cmd = self.command_in.get("control_mode") - if cm != cm_cmd: - unexpected_mode = True - if self.MODE_HM == cm: - unexpected_mode = False - elif self.command_in.get("move_request"): - unexpected_mode = (self.MODE_PP != cm) - elif self.command_in.get("velocity_request"): - unexpected_mode = (self.MODE_PV != cm) - elif self.command_in.get("torque_request"): - unexpected_mode = (self.MODE_PT != cm) - if unexpected_mode: - goal_reached = False - cm_str = self.control_mode_str(cm) - cm_cmd_str = self.control_mode_str(cm_cmd) - goal_reasons.append(f"control_mode {cm_str} != {cm_cmd_str}") + if cm != cm_cmd and cm != self.MODE_HM: + goal_reached = False + cm_str = self.control_mode_str(cm) + cm_cmd_str = self.control_mode_str(cm_cmd) + goal_reasons.append(f"control_mode {cm_str} != {cm_cmd_str}") + + # Raise fault if device unexpectedly disabled + state_cmd = self.command_in.get("state") + if state_cmd == "OPERATION ENABLED": + if not self.test_sw_bit(sw, "READY_TO_SWITCH_ON"): + fault = True + fault_desc = "Enabled drive unexpectedly disabled" # Log status word changes if self.log_status_word_changes and fb_out.changed("status_word"): @@ -370,7 +304,6 @@ def get_feedback(self): f"Unknown status word 0x{sw:X}; " f"state {fb_out.get('state')} unchanged" ) - state_cmd = self.command_in.get("state") if self._get_next_transition() >= 0: goal_reached = False sw = fb_in.get("status_word") @@ -386,12 +319,6 @@ def get_feedback(self): ferror = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_2") fb_out.update(following_error=ferror) - # Raise fault if device unexpectedly disabled - if state_cmd == "OPERATION ENABLED": - if not self.test_sw_bit(sw, "READY_TO_SWITCH_ON"): - fault = True - fault_desc = "Enabled drive unexpectedly disabled" - # Calculate 'transition' feedback new_st, old_st = fb_out.changed("state", return_vals=True) if (old_st, new_st) == ("START", "NOT READY TO SWITCH ON"): @@ -411,28 +338,6 @@ def get_feedback(self): if not sto_success: goal_reached = False goal_reasons.append(sto_reason) - # Mode-specific functions - if cm == self.MODE_HM: - # Calculate homing status - hm_success, hm_reason = self.get_feedback_hm(sw) - if not hm_success: - goal_reached = False - goal_reasons.append(hm_reason) - elif cm == self.MODE_PP: - # Calculate move status - pp_success, pp_reason = self.get_feedback_pp(sw) - if not pp_success: - goal_reached = False - goal_reasons.append(pp_reason) - - # Log status word changes - if self.log_status_word_changes and fb_out.changed("status_word"): - self.logger.info(f"status_word: {self.sw_to_str(sw)}") - - # If device not yet operational, don't do any more, incl. log faults, - # etc. - if not fb_out.get("oper"): - return fb_out # Fault reported by drive if self.test_sw_bit(sw, "FAULT"): @@ -441,7 +346,7 @@ def get_feedback(self): if fb_out.get("error_code"): error_code = fb_out.get("error_code") fault_desc += f", code {error_code}" - if (error_desc := fb_out.get("description")): + if error_desc := fb_out.get("description"): fault_desc += f" '{error_desc}'" else: fault_desc += " (no error code)" @@ -460,17 +365,10 @@ def get_feedback(self): goal_reached = False goal_reasons.append(pp_reason) elif cm == self.MODE_PV: - # Calculate velocity status pv_success, pv_reason = self.get_feedback_pv(sw) if not pv_success: goal_reached = False goal_reasons.append(pv_reason) - elif cm == self.MODE_PT: - # Calculate torque status - pt_success, pt_reason = self.get_feedback_pt(sw) - if not pt_success: - goal_reached = False - goal_reasons.append(pt_reason) # If in CiA402 FAULT state, set device fault if state_cmd == "FAULT": @@ -538,8 +436,6 @@ def sw_to_str(cls, sw): home_request=False, move_request=False, relative_target=False, - velocity_request=False, - torque_request=False ) command_in_data_types = dict( state="str", @@ -547,8 +443,6 @@ def sw_to_str(cls, sw): home_request="bit", move_request="bit", relative_target="bit", - velocity_request="bit", - torque_request="bit" ) # ------- Command out ------- @@ -691,40 +585,6 @@ def pp_request_cw_flags(self): OPERATION_MODE_SPECIFIC_3=relative_target, ) - def pv_request_cw_flags(self): - # there are no operation specific flags for PV mode - # this is just here for logging consistency - # - # Check for velocity request - if self.command_in.get("velocity_request"): - if self.command_in.changed("velocity_request"): - self.logger.info("Velocity operation requested") - # Fast track as long as request in effect - self.command_out.update(fasttrack=True) - else: - # Clear request - #sw = self.feedback_in.get("status_word") - #stopped = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") - if self.command_in.changed("velocity_request"): - self.logger.info("velocity request cleared") - return dict() - - def pt_request_cw_flags(self): - # there are no operation specific flags for PT mode - # this is just here for logging consistency - # - # Check for torque request - if self.command_in.get("torque_request"): - if self.command_in.changed("torque_request"): - self.logger.info("Torque operation requested") - # Fast track as long as request in effect - self.command_out.update(fasttrack=True) - else: - # Clear request - if self.command_in.changed("torque_request"): - self.logger.info("torque request cleared") - return dict() - @classmethod @lru_cache def cw_to_str(cls, cw): @@ -758,10 +618,6 @@ def _get_next_control_word(self, cmd_out): cw_flags.update(self.hm_request_cw_flags()) elif next_cm == self.MODE_PP: cw_flags.update(self.pp_request_cw_flags()) - elif next_cm == self.MODE_PV: - cw_flags.update(self.pv_request_cw_flags()) - elif next_cm == self.MODE_PT: - cw_flags.update(self.pt_request_cw_flags()) else: cw_flags.update(OPERATION_MODE_SPECIFIC_1=False) next_cw = self._add_control_word_flags(control_word, **cw_flags) @@ -901,12 +757,6 @@ def _add_control_word_flags(cls, control_word, **flags): def _get_next_control_mode(self, cmd_out): if self.command_in.get("home_request"): next_cm = self.MODE_HM - elif self.command_in.get("move_request"): - next_cm = self.MODE_PP - elif self.command_in.get("velocity_request"): - next_cm = self.MODE_PV - elif self.command_in.get("torque_request"): - next_cm = self.MODE_PT else: # Otherwise, copy control_mode from command_in next_cm = self.command_in.get("control_mode") @@ -934,7 +784,7 @@ class CiA402SimDevice(CiA402Device, CiA301SimDevice, ErrorSimDevice): velocity_cmd="float", velocity_fb="float", torque_cmd="float", - torque_fb="float" + torque_fb="float", ) feedback_in_defaults = dict( position_cmd=0.0, @@ -942,7 +792,7 @@ class CiA402SimDevice(CiA402Device, CiA301SimDevice, ErrorSimDevice): velocity_cmd=0.0, velocity_fb=0.0, torque_cmd=0.0, - torque_fb=0.0 + torque_fb=0.0, ) feedback_out_data_types = dict(**feedback_in_data_types) @@ -959,8 +809,8 @@ class CiA402SimDevice(CiA402Device, CiA301SimDevice, ErrorSimDevice): # diff. btw. pos. cmd + fb to signal target reached position_goal_tolerance = 0.01 - velocity_goal_tolerance = 0.01 # TBD - torque_goal_tolerance = 0.01 # TBD + velocity_goal_tolerance = 0.01 # TBD + torque_goal_tolerance = 0.01 # TBD # ------- Sim feedback ------- @@ -981,44 +831,27 @@ def target_reached(self, sw, cw): if new_setpoint or setpoint_ack: # Pretend we haven't reached new target before it's even set return False - dtg = abs(fb_in.get("position_cmd") - fb_in.get("position_fb")) - return dtg < self.position_goal_tolerance + perr = abs(fb_in.get("position_cmd") - fb_in.get("position_fb")) + return perr < self.position_goal_tolerance elif control_mode == self.MODE_PV: - #zero_speed = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") - #if zero_speed: ?? - dtg = abs(fb_in.get("velocity_cmd") - fb_in.get("velocity_fb")) - return dtg < self.velocity_goal_tolerance + # zero_speed = self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") + # if zero_speed: ?? + verr = abs(fb_in.get("velocity_cmd") - fb_in.get("velocity_fb")) + return verr < self.velocity_goal_tolerance elif control_mode == self.MODE_PT: - dtg = abs(fb_in.get("torque_cmd") - fb_in.get("torque_fb")) - return dtg < self.torque_goal_tolerance + terr = abs(fb_in.get("torque_cmd") - fb_in.get("torque_fb")) + return terr < self.torque_goal_tolerance - def set_sim_feedback_pp(self, cw, sw): + def set_sim_feedback_ppvt(self, cw, sw): # In MODE_PP, cw OPERATION_MODE_SPECIFIC_1 is NEW_SETPOINT cmd, sw # OPERATION_MODE_SPECIFIC_1 is SETPOINT_ACKNOWLEDGE fb if self.test_cw_bit(cw, "OPERATION_MODE_SPECIFIC_1"): + # MODE_PP only: # If cw NEW_SETPOINT is set, then set sw SETPOINT_ACKNOWLEDGE self.logger.info("sim SETPOINT_ACKNOWLEDGE set") return dict(OPERATION_MODE_SPECIFIC_1=True) elif self.target_reached(sw, cw): - # Target reached when target position reached - if not self.test_sw_bit(sw, "TARGET_REACHED"): - self.logger.info("sim TARGET_REACHED set") - return dict(TARGET_REACHED=True) - else: - return dict() - - def set_sim_feedback_pv(self, cw, sw): - if self.target_reached(sw, cw): - # Target reached when target velocity reached - if not self.test_sw_bit(sw, "TARGET_REACHED"): - self.logger.info("sim TARGET_REACHED set") - return dict(TARGET_REACHED=True) - else: - return dict() - - def set_sim_feedback_pt(self, cw, sw): - if self.target_reached(sw, cw): - # Target reached when target torque reached + # Target reached when target torque/velocity/position reached if not self.test_sw_bit(sw, "TARGET_REACHED"): self.logger.info("sim TARGET_REACHED set") return dict(TARGET_REACHED=True) @@ -1074,14 +907,10 @@ def set_sim_feedback(self): pass # Don't update mode-specific flags elif control_mode == self.MODE_HM: sw_flags.update(self.set_sim_feedback_hm(control_word)) - elif control_mode == self.MODE_PP: + elif control_mode in (self.MODE_PP, self.MODE_PV, self.MODE_PT): # Test previous cw because target_reached() looks at fb_in, which is # set after command_in - sw_flags.update(self.set_sim_feedback_pp(cw_prev, sw_prev)) - elif control_mode == self.MODE_PV: - sw_flags.update(self.set_sim_feedback_pv(cw_prev, sw_prev)) - elif control_mode == self.MODE_PT: - sw_flags.update(self.set_sim_feedback_pt(cw_prev, sw_prev)) + sw_flags.update(self.set_sim_feedback_ppvt(cw_prev, sw_prev)) status_word = self.add_status_word_flags(status_word, **sw_flags) diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index 4b34ed8f..d4173af3 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -18,6 +18,10 @@ control_mode_fb: 8 position_cmd: 0.0 position_fb: 0.0 + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 sto: False error_code: 0x00000000 feedback_out: @@ -35,6 +39,11 @@ goal_reached: True goal_reason: Reached move_success: False + velocity_zero: False + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 following_error: False move_setpoint_ack: False position_cmd: 0.0 @@ -65,6 +74,10 @@ control_mode_fb: 6 position_cmd: 0.0 position_fb: 0.0 + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 sto: False error_code: 0x00000000 diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index 17eafe1f..e08ced48 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -20,6 +20,10 @@ control_mode_fb: 1 # MODE_PP position_cmd: 0.0 position_fb: 15.0 + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 sto: False error_code: 0x00000000 feedback_out: @@ -37,6 +41,11 @@ goal_reached: True goal_reason: Reached move_success: False + velocity_zero: False + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 following_error: False move_setpoint_ack: False position_cmd: 0.0 @@ -67,6 +76,10 @@ control_mode_fb: 1 # MODE_PP position_cmd: 0.0 position_fb: 0.0 + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 sto: False error_code: 0x00000000 diff --git a/hw_device_mgr/cia_402/tests/pt.cases.yaml b/hw_device_mgr/cia_402/tests/pt.cases.yaml new file mode 100644 index 00000000..94ae65f5 --- /dev/null +++ b/hw_device_mgr/cia_402/tests/pt.cases.yaml @@ -0,0 +1,230 @@ +# Test cases for PT mode +# +- desc: "PT move: Start OPERATION ENABLED and MODE_PT" + sim_feedback_set: + # Jump directly to online, mode CSP, OPERATION ENABLED + online: True + oper: True + status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED + control_mode_fb: 4 # MODE_PT + command_in_set: + # Override command_in "state", queried by get_feedback(), to save + # additional setup of previous cycles + state: OPERATION ENABLED + control_mode: 4 # MODE_PT + feedback_in: + online: True + oper: True + status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED + control_mode_fb: 4 # MODE_PT + position_cmd: 0.0 + position_fb: 0 + velocity_cmd: 0 + velocity_fb: 0.0 + torque_cmd: 0 + torque_fb: 0 + sto: False + error_code: 0x00000000 + feedback_out: + online: True + oper: True + param_state: 0x02 # Complete + status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED + control_mode_fb: 4 # MODE_PT + state: OPERATION ENABLED + transition: -1 + home_success: False + home_error: False + home_found: False + fault: False + goal_reached: True + goal_reason: Reached + move_success: False + velocity_zero: False + following_error: False + move_setpoint_ack: False + position_cmd: 0.0 + position_fb: 0.0 + velocity_cmd: 0 + velocity_fb: 0.0 + torque_cmd: 0 + torque_fb: 0 + sto: False + error_code: 0x00000000 + description: No error + fault_desc: "" + shutdown_complete: False + command_in: + state: OPERATION ENABLED + control_mode: 4 # MODE_PT + reset_fault: False + home_request: False + move_request: False + relative_target: False + shutdown: False + command_out: + control_word: 0x000F # OPERATION ENABLED + control_mode: 4 # MODE_PT + init_params: True + fasttrack: False + shutdown_latch: False + sim_feedback: + online: True + oper: True + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED + control_mode_fb: 4 # MODE_PT + position_cmd: 0.0 + position_fb: 0.0 + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 + sto: False + error_code: 0x00000000 + +- desc: "PT move: Set PT command" + sim_feedback_set: + torque_cmd: 15.0 + feedback_in: + torque_cmd: 15.0 + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED + feedback_out: + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED + torque_cmd: 15.0 + command_out: + init_params: False + sim_feedback: + status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED +- desc: "PT move: Wait for torque (1)" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 10.0 # Catching up.... + feedback_in: + status_word: 0x0037 + torque_fb: 10.0 + feedback_out: + status_word: 0x0037 + torque_fb: 10.0 +- desc: "PT move: Wait for torque (2)" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 15.0 # At torque + feedback_in: + torque_fb: 15.0 + feedback_out: + torque_fb: 15.0 + sim_feedback: + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED +- desc: "PT move: Torque cmd complete" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 15.0 # At torque + feedback_in: + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED + feedback_out: + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED +- desc: "PT move: Torque cmd hold" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 15.0 + +# +# Torque command interrupted by drive fault +# +- desc: "PT move FAULT: Command move_request" + sim_feedback_set: + torque_cmd: 15.0 + # Simulate the fault + torque_fb: 0.0 + status_word: 0x001F # FAULT REACTION ACTIVE + feedback_in: + status_word: 0x001F # FAULT REACTION ACTIVE + torque_fb: 0.0 + feedback_out: + status_word: 0x001F # FAULT REACTION ACTIVE + state: FAULT REACTION ACTIVE + transition: 13 # (Any)->FAULT REACTION ACTIVE + goal_reason: Fault state reached; state FAULT REACTION ACTIVE != OPERATION ENABLED + fault: True + fault_desc: Drive status word FAULT bit set (no error code) + torque_fb: 0.0 + command_out: + control_word: 0x0000 + sim_feedback: + status_word: 0x0018 # FAULT + VOLTAGE_ENABLED +- desc: "PT move FAULT: FAULT; clear fault" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 0.0 + feedback_in: + status_word: 0x0018 # FAULT + VOLTAGE_ENABLED + feedback_out: + status_word: 0x0018 # FAULT + VOLTAGE_ENABLED + state: FAULT + transition: 14 # FAULT REACTION ACTIVE->FAULT + goal_reason: Fault state reached; state FAULT != OPERATION ENABLED + command_out: + control_word: 0x0080 # Clear fault + sim_feedback: + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - SETPOINT_ACK +- desc: "PT move FAULT: Trans 15 FAULT->SWITCH ON DISABLED; cancel move request" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 0.0 + feedback_in: + position_fb: 0.0 # Move complete + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - SETPOINT_ACK + feedback_out: + position_fb: 0.0 # Move complete + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - SETPOINT_ACK + state: SWITCH ON DISABLED + transition: 15 # FAULT->SWITCH ON DISABLED + goal_reason: Fault state reached; state SWITCH ON DISABLED != OPERATION ENABLED + # fault: True # Already True + fault_desc: Enabled drive unexpectedly disabled + command_out: + control_word: 0x0006 # READY TO SWITCH ON + sim_feedback: + status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED +- desc: "PT move FAULT: Command SWITCH ON DISABLED" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 0.0 + feedback_in: + status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED + feedback_out: + status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED + state: READY TO SWITCH ON + transition: 2 # SWITCH ON DISABLED->READY TO SWITCH ON + goal_reached: False + goal_reason: state READY TO SWITCH ON != OPERATION ENABLED + fault: False + fault_desc: "" + command_in: + state: SWITCH ON DISABLED + command_out: + control_word: 0x0000 + sim_feedback: + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED +- desc: "PT move FAULT: Done" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 0.0 + feedback_in: + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED + feedback_out: + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED + state: SWITCH ON DISABLED + transition: 7 # READY TO SWITCH ON->SWITCH ON DISABLED + goal_reached: True + goal_reason: Reached +- desc: "PT move FAULT: Hold" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 0.0 + feedback_out: + transition: -1 +- desc: "PT move FAULT: Hold" + sim_feedback_set: + torque_cmd: 15.0 + torque_fb: 0.0 diff --git a/hw_device_mgr/cia_402/tests/pv.cases.yaml b/hw_device_mgr/cia_402/tests/pv.cases.yaml new file mode 100644 index 00000000..09fbbf07 --- /dev/null +++ b/hw_device_mgr/cia_402/tests/pv.cases.yaml @@ -0,0 +1,230 @@ +# Test cases for PV mode +# +- desc: "PV move: Start OPERATION ENABLED and MODE_PV" + sim_feedback_set: + # Jump directly to online, mode CSP, OPERATION ENABLED + online: True + oper: True + status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED + control_mode_fb: 3 # MODE_PV + command_in_set: + # Override command_in "state", queried by get_feedback(), to save + # additional setup of previous cycles + state: OPERATION ENABLED + control_mode: 3 # MODE_PV + feedback_in: + online: True + oper: True + status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED + control_mode_fb: 3 # MODE_PV + position_cmd: 0.0 + position_fb: 0 + velocity_cmd: 0 + velocity_fb: 0.0 + torque_cmd: 0 + torque_fb: 0 + sto: False + error_code: 0x00000000 + feedback_out: + online: True + oper: True + param_state: 0x02 # Complete + status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED + control_mode_fb: 3 # MODE_PV + state: OPERATION ENABLED + transition: -1 + home_success: False + home_error: False + home_found: False + fault: False + goal_reached: True + goal_reason: Reached + move_success: False + velocity_zero: False + following_error: False + move_setpoint_ack: False + position_cmd: 0.0 + position_fb: 0.0 + velocity_cmd: 0 + velocity_fb: 0.0 + torque_cmd: 0 + torque_fb: 0 + sto: False + error_code: 0x00000000 + description: No error + fault_desc: "" + shutdown_complete: False + command_in: + state: OPERATION ENABLED + control_mode: 3 # MODE_PV + reset_fault: False + home_request: False + move_request: False + relative_target: False + shutdown: False + command_out: + control_word: 0x000F # OPERATION ENABLED + control_mode: 3 # MODE_PV + init_params: True + fasttrack: False + shutdown_latch: False + sim_feedback: + online: True + oper: True + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED + control_mode_fb: 3 # MODE_PV + position_cmd: 0.0 + position_fb: 0.0 + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 + sto: False + error_code: 0x00000000 + +- desc: "PV move: Set PV command" + sim_feedback_set: + velocity_cmd: 15.0 + feedback_in: + velocity_cmd: 15.0 + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED + feedback_out: + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED + velocity_cmd: 15.0 + command_out: + init_params: False + sim_feedback: + status_word: 0x0037 # OPERATION ENABLED + VOLTAGE_ENABLED +- desc: "PV move: Wait for velocity (1)" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 10.0 # Catching up.... + feedback_in: + status_word: 0x0037 + velocity_fb: 10.0 + feedback_out: + status_word: 0x0037 + velocity_fb: 10.0 +- desc: "PV move: Wait for velocity (2)" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 15.0 # At velocity + feedback_in: + velocity_fb: 15.0 + feedback_out: + velocity_fb: 15.0 + sim_feedback: + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED +- desc: "PV move: Velocity cmd complete" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 15.0 # At velocity + feedback_in: + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED + feedback_out: + status_word: 0x0437 # OPERATION ENABLED + VOLTAGE_ENABLED + TARGET_REACHED +- desc: "PV move: Velocity cmd hold" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 15.0 + +# +# Velocity command interrupted by drive fault +# +- desc: "PV move FAULT: Command move_request" + sim_feedback_set: + velocity_cmd: 15.0 + # Simulate the fault + velocity_fb: 0.0 + status_word: 0x001F # FAULT REACTION ACTIVE + feedback_in: + status_word: 0x001F # FAULT REACTION ACTIVE + velocity_fb: 0.0 + feedback_out: + status_word: 0x001F # FAULT REACTION ACTIVE + state: FAULT REACTION ACTIVE + transition: 13 # (Any)->FAULT REACTION ACTIVE + goal_reason: Fault state reached; state FAULT REACTION ACTIVE != OPERATION ENABLED + fault: True + fault_desc: Drive status word FAULT bit set (no error code) + velocity_fb: 0.0 + command_out: + control_word: 0x0000 + sim_feedback: + status_word: 0x0018 # FAULT + VOLTAGE_ENABLED +- desc: "PV move FAULT: FAULT; clear fault" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 0.0 + feedback_in: + status_word: 0x0018 # FAULT + VOLTAGE_ENABLED + feedback_out: + status_word: 0x0018 # FAULT + VOLTAGE_ENABLED + state: FAULT + transition: 14 # FAULT REACTION ACTIVE->FAULT + goal_reason: Fault state reached; state FAULT != OPERATION ENABLED + command_out: + control_word: 0x0080 # Clear fault + sim_feedback: + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - SETPOINT_ACK +- desc: "PV move FAULT: Trans 15 FAULT->SWITCH ON DISABLED; cancel move request" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 0.0 + feedback_in: + position_fb: 0.0 # Move complete + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - SETPOINT_ACK + feedback_out: + position_fb: 0.0 # Move complete + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - SETPOINT_ACK + state: SWITCH ON DISABLED + transition: 15 # FAULT->SWITCH ON DISABLED + goal_reason: Fault state reached; state SWITCH ON DISABLED != OPERATION ENABLED + # fault: True # Already True + fault_desc: Enabled drive unexpectedly disabled + command_out: + control_word: 0x0006 # READY TO SWITCH ON + sim_feedback: + status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED +- desc: "PV move FAULT: Command SWITCH ON DISABLED" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 0.0 + feedback_in: + status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED + feedback_out: + status_word: 0x0031 # READY TO SWITCH ON + VOLTAGE_ENABLED + state: READY TO SWITCH ON + transition: 2 # SWITCH ON DISABLED->READY TO SWITCH ON + goal_reached: False + goal_reason: state READY TO SWITCH ON != OPERATION ENABLED + fault: False + fault_desc: "" + command_in: + state: SWITCH ON DISABLED + command_out: + control_word: 0x0000 + sim_feedback: + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED +- desc: "PV move FAULT: Done" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 0.0 + feedback_in: + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED + feedback_out: + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED + state: SWITCH ON DISABLED + transition: 7 # READY TO SWITCH ON->SWITCH ON DISABLED + goal_reached: True + goal_reason: Reached +- desc: "PV move FAULT: Hold" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 0.0 + feedback_out: + transition: -1 +- desc: "PV move FAULT: Hold" + sim_feedback_set: + velocity_cmd: 15.0 + velocity_fb: 0.0 diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index 0b3762f8..0a699d5e 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -13,6 +13,10 @@ control_mode_fb: 0 # Undefined position_cmd: 0 position_fb: 0 + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 # STO sto: False # errors @@ -35,6 +39,11 @@ goal_reached: False goal_reason: Offline move_success: False + velocity_zero: False + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 following_error: False move_setpoint_ack: False position_cmd: 0 @@ -70,6 +79,10 @@ control_mode_fb: 0 # Undefined position_cmd: 0.0 position_fb: 0.0 + velocity_cmd: 0 + velocity_fb: 0 + torque_cmd: 0 + torque_fb: 0 # STO sto: False # errors diff --git a/hw_device_mgr/cia_402/tests/test_device_read_update_write.py b/hw_device_mgr/cia_402/tests/test_device_read_update_write.py index cfe32904..e84bf5d4 100644 --- a/hw_device_mgr/cia_402/tests/test_device_read_update_write.py +++ b/hw_device_mgr/cia_402/tests/test_device_read_update_write.py @@ -23,16 +23,25 @@ def setup_test(self, test_case): mno_home_found = mno.setdefault("home_found", set()) mno_home_found.add((0x00100000, 0x000C010D)) - def test_read_update_write(self, obj): + def read_update_write_helper(self, obj, ruw_yaml): if hasattr(obj, "MODE_CSP"): # CiA 402 device self.read_update_write_package = self.read_update_write_402_package - self.read_update_write_yaml = self.read_update_write_402_yaml + self.read_update_write_yaml = ruw_yaml self.is_402_device = True else: self.is_402_device = False super().test_read_update_write(obj) + def test_read_update_write(self, obj): + self.read_update_write_helper(obj, self.read_update_write_402_yaml) + + def test_read_update_write_pv(self, obj): + self.read_update_write_helper(obj, "pv.cases.yaml") + + def test_read_update_write_pt(self, obj): + self.read_update_write_helper(obj, "pt.cases.yaml") + class TestCiA402DeviceRUWHMTimeout(TestCiA402DeviceRUW): def test_read_update_write(self, obj, mock_time): diff --git a/hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml b/hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml old mode 100755 new mode 100644 index 1bc81a7d..55145178 --- a/hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml +++ b/hw_device_mgr/devices/device_xml/STD60_EOE_1Axis_06008_NEW_v1_0.xml @@ -3755,7 +3755,7 @@ rw - + DT2006 @@ -3843,7 +3843,7 @@ rw - + 20 Touch Probe 1 filter time constant @@ -3933,7 +3933,7 @@ Actual motor rotational speed INT 16 - 16 + 16 ro T @@ -6837,7 +6837,7 @@ #x607A0020 - + 4th Output Object to be mapped @@ -8079,7 +8079,7 @@ 51200 50000 - + Time of home searching @@ -8112,7 +8112,7 @@ 10000 0 - + ro @@ -8196,7 +8196,7 @@ 4294967295 27486951 - + Touch Probe 1 filter time constant @@ -10231,7 +10231,7 @@ rw - - + @@ -18,7 +18,7 @@ - + @@ -35,7 +35,7 @@ - + @@ -69,7 +69,7 @@ - + @@ -93,7 +93,7 @@ - + @@ -110,7 +110,7 @@ - + diff --git a/hw_device_mgr/lcec/tests/test_config.py b/hw_device_mgr/lcec/tests/test_config.py index 2e81135e..c798ae3c 100644 --- a/hw_device_mgr/lcec/tests/test_config.py +++ b/hw_device_mgr/lcec/tests/test_config.py @@ -10,7 +10,7 @@ class TestLCECConfig(BaseLCECTestClass, _TestEtherCATConfig): ethercat_conf_xml_package = "hw_device_mgr.lcec.tests" ethercat_conf_xml_resource = "ethercat.conf.xml" - def test_gen_ethercat_xml(self, config_cls, tmp_path): + def test_gen_ethercat_xml(self, config_cls, tmp_path, dcs_data): # Read expected conf.xml rsrc = (self.ethercat_conf_xml_package, self.ethercat_conf_xml_resource) with self.open_resource(*rsrc) as f: From 8c49bca433367784d4a4265ec3e09e71027cb4f6 Mon Sep 17 00:00:00 2001 From: John Morris Date: Sun, 30 Apr 2023 22:31:04 -0500 Subject: [PATCH 095/121] cia_301: Add `overlappingPdos` key to test data For testing `lcec` component --- hw_device_mgr/cia_301/config.py | 1 + hw_device_mgr/cia_301/tests/device_config.yaml | 1 + 2 files changed, 2 insertions(+) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index 480a2468..e3c65ea2 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -228,6 +228,7 @@ def set_device_config(cls, config): - `vendor_id`, `product_code`: `int` values for matching device model + - Other device-specific keys - `bus`: Bus `int` value - `positions`: `list` of matching `int` positions on bus diff --git a/hw_device_mgr/cia_301/tests/device_config.yaml b/hw_device_mgr/cia_301/tests/device_config.yaml index aeaadcb0..a07050bf 100644 --- a/hw_device_mgr/cia_301/tests/device_config.yaml +++ b/hw_device_mgr/cia_301/tests/device_config.yaml @@ -73,6 +73,7 @@ # # vendor_id: 0xB090C0 # product_code: 0xB0905011 + overlappingPdos: true addresses: # [bus, position, (optional) alias]; alias (default 0) is used by From 415d5505323963526b29d23ada27d25fb861bb12 Mon Sep 17 00:00:00 2001 From: Kyle Cesare Date: Mon, 1 May 2023 23:40:49 +0000 Subject: [PATCH 096/121] Fix setting of overlappingPdos flag. --- hw_device_mgr/lcec/config.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/hw_device_mgr/lcec/config.py b/hw_device_mgr/lcec/config.py index b17d7693..79a38ca4 100644 --- a/hw_device_mgr/lcec/config.py +++ b/hw_device_mgr/lcec/config.py @@ -59,7 +59,7 @@ def gen_ethercat_xml(cls, bus_configs=dict(), devs=None): ) overlapping_pdos = config.get("overlappingPdos", False) if overlapping_pdos: - slave_xml["overlappingPdos"] = "true" + slave_xml.attrib["overlappingPdos"] = "true" master.append(slave_xml) # if dev.dcs(): From 0c929dce6b8bc9cd0c54da02c30179865d9b6fbe Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 1 May 2023 22:45:52 -0500 Subject: [PATCH 097/121] lcec: Rename overlapping PDOs config key For consistency --- hw_device_mgr/lcec/config.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/hw_device_mgr/lcec/config.py b/hw_device_mgr/lcec/config.py index 79a38ca4..40afc722 100644 --- a/hw_device_mgr/lcec/config.py +++ b/hw_device_mgr/lcec/config.py @@ -57,7 +57,7 @@ def gen_ethercat_xml(cls, bus_configs=dict(), devs=None): pid=str(dev.product_code), configPdos="true", ) - overlapping_pdos = config.get("overlappingPdos", False) + overlapping_pdos = config.get("overlapping_pdos", False) if overlapping_pdos: slave_xml.attrib["overlappingPdos"] = "true" master.append(slave_xml) From 34b7c44aa8224239949343a4fa035a19c2ee19af Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 10:53:10 -0500 Subject: [PATCH 098/121] base class: Add sim junction box to tests --- hw_device_mgr/tests/base_test_class.py | 3 ++- hw_device_mgr/tests/bogus_devices/device.py | 6 ++++++ hw_device_mgr/tests/sim_devices.yaml | 8 ++------ 3 files changed, 10 insertions(+), 7 deletions(-) diff --git a/hw_device_mgr/tests/base_test_class.py b/hw_device_mgr/tests/base_test_class.py index 703c91a2..83e904d4 100644 --- a/hw_device_mgr/tests/base_test_class.py +++ b/hw_device_mgr/tests/base_test_class.py @@ -6,6 +6,7 @@ BogusV1Servo, BogusV2Servo, BogusV1IO, + BogusV1JBox, ) import logging @@ -21,7 +22,7 @@ class BaseTestClass(ConfigIO): # Classes under test in this module data_type_class = BogusDataType device_class = BogusDevice - device_model_classes = BogusV1IO, BogusV2Servo, BogusV1Servo + device_model_classes = BogusV1IO, BogusV2Servo, BogusV1Servo, BogusV1JBox # Sim mode by default sim = True diff --git a/hw_device_mgr/tests/bogus_devices/device.py b/hw_device_mgr/tests/bogus_devices/device.py index 20da6a9c..da286309 100644 --- a/hw_device_mgr/tests/bogus_devices/device.py +++ b/hw_device_mgr/tests/bogus_devices/device.py @@ -25,3 +25,9 @@ class BogusV1IO(BogusDevice): name = "bogo_v1_io" test_category = "bogus_v1_io" model_id = 0xB0901000 + + +class BogusV1JBox(BogusDevice): + name = "bogo_v1_jbox" + test_category = "bogus_v1_jbox" + model_id = 0xB0908000 diff --git a/hw_device_mgr/tests/sim_devices.yaml b/hw_device_mgr/tests/sim_devices.yaml index c9ebca2b..6511a1ef 100644 --- a/hw_device_mgr/tests/sim_devices.yaml +++ b/hw_device_mgr/tests/sim_devices.yaml @@ -21,12 +21,8 @@ 607D-02h: 10 - test_category: bogus_v1_io address: [0, 16] -- test_category: bogus_v1_servo - address: [0, 18, 4] - params: - 605A-00h: 3 - 607D-01h: -400 - 607D-02h: 400 +- test_category: bogus_v1_jbox + address: [0, 18] - test_category: bogus_v2_servo address: [0, 19, 5] params: From 3e80bea68e0b3b2596746a6cea3b7d220f3357b3 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 10:53:45 -0500 Subject: [PATCH 099/121] cia_301: Add sim junction box to tests Junction box is unusual because no SDOs --- hw_device_mgr/cia_301/config.py | 2 +- .../cia_301/tests/base_test_class.py | 2 ++ .../cia_301/tests/bogus_devices/device.py | 6 ++++++ hw_device_mgr/cia_301/tests/dcs_data.yaml | 1 + .../cia_301/tests/device_config.yaml | 20 +++++++++++++++++++ hw_device_mgr/cia_301/tests/sim_sdo_data.yaml | 1 + hw_device_mgr/cia_301/tests/test_config.py | 3 +++ 7 files changed, 34 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index e3c65ea2..a3528f6c 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -63,7 +63,7 @@ def __init__( @classmethod def format_model_id(cls, model_id): - assert None not in model_id + assert None not in model_id, f"Invalid model ID {model_id} for {cls}" return tuple(cls.data_type_class.uint32(i) for i in model_id) @cached_property diff --git a/hw_device_mgr/cia_301/tests/base_test_class.py b/hw_device_mgr/cia_301/tests/base_test_class.py index 0c220c3c..9d9dedd0 100644 --- a/hw_device_mgr/cia_301/tests/base_test_class.py +++ b/hw_device_mgr/cia_301/tests/base_test_class.py @@ -8,6 +8,7 @@ BogusCiA301V1Servo, BogusCiA301V2Servo, BogusCiA301V1IO, + BogusCiA301V1JBox, ) from ..command import CiA301SimCommand @@ -41,6 +42,7 @@ class BaseCiA301TestClass(BaseTestClass): BogusCiA301V1Servo, BogusCiA301V2Servo, BogusCiA301V1IO, + BogusCiA301V1JBox, ) @classmethod diff --git a/hw_device_mgr/cia_301/tests/bogus_devices/device.py b/hw_device_mgr/cia_301/tests/bogus_devices/device.py index 89527399..85eb6e84 100644 --- a/hw_device_mgr/cia_301/tests/bogus_devices/device.py +++ b/hw_device_mgr/cia_301/tests/bogus_devices/device.py @@ -27,3 +27,9 @@ class BogusCiA301V1IO(BogusCiA301Device): name = "bogo_cia301_v1_io" test_category = "bogus_v1_io" product_code = 0xB0901010 + + +class BogusCiA301V1JBox(BogusCiA301Device): + name = "bogo_cia301_v1_jbox" + test_category = "bogus_v1_jbox" + product_code = 0xB0908010 diff --git a/hw_device_mgr/cia_301/tests/dcs_data.yaml b/hw_device_mgr/cia_301/tests/dcs_data.yaml index 1c15672d..5c49bf09 100644 --- a/hw_device_mgr/cia_301/tests/dcs_data.yaml +++ b/hw_device_mgr/cia_301/tests/dcs_data.yaml @@ -19,3 +19,4 @@ bogus_v2_servo: Desc: DC unused AssignActivate: 0x0 bogus_v1_io: [] # No DCs +bogus_v1_jbox: [] # No DCs diff --git a/hw_device_mgr/cia_301/tests/device_config.yaml b/hw_device_mgr/cia_301/tests/device_config.yaml index a07050bf..0c65fbf0 100644 --- a/hw_device_mgr/cia_301/tests/device_config.yaml +++ b/hw_device_mgr/cia_301/tests/device_config.yaml @@ -214,3 +214,23 @@ - bitLen: 5 # (No parameters) + + +# +# B090.80 Junction Box +# +- + test_category: bogus_v1_jbox + # test_category will be replaced with the following (or similar) in + # the `device_config` fixture: + # + # vendor_id: 0xB090C0 + # product_code: 0xB0908010 + + addresses: + # [bus, alias, position]; alias is used by EtherCAT devices and + # will be ignored for plain cia_301 device tests + - [0, 18] + + config_pdos: False + # (No sync managers,no parameters) diff --git a/hw_device_mgr/cia_301/tests/sim_sdo_data.yaml b/hw_device_mgr/cia_301/tests/sim_sdo_data.yaml index dd74545f..c93db10a 100644 --- a/hw_device_mgr/cia_301/tests/sim_sdo_data.yaml +++ b/hw_device_mgr/cia_301/tests/sim_sdo_data.yaml @@ -652,3 +652,4 @@ bogus_v1_io: subindex: 0x01 data_type: uint8 name: Inputs +bogus_v1_jbox: {} diff --git a/hw_device_mgr/cia_301/tests/test_config.py b/hw_device_mgr/cia_301/tests/test_config.py index c3c38492..cfaa8eb8 100644 --- a/hw_device_mgr/cia_301/tests/test_config.py +++ b/hw_device_mgr/cia_301/tests/test_config.py @@ -26,6 +26,9 @@ def test_add_device_sdos(self, obj, config_cls, sdo_data): print("test obj model_id:", obj.model_id) assert obj.model_id in config_cls._model_sdos obj_sdos = obj._model_sdos[obj.model_id] + if not sdo_data: + assert not obj_sdos + return assert obj_sdos print("test obj SDOs:\n", pformat(obj_sdos)) assert list(sorted(obj_sdos)) == list(sorted(sdo_data)) From 665750bb04fdfc45ebba440e187235bb2750967f Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 10:54:35 -0500 Subject: [PATCH 100/121] cia_402: Add sim junction box to tests --- hw_device_mgr/cia_402/tests/base_test_class.py | 2 ++ hw_device_mgr/cia_402/tests/bogus_devices/device.py | 6 ++++++ 2 files changed, 8 insertions(+) diff --git a/hw_device_mgr/cia_402/tests/base_test_class.py b/hw_device_mgr/cia_402/tests/base_test_class.py index 1f5cbc9e..a1d4f322 100644 --- a/hw_device_mgr/cia_402/tests/base_test_class.py +++ b/hw_device_mgr/cia_402/tests/base_test_class.py @@ -4,6 +4,7 @@ BogusCiA402V1Servo, BogusCiA402V2Servo, BogusCiA402V1IO, + BogusCiA402V1JBox, ) import pytest @@ -19,6 +20,7 @@ class BaseCiA402TestClass(BaseCiA301TestClass): BogusCiA402V1Servo, BogusCiA402V2Servo, BogusCiA402V1IO, + BogusCiA402V1JBox, ) @pytest.fixture diff --git a/hw_device_mgr/cia_402/tests/bogus_devices/device.py b/hw_device_mgr/cia_402/tests/bogus_devices/device.py index 2225ffd4..bfa3a534 100644 --- a/hw_device_mgr/cia_402/tests/bogus_devices/device.py +++ b/hw_device_mgr/cia_402/tests/bogus_devices/device.py @@ -29,3 +29,9 @@ class BogusCiA402V1IO(BogusCiA402Device): name = "bogo_cia402_v1_io" test_category = "bogus_v1_io" product_code = 0xB0901020 + + +class BogusCiA402V1JBox(BogusCiA402Device): + name = "bogo_cia402_v1_jbox" + test_category = "bogus_v1_jbox" + product_code = 0xB0908020 From 4a38fdcac5e67d8137608af9c79cf54e888face5 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 10:54:55 -0500 Subject: [PATCH 101/121] devices: Add sim junction box and IO module classes Junction box ESI is unusual because it doesn't contain mailboxes or object dictionary definitions. --- hw_device_mgr/devices/bogus.py | 25 ++++++++++ .../devices/device_xml/BogusJunction.xml | 49 +++++++++++++++++++ 2 files changed, 74 insertions(+) create mode 100644 hw_device_mgr/devices/device_xml/BogusJunction.xml diff --git a/hw_device_mgr/devices/bogus.py b/hw_device_mgr/devices/bogus.py index 9416b8e3..a9abbb67 100644 --- a/hw_device_mgr/devices/bogus.py +++ b/hw_device_mgr/devices/bogus.py @@ -23,3 +23,28 @@ class BogusV2Servo(BogusDevice): """Bogus Device Co V2 servo drive.""" product_code = 0xB0905031 + + +class BogusOtherDevice(EtherCATSimDevice): + """Base class for Bogus Device Co devices other than motors.""" + + category = "bogus_other" + vendor_id = 0xB090C0 + xml_description_package = "hw_device_mgr.devices.device_xml" + device_error_package = "hw_device_mgr.devices.device_err" + device_error_yaml = "unpopulated.yaml" + + +class BogusJBox(BogusOtherDevice): + """Bogus Device Co Junction Box.""" + + product_code = 0xB0908030 + xml_description_fname = "BogusJunction.xml" + + +class BogusIO(BogusOtherDevice): + """Bogus Device Co V1 IO Module.""" + + product_code = 0xB0901030 + xml_description_fname = "BogusIO.xml" + device_error_yaml = "bogus_v1_error_io.yaml" diff --git a/hw_device_mgr/devices/device_xml/BogusJunction.xml b/hw_device_mgr/devices/device_xml/BogusJunction.xml new file mode 100644 index 00000000..fedaed60 --- /dev/null +++ b/hw_device_mgr/devices/device_xml/BogusJunction.xml @@ -0,0 +1,49 @@ + + + + #xB090C0 + Bogus HW Devices Inc. Co., Ltd. + www.bogus-devices.com + + + + + BOGO Series + EtherCAT Infrastructure components + + + + + B090.JU_BOX.3.0 + + + + EBUS + + + MII + + + + MII + + + + MII + + + + EC_INF + + + 2048 + 000D00000A00 + + + + + + From 451d0b177ee8aeb15dec65b028108bcd6587eef0 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 10:56:47 -0500 Subject: [PATCH 102/121] errors: Add sim junction box to tests --- hw_device_mgr/errors/tests/base_test_class.py | 8 +++++++- hw_device_mgr/errors/tests/bogus_devices/device.py | 7 +++++++ hw_device_mgr/errors/tests/test_device.py | 3 +++ 3 files changed, 17 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/errors/tests/base_test_class.py b/hw_device_mgr/errors/tests/base_test_class.py index 50713310..0a8f1b8e 100644 --- a/hw_device_mgr/errors/tests/base_test_class.py +++ b/hw_device_mgr/errors/tests/base_test_class.py @@ -4,9 +4,15 @@ BogusErrorV1Servo, BogusErrorV2Servo, BogusErrorV1IO, + BogusErrorV1JBox, ) class ErrorBaseTestClass(BaseTestClass): device_class = BogusErrorDevice - device_model_classes = BogusErrorV1Servo, BogusErrorV2Servo, BogusErrorV1IO + device_model_classes = ( + BogusErrorV1Servo, + BogusErrorV2Servo, + BogusErrorV1IO, + BogusErrorV1JBox, + ) diff --git a/hw_device_mgr/errors/tests/bogus_devices/device.py b/hw_device_mgr/errors/tests/bogus_devices/device.py index b70b4858..0d28519d 100644 --- a/hw_device_mgr/errors/tests/bogus_devices/device.py +++ b/hw_device_mgr/errors/tests/bogus_devices/device.py @@ -31,3 +31,10 @@ class BogusErrorV1IO(BogusErrorDevice): test_category = "bogus_v1_io" model_id = 0xB0901041 device_error_yaml = "bogus_v1_error_io.yaml" + + +class BogusErrorV1JBox(BogusErrorDevice): + name = "bogus_v1_error_jbox" + test_category = "bogus_v1_jbox" + model_id = 0xB0908041 + device_error_yaml = "unpopulated.yaml" diff --git a/hw_device_mgr/errors/tests/test_device.py b/hw_device_mgr/errors/tests/test_device.py index b04e0e5b..8adb92c8 100644 --- a/hw_device_mgr/errors/tests/test_device.py +++ b/hw_device_mgr/errors/tests/test_device.py @@ -16,6 +16,9 @@ def test_error_descriptions(self, obj): print("yaml:", obj.device_error_package, obj.device_error_yaml) errs = obj.error_descriptions() assert isinstance(errs, dict) + if obj.device_error_yaml == "unpopulated.yaml": + assert len(errs) == 0 + return assert len(errs) > 0 for err_code, data in errs.items(): assert isinstance(err_code, int) From 609a695f45b94ab930599692fec0ff9cfd47327e Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 10:57:19 -0500 Subject: [PATCH 103/121] hal: Add sim junction box to tests --- hw_device_mgr/hal/tests/base_test_class.py | 8 +++++++- hw_device_mgr/hal/tests/bogus_devices/device.py | 6 ++++++ 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/hal/tests/base_test_class.py b/hw_device_mgr/hal/tests/base_test_class.py index 8aaa97d9..6c83686f 100644 --- a/hw_device_mgr/hal/tests/base_test_class.py +++ b/hw_device_mgr/hal/tests/base_test_class.py @@ -6,6 +6,7 @@ BogusHALV1Servo, BogusHALV2Servo, BogusHALV1IO, + BogusHALV1JBox, ) from .mock_hal import MockHALComponent @@ -14,7 +15,12 @@ class BaseHALTestClass(BaseCiA402TestClass): # Classes under test in this module data_type_class = HALDataType device_class = BogusHALDevice - device_model_classes = BogusHALV1Servo, BogusHALV2Servo, BogusHALV1IO + device_model_classes = ( + BogusHALV1Servo, + BogusHALV2Servo, + BogusHALV1IO, + BogusHALV1JBox, + ) @pytest.fixture def mock_halcomp(self): diff --git a/hw_device_mgr/hal/tests/bogus_devices/device.py b/hw_device_mgr/hal/tests/bogus_devices/device.py index 8574a896..bfd0a77f 100644 --- a/hw_device_mgr/hal/tests/bogus_devices/device.py +++ b/hw_device_mgr/hal/tests/bogus_devices/device.py @@ -25,3 +25,9 @@ class BogusHALV1IO(BogusHALDevice): name = "bogo_hal_v1_io" test_category = "bogus_v1_io" product_code = 0xB0901050 + + +class BogusHALV1JBox(BogusHALDevice): + name = "bogo_hal_v1_jbox" + test_category = "bogus_v1_jbox" + product_code = 0xB0908050 From ffe246f37884e11c646b83cd7704ade0b50bb6d6 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 10:57:29 -0500 Subject: [PATCH 104/121] ethercat: Add sim junction box to tests --- hw_device_mgr/ethercat/tests/base_test_class.py | 3 +++ hw_device_mgr/ethercat/tests/bogus_devices/device.py | 8 ++++++++ 2 files changed, 11 insertions(+) diff --git a/hw_device_mgr/ethercat/tests/base_test_class.py b/hw_device_mgr/ethercat/tests/base_test_class.py index 4a67be6e..94dcae69 100644 --- a/hw_device_mgr/ethercat/tests/base_test_class.py +++ b/hw_device_mgr/ethercat/tests/base_test_class.py @@ -8,6 +8,7 @@ BogusEtherCATServo, BogusOtherCATServo, BogusEtherCATIO, + BogusEtherCATJBox, ) import re import pytest @@ -24,6 +25,7 @@ class BaseEtherCATTestClass(BaseCiA402TestClass): BogusEtherCATServo, BogusOtherCATServo, BogusEtherCATIO, + BogusEtherCATJBox, ) sdo_model_id_clone = tuple( [ @@ -32,6 +34,7 @@ class BaseEtherCATTestClass(BaseCiA402TestClass): (0x00B090C0, 0xB0905030), (0x00B090C0, 0xB0905031), (0x00B090C0, 0xB0901030), + (0x00B090C0, 0xB0908030), ) ] ) diff --git a/hw_device_mgr/ethercat/tests/bogus_devices/device.py b/hw_device_mgr/ethercat/tests/bogus_devices/device.py index 9ad15f4b..25c14c3c 100644 --- a/hw_device_mgr/ethercat/tests/bogus_devices/device.py +++ b/hw_device_mgr/ethercat/tests/bogus_devices/device.py @@ -33,3 +33,11 @@ class BogusEtherCATIO(BogusEtherCATDevice): product_code = 0xB0901030 xml_description_fname = "BogusIO.xml" device_error_yaml = "bogus_v1_error_io.yaml" + + +class BogusEtherCATJBox(BogusEtherCATDevice): + name = "bogo_ethercat_jbox" + test_category = "bogus_v1_jbox" + product_code = 0xB0908030 + xml_description_fname = "BogusJunction.xml" + device_error_yaml = "unpopulated.yaml" From ab74dcabe4bd8aa856a3067ebe1f35cb1bf830a1 Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 10:58:56 -0500 Subject: [PATCH 105/121] lcec: Support devices with no sync managers or object dictionaries Some devices have fixed PDO mappings (e.g. iTegva IO modules) or no sync manager mailboxes or object dictionaries at all (e.g. Beckhoff CU1128 junction box). - Make `ethercat.conf.xml` ` element + config_pdos = "true" if config.get("config_pdos", True) else "false" slave_xml = etree.Element( "slave", idx=str(0 if dev.alias else dev.position), @@ -55,7 +56,7 @@ def gen_ethercat_xml(cls, bus_configs=dict(), devs=None): type="generic", vid=str(dev.vendor_id), pid=str(dev.product_code), - configPdos="true", + configPdos=config_pdos, ) overlapping_pdos = config.get("overlapping_pdos", False) if overlapping_pdos: @@ -78,7 +79,8 @@ def gen_ethercat_xml(cls, bus_configs=dict(), devs=None): sync0Shift=str(s0s), ) # - for sm_ix, sm_data in config["sync_manager"].items(): + sync_manager = config.get("sync_manager", dict()) + for sm_ix, sm_data in sync_manager.items(): assert "dir" in sm_data assert sm_data["dir"] in {"in", "out"} sm_xml = etree.Element( diff --git a/hw_device_mgr/lcec/tests/base_test_class.py b/hw_device_mgr/lcec/tests/base_test_class.py index e2bab906..282ebfd9 100644 --- a/hw_device_mgr/lcec/tests/base_test_class.py +++ b/hw_device_mgr/lcec/tests/base_test_class.py @@ -11,6 +11,7 @@ BogusLCECV1Servo, BogusLCECV2Servo, BogusLCECV1IO, + BogusLCECV1JBox, ) @@ -21,7 +22,12 @@ class BaseLCECTestClass(BaseEtherCATTestClass, BaseHALTestClass): command_class = LCECSimCommand config_class = LCECSimConfig device_class = BogusLCECDevice - device_model_classes = BogusLCECV1Servo, BogusLCECV2Servo, BogusLCECV1IO + device_model_classes = ( + BogusLCECV1Servo, + BogusLCECV2Servo, + BogusLCECV1IO, + BogusLCECV1JBox, + ) @classmethod def lcec_data_type(cls, type_str): diff --git a/hw_device_mgr/lcec/tests/bogus_devices/device.py b/hw_device_mgr/lcec/tests/bogus_devices/device.py index f5b35e6e..9042845c 100644 --- a/hw_device_mgr/lcec/tests/bogus_devices/device.py +++ b/hw_device_mgr/lcec/tests/bogus_devices/device.py @@ -34,3 +34,11 @@ class BogusLCECV1IO(BogusLCECDevice): product_code = 0xB0901060 xml_description_fname = "BogusIO.xml" device_error_yaml = "bogus_v1_error_io.yaml" + + +class BogusLCECV1JBox(BogusLCECDevice): + name = "bogo_lcec_v1_jbox" + test_category = "bogus_v1_jbox" + product_code = 0xB0908060 + xml_description_fname = "BogusJunction.xml" + device_error_yaml = "unpopulated.yaml" diff --git a/hw_device_mgr/lcec/tests/ethercat.conf.xml b/hw_device_mgr/lcec/tests/ethercat.conf.xml index 411f2278..7ecbc4a7 100644 --- a/hw_device_mgr/lcec/tests/ethercat.conf.xml +++ b/hw_device_mgr/lcec/tests/ethercat.conf.xml @@ -1,48 +1,48 @@ - + - - + + - - + + - + - - + + - - + + - + - - + + @@ -65,11 +65,11 @@ - + - + @@ -93,31 +93,15 @@ - - - - - - - - - - - - - - - - - - + + - - + + @@ -140,7 +124,7 @@ - + From 27fbcd7e03cef95179edd8fbf244199df3f16fcc Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 13:11:48 -0500 Subject: [PATCH 106/121] mgr: Don't send commands to non-CiA402 devices --- hw_device_mgr/mgr/mgr.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 5199c30f..29b29e09 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -112,13 +112,13 @@ def init_devices( for name, skip_set in self.device_translated_interfaces.items(): dev_intf = dev.interface(name) mgr_intf = self.interface(name) - for attr_name, val in dev_intf.get().items(): + for attr_name in dev_intf.keys(): if attr_name in skip_set: continue mgr_attr_name = prefix + attr_name - mgr_intf.add_attribute( - mgr_attr_name, val, dev_intf.get_data_type(attr_name) - ) + default = dev_intf.defaults[attr_name] + data_type = dev_intf.get_data_type(attr_name) + mgr_intf.add_attribute(mgr_attr_name, default, data_type) @classmethod def scan_devices(cls, **kwargs): @@ -701,6 +701,8 @@ def set_drive_command(self): reset = self.command_out.get("reset_fault_cmd") shutdown = self.command_in.get("shutdown") for dev in self.devices: + if not hasattr(dev, "MODE_CSP"): + continue # Not a CiA402 device if "command_in" in self.device_translated_interfaces: # Copy mgr command_out to matching device command_in dev_command_in = dev.interface("command_in") From 56354b417e0dd4fb76820e90a5f75701bb5ab63b Mon Sep 17 00:00:00 2001 From: John Morris Date: Tue, 2 May 2023 13:12:40 -0500 Subject: [PATCH 107/121] mgr_ros: Fix exception when handling exception in main loop --- hw_device_mgr/mgr_ros/mgr.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/hw_device_mgr/mgr_ros/mgr.py b/hw_device_mgr/mgr_ros/mgr.py index e5cc5756..be1422d0 100644 --- a/hw_device_mgr/mgr_ros/mgr.py +++ b/hw_device_mgr/mgr_ros/mgr.py @@ -85,7 +85,7 @@ def read_update_write(self): for line in traceback.format_exc().splitlines(): self.logger.error(line) self.command_in.set( - state_cmd="fault", state_log="Unexpected exception" + state_cmd=self.STATE_FAULT, state_log="Unexpected exception" ) if self.fast_track: # This update included a state transition; skip From 5b59d46741a1b7db57a3b9d8142423b8c96629ee Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 10 May 2023 13:22:19 -0500 Subject: [PATCH 108/121] ethercat: No-op remove comment `REAL` data type seen in both Elmo and Ingenia ESIs. --- hw_device_mgr/ethercat/data_types.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/hw_device_mgr/ethercat/data_types.py b/hw_device_mgr/ethercat/data_types.py index cf2afac4..41c6faa5 100644 --- a/hw_device_mgr/ethercat/data_types.py +++ b/hw_device_mgr/ethercat/data_types.py @@ -18,7 +18,7 @@ class EtherCATDataType(DataType): uint16=dict(name="UINT"), uint32=dict(name="UDINT"), uint64=dict(name="ULINT"), - float=dict(name="REAL"), # Never seen in the wild + float=dict(name="REAL"), double=dict(name="LREAL"), # Never seen in the wild str=dict( # Sequence of octets From 29bb53b559d8c4c363a93e7e0506b4e12e3c746d Mon Sep 17 00:00:00 2001 From: John Morris Date: Sun, 14 May 2023 11:45:17 -0500 Subject: [PATCH 109/121] cia_301: Allow per-device PDO entry values in device config The recently-added PDO entry `scale` and `offset` args need different values for different drives in the same machine. --- hw_device_mgr/cia_301/config.py | 18 ++++++++++++++++++ hw_device_mgr/cia_301/tests/device_config.yaml | 2 +- 2 files changed, 19 insertions(+), 1 deletion(-) diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index a3528f6c..0c40ce9c 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -290,6 +290,23 @@ def munge_config(cls, config_raw, address, skip_optional=True): break else: raise KeyError(f"No address '{address}' in device config '{addrs}'") + + # Flatten out sync_manager pdo_mapping entries; needs deep copy + sm_conf = config_cooked.get("sync_manager", dict()).copy() + config_cooked["sync_manager"] = sm_conf + for sm_idx, sm_idx_conf in list(sm_conf.items()): + if sm_idx_conf.get("pdo_mapping", {}).get("entries", None) is None: + continue # Targeting PDO mapping entries with scale/offset keys + sm_conf[sm_idx] = sm_idx_conf = sm_idx_conf.copy() + pm = sm_idx_conf["pdo_mapping"] = sm_idx_conf["pdo_mapping"].copy() + assert isinstance(pm["entries"], list) + entries = pm["entries"] = list(pm["entries"]) # Copy list + for entry_idx, entry in enumerate(entries): + entries[entry_idx] = entry = entry.copy() + for key, val in entry.items(): + if isinstance(val, list) and key != "bits": + entry[key] = val[pos_ix] + # Flatten out param_values key config_cooked["param_values"] = dict() for ix, val in config_raw.get("param_values", dict()).items(): @@ -309,6 +326,7 @@ def munge_config(cls, config_raw, address, skip_optional=True): if isinstance(val, list): val = val[pos_ix] config_cooked["param_values"][ix] = val + # Return pruned config dict return config_cooked diff --git a/hw_device_mgr/cia_301/tests/device_config.yaml b/hw_device_mgr/cia_301/tests/device_config.yaml index 0c65fbf0..456c9d95 100644 --- a/hw_device_mgr/cia_301/tests/device_config.yaml +++ b/hw_device_mgr/cia_301/tests/device_config.yaml @@ -104,7 +104,7 @@ name: control_word - index: 607Ah name: position_cmd - scale: -42.555555553 + scale: [-10, -11, -12, -13, -0.4, -0.5] offset: 42 '3': # TPDOs: Transmit PDOs ("in" from drive) From 77e58e0bc4a641a3be6190525345efe79f1523a8 Mon Sep 17 00:00:00 2001 From: John Morris Date: Sun, 14 May 2023 11:48:40 -0500 Subject: [PATCH 110/121] lcec: Update test for per-drive PDO `scale` values --- hw_device_mgr/lcec/tests/ethercat.conf.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/hw_device_mgr/lcec/tests/ethercat.conf.xml b/hw_device_mgr/lcec/tests/ethercat.conf.xml index 7ecbc4a7..b9d6f016 100644 --- a/hw_device_mgr/lcec/tests/ethercat.conf.xml +++ b/hw_device_mgr/lcec/tests/ethercat.conf.xml @@ -42,7 +42,7 @@ - + @@ -101,7 +101,7 @@ - + From 771a1b0c2f13d898332d76b56b62e5630a370776 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 15 May 2023 12:29:13 -0500 Subject: [PATCH 111/121] .github: Update CI & fix build failures - Fix CI Docker image namespace, following upstream [1] (possibly temporary) - Update CI Docker image and CI config to Humble/Jammy - Remove `clang` tests & ccache config; fixes failure on Ubuntu Jammy, with no `clang-format-10` package; no C code here anyway - Update pre-commit GH action tag to latest 3.0.0 [1]: https://github.com/ros-planning/moveit2/pull/1908 --- .github/workflows/ci.yaml | 19 ++++--------------- .github/workflows/format.yaml | 4 +--- .github/workflows/upstream.rosinstall | 6 +++--- 3 files changed, 8 insertions(+), 21 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index a77f2647..6489776d 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -18,11 +18,10 @@ jobs: fail-fast: false matrix: env: - - IMAGE: foxy-ci - CLANG_TIDY: pedantic + - IMAGE: humble-ci env: CXXFLAGS: "-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-deprecated-copy" - DOCKER_IMAGE: ghcr.io/ros-planning/moveit2:${{ matrix.env.IMAGE }} + DOCKER_IMAGE: moveit/moveit2:${{ matrix.env.IMAGE }} UPSTREAM_WORKSPACE: .github/workflows/upstream.rosinstall BEFORE_SETUP_UPSTREAM_WORKSPACE: .github/workflows/upstream_install.sh # Pull any updates to the upstream workspace (after restoring it from cache) @@ -32,18 +31,14 @@ jobs: AFTER_BUILD_TARGET_WORKSPACE: ccache -s CCACHE_DIR: ${{ github.workspace }}/.ccache BASEDIR: ${{ github.workspace }}/.work - CLANG_TIDY_BASE_REF: ${{ github.event_name != 'workflow_dispatch' && (github.base_ref || github.ref) || '' }} - BEFORE_CLANG_TIDY_CHECKS: (cd $TARGET_REPO_PATH; clang-tidy --list-checks) - CC: ${{ matrix.env.CLANG_TIDY && 'clang' }} - CXX: ${{ matrix.env.CLANG_TIDY && 'clang++' }} - name: ${{ matrix.env.IMAGE }}${{ matrix.env.CLANG_TIDY && (github.event_name != 'workflow_dispatch' && ' + clang-tidy (delta)' || ' + clang-tidy (all)') || '' }} + name: ${{ matrix.env.IMAGE }} runs-on: ubuntu-latest steps: - name: "Free up disk space" if: matrix.env.CCOV run: | - sudo apt-get -qq purge build-essential "ghc*" + sudo apt-get -qq purge build-essential ghc\* sudo apt-get clean # cleanup docker images not used by us docker system prune -af @@ -98,12 +93,6 @@ jobs: with: name: test-results-${{ matrix.env.IMAGE }} path: ${{ env.BASEDIR }}/target_ws/**/test_results/**/*.xml - - name: Upload clang-tidy changes - uses: rhaschke/upload-git-patch-action@main - if: matrix.env.CLANG_TIDY - with: - name: clang-tidy - path: ${{ env.BASEDIR }}/target_ws/src/$(basename $(pwd)) - name: Prepare target_ws for cache run: | du -sh ${{ env.BASEDIR }}/target_ws diff --git a/.github/workflows/format.yaml b/.github/workflows/format.yaml index dac65683..be59c65e 100644 --- a/.github/workflows/format.yaml +++ b/.github/workflows/format.yaml @@ -15,11 +15,9 @@ jobs: steps: - uses: actions/checkout@v2 - uses: actions/setup-python@v2 - - name: Install clang-format-10 - run: sudo apt-get install clang-format-10 - name: Install black run: sudo -H pip3 install black - - uses: pre-commit/action@v2.0.3 + - uses: pre-commit/action@v3.0.0 id: precommit - name: Upload pre-commit changes if: failure() && steps.precommit.outcome == 'failure' diff --git a/.github/workflows/upstream.rosinstall b/.github/workflows/upstream.rosinstall index bc3bf45c..28e9f8b1 100644 --- a/.github/workflows/upstream.rosinstall +++ b/.github/workflows/upstream.rosinstall @@ -1,7 +1,7 @@ - git: local-name: hal_ros_control uri: https://github.com/zultron/hal_ros_control.git - version: 2022-01-07-foxy-devel + version: zultron/2023-04-14-humble-devel - git: local-name: ros2_control_demos # FIXME The rrbot demo avoids duplicating the rrbot description @@ -11,6 +11,6 @@ # packages. # # uri: https://github.com/ros-controls/ros2_control_demos.git - # version: foxy + # version: humble uri: https://github.com/zultron/ros2_control_demos.git - version: foxy-dev-parameterize-hardware-plugin + version: zultron/2023-04-14-humble-dev-parameterize-hardware-plugin From 1d116e5a8368b2d361615471747a7ca12d12489e Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 15 May 2023 12:56:18 -0500 Subject: [PATCH 112/121] docker: Fix `python-attrs-pip` rosdep key Waiting for these to shake out: https://github.com/ros/rosdistro/pull/36888 https://github.com/ros/rosdistro/pull/36893 --- .github/workflows/upstream_install.sh | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/.github/workflows/upstream_install.sh b/.github/workflows/upstream_install.sh index f9153263..f30b36a8 100755 --- a/.github/workflows/upstream_install.sh +++ b/.github/workflows/upstream_install.sh @@ -41,6 +41,20 @@ cat >$UPSTREAM_ROSDEP_YML <<-EOF debian: [machinekit-hal-dev] ubuntu: [machinekit-hal-dev] EOF + +# FIXME Waiting for these to shake out: +# https://github.com/ros/rosdistro/pull/36888 +# https://github.com/ros/rosdistro/pull/36893 +cat >>$UPSTREAM_ROSDEP_YML <<-EOF + python-attrs-pip: + debian: + pip: + packages: [attrs] + ubuntu: + pip: + packages: [attrs] + EOF + echo "yaml file://$UPSTREAM_ROSDEP_YML" > \ /etc/ros/rosdep/sources.list.d/10-local.list rosdep update From 8eb79b92f6dc4f11a255076120ec4d7cbfd0a8a3 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 15 May 2023 13:12:10 -0500 Subject: [PATCH 113/121] pre-commit: Remove inapplicable checks --- .pre-commit-config.yaml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index dd070924..8cd5ee25 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -7,9 +7,7 @@ repos: - id: trailing-whitespace - id: check-docstring-first - id: check-executables-have-shebangs - - id: check-json - id: check-merge-conflict - - id: check-symlinks - id: check-xml - id: check-yaml - id: end-of-file-fixer From edbff9f2d71261b7349332c328aabc9a2cf53580 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 22 May 2023 17:36:15 -0500 Subject: [PATCH 114/121] mgr_ros: Treat empty sim device data path as unset --- hw_device_mgr/mgr_ros/mgr.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/hw_device_mgr/mgr_ros/mgr.py b/hw_device_mgr/mgr_ros/mgr.py index be1422d0..1e878704 100644 --- a/hw_device_mgr/mgr_ros/mgr.py +++ b/hw_device_mgr/mgr_ros/mgr.py @@ -56,7 +56,7 @@ class init. if "sim_device_data" in kwargs: raise TypeError("unexpected 'sim_device_data' argument") sim_device_data_path = self.get_param("sim_device_data_path", None) - if sim_device_data_path is not None: + if sim_device_data_path: sim_device_data = self.load_yaml_path(sim_device_data_path) assert sim_device_data, f"Empty YAML file '{sim_device_data_path}'" kwargs["sim_device_data"] = sim_device_data From ce1a87b671976857e1c574c0cb009548d4de6d69 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 4 Aug 2025 18:09:24 -0500 Subject: [PATCH 115/121] Fix ROS packaging - Don't depend on unneeded things - Don't fail when `multilatency` comp can't be instaled --- package.xml | 6 +----- setup.py | 31 ++++++++++++++++++++++++++++--- 2 files changed, 29 insertions(+), 8 deletions(-) diff --git a/package.xml b/package.xml index 8ab0b240..936a54de 100644 --- a/package.xml +++ b/package.xml @@ -8,18 +8,14 @@ BSD - ament_cmake - ament_cmake_python - rosidl_default_generators catkin hal_hw_interface rospy - + rclpy - rosidl_default_runtime python3-ruamel.yaml diff --git a/setup.py b/setup.py index da9cafca..b41e3777 100644 --- a/setup.py +++ b/setup.py @@ -1,7 +1,9 @@ from setuptools import setup from setuptools.command.install import install +from warnings import warn import subprocess import os +import sys package_name = "hw_device_mgr" @@ -43,14 +45,37 @@ class CustomInstall(install): + user_options = install.user_options + [ + ( + 'sudo-halcompile=', + None, + 'If needed to install HAL components, sudo executable (ROS 2 only).' + ), + ] + + def initialize_options(self): + super().initialize_options() + self.sudo_halcompile = None + + def finalize_options(self): + super().finalize_options() + # You can add validation or default value logic here + if self.sudo_halcompile: + print(f"Prepending to halcompile: {self.sudo_halcompile}") + def run(self): """Run halcompile on `multilatency.comp`.""" if os.environ.get("ROS_VERSION", None) == "2": # ROS1 builds comp from CMakeFile comp_src = "hw_device_mgr/latency/multilatency.comp" - subprocess.check_call( - ["/usr/bin/env", "halcompile", "--install", comp_src] - ) + cmd = ["/usr/bin/env", "halcompile", "--install", comp_src] + if self.sudo_halcompile: + cmd.insert(0, self.sudo_halcompile) + res = subprocess.run(cmd, capture_output=True) + if res.returncode != 0: + warn(f"Command failed, {repr(cmd)}") + for line in res.stderr.decode().splitlines(): + warn(f"stderr: {line}") super().run() From c3762aed1cc9fde1e002227e8b29c0d43c169cc8 Mon Sep 17 00:00:00 2001 From: John Morris Date: Mon, 4 Aug 2025 18:10:39 -0500 Subject: [PATCH 116/121] mgr_ros: Log sim device data YAML file path --- hw_device_mgr/mgr_ros/mgr.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/hw_device_mgr/mgr_ros/mgr.py b/hw_device_mgr/mgr_ros/mgr.py index 1e878704..70502352 100644 --- a/hw_device_mgr/mgr_ros/mgr.py +++ b/hw_device_mgr/mgr_ros/mgr.py @@ -57,6 +57,9 @@ class init. raise TypeError("unexpected 'sim_device_data' argument") sim_device_data_path = self.get_param("sim_device_data_path", None) if sim_device_data_path: + self.logger.info( + f"Reading sim device data from '{sim_device_data_path}'" + ) sim_device_data = self.load_yaml_path(sim_device_data_path) assert sim_device_data, f"Empty YAML file '{sim_device_data_path}'" kwargs["sim_device_data"] = sim_device_data From c9011a40e164f40f533a903aebf0d517f05e4e43 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 6 Aug 2025 11:29:13 -0500 Subject: [PATCH 117/121] Update pre-commit and fix formatting errors --- .pre-commit-config.yaml | 4 ++-- hw_device_mgr/ethercat/xml_reader.py | 35 +--------------------------- setup.py | 5 ++-- 3 files changed, 5 insertions(+), 39 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 8cd5ee25..0211277a 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -22,8 +22,8 @@ repos: args: [-l, "80"] types: [python] -- repo: https://github.com/myint/docformatter - rev: v1.7.5 +- repo: https://github.com/PyCQA/docformatter + rev: v1.7.7 hooks: - id: docformatter args: [--pre-summary-newline, --in-place] diff --git a/hw_device_mgr/ethercat/xml_reader.py b/hw_device_mgr/ethercat/xml_reader.py index a3ee2a63..2ef927db 100644 --- a/hw_device_mgr/ethercat/xml_reader.py +++ b/hw_device_mgr/ethercat/xml_reader.py @@ -90,7 +90,7 @@ def tree_to_obj(self, tree): Translate an XML element into a Python object. The resulting object can be printed and won't lose information; - used in fall-through cases. + used in fallthrough cases. """ return dict( tag=tree.tag, @@ -208,39 +208,6 @@ def devices_xml(self): # return self.tree.xpath("/EtherCATInfo/Descriptions/Devices/Device") - """Map XML data types to `ethercat -t TYPE` - - http://www.dige.ai/uploadfiles/2020/01/20200109105424701.pdf - https://etherlab.org/download/ethercat/ethercat-1.5.2.pdf - - Format: 'XML_type': 'etherlab_type' # NUMBITS Description - """ - - # Data type definitiens - # - # - # - # - # USINT - # 8 - # - # - # DT1018 - # 144 - # - # 0 - # SubIndex 000 - # USINT - # 8 - # 0 - # - # ro - # - # - # [...] - # - # [...] - def expand_subitems(self, subitems): """Translate `SubItem` objects within complex `DataType` objects.""" subidx = 0 diff --git a/setup.py b/setup.py index b41e3777..9fa98850 100644 --- a/setup.py +++ b/setup.py @@ -3,7 +3,6 @@ from warnings import warn import subprocess import os -import sys package_name = "hw_device_mgr" @@ -47,9 +46,9 @@ class CustomInstall(install): user_options = install.user_options + [ ( - 'sudo-halcompile=', + "sudo-halcompile=", None, - 'If needed to install HAL components, sudo executable (ROS 2 only).' + "If needed to install HAL components, sudo executable (ROS 2 only).", ), ] From a8b992d35bc7962ba63191cac80467e0afd81488 Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 6 Aug 2025 12:03:20 -0500 Subject: [PATCH 118/121] Fix tests for "cia_402: [...] switch on disabled, don't quick stop" --- .../cia_402/tests/hm_timeout.cases.yaml | 4 +- .../cia_402/tests/pp_timeout.cases.yaml | 4 +- hw_device_mgr/cia_402/tests/pt.cases.yaml | 1 + hw_device_mgr/cia_402/tests/pv.cases.yaml | 1 + .../tests/read_update_write.cases.yaml | 26 ++++-------- .../mgr/tests/read_update_write.cases.yaml | 40 +++++-------------- 6 files changed, 25 insertions(+), 51 deletions(-) diff --git a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml index 74771c93..f0cb84ad 100644 --- a/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/hm_timeout.cases.yaml @@ -114,8 +114,8 @@ state: FAULT home_request: False command_out: - control_word: 0x0002 # QUICK STOP ACTIVE + control_word: 0x0000 # SWITCH ON DISABLED control_mode: 8 # MODE_CSP sim_feedback: - status_word: 0x0017 # QUICK_STOP_ACTIVE + VOLTAGE_ENABLED - HOMING_START + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - HOMING_START control_mode_fb: 8 # MODE_CSP diff --git a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml index ad30091e..0e220bee 100644 --- a/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pp_timeout.cases.yaml @@ -132,8 +132,8 @@ state: FAULT home_request: False command_out: - control_word: 0x0002 # QUICK STOP ACTIVE + control_word: 0x0000 # SWITCH ON DISABLED control_mode: 1 # MODE_PP sim_feedback: - status_word: 0x0017 # QUICK_STOP_ACTIVE + VOLTAGE_ENABLED - HOMING_START + status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - HOMING_START control_mode_fb: 1 # MODE_PP diff --git a/hw_device_mgr/cia_402/tests/pt.cases.yaml b/hw_device_mgr/cia_402/tests/pt.cases.yaml index 94ae65f5..ec01c060 100644 --- a/hw_device_mgr/cia_402/tests/pt.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pt.cases.yaml @@ -62,6 +62,7 @@ move_request: False relative_target: False shutdown: False + quick_stop: False command_out: control_word: 0x000F # OPERATION ENABLED control_mode: 4 # MODE_PT diff --git a/hw_device_mgr/cia_402/tests/pv.cases.yaml b/hw_device_mgr/cia_402/tests/pv.cases.yaml index 09fbbf07..99268d08 100644 --- a/hw_device_mgr/cia_402/tests/pv.cases.yaml +++ b/hw_device_mgr/cia_402/tests/pv.cases.yaml @@ -62,6 +62,7 @@ move_request: False relative_target: False shutdown: False + quick_stop: False command_out: control_word: 0x000F # OPERATION ENABLED control_mode: 3 # MODE_PV diff --git a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml index f6af5357..2ba1911d 100644 --- a/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/cia_402/tests/read_update_write.cases.yaml @@ -437,31 +437,21 @@ # Controller commands FAULT in response to external event state: FAULT command_out: - control_word: 0x0002 - sim_feedback: - status_word: 0x0017 -- desc: "Disable enabled: Command disable; 402 state machine transition 11" - feedback_in: - status_word: 0x0017 - feedback_out: - status_word: 0x0017 - state: QUICK STOP ACTIVE - transition: 11 - fault: True - fault_desc: FAULT command from controller (from state OPERATION ENABLED) + control_word: 0x0000 # SWITCH ON DISABLED sim_feedback: status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED -- desc: "Disable enabled: Command disable; 402 state machine transition 12" +- desc: "Disable enabled: Command disable; 402 state machine transition 9" feedback_in: status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED feedback_out: status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED state: SWITCH ON DISABLED - transition: -1 - goal_reason: Reached - command_out: - control_word: 0x0000 + transition: 9 + fault: True + fault_desc: FAULT command from controller (from state OPERATION ENABLED) - desc: "Disable disabled: Hold SWITCH ON DISABLED x1" + feedback_out: + transition: -1 - desc: "Disable disabled: Hold SWITCH ON DISABLED x2" # @@ -612,7 +602,7 @@ # Controller commands disable state: SWITCH ON DISABLED command_out: - control_word: 0x0002 # QUICK STOP ACTIVE + control_word: 0x0002 # QUICK STOP sim_feedback: status_word: 0x0017 # QUICK STOP ACTIVE + VOLTAGE_ENABLED - desc: "Home: 402 state machine transition 11" diff --git a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index 5106a61e..1ad31f37 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -275,7 +275,7 @@ # (In real life, upper layers would hold fault) # OPERATION ENABLED -> FAULT -> SWITCH ON DISABLED -> (towards) OPERATION ENABLED # -- desc: "Sim fault: Drive 1 faults; others enter QUICK STOP ACTIVE" +- desc: "Sim fault: Drive 1 faults; others enter SWITCH ON DISABLED" sim_feedback_set: # Simulate the fault d.1.status_word: 0x001F # FAULT REACTION ACTIVE + VOLTAGE_ENABLED @@ -302,33 +302,31 @@ state_log: Manager fault command_complete: False drive_state: FAULT - d.x.control_word: 0x0002 # QUICK STOP ACTIVE - d.1.control_word: 0x0000 # SWITCH ON DISABLED + d.x.control_word: 0x0000 # SWITCH ON DISABLED sim_feedback: - d.x.status_word: 0x0017 # QUICK STOP + VOLTAGE_ENABLED + d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED -- desc: "Sim fault: Non-faulted drives enter QUICK STOP ACTIVE" +- desc: "Sim fault: Settle into fault state" sim_feedback_set: d.1.error_code: 0xDEADBEEF # Bogus error code feedback_in: - d.x.status_word: 0x0017 # QUICK STOP + VOLTAGE_ENABLED + d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED feedback_out: goal_reached: False goal_reason: Waiting on device manager internal transitions - fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' ({drives[1]}) # drive_1 holds state - d.1.fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED d.1.state: FAULT d.1.transition: 14 d.1.goal_reason: Reached - # ...while other drives enter QUICK STOP ACTIVE + d.1.fault_desc: Drive status word FAULT bit set, code 0xDEADBEEF 'Unknown error code 0xDEADBEEF' + # ...while other drives enter SWITCH ON DISABLED d.x.fault: True d.x.fault_desc: FAULT command from controller (from state OPERATION ENABLED) - d.x.status_word: 0x0017 # QUICK STOP + VOLTAGE_ENABLED - d.x.state: QUICK STOP ACTIVE - d.x.transition: 11 + d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED + d.x.state: SWITCH ON DISABLED + d.x.transition: 9 command_out: state_log: Manager fault # Manager does NOT all drives in FAULT state, but in STATE_FAULT @@ -337,28 +335,12 @@ sim_feedback: d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED -- desc: "Sim fault: Non-faulted drives enter SWITCH ON DISABLED" +- desc: "Sim fault: Hold fault command x1" sim_feedback_set: d.1.error_code: 0xDEADBEEF # Bogus error code - feedback_in: - d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED - d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED feedback_out: goal_reached: True goal_reason: Reached - d.1.status_word: 0x0018 # FAULT + VOLTAGE_ENABLED - d.1.state: FAULT - d.x.status_word: 0x0050 # SWITCH ON DISABLED + VOLTAGE_ENABLED - d.x.state: SWITCH ON DISABLED - d.x.transition: -1 - d.x.goal_reached: True - d.x.goal_reason: Reached - command_out: - d.x.control_word: 0x0000 # SWITCH ON DISABLED -- desc: "Sim fault: Hold fault command x1" - sim_feedback_set: - d.1.error_code: 0xDEADBEEF # Bogus error code - feedback_out: d.x.transition: -1 # No transition - desc: "Sim fault: Hold fault command x2" sim_feedback_set: From f0e39a69c47a59682d9fd1ec2e1c6af11ce12b3b Mon Sep 17 00:00:00 2001 From: John Morris Date: Wed, 6 Aug 2025 13:32:20 -0500 Subject: [PATCH 119/121] mgr_ros: Fix sim_device_data handling Update to "Add device class `init_class()` method" commit --- hw_device_mgr/mgr/mgr.py | 2 +- hw_device_mgr/mgr_ros/mgr.py | 68 ++++++++++++------- .../mgr_ros/tests/base_test_class.py | 8 +++ hw_device_mgr/mgr_ros/tests/test_mgr.py | 2 +- .../tests/test_mgr_read_update_write.py | 4 +- 5 files changed, 56 insertions(+), 28 deletions(-) diff --git a/hw_device_mgr/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 29b29e09..4b288e0e 100644 --- a/hw_device_mgr/mgr/mgr.py +++ b/hw_device_mgr/mgr/mgr.py @@ -79,7 +79,7 @@ def init(self, /, mgr_config, device_config, **kwargs): self.logger.info("Device manager initialization complete") @classmethod - def init_class(cls, sim_device_data=None, kwargs=dict()): + def init_class(cls, sim_device_data=None, **kwargs): # Initialize device classes, incl. any sim discovery data if sim_device_data: kwargs.update(sim_device_data=sim_device_data) diff --git a/hw_device_mgr/mgr_ros/mgr.py b/hw_device_mgr/mgr_ros/mgr.py index 70502352..04ca92e0 100644 --- a/hw_device_mgr/mgr_ros/mgr.py +++ b/hw_device_mgr/mgr_ros/mgr.py @@ -5,14 +5,52 @@ class ROSHWDeviceMgr(HWDeviceMgr, ConfigIO): - def get_param(self, name, default=None): - if self.ros_node.has_parameter(name): - param = self.ros_node.get_parameter(name) + @classmethod + def get_param(cls, name, default=None): + if cls.ros_node.has_parameter(name): + param = cls.ros_node.get_parameter(name) else: - param = self.ros_node.declare_parameter(name, value=default) + param = cls.ros_node.declare_parameter(name, value=default) return param.value - def init(self, /, argv, **kwargs): + @classmethod + def init_ros(cls, argv): + """ + Initialize manager instance. + + Init ROS node, shutdown callback and rate object, and read + manager config and device config YAML path from ROS params, in + addition to base class init. + """ + # Init ROS node + node_kwargs = dict( + allow_undeclared_parameters=True, + automatically_declare_parameters_from_overrides=True, + ) + + rclpy.init(args=argv) + cls.ros_node = rclpy.create_node(cls.name, **node_kwargs) + cls.ros_context = rclpy.utilities.get_default_context() + + @classmethod + def init_class(cls, argv, **kwargs): + cls.init_ros(argv) + + # Init sim device data + if "sim_device_data" in kwargs: + raise TypeError("unexpected 'sim_device_data' argument") + sim_device_data_path = cls.get_param("sim_device_data_path", None) + if sim_device_data_path: + cls.get_logger(cls.name).info( + f"Reading sim device data from '{sim_device_data_path}'" + ) + sim_device_data = cls.load_yaml_path(sim_device_data_path) + assert sim_device_data, f"Empty YAML file '{sim_device_data_path}'" + kwargs["sim_device_data"] = sim_device_data + + super().init_class(**kwargs) + + def init(self, /, **kwargs): """ Initialize manager instance. @@ -26,15 +64,6 @@ class init. If the ROS param `sim_device_data_path` is non-empty, it must be a `str` containing the path to a YAML file with the sim device configuration. """ - # - Init ROS node - node_kwargs = dict( - allow_undeclared_parameters=True, - automatically_declare_parameters_from_overrides=True, - ) - - rclpy.init(args=argv) - self.ros_node = rclpy.create_node(self.name, **node_kwargs) - self.ros_context = rclpy.utilities.get_default_context() self.logger.info(f"Initializing '{self.name}' ROS node") # - mgr_config if "mgr_config" in kwargs: @@ -52,17 +81,6 @@ class init. self.logger.info(f"Reading device config from '{device_config_path}'") device_config = self.load_yaml_path(device_config_path) assert device_config, f"Empty YAML file '{device_config_path}'" - # - sim device data - if "sim_device_data" in kwargs: - raise TypeError("unexpected 'sim_device_data' argument") - sim_device_data_path = self.get_param("sim_device_data_path", None) - if sim_device_data_path: - self.logger.info( - f"Reading sim device data from '{sim_device_data_path}'" - ) - sim_device_data = self.load_yaml_path(sim_device_data_path) - assert sim_device_data, f"Empty YAML file '{sim_device_data_path}'" - kwargs["sim_device_data"] = sim_device_data # super().init( mgr_config=mgr_config, device_config=device_config, **kwargs diff --git a/hw_device_mgr/mgr_ros/tests/base_test_class.py b/hw_device_mgr/mgr_ros/tests/base_test_class.py index a24a796d..f789334b 100644 --- a/hw_device_mgr/mgr_ros/tests/base_test_class.py +++ b/hw_device_mgr/mgr_ros/tests/base_test_class.py @@ -82,6 +82,14 @@ def device_config(self, sim_device_data_path): self.dump_yaml_path(sim_device_data_path, sim_device_data) yield dev_conf + @classmethod + def init_sim(cls, **kwargs): + # Don't add sim_device_data like parent method does + print(f"init_sim({cls}, **{kwargs})") + cls.device_class.clear_devices() + argv = list() + cls.device_class.init_class(argv, **kwargs) + @pytest.fixture def device_config_path(self, tmp_path, device_config, mock_rclpy): # Clean data types from device config to dump into YAML file & diff --git a/hw_device_mgr/mgr_ros/tests/test_mgr.py b/hw_device_mgr/mgr_ros/tests/test_mgr.py index aa22db0a..69a0395a 100644 --- a/hw_device_mgr/mgr_ros/tests/test_mgr.py +++ b/hw_device_mgr/mgr_ros/tests/test_mgr.py @@ -20,7 +20,7 @@ class TestROSHWDeviceMgr(BaseROSMgrTestClass, _TestHWDeviceMgr): def obj(self, category_cls): # init() signature changed, so can't use parent test class obj fixture self.obj = self.device_class() - self.obj.init(argv=list()) + self.obj.init() yield self.obj def test_ros_params(self, obj): diff --git a/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py b/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py index dfed80be..b735a83d 100644 --- a/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py +++ b/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py @@ -14,5 +14,7 @@ class TestROSHWDeviceMgrRUW(BaseROSMgrTestClass, _TestHWDeviceMgrRUW): def obj(self, category_cls): # init() signature changed, so can't use parent test class obj fixture self.obj = self.device_class() - self.obj.init(argv=list()) + self.obj.init() + for d in self.obj.devices: + d.config.init_params = False yield self.obj From c7536697089f273fbebb117851b5f9a8427639b6 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 7 Aug 2025 17:12:34 -0500 Subject: [PATCH 120/121] cia_301: Fix logic for devices that don't need params set --- hw_device_mgr/cia_301/device.py | 8 ++++---- hw_device_mgr/devices/itegva_e7x.py | 6 ++++++ 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/hw_device_mgr/cia_301/device.py b/hw_device_mgr/cia_301/device.py index a0b4cb8c..5d077f23 100644 --- a/hw_device_mgr/cia_301/device.py +++ b/hw_device_mgr/cia_301/device.py @@ -124,6 +124,8 @@ def get_feedback(self): p_init_err = self.config.param_init_error if not self.config.init_params: param_state = self.PARAM_STATE_COMPLETE + if old_ps != self.PARAM_STATE_COMPLETE: # Log once only + self.logger.info("Device not configured to update params") elif p_init_err: try: errstr = "{1}({2}, {3}): {0}".format(*p_init_err) @@ -246,13 +248,11 @@ def add_device_dcs(cls, dcs_data): @classmethod def get_device(cls, address=None, **kwargs): registry = cls._address_registry.setdefault(cls.name, dict()) - config = address - address = config.address if hasattr(address, "address") else address if address in registry: return registry[address] # kwargs will contain skip_optional_config_values at this point, but it # will be consumed by __init__ for this class - device_obj = cls(address=config, **kwargs) + device_obj = cls(address=address, **kwargs) registry[address] = device_obj return device_obj @@ -269,7 +269,7 @@ def scan_devices(cls, bus=0, get_device_kwargs=dict(), **kwargs): raise NotImplementedError( f"Unknown model {config.model_id} at {config.address}" ) - dev = device_cls.get_device(config, **get_device_kwargs) + dev = device_cls.get_device(config.address, **get_device_kwargs) devices.append(dev) return devices diff --git a/hw_device_mgr/devices/itegva_e7x.py b/hw_device_mgr/devices/itegva_e7x.py index f93823d7..b6e2ccf6 100644 --- a/hw_device_mgr/devices/itegva_e7x.py +++ b/hw_device_mgr/devices/itegva_e7x.py @@ -1,12 +1,18 @@ +from ..ethercat.config import EtherCATConfig from ..ethercat.device import EtherCATDevice +class ITegvaE7xConfig(EtherCATConfig): + init_params = False + + class ITegvaE7xDevice(EtherCATDevice): """Base class for iTegva E7x series IO modules.""" vendor_id = 0x00000A09 xml_description_package = "hw_device_mgr.devices.device_xml" xml_description_fname = "iTegva_E7x_Series.xml" + config_class = ITegvaE7xConfig # "Access_Bit": IOs individually accessible via bit PDOs From 96a3b72eb3f364e892202b6ca2534f0dd701f789 Mon Sep 17 00:00:00 2001 From: John Morris Date: Thu, 7 Aug 2025 18:02:29 -0500 Subject: [PATCH 121/121] Update pre-commit hooks & GH Actions --- .github/workflows/ci.yaml | 4 ++-- .github/workflows/format.yaml | 4 ++-- .github/workflows/upstream_install.sh | 13 ------------- .pre-commit-config.yaml | 4 ++-- hw_device_mgr/cia_301/config.py | 2 +- hw_device_mgr/device.py | 2 +- hw_device_mgr/devices/elmo_gold.py | 2 +- hw_device_mgr/latency/ecat_pcap_decode.py | 2 +- .../tests/test_device_read_update_write.py | 4 ++-- 9 files changed, 12 insertions(+), 25 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 6489776d..95d510e6 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -49,7 +49,7 @@ jobs: # free up a lot of stuff from /usr/local sudo rm -rf /usr/local df -h - - uses: actions/checkout@v2 + - uses: actions/checkout@v4 - name: Cache upstream workspace uses: pat-s/always-upload-cache@v2.1.5 with: @@ -88,7 +88,7 @@ jobs: uses: ros-industrial/industrial_ci@master env: ${{ matrix.env }} - name: Upload test artifacts (on failure) - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 if: failure() && (steps.ici.outputs.run_target_test || steps.ici.outputs.target_test_results) with: name: test-results-${{ matrix.env.IMAGE }} diff --git a/.github/workflows/format.yaml b/.github/workflows/format.yaml index be59c65e..7f91cf54 100644 --- a/.github/workflows/format.yaml +++ b/.github/workflows/format.yaml @@ -14,10 +14,10 @@ jobs: runs-on: ubuntu-latest steps: - uses: actions/checkout@v2 - - uses: actions/setup-python@v2 + - uses: actions/setup-python@v3 - name: Install black run: sudo -H pip3 install black - - uses: pre-commit/action@v3.0.0 + - uses: pre-commit/action@v3.0.1 id: precommit - name: Upload pre-commit changes if: failure() && steps.precommit.outcome == 'failure' diff --git a/.github/workflows/upstream_install.sh b/.github/workflows/upstream_install.sh index f30b36a8..3941a005 100755 --- a/.github/workflows/upstream_install.sh +++ b/.github/workflows/upstream_install.sh @@ -42,19 +42,6 @@ cat >$UPSTREAM_ROSDEP_YML <<-EOF ubuntu: [machinekit-hal-dev] EOF -# FIXME Waiting for these to shake out: -# https://github.com/ros/rosdistro/pull/36888 -# https://github.com/ros/rosdistro/pull/36893 -cat >>$UPSTREAM_ROSDEP_YML <<-EOF - python-attrs-pip: - debian: - pip: - packages: [attrs] - ubuntu: - pip: - packages: [attrs] - EOF - echo "yaml file://$UPSTREAM_ROSDEP_YML" > \ /etc/ros/rosdep/sources.list.d/10-local.list rosdep update diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 0211277a..eb7775d6 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,6 +1,6 @@ repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.5.0 + rev: v5.0.0 hooks: - id: check-ast - id: fix-byte-order-marker @@ -29,7 +29,7 @@ repos: args: [--pre-summary-newline, --in-place] - repo: https://github.com/pycqa/flake8 - rev: 7.0.0 + rev: 7.3.0 hooks: - id: flake8 diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index 0c40ce9c..0cc5cb0e 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -31,7 +31,7 @@ class CiA301Config(LoggingMixin): @cached_property def logging_name(self): - return f"{self.name}@{str(self.address).replace(' ','')}" + return f"{self.name}@{str(self.address).replace(' ', '')}" data_type_class = CiA301DataType command_class = CiA301Command diff --git a/hw_device_mgr/device.py b/hw_device_mgr/device.py index 76c70b72..614c55cf 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -229,7 +229,7 @@ def write(self): """Write `command_out` to hardware interface.""" def __str__(self): - return f"{self.name}@{str(self.address).replace(' ','')}" + return f"{self.name}@{str(self.address).replace(' ', '')}" def __repr__(self): return f"<{self.__str__()}>" diff --git a/hw_device_mgr/devices/elmo_gold.py b/hw_device_mgr/devices/elmo_gold.py index c9a4fd2d..92bad0b6 100644 --- a/hw_device_mgr/devices/elmo_gold.py +++ b/hw_device_mgr/devices/elmo_gold.py @@ -18,7 +18,7 @@ def set_params_volatile(self, nv=False): # Params have to be explicitly saved if nv: for i, char in enumerate("save"): - self.config.download(f"1010-0{i+1}h", ord(char)) + self.config.download(f"1010-0{i + 1}h", ord(char)) # FIXME These models differ only by revision, but the CiA 301 class diff --git a/hw_device_mgr/latency/ecat_pcap_decode.py b/hw_device_mgr/latency/ecat_pcap_decode.py index 11f3e57b..be4580ca 100755 --- a/hw_device_mgr/latency/ecat_pcap_decode.py +++ b/hw_device_mgr/latency/ecat_pcap_decode.py @@ -24,7 +24,7 @@ def __init__(self, x, base=10, *, pdo, length): self.length = length def __str__(self): - return f"0x{{:0{int(self.length)*2}X}}".format(self) + return f"0x{{:0{int(self.length) * 2}X}}".format(self) def __repr__(self): return f"" diff --git a/hw_device_mgr/tests/test_device_read_update_write.py b/hw_device_mgr/tests/test_device_read_update_write.py index 5bc0b86d..30187825 100644 --- a/hw_device_mgr/tests/test_device_read_update_write.py +++ b/hw_device_mgr/tests/test_device_read_update_write.py @@ -211,12 +211,12 @@ def check_data_values( # Print debug info if actual_val is MISSING: msg = "MISSING" if missing_not_ok else "(missing; ok)" - print(f'{" "*indent}{prefix}{param}: {msg}') + print(f'{" " * indent}{prefix}{param}: {msg}') elif isinstance(expected_val, dict): if actual_val: self.print_dict(actual_val, prefix + param, indent=indent) else: - print(f'{" "*indent}{prefix}{param}: {{}}') + print(f'{" " * indent}{prefix}{param}: {{}}') else: self.print_dict(actual_val, param, indent=indent, prefix=prefix) # Check param actual vs expected