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 8da7fce0..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 @@ -22,14 +22,14 @@ 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] - repo: https://github.com/pycqa/flake8 - rev: 6.1.0 + rev: 7.3.0 hooks: - id: flake8 diff --git a/hw_device_mgr/async_task_queue.py b/hw_device_mgr/async_task_queue.py index a9e6afff..6baee8f7 100644 --- a/hw_device_mgr/async_task_queue.py +++ b/hw_device_mgr/async_task_queue.py @@ -1,65 +1,35 @@ import threading import queue -from functools import cached_property, lru_cache +from functools import 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 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") - - @cached_property - def progress_queue(self): - """Property returning the progress queue singleton instance.""" - return self._get_queue("progress") + # Class-level singleton queue data + _queue_names = list() + _cmd_queues = dict() + _errors = dict() + _queue_stop = dict() - def __init__(self): - self.cmd_version = 0 + _queues = list() # - # Worker-related methods + # Class methods: worker thread is managed by the class itself # - # There should only ever be a single worker thread running, even if many - # AsyncTaskQueue instances are enqueuing commands. - # - - 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() - @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() + @classmethod + def _work(cls): + """ + Worker thread loop callback. - # - # Command-side-related methods - # - # Multiple instances may exist, but must all be running in the same - # (probably main) thread. + 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 _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)) + 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() - @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") + # + # Instance methods: Named instances + # + + 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): - """Join worker thread after queue is drained; blocks.""" - 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/cached_attr_mgr.py b/hw_device_mgr/cached_attr_mgr.py new file mode 100644 index 00000000..6361e4bb --- /dev/null +++ b/hw_device_mgr/cached_attr_mgr.py @@ -0,0 +1,14 @@ +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/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/command.py b/hw_device_mgr/cia_301/command.py index 180c8eb3..80259d37 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") @@ -52,10 +53,17 @@ 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.""" + # 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 +72,10 @@ class CiA301SimCommand(CiA301Command): # Per-device param value storage: [address][ix, subix] = value sim_sdo_values = dict() + def sim_sleep(self): + 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 @@ -99,6 +111,7 @@ 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(): if dd["address"][0] != bus: @@ -108,9 +121,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 - return val or 0 + self.sim_sleep() + return val def download( self, @@ -123,4 +137,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 diff --git a/hw_device_mgr/cia_301/config.py b/hw_device_mgr/cia_301/config.py index 697aca4f..0cc5cb0e 100644 --- a/hw_device_mgr/cia_301/config.py +++ b/hw_device_mgr/cia_301/config.py @@ -1,36 +1,43 @@ 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 +class CiA301ConfigException(RuntimeError): + pass + + class CiA301Config(LoggingMixin): """ CiA 301 device configuration interface. - This class presents a high-level configuration interface to CiA 301 - devices. The class can scan the bus for devices and their models & - positions. Class instances correspond to a single device, and can - initialize device parameter values from a configuration at init, and - can upload and download SDO values during operation. + This class presents a high-level configuration interface to + CiA 301 devices. The class can scan the bus for devices and + their models & positions. Class instances correspond to a single + device, and can initialize device parameter values from a + configuration at init, and can upload and download SDO values + during operation. It uses a low-level `CiA301Command` interface to scan the bus and - upload/download object dictionary values, and presents a high-level - interface for manipulating devices. + upload/download object dictionary values, and presents a + high-level interface for manipulating devices. This abstract class must be subclassed and `command_class` defined 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 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 @@ -39,14 +46,19 @@ 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, ): if hasattr(address, "address"): self.address = address.address # Config object passed as address else: self.address = self.canon_address(address) self.model_id = self.format_model_id(model_id) - self.params_queue = AsyncParamsQueue() + self.name = name or str(self.model_id) + self.params_queue = AsyncTaskQueue(self.name) self.skip_optional_config_values = skip_optional_config_values @classmethod @@ -78,6 +90,10 @@ 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 + self.clear_cached_properties() # reset logging_name etc. + def __str__(self): cname = self.__class__.__name__ return f"{cname}:{self.model_id}@{self.address}".replace(" ", "") @@ -85,6 +101,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 # @@ -166,33 +185,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) - msg = f"(was {old})" if old is not None else "" - if val == old: - return # SDO value already correct + val = sdo.data_type(val) 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, @@ -370,33 +377,55 @@ 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"] + 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(): + 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 + + 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): + """ + 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 @@ -415,8 +444,14 @@ def scan_bus(cls, bus=0, skip_optional_config_values=True, **kwargs): **kwargs, ) res.append(config) + config.logger.info(f"{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.""" @@ -424,7 +459,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 8b81e08e..6fbe72b9 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) @@ -40,7 +41,12 @@ 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 + p_state = self.feedback_out.get("param_state") + if self.config.init_params and p_state != self.PARAM_STATE_COMPLETE: + return 30 + return 10 def __init__( self, address=None, skip_optional_config_values=True, **kwargs @@ -55,9 +61,14 @@ 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) + def clear_cached_properties(self, *args): + super().clear_cached_properties(*args) + self.config.clear_cached_properties() + @classmethod @lru_cache def device_model_id(cls): @@ -102,22 +113,50 @@ 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() # 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 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) + 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 + 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 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 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"): + 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") @@ -130,6 +169,13 @@ 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") + 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) @@ -138,12 +184,35 @@ 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 + 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 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: + 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 def munge_sdo_data(cls, sdo_data): # Turn per-model name SDO data from YAML into per-model_id SDO data @@ -179,18 +248,16 @@ 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 @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 @@ -202,10 +269,16 @@ 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.address, **get_device_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.""" @@ -253,17 +326,20 @@ 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 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/base_test_class.py b/hw_device_mgr/cia_301/tests/base_test_class.py index 24af573f..9d9dedd0 100644 --- a/hw_device_mgr/cia_301/tests/base_test_class.py +++ b/hw_device_mgr/cia_301/tests/base_test_class.py @@ -72,21 +72,21 @@ def munge_device_config(cls, device_config): Return a copy of `device_config` with minor processing. Optionally, to make the YAML file reusable, each configuration's - `vendor_id` and `product_code` keys may be replaced with a - `category` key matching a parent of classes listed; this fixture - will re-add those keys. - - The `addresses` key contains a list of device addresses. To be - reusable for EtherCAT, addresses are lists of two or three - integers, `[bus, position, (optional) alias]`. Plain CiA301 - devices don't use aliases, so the `alias` element is removed. + `vendor_id` and `product_code` keys may be replaced with a `category` + key matching a parent of classes listed; this fixture will re-add those + keys. + + The `addresses` key contains a list of device addresses. To be reusable + for EtherCAT, addresses are lists of two or three integers, `[bus, + position, (optional) alias]`. Plain CiA301 devices don't use aliases, + so the `alias` element is removed. """ new_device_config = list() for conf in 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() @@ -130,8 +130,8 @@ def device_config(self, category_cls): """ Device configuration data fixture. - Load device configuration with `load_device_config()` and munge - with `munge_device_config()`. + Load device configuration with `load_device_config()` and munge with + `munge_device_config()`. Device configuration in the same format as non-test configuration, described in `Config` classes. @@ -224,7 +224,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(): @@ -310,7 +310,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/cia_301/tests/read_update_write.cases.yaml b/hw_device_mgr/cia_301/tests/read_update_write.cases.yaml index 4d30d037..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 @@ -13,7 +13,15 @@ goal_reason: Offline fault: False fault_desc: "" - param_state: 0 # Unknown + 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 @@ -22,8 +30,10 @@ 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 + command_out: + init_params: True sim_feedback: oper: True - desc: "NMT Pre-operational -> Operational" @@ -33,7 +43,8 @@ oper: True goal_reached: True goal_reason: Reached - param_state: 2 # Complete + command_out: + init_params: False - desc: "NMT Operational; hold state x1" - desc: "NMT Operational; hold state x2" # @@ -75,11 +86,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" @@ -93,11 +104,13 @@ 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 + command_out: + init_params: True sim_feedback: oper: True - desc: "NMC offline after online; resume operational" @@ -107,7 +120,8 @@ oper: True goal_reached: True goal_reason: Reached - param_state: 0x02 # Complete fault: False fault_desc: "" + command_out: + init_params: False - 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 d7d97202..cfaa8eb8 100644 --- a/hw_device_mgr/cia_301/tests/test_config.py +++ b/hw_device_mgr/cia_301/tests/test_config.py @@ -75,23 +75,29 @@ 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 + 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 pq.all_cmds_complete() + 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(): assert obj.upload(sdo_ix) == val 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..317703ee --- /dev/null +++ b/hw_device_mgr/cia_301/tests/test_device_read_update_write.py @@ -0,0 +1,38 @@ +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.config.init_params = False + 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/device.py b/hw_device_mgr/cia_402/device.py index b7842532..783cdf98 100644 --- a/hw_device_mgr/cia_402/device.py +++ b/hw_device_mgr/cia_402/device.py @@ -25,6 +25,10 @@ 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 + - `velocity_zero`: Drive reports zero speed in PV mode """ data_types = CiA301DataType @@ -48,6 +52,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): @@ -80,8 +86,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; others=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, ) @@ -107,8 +113,10 @@ def control_mode_str(cls, mode): transition="int8", home_success="bit", home_error="bit", + move_setpoint_ack="bit", move_success="bit", - move_error="bit", + following_error="bit", + velocity_zero="bit", ) feedback_out_defaults = dict( **feedback_in_defaults, @@ -116,8 +124,10 @@ def control_mode_str(cls, mode): transition=-1, home_success=False, home_error=False, + move_setpoint_ack=False, move_success=False, - move_error=False, + following_error=False, + velocity_zero=False, ) log_status_word_changes = True @@ -166,28 +176,38 @@ 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 + ) 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, fault_desc=reason, ) 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_setpoint_ack=sp_ack) return success, reason + def get_feedback_pv(self, sw): + # Control mode is PV + self.feedback_out.update( + velocity_zero=self.test_sw_bit(sw, "OPERATION_MODE_SPECIFIC_1") + ) + return True, None + def get_feedback_sto(self): # Process active STO: Raise fault on OPERATION ENABLED command if not self.feedback_in.get("sto"): @@ -195,6 +215,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") @@ -227,28 +253,44 @@ def get_feedback(self): fb_out = super().get_feedback() fb_in = self.feedback_in - # If device not operational, set default "START" state - if not fb_out.get("oper"): - fb_out.update(**self.feedback_out_defaults) + # If shutting down, there's nothing to do here + if self.command_out.get("shutdown_latch"): 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") 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: + 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"): + 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 @@ -264,7 +306,6 @@ def get_feedback(self): ) 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 ( @@ -273,17 +314,10 @@ 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) - - # 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" - ): - fault = True - fault_desc = "Enabled drive unexpectedly disabled" - 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) # Calculate 'transition' feedback new_st, old_st = fb_out.changed("state", return_vals=True) @@ -298,6 +332,25 @@ 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) + + # 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 @@ -311,27 +364,14 @@ def get_feedback(self): 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() - if not sto_success: + elif cm == self.MODE_PV: + pv_success, pv_reason = self.get_feedback_pv(sw) + if not pv_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) + goal_reasons.append(pv_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 @@ -339,27 +379,20 @@ 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"): - sw_old, sw_new = fb_out.changed("status_word", return_vals=True) - sw_old &= 0x3FFF - sw_new &= 0x3FFF - if sw_old != sw_new: - self.logger.info(f"status_word: {self.sw_to_str(sw)}") - if not 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=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") + fb_out.update(goal_reached=goal_reached, goal_reason=goal_reason) return fb_out @classmethod @@ -403,6 +436,7 @@ def sw_to_str(cls, sw): home_request=False, move_request=False, relative_target=False, + quick_stop=False, ) command_in_data_types = dict( state="str", @@ -410,6 +444,7 @@ def sw_to_str(cls, sw): home_request="bit", move_request="bit", relative_target="bit", + quick_stop="bit", ) # ------- Command out ------- @@ -450,7 +485,20 @@ def sw_to_str(cls, sw): "READY TO SWITCH ON": ["SWITCHED ON", 3], "FAULT": ["SWITCH ON DISABLED", 15], "FAULT REACTION ACTIVE": ["FAULT", 14], - "QUICK STOP ACTIVE": ["SWITCH ON DISABLED", 12], + "QUICK STOP ACTIVE": ["OPERATION ENABLED", 16], + }, + "QUICK STOP ACTIVE": { + # OPERATION ENABLED transition to QUICK STOP ACTIVE & stay there; + "OPERATION ENABLED": ["QUICK STOP ACTIVE", 11], + "QUICK STOP ACTIVE": ["QUICK STOP ACTIVE", -1], # End + # Otherwise, transition to SWITCH ON DISABLED + "START": ["START", 0], + "NOT READY TO SWITCH ON": ["SWITCH ON DISABLED", 1], + "READY TO SWITCH ON": ["SWITCH ON DISABLED", 7], + "SWITCHED ON": ["SWITCH ON DISABLED", 10], + "FAULT REACTION ACTIVE": ["FAULT", 14], + "FAULT": ["SWITCH ON DISABLED", 15], + "SWITCH ON DISABLED": ["SWITCH ON DISABLED", -1], # End }, # These tr'ns take longer from OPERATION ENABLED -> SWITCH ON DISABLED # 'OPERATION ENABLED': ['SWITCHED ON', 5], @@ -472,10 +520,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 - "OPERATION ENABLED": ["QUICK STOP ACTIVE", 11], - "QUICK STOP ACTIVE": ["SWITCH ON DISABLED", 12], # Drives in all other states transition to SWITCH ON DISABLED + "OPERATION ENABLED": ["SWITCH ON DISABLED", 9], + "QUICK STOP ACTIVE": ["SWITCH ON DISABLED", 12], "START": ["NOT READY TO SWITCH ON", 0], "NOT READY TO SWITCH ON": ["SWITCH ON DISABLED", 1], "SWITCH ON DISABLED": ["SWITCH ON DISABLED", -1], # End state @@ -496,14 +543,25 @@ 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) + state_cmd = self.command_in.get("state") + if state_cmd == "OPERATION ENABLED": + if self.command_in.get("quick_stop"): + # Override current command in + self.command_in.update(state="QUICK STOP ACTIVE") + if self.command_in.changed("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 + 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 - 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"): @@ -514,19 +572,18 @@ 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 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 + # 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 @@ -537,7 +594,14 @@ 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 + 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, + ) @classmethod @lru_cache @@ -565,23 +629,16 @@ def _get_next_control_word(self, cmd_out): # Add flags and return next_cm = cmd_out.get("control_mode") - operation_mode_specific_3 = False + cw_flags = dict(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) @@ -597,7 +654,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 } @@ -657,9 +714,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, @@ -695,6 +752,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): @@ -715,7 +774,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"): - # If `home_request` is set, command homing mode next_cm = self.MODE_HM else: # Otherwise, copy control_mode from command_in @@ -725,6 +783,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): @@ -739,10 +799,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) @@ -759,6 +827,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 ------- @@ -771,23 +841,37 @@ 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 - - def set_sim_feedback_pp(self, cw, sw): + 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 + 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: ?? + verr = abs(fb_in.get("velocity_cmd") - fb_in.get("velocity_fb")) + return verr < self.velocity_goal_tolerance + elif control_mode == self.MODE_PT: + terr = abs(fb_in.get("torque_cmd") - fb_in.get("torque_fb")) + return terr < self.torque_goal_tolerance + + 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 + # 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) else: return dict() @@ -841,10 +925,11 @@ 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)) + sw_flags.update(self.set_sim_feedback_ppvt(cw_prev, sw_prev)) + status_word = self.add_status_word_flags(status_word, **sw_flags) sfb.update( 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..f0cb84ad 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,22 +39,35 @@ goal_reached: True goal_reason: Reached move_success: False - move_error: 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 position_fb: 0.0 sto: False error_code: 0x00000000 description: No error fault_desc: "" + shutdown_complete: False command_in: state: OPERATION ENABLED control_mode: 8 + reset_fault: False home_request: True move_request: False relative_target: False + shutdown: False + quick_stop: False command_out: control_word: 0x000F control_mode: 6 + init_params: False + fasttrack: False + shutdown_latch: False sim_feedback: online: True oper: True @@ -58,6 +75,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 @@ -87,12 +108,14 @@ # 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 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 aebc3bbb..0e220bee 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,22 +41,35 @@ goal_reached: True goal_reason: Reached move_success: False - move_error: 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 position_fb: 15.0 sto: False error_code: 0x00000000 description: No error fault_desc: "" + shutdown_complete: False command_in: state: OPERATION ENABLED control_mode: 1 # MODE_PP + reset_fault: False home_request: False move_request: True relative_target: False + shutdown: False + quick_stop: 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 @@ -60,6 +77,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 @@ -81,6 +102,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 +114,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 @@ -103,12 +126,14 @@ # 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 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 new file mode 100644 index 00000000..ec01c060 --- /dev/null +++ b/hw_device_mgr/cia_402/tests/pt.cases.yaml @@ -0,0 +1,231 @@ +# 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 + quick_stop: 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..99268d08 --- /dev/null +++ b/hw_device_mgr/cia_402/tests/pv.cases.yaml @@ -0,0 +1,231 @@ +# 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 + quick_stop: 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 9ea68fa9..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 @@ -13,11 +13,16 @@ 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 error_code: 0x00000000 feedback_out: + shutdown_complete: False # CiA 301 online: False oper: False @@ -34,7 +39,13 @@ goal_reached: False goal_reason: Offline move_success: False - move_error: 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 position_fb: 0 # STO @@ -44,16 +55,22 @@ description: No error fault_desc: "" command_in: + shutdown: False # CiA 402 state: SWITCH ON DISABLED control_mode: 8 # MODE_CSP home_request: False move_request: False relative_target: False + reset_fault: False + quick_stop: False command_out: + shutdown_latch: False # CiA 402 control_word: 0x0000 control_mode: 8 # MODE_CSP + init_params: False + fasttrack: False sim_feedback: # CiA 301 online: True @@ -63,6 +80,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 @@ -74,8 +95,10 @@ 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 + command_out: + init_params: True sim_feedback: # CiA 301 oper: True @@ -96,6 +119,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 @@ -181,9 +206,8 @@ state: FAULT REACTION ACTIVE 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 + 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: @@ -199,7 +223,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 @@ -214,7 +238,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: @@ -228,6 +252,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: "" @@ -252,8 +277,9 @@ 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_reached: True + goal_reason: Fault state reached; state FAULT REACTION ACTIVE != OPERATION ENABLED error_code: 0xDEADBEEF description: Unknown error code 0xDEADBEEF command_out: @@ -269,7 +295,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 @@ -278,8 +304,8 @@ error_code: 0xDEADBEEF # Bogus error code feedback_out: transition: -1 - goal_reached: True 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 @@ -315,7 +341,6 @@ - desc: "Disable: Hold state x1" feedback_out: transition: -1 - goal_reached: True goal_reason: Reached - desc: "Disable: Hold state x2" @@ -330,7 +355,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" # @@ -397,8 +422,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 @@ -414,33 +437,18 @@ # 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 - 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) - command_out: - control_word: 0x0000 + 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: 12 - goal_reached: True - goal_reason: Reached + 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 @@ -473,8 +481,7 @@ # 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 + 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: @@ -496,6 +503,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: "" @@ -508,7 +516,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 @@ -595,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" @@ -686,6 +693,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 @@ -704,6 +712,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)" @@ -715,6 +724,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 @@ -743,6 +753,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 @@ -762,6 +774,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" @@ -789,10 +802,10 @@ status_word: 0x001F # FAULT REACTION ACTIVE - Bit 12 SETPOINT_ACK clear state: FAULT REACTION ACTIVE transition: 13 # (Any)->FAULT REACTION ACTIVE - goal_reason: state FAULT REACTION ACTIVE != OPERATION ENABLED; Move request while drive not enabled; Fault (no error code) - move_error: True + goal_reached: True + 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: @@ -806,8 +819,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) - move_error: True + goal_reason: Fault state reached; state FAULT != OPERATION ENABLED; Move request while drive not enabled command_out: control_word: 0x0080 # Clear fault sim_feedback: @@ -821,7 +833,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: @@ -829,6 +841,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" @@ -838,8 +851,8 @@ 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 fault_desc: "" command_in: 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..e84bf5d4 --- /dev/null +++ b/hw_device_mgr/cia_402/tests/test_device_read_update_write.py @@ -0,0 +1,137 @@ +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 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 = 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): + # 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/device.py b/hw_device_mgr/device.py index 461b1ff5..614c55cf 100644 --- a/hw_device_mgr/device.py +++ b/hw_device_mgr/device.py @@ -22,9 +22,16 @@ 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", ) - command_in_data_types = dict() - command_out_data_types = dict() feedback_in_defaults = dict() feedback_out_defaults = dict( @@ -32,9 +39,21 @@ 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_in_defaults = dict() - command_out_defaults = dict() + command_out_defaults = dict( + fasttrack=False, + shutdown_latch=False, + ) + + feedback_in_overlap = set() + feedback_out_overlap = set() + command_in_overlap = set() + command_out_overlap = set() interface_names = { "feedback_in", @@ -45,6 +64,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.""" @@ -55,8 +77,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): """ @@ -73,18 +96,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 @@ -107,11 +133,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) @@ -125,15 +151,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() @@ -146,8 +163,21 @@ 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): + """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 @@ -181,9 +211,19 @@ 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 - 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("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 def write(self): """Write `command_out` to hardware interface.""" @@ -291,6 +331,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 @@ -383,6 +428,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", @@ -403,7 +449,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. @@ -425,6 +471,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): @@ -451,5 +498,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/devices/device_err/inovance_is620n.yaml b/hw_device_mgr/devices/device_err/inovance_is620n.yaml index 23ed386b..7d27b67c 100644 --- a/hw_device_mgr/devices/device_err/inovance_is620n.yaml +++ b/hw_device_mgr/devices/device_err/inovance_is620n.yaml @@ -1,433 +1,489 @@ # From Inovance drive manual, table 9.2.1 "Fault Code List" (type=1,2) # and table 9.2.2 "Warning Code List" (type=3) # -# key: "203Fh (Auxiliary Code)" column; multiple values in that -# column (esp. 104) are individually enumerated with same values # display: "Display" column; code displayed on drive LED panel # description: "Fault Name" column # type: "Type" column; indicates severity, with 1 most severe # resettable: "Resettable" column; indicates whether resettable # without power cycle # error_code: "603Fh (Error Code)" column +# auxiliary_code: "203Fh (Auxiliary Code)" column; may have +# multiple values -'0x01010101': +'0x0101': description: Parameter abnormal type: 1 resettable: false display: 101 error_code: 0x6320 -'0x01020102': + auxiliary_code: 0x01010101 +'0x0102': description: Programmable logic configuration fault type: 1 resettable: false display: 102 error_code: 0x7500 -'0x01030103': + auxiliary_code: 0x01020102 +'0x0103': description: FPGA software version too early type: 1 resettable: false display: 103 error_code: 0x7500 -'0x01040104': + auxiliary_code: 0x01030103 +'0x0104': description: Programmable logic interruption fault type: 1 resettable: false display: 104 error_code: 0x7500 -'0x01000104': - description: Programmable logic interruption fault - type: 1 - resettable: false - display: 104 - error_code: 0x7500 -'0x0E940104': - description: Programmable logic interruption fault - type: 1 - resettable: false - display: 104 - error_code: 0x7500 -'0x01050105': + auxiliary_code: 0x01040104 0x01000104 0x0E940104 +'0x0105': description: Internal program abnormal type: 1 resettable: false display: 105 error_code: 0x6320 -'0x01080108': + auxiliary_code: 0x01050105 +'0x0108': description: Parameter storage fault type: 1 resettable: false display: 108 error_code: 0x5530 -'0x01110111': + auxiliary_code: 0x01080108 +'0x0111': description: Group 2000h/2001h parameter abnormal type: 1 resettable: false display: 111 error_code: 0x6320 -'0x01200120': + auxiliary_code: 0x01110111 +'0x0120': description: Product model matching fault type: 1 resettable: false display: 120 error_code: 0x7122 -'0x01210121': + auxiliary_code: 0x01200120 +'0x0121': description: Invalid S-ON command type: 2 resettable: true display: 121 error_code: 0x5441 -'0x01220122': + auxiliary_code: 0x01210121 +'0x0122': description: Product matching fault in absolute position mode type: 1 resettable: false display: 122 error_code: 0x7122 -'0x01300130': + auxiliary_code: 0x01220122 +'0x0130': description: Different DIs allocated with the same function type: 1 resettable: true display: 130 error_code: 0x6320 -'0x01310131': + auxiliary_code: 0x01300130 +'0x0131': description: DO function No. exceeding the number of functions type: 1 resettable: true display: 131 error_code: 0x6320 -'0x01360136': + auxiliary_code: 0x01310131 +'0x0136': description: Data check error or no parameter stored in the motor ROM type: 1 resettable: false display: 136 error_code: 0x7305 -'0x02000200': + auxiliary_code: 0x01360136 +'0x0200': description: Overcurrent 1 type: 1 resettable: false display: 200 error_code: 0x2311 -'0x02010201': + auxiliary_code: 0x02000200 +'0x0201': description: Overcurrent 2 type: 1 resettable: false display: 201 error_code: 0x2312 -'0x02070207': + auxiliary_code: 0x02010201 +'0x0207': description: Shaft D/Q current overflow type: 1 resettable: true display: 207 error_code: 0x0FFF -'0x02080208': + auxiliary_code: 0x02070207 +'0x0208': description: FPGA sampling operation timeout type: 1 resettable: false display: 208 error_code: 0x0FFF -'0x02100210': + auxiliary_code: 0x02080208 +'0x0210': description: Output short-circuit to ground type: 1 resettable: false display: 210 error_code: 0x2330 -'0x02200220': + auxiliary_code: 0x02100210 +'0x0220': description: Phase sequence incorrect type: 1 resettable: false display: 220 error_code: 0x0FFF -'0x02340234': + auxiliary_code: 0x02200220 +'0x0234': description: Runaway type: 1 resettable: false display: 234 error_code: 0x0FFF -'0x04000400': + auxiliary_code: 0x02340234 +'0x0400': description: Main circuit overvoltage type: 1 resettable: true display: 400 error_code: 0x3210 -'0x04100410': + auxiliary_code: 0x04000400 +'0x0410': description: Main circuit undervoltage type: 1 resettable: true display: 410 error_code: 0x3220 -'0x04200420': + auxiliary_code: 0x04100410 +'0x0420': description: Main circuit phase loss type: 2 resettable: true display: 420 error_code: 0x3130 -'0x04300430': + auxiliary_code: 0x04200420 +'0x0430': description: Control power undervoltage type: 1 resettable: false display: 430 error_code: 0x3120 -'0x05000500': + auxiliary_code: 0x04300430 +'0x0500': description: Motor overspeed type: 1 resettable: true display: 500 error_code: 0x8400 -'0x05100510': + auxiliary_code: 0x05000500 +'0x0510': description: Pulse output overspeed type: 2 resettable: true display: 510 error_code: 0x0FFF -'0x06020602': + auxiliary_code: 0x05100510 +'0x0602': description: Angle auto-tuning failure type: 1 resettable: true display: 602 error_code: 0x0FFF -'0x06100610': + auxiliary_code: 0x06020602 +'0x0610': description: Servo drive overload type: 2 resettable: true display: 610 error_code: 0x3230 -'0x06200620': + auxiliary_code: 0x06100610 +'0x0620': description: Motor overload type: 2 resettable: true display: 620 error_code: 0x3230 -'0x06300630': + auxiliary_code: 0x06200620 +'0x0630': description: Motor rotor locked type: 2 resettable: true display: 630 error_code: 0x7121 -'0x06500650': + auxiliary_code: 0x06300630 +'0x0650': description: Heatsink overheat type: 2 resettable: true display: 650 error_code: 0x4210 -'0x07300731': + auxiliary_code: 0x06500650 +'0x0731': description: Encoder battery failed type: 2 resettable: true display: 731 error_code: 0x7305 -'0x07300732': + auxiliary_code: 0x07300731 +'0x0732': description: Encoder multi-turn counting error type: 2 resettable: true display: 733 error_code: 0x7305 -'0x07300733': + auxiliary_code: 0x07300732 +'0x0733': description: Encoder multi-turn counting overflow type: 2 resettable: true display: 735 error_code: 0x7305 -'0x07400740': + auxiliary_code: 0x07300733 +'0x0740': description: Encoder interference type: 1 resettable: false display: 740 error_code: 0x7305 + auxiliary_code: 0x07400740 solution: Caused by spurious inputs on the encoder Z wire. Can be caused by drive logic power-off (not an error), encoder wire damage, electromagnetic interference, or a bad encoder. -'0x07700770': +'0x0770': description: External encoder scale fault type: 1 resettable: true display: 770 error_code: 0x7305 -'0x0A330A33': + auxiliary_code: 0x07700770 +'0x0A33': description: Encoder data abnormal type: 1 resettable: false display: A33 error_code: 0x7305 -'0x0A340A34': + auxiliary_code: 0x0A330A33 +'0x0A34': description: Encoder communication check abnormal type: 1 resettable: false display: A34 error_code: 0x7305 -'0x0A350A35': + auxiliary_code: 0x0A340A34 +'0x0A35': description: Z signal lost type: 1 resettable: false display: A35 error_code: 0x7305 -'0x0b000b00': + auxiliary_code: 0x0A350A35 +'0x0b00': description: Position deviation excess type: 2 resettable: true display: B00 error_code: 0x8611 -'0x0b010b01': + auxiliary_code: 0x0b000b00 +'0x0b01': description: Position reference excess type: 2 resettable: YES display: B01 error_code: 0x0FFF -'0x0b020b02': + auxiliary_code: 0x0b010b01 +'0x0b02': description: Position deviation exceeding threshold in fully closed-loop type: 2 resettable: true display: B02 error_code: 0x8611 -'0x0b030b03': + auxiliary_code: 0x0b020b02 +'0x0b03': description: Electronic gear ratio setting exceeding limit type: 2 resettable: true display: B03 error_code: 0x6320 -'0x0B040B04': + auxiliary_code: 0x0b030b03 +'0x0B04': description: Parameter setting error with fully closed-loop function type: 2 resettable: true display: B04 error_code: 0x6320 -'0x0d090d09': + auxiliary_code: 0x0B040B04 +'0x0d09': description: Software upper/lower limit setting incorrect* type: 2 resettable: true display: D09 error_code: 0x6320 -'0x0d100d10': + auxiliary_code: 0x0d090d09 +'0x0d10': description: Home offset setting incorrect* type: 2 resettable: true display: D10 error_code: 0x6320 -'0x0E070E07': + auxiliary_code: 0x0d100d10 +'0x0E07': description: Network state abnormal switchover type: 2 resettable: true display: E07 error_code: 0x0FFF -'0x0E080E08': + auxiliary_code: 0x0E070E07 +'0x0E08': description: Synchronization loss* type: 2 resettable: true display: E08 error_code: 0x0FFF -'0x0E110E11': + auxiliary_code: 0x0E080E08 +'0x0E11': description: XML configuration file not burnt type: 2 resettable: true display: E11 error_code: 0x0FFF -'0x0E120E12': + auxiliary_code: 0x0E110E11 +'0x0E12': description: Network initialization failure* type: 2 resettable: true display: E12 error_code: 0x0E12 -'0x0E130E13': + auxiliary_code: 0x0E120E12 +'0x0E13': description: Synchronization cycle setting incorrect* type: 2 resettable: true display: E13 error_code: 0x0E13 -'0x0E150E15': + auxiliary_code: 0x0E130E13 +'0x0E15': description: Synchronization cycle error being large* type: 2 resettable: true display: E15 error_code: 0x0E15 -'0x01100110': + auxiliary_code: 0x0E150E15 +'0x0110': description: Setting error of frequency-division pulse output type: 3 resettable: true display: 110 error_code: 0x6320 -'0x06010601': + auxiliary_code: 0x01100110 +'0x0601': description: Homing timeout type: 3 resettable: true display: 601 error_code: 0x0FFF -'0x07300730': + auxiliary_code: 0x06010601 +'0x0730': description: Encoder battery warning type: 3 resettable: true display: 730 error_code: 0x7305 -'0x09000900': + auxiliary_code: 0x07300730 +'0x0900': description: DI emergency braking type: 3 resettable: true display: 900 error_code: 0x5442 -'0x09090909': + auxiliary_code: 0x09000900 +'0x0909': description: Motor overload warning type: 3 resettable: true display: 909 error_code: 0x3230 -'0x09200920': + auxiliary_code: 0x09090909 +'0x0920': description: Regenerative resistor overload type: 3 resettable: true display: 920 error_code: 0x3210 -'0x09220922': + auxiliary_code: 0x09200920 +'0x0922': description: Resistance of external braking resistor too small type: 3 resettable: true display: 922 error_code: 0x6320 -'0x09390939': + auxiliary_code: 0x09220922 +'0x0939': description: Motor power cable breaking type: 3 resettable: true display: 939 error_code: 0x3331 -'0x09410941': + auxiliary_code: 0x09390939 +'0x0941': description: Parameter modification taking effect only after power-on again type: 3 resettable: true display: 941 error_code: 0x6320 -'0x09420942': + auxiliary_code: 0x09410941 +'0x0942': description: Parameter storage too frequent type: 3 resettable: true display: 942 error_code: 0x7600 -'0x09500950': + auxiliary_code: 0x09420942 +'0x0950': description: Positive limit switch warning type: 3 resettable: true display: 950 error_code: 0x5443 -'0x09520952': + auxiliary_code: 0x09500950 +'0x0952': description: Negative limit switch warning type: 3 resettable: true display: 952 error_code: 0x5444 -'0x09800980': + auxiliary_code: 0x09520952 +'0x0980': description: Encoder internal fault type: 3 resettable: true display: 980 error_code: 0x7305 -'0x09900990': + auxiliary_code: 0x09800980 +'0x0990': description: Power input phase loss warning type: 3 resettable: true display: 990 error_code: 0x3130 -'0x09980998': + auxiliary_code: 0x09900990 +'0x0998': description: Homing mode setting incorrect type: 3 resettable: true display: 998 error_code: 0x0FFF -'0x0A400A40': + auxiliary_code: 0x09980998 +'0x0A40': description: Parameter auto-tuning failure type: 3 resettable: true display: A40 error_code: 0x0FFF + auxiliary_code: 0x0A400A40 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_err/inovance_sv660n.yaml b/hw_device_mgr/devices/device_err/inovance_sv660n.yaml index 48009824..6a81daa1 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,102 @@ # # 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': +'0x0939': + display: E939.0 + description: Motor power cables disconnected + type: 1 + resettable: true +'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/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 100644 index 00000000..55145178 --- /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/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 new file mode 100644 index 00000000..55ceb5dd --- /dev/null +++ b/hw_device_mgr/devices/device_xml/SV670_EOE_1Axis_05003_220801.xml @@ -0,0 +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 + + + + diff --git a/hw_device_mgr/devices/inovance_std60.py b/hw_device_mgr/devices/inovance_std60.py new file mode 100644 index 00000000..84cc1fe2 --- /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("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 diff --git a/hw_device_mgr/devices/inovance_sv660.py b/hw_device_mgr/devices/inovance_sv660.py index bb7fdb6d..eb05567b 100644 --- a/hw_device_mgr/devices/inovance_sv660.py +++ b/hw_device_mgr/devices/inovance_sv660.py @@ -1,7 +1,9 @@ -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 +from functools import lru_cache +import time class InovanceSV660Config(EtherCATConfig): @@ -30,6 +32,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("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.""" @@ -45,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") @@ -58,8 +93,17 @@ 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, CiA402SimDevice): +class SimInovanceSV660(InovanceSV660, EtherCATSimDevice, CiA402SimDevice): def set_sim_feedback(self): # Simulate home_found feedback sfb = super().set_sim_feedback() diff --git a/hw_device_mgr/devices/inovance_sv670.py b/hw_device_mgr/devices/inovance_sv670.py new file mode 100644 index 00000000..551cf25e --- /dev/null +++ b/hw_device_mgr/devices/inovance_sv670.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 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("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" + xml_description_fname = "SV670_EOE_1Axis_05003_220801.xml" + device_error_package = "hw_device_mgr.devices.device_err" + device_error_yaml = "inovance_sv660n.yaml" + config_class = InovanceSV670Config + 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 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 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 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): 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..e4fc469e --- /dev/null +++ b/hw_device_mgr/devices/tests/test_device_read_update_write.py @@ -0,0 +1,30 @@ +from .base_test_class import BaseDevicesTestClass +from ...ethercat.tests.test_device_read_update_write import ( + TestEtherCATDeviceRUW as _TestEtherCATDeviceRUW, +) +import re +from functools import lru_cache + + +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") + + @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..5040bf0c 100644 --- a/hw_device_mgr/devices/tests/test_devices.py +++ b/hw_device_mgr/devices/tests/test_devices.py @@ -10,3 +10,12 @@ 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 fd73e94a..9c2da93b 100644 --- a/hw_device_mgr/errors/device.py +++ b/hw_device_mgr/errors/device.py @@ -11,8 +11,7 @@ class ErrorDevice(Device, ConfigIO): Error code is fed into `error_code` feedback. The `set_feedback()` method looks up the error code in the - `device_err/{name}.yaml` file and adds `description` strings to - feedback. + `device_err/{name}.yaml` file and adds `description` strings to feedback. """ device_error_package = None @@ -52,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/ethercat/command.py b/hw_device_mgr/ethercat/command.py index f3ef2726..b519fdc0 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,41 @@ 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 88e65f7c..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. @@ -13,9 +22,9 @@ class EtherCATConfig(CiA301Config): EtherCAT CoE shares much in common with CiA 301, and this class subclasses `CiA301Config`. - Each EtherCAT device comes with an ESI "EtherCAT Slave Information" - XML file that describes the device's object dictionary, sync - managers, etc. + Each EtherCAT device comes with an ESI "EtherCAT Slave + Information" XML file that describes the device's object + dictionary, sync managers, etc. """ data_type_class = EtherCATDataType @@ -38,6 +47,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) @@ -133,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/ethercat/device.py b/hw_device_mgr/ethercat/device.py index 68092ed0..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() @@ -105,22 +108,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 - 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) - 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/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/ethercat/xml_reader.py b/hw_device_mgr/ethercat/xml_reader.py index 386746d0..4899f713 100644 --- a/hw_device_mgr/ethercat/xml_reader.py +++ b/hw_device_mgr/ethercat/xml_reader.py @@ -96,7 +96,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, @@ -215,39 +215,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/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 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..594c0ea9 --- /dev/null +++ b/hw_device_mgr/hal/tests/test_device_read_update_write.py @@ -0,0 +1,71 @@ +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.config.init_params = False + self.obj.init(comp=mock_halcomp) + yield self.obj + + ######################################### + # Test read()/update()/write() integration + # + + 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(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/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/lcec/command.py b/hw_device_mgr/lcec/command.py index 519d295f..18dd90cf 100644 --- a/hw_device_mgr/lcec/command.py +++ b/hw_device_mgr/lcec/command.py @@ -17,6 +17,18 @@ 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 +109,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 +133,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}", @@ -139,6 +145,21 @@ def download( **kwargs, ) + def alias( + self, + address=None, + alias=None, + **kwargs, + ): + self._ethercat( + "alias", + *self.address_to_args(address), + "--", + str(alias), + log_lev="info", + **kwargs, + ) + class LCECSimCommand(LCECCommand, EtherCATSimCommand): """Simulated LCEC device.""" diff --git a/hw_device_mgr/lcec/config.py b/hw_device_mgr/lcec/config.py index 3e840801..508226d1 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() diff --git a/hw_device_mgr/lcec/tests/base_test_class.py b/hw_device_mgr/lcec/tests/base_test_class.py index e4a7413e..282ebfd9 100644 --- a/hw_device_mgr/lcec/tests/base_test_class.py +++ b/hw_device_mgr/lcec/tests/base_test_class.py @@ -81,7 +81,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( 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..6da13646 --- /dev/null +++ b/hw_device_mgr/lcec/tests/test_device_read_update_write.py @@ -0,0 +1,19 @@ +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.config.init_params = False + self.obj.init(comp=mock_halcomp) + yield self.obj diff --git a/hw_device_mgr/logging/__init__.py b/hw_device_mgr/logging/__init__.py index 78d37e48..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 +from functools import cached_property, lru_cache +from ..cached_attr_mgr import CachedAttrMixin class Logging: @@ -28,6 +29,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]) @@ -41,14 +43,22 @@ def getLogger(cls, name): return cls(name) -class LoggingMixin: +class LoggingMixin(CachedAttrMixin): """Mixin class that provides a `logger` attribute.""" logging_class = Logging + @cached_property 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()) + 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/mgr/mgr.py b/hw_device_mgr/mgr/mgr.py index 5a47824c..4b288e0e 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, @@ -44,6 +45,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 +53,7 @@ def device_model_id(cls): command_complete="bit", reset="bit", drive_state="str", + reset_fault_cmd="bit", ) #################################################### @@ -76,13 +79,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): + # 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(), ): @@ -95,9 +100,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: @@ -130,9 +132,14 @@ 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` cmd, controlled by manager - command_in={"state"}, + # - Don't expose device `state`, `reset_fault`, `shutdown`, + # controlled by manager + command_in={"state", "reset_fault", "shutdown"}, ) @lru_cache @@ -166,6 +173,13 @@ 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", ) @@ -180,18 +194,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): - if self.fsm_check_devices_online(e, "INIT"): - return False - return self.fsm_check_drive_goal_state(e) + 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 @@ -217,6 +241,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): @@ -242,7 +267,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) @@ -250,6 +276,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 # @@ -294,7 +335,7 @@ 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): @@ -331,6 +372,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( @@ -348,7 +394,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 +412,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.""" @@ -397,6 +447,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: @@ -423,6 +474,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): @@ -458,7 +513,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 @@ -517,7 +572,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, @@ -525,23 +580,30 @@ 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 # 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 @@ -571,7 +633,10 @@ def set_command(self, **cmd_in_kwargs): ) if new_state_cmd: self.logger.warning("Ignoring new state command") - cmd_out.update(state=self.STATE_FAULT, state_log="Manager fault") + cmd_out.update( + state=self.STATE_FAULT, + state_log="Manager fault", + ) elif new_state_cmd: # state_set went high; latch state_cmd from kwargs cmd_out.update( @@ -590,15 +655,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 @@ -630,23 +695,11 @@ 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()) + 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 @@ -654,18 +707,25 @@ def set_drive_command(self): # 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( + 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"), - **{ - k: mgr_vals[f"{prefix}{k}"] - for k in dev_command_in.keys() - if k not in skip - }, + reset_fault=reset, ) + dev.set_command(**kwargs) else: dev.set_command( + shutdown=shutdown, state=self.command_out.get("drive_state"), + reset_fault=reset, ) + if dev.command_out.get("fasttrack"): + self.fast_track = True def query_devices(self, changed=False, **kwargs): res = list() 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/read_update_write.cases.yaml b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml index 0c803b53..1ad31f37 100644 --- a/hw_device_mgr/mgr/tests/read_update_write.cases.yaml +++ b/hw_device_mgr/mgr/tests/read_update_write.cases.yaml @@ -14,6 +14,10 @@ d.x.control_mode_fb: 0 # Undefined d.x.position_cmd: 0.0 d.x.position_fb: 0.0 + d.x.velocity_cmd: 0 + d.x.velocity_fb: 0 + d.x.torque_cmd: 0 + d.x.torque_fb: 0 # - STO d.x.sto: False # - errors @@ -25,7 +29,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 @@ -43,33 +49,44 @@ d.x.goal_reached: False d.x.goal_reason: Offline d.x.move_success: False - d.x.move_error: False + d.x.velocity_zero: False + d.x.move_setpoint_ack: False + d.x.following_error: False # - STO d.x.sto: False # - errors 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 + reset_fault: False # Drives # - CiA 402 d.x.control_mode: 8 # MODE_CSP d.x.home_request: False d.x.move_request: False d.x.relative_target: False + d.x.quick_stop: False command_out: + shutdown_latch: False # 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 + d.x.shutdown_latch: False # - 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 # - CiA 301 @@ -80,6 +97,10 @@ d.x.control_mode_fb: 0 # Undefined d.x.position_cmd: 0.0 d.x.position_fb: 0.0 + d.x.velocity_cmd: 0 + d.x.velocity_fb: 0 + d.x.torque_cmd: 0 + d.x.torque_fb: 0 # - STO d.x.sto: False # - errors @@ -93,14 +114,17 @@ 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 + command_out: + d.x.init_params: True sim_feedback: # Drives # - CiA 301 @@ -126,6 +150,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 @@ -151,10 +177,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: @@ -165,7 +192,7 @@ - desc: "Init: Hold state 1" feedback_out: goal_reached: True - goal_reason: "" + goal_reason: Reached - desc: "Init: Hold state 2" # @@ -239,7 +266,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" @@ -248,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 @@ -258,18 +285,16 @@ 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]}) + 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_reached: False - 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: @@ -277,67 +302,45 @@ 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: state QUICK STOP ACTIVE != FAULT; FAULT command from controller (was OPERATION ENABLED) ({drives[0]},{drives[2]},{drives3plus}) - fault_desc: 0xDEADBEEF Unknown error code 0xDEADBEEF ({drives[1]}) + goal_reason: Waiting on device manager internal transitions # 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.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 (was OPERATION ENABLED) - 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) + d.x.fault_desc: FAULT command from controller (from state OPERATION ENABLED) + 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 # 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 -- desc: "Sim fault: Non-faulted drives enter SWITCH ON DISABLED" - 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: "" - 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.goal_reached: True - d.x.goal_reason: Reached - desc: "Sim fault: Hold fault command x1" sim_feedback_set: d.1.error_code: 0xDEADBEEF # Bogus error code feedback_out: + goal_reached: True + goal_reason: Reached d.x.transition: -1 # No transition - desc: "Sim fault: Hold fault command x2" sim_feedback_set: @@ -433,17 +436,16 @@ d.1.status_word: 0x0033 # SWITCHED ON + VOLTAGE_ENABLED 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]}) + 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_reached: False - 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 @@ -468,13 +470,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 @@ -497,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: @@ -547,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 @@ -680,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 @@ -749,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" @@ -784,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 @@ -796,8 +798,9 @@ 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 + d.2.goal_reason: Fault state reached; state SWITCH ON DISABLED != SWITCHED ON command_in: state_set: 0 # clear command latch command_out: @@ -821,7 +824,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 @@ -832,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.py b/hw_device_mgr/mgr/tests/test_mgr.py index 0b913d7d..8932ad59 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): @@ -16,67 +13,13 @@ 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, - 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])\.(.*)$") - 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}") @@ -91,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) @@ -105,168 +48,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..815378a8 --- /dev/null +++ b/hw_device_mgr/mgr/tests/test_mgr_read_update_write.py @@ -0,0 +1,260 @@ +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, extra_obj_fixtures + ): + 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])\.(.*)$") + 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, 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"}: + # 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 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) + + 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 + # 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..1ce1888e --- /dev/null +++ b/hw_device_mgr/mgr_hal/tests/test_mgr_read_update_write.py @@ -0,0 +1,65 @@ +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, double=False): + 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}, double=double + ) + + 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/mgr.py b/hw_device_mgr/mgr_ros/mgr.py index eaa5ec25..517fff6f 100644 --- a/hw_device_mgr/mgr_ros/mgr.py +++ b/hw_device_mgr/mgr_ros/mgr.py @@ -5,37 +5,65 @@ 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. - - The ROS param `device_config_path` must be a `str` containing - the path to the device configuration YAML file. - - 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 + # 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() + 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. + + 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. + + The ROS param `device_config_path` must be a `str` containing the path + to the device configuration YAML file. + + 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. + """ self.logger.info(f"Initializing '{self.name}' ROS node") # - mgr_config if "mgr_config" in kwargs: @@ -53,14 +81,6 @@ def init(self, /, argv, **kwargs): 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: - 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 3866ac29..f789334b 100644 --- a/hw_device_mgr/mgr_ros/tests/base_test_class.py +++ b/hw_device_mgr/mgr_ros/tests/base_test_class.py @@ -65,8 +65,8 @@ def device_config(self, sim_device_data_path): """ Device configuration data fixture. - Load device configuration with `load_device_config()` and munge - with `munge_device_config()`. + Load device configuration with `load_device_config()` and munge with + `munge_device_config()`. Device configuration in the same format as non-test configuration, described in `Config` classes. @@ -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 a120f243..69a0395a 100644 --- a/hw_device_mgr/mgr_ros/tests/test_mgr.py +++ b/hw_device_mgr/mgr_ros/tests/test_mgr.py @@ -18,10 +18,9 @@ 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()) + 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 new file mode 100644 index 00000000..b735a83d --- /dev/null +++ b/hw_device_mgr/mgr_ros/tests/test_mgr_read_update_write.py @@ -0,0 +1,20 @@ +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() signature changed, so can't use parent test class obj fixture + self.obj = self.device_class() + self.obj.init() + for d in self.obj.devices: + d.config.init_params = False + 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 437fea31..83e904d4 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 ( @@ -39,7 +38,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): @@ -65,7 +64,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 @@ -87,7 +86,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: @@ -207,7 +206,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 @@ -235,11 +234,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/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 diff --git a/hw_device_mgr/tests/test_device.py b/hw_device_mgr/tests/test_device.py index c92c5f2e..e6f08a1e 100644 --- a/hw_device_mgr/tests/test_device.py +++ b/hw_device_mgr/tests/test_device.py @@ -11,9 +11,19 @@ class TestDevice(BaseTestClass): "SimDevice", "Device", "LoggingMixin", + "CachedAttrMixin", "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 +204,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..30187825 --- /dev/null +++ b/hw_device_mgr/tests/test_device_read_update_write.py @@ -0,0 +1,275 @@ +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 & mgr state + # + # Unlike check data, override data isn't carried over from + # previous iterations + # + self.set_override_data(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 + } + + self.read_update_write_conv_test_data() + # 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()) + dst.setdefault(intf, dict()).update(values) + + # + # Read, get_feedback, set_command, write + # + def read_and_check(self): + 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): + self.override_data("feedback_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): + 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") + 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, 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, double=False): + ovr_data = self.ovr_data.get(interface, dict()) + if not ovr_data: + print(f" {interface}: {{}} (no overrides)") + return + 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) + + 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, expected=None): + # Prepare expected data + expected = expected or 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 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() + self.get_feedback_and_check() + self.set_command_and_check() + 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() + self.set_initial_state(test_cases[0]) + # Now loop over cases + for test_case in test_cases: + self.read_update_write_loop(test_case) 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 a1854e50..9fa98850 100644 --- a/setup.py +++ b/setup.py @@ -1,5 +1,6 @@ from setuptools import setup from setuptools.command.install import install +from warnings import warn import subprocess import os @@ -43,14 +44,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) != "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( - ["/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()