From 1a21371c7d6b931a3d798d90cd200d4ff71b3dac Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Filipe=20Silva?= Date: Thu, 14 Nov 2019 18:26:04 +0000 Subject: [PATCH 001/199] added fallback in statusword property, resolves #168 Enable the statusword to get the value from the driver even if it's not configured in the TPDOS through the SDO mechanism. --- canopen/profiles/p402.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 3a7c0cd5..a9d02d5a 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -369,12 +369,14 @@ def on_TPDOs_update_callback(self, mapobject): @property def statusword(self): """Returns the last read value of the Statusword (0x6041) from the device. - :raise ValueError: The Object 0x6041 (Statusword) is not configured in this device. + If the the object 0x6041 is not configured in any TPDO it will fallback to the SDO mechanism + and try to tget the value. """ try: return self.tpdo_values[0x6041] except KeyError: - raise KeyError('The object 0x6041 (Statusword) is not configured in this device.') + logger.warning('The object 0x6041 is not supported by the PDO mechanism, fallback to SDO') + return self.sdo[0x6041].raw = value @property def controlword(self): From d4e7c7150d0afa9ac9fe1be763dddc728b084b51 Mon Sep 17 00:00:00 2001 From: gsulc Date: Thu, 14 Nov 2019 18:34:19 -0500 Subject: [PATCH 002/199] fix problem from 1a21371 Commit 1a21371c7d6b931a3d798d90cd200d4ff71b3dac is broken. For issue #168 --- canopen/profiles/p402.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index a9d02d5a..4ac36c09 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -375,8 +375,8 @@ def statusword(self): try: return self.tpdo_values[0x6041] except KeyError: - logger.warning('The object 0x6041 is not supported by the PDO mechanism, fallback to SDO') - return self.sdo[0x6041].raw = value + logger.warning('The object 0x6041 is not a configured TPDO, fallback to SDO') + return self.sdo[0x6041].raw @property def controlword(self): From 56c7cdeddff1759bb495e4e66a7f3de0b65a4e2c Mon Sep 17 00:00:00 2001 From: Yegor Yefremov Date: Tue, 19 Nov 2019 15:20:06 +0100 Subject: [PATCH 003/199] Fix typos --- README.rst | 2 +- canopen/node/remote.py | 2 +- canopen/pdo/base.py | 2 +- canopen/profiles/p402.py | 14 +++++++------- doc/lss.rst | 2 +- examples/simple_ds402_node.py | 2 +- test/test_pdo.py | 2 +- 7 files changed, 13 insertions(+), 13 deletions(-) diff --git a/README.rst b/README.rst index 436efc7d..98435953 100644 --- a/README.rst +++ b/README.rst @@ -74,7 +74,7 @@ The PDOs can be access by three forms: **3rd:** :code:`node.pdo[0x1A00]` or :code:`node.pdo[0x1600]` -The :code:`n` is the PDO index (normaly 1 to 4). The second form of access is for backward compability. +The :code:`n` is the PDO index (normally 1 to 4). The second form of access is for backward compatibility. .. code-block:: python diff --git a/canopen/node/remote.py b/canopen/node/remote.py index a4d280f3..5a531868 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -21,7 +21,7 @@ class RemoteNode(BaseNode): Object dictionary as either a path to a file, an ``ObjectDictionary`` or a file like object. :param bool load_od: - Enable the Object Dictionary to be sent trought SDO's to the remote + Enable the Object Dictionary to be sent trough SDO's to the remote node at startup. :type object_dictionary: :class:`str`, :class:`canopen.ObjectDictionary` """ diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 74363ed9..b1139d11 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -18,7 +18,7 @@ class PdoBase(Mapping): - """Represents the base implemention for the PDO object. + """Represents the base implementation for the PDO object. :param object node: Parent object associated with this PDO instance diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 4ac36c09..64994fc4 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -198,7 +198,7 @@ def __init__(self, node_id, object_dictionary): def setup_402_state_machine(self): """Configured the state machine by searching for the PDO that has the StatusWord mappend. - :raise ValueError: If the the node can't finde a Statusword configured + :raise ValueError: If the the node can't find a Statusword configured in the any of the TPDOs """ # the node needs to be in pre-operational mode @@ -250,9 +250,9 @@ def reset_from_fault(self): def homing(self, timeout=30, set_new_home=True): """Function to execute the configured Homing Method on the node :param int timeout: Timeout value (default: 30) - :param bool set_new_home: Difines if the node should set the home offset + :param bool set_new_home: Defines if the node should set the home offset object (0x607C) to the current position after the homing procedure (default: true) - :return: If the homing was complet with success + :return: If the homing was complete with success :rtype: bool """ result = False @@ -324,7 +324,7 @@ def op_mode(self, mode): result = False if not self.is_op_mode_supported(mode): - raise TypeError('Operation mode not suppported by the node.') + raise TypeError('Operation mode not supported by the node.') if self.state == 'OPERATION ENABLED': self.state = 'SWITCHED ON' @@ -432,9 +432,9 @@ def state(self, new_state): :param string new_state: Target state :param int timeout: :raise RuntimeError: Occurs when the time defined to change the state is reached - :raise TypeError: Occurs when trying to execute a ilegal transition in the sate machine + :raise TypeError: Occurs when trying to execute a illegal transition in the state machine """ - t_to_new_state = time.time() + 8 # 800 milliseconds tiemout + t_to_new_state = time.time() + 8 # 800 milliseconds timeout while self.state != new_state: try: if new_state == 'OPERATION ENABLED': @@ -456,5 +456,5 @@ def state(self, new_state): # check the timeout if time.time() > t_to_new_state: raise RuntimeError('Timeout when trying to change state') - time.sleep(0.01) # 10 miliseconds of sleep + time.sleep(0.01) # 10 milliseconds of sleep diff --git a/doc/lss.rst b/doc/lss.rst index 792c61d3..2906e06b 100644 --- a/doc/lss.rst +++ b/doc/lss.rst @@ -29,7 +29,7 @@ Finally, you can switch to LSS waiting state. Examples -------- -Switch all the slave into CONFIGURATION state. There is no response for the mesage. :: +Switch all the slave into CONFIGURATION state. There is no response for the message. :: network.lss.send_switch_state_global(network.lss.CONFIGURATION_STATE) diff --git a/examples/simple_ds402_node.py b/examples/simple_ds402_node.py index c569e439..ae7deab9 100644 --- a/examples/simple_ds402_node.py +++ b/examples/simple_ds402_node.py @@ -146,7 +146,7 @@ traceback.print_exc() finally: # Disconnect from CAN bus - print('going to exit... stoping...') + print('going to exit... stopping...') if network: for node_id in network: diff --git a/test/test_pdo.py b/test/test_pdo.py index cefc0afb..6bba18fe 100644 --- a/test/test_pdo.py +++ b/test/test_pdo.py @@ -44,7 +44,7 @@ def test_bit_mapping(self): self.assertEqual(node.tpdo[1]['BOOLEAN value'].raw, False) self.assertEqual(node.tpdo[1]['BOOLEAN value 2'].raw, True) - # Test diferent types of access + # Test different types of access self.assertEqual(node.pdo[0x1600]['INTEGER16 value'].raw, -3) self.assertEqual(node.pdo['INTEGER16 value'].raw, -3) self.assertEqual(node.pdo.tx[1]['INTEGER16 value'].raw, -3) From e92a4e42e92e8ef480560b128c8a2a55988e8592 Mon Sep 17 00:00:00 2001 From: gsulc Date: Mon, 25 Nov 2019 10:58:06 -0500 Subject: [PATCH 004/199] small 402 refactor Some small changes to p402.py to make it a little easier to understand. I have two open questions about setup_402_state_machine(): why is it necessary to enter the "Pre-Operational" NMT state to read the pdo configurations. And why change state to "Switch on Disabled"? Shouldn't the present state be kept? --- canopen/profiles/p402.py | 227 ++++++++++++++++++++------------------- 1 file changed, 116 insertions(+), 111 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 4ac36c09..34842b9d 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -6,10 +6,8 @@ logger = logging.getLogger(__name__) - class State402(object): - - # Control word 0x6040 commands + # Controlword (0x6040) commands CW_OPERATION_ENABLED = 0x0F CW_SHUTDOWN = 0x06 CW_SWITCH_ON = 0x07 @@ -47,7 +45,7 @@ class State402(object): 'QUICK STOP ACTIVE' : [0x6F, 0x07] } - # Transition path to enable the DS402 node + # Transition path to get to the 'OPERATION ENABLED' state NEXTSTATE2ENABLE = { ('START') : 'NOT READY TO SWITCH ON', ('FAULT', 'NOT READY TO SWITCH ON') : 'SWITCH ON DISABLED', @@ -137,9 +135,7 @@ class OperationMode(object): 'INTERPOLATED POSITION' : 0x40 } - class Homing(object): - CW_START = 0x10 CW_HALT = 0x100 @@ -187,24 +183,28 @@ class BaseNode402(RemoteNode): def __init__(self, node_id, object_dictionary): super(BaseNode402, self).__init__(node_id, object_dictionary) - - self.is_statusword_configured = False - - #: List of values obtained by the configured TPDOs in a dictionary {object (hex), value} - self.tpdo_values = {} - #! list of mapped objects configured in the RPDOs in a dictionary {object (hex, pointer (RPDO object) } - self.rpdo_pointers = {} + self.tpdo_values = dict() # { index: TPDO_value } + self.rpdo_pointers = dict() # { index: RPDO_pointer } def setup_402_state_machine(self): - """Configured the state machine by searching for the PDO that has the - StatusWord mappend. - :raise ValueError: If the the node can't finde a Statusword configured + """Configure the state machine by searching for a TPDO that has the + StatusWord mapped. + :raise ValueError: If the the node can't find a Statusword configured in the any of the TPDOs """ - # the node needs to be in pre-operational mode - self.nmt.state = 'PRE-OPERATIONAL' - self.pdo.read() # read all the PDOs (TPDOs and RPDOs) - # + self.nmt.state = 'PRE-OPERATIONAL' # Why is this necessary? + self.setup_pdos() + self._check_controlword_configured() + self._check_statusword_configured() + self.nmt.state = 'OPERATIONAL' + self.state = 'SWITCH ON DISABLED' # Why change state? + + def setup_pdos(self): + self.pdo.read() # TPDO and RPDO configurations + self._init_tpdo_values() + self._init_rpdo_pointers() + + def _init_tpdo_values(self): for tpdo in self.tpdo.values(): if tpdo.enabled: tpdo.add_callback(self.on_TPDOs_update_callback) @@ -212,40 +212,44 @@ def setup_402_state_machine(self): logger.debug('Configured TPDO: {0}'.format(obj.index)) if obj.index not in self.tpdo_values: self.tpdo_values[obj.index] = 0 - # + + def _init_rpdo_pointers(self): + # If RPDOs have overlapping indecies, rpdo_pointers will point to + # the first RPDO that has that index configured. for rpdo in self.rpdo.values(): for obj in rpdo: logger.debug('Configured RPDO: {0}'.format(obj.index)) if obj.index not in self.rpdo_pointers: - self.rpdo_pointers[obj.index] = obj + self.rpdo_pointers[obj.index] = obj - # Check if the Controlword is configured - if 0x6040 not in self.rpdo_pointers: - logger.warning('Controlword not configured in the PDOs of this node, using SDOs to set Controlword') + def _check_controlword_configured(self): + if 0x6040 not in self.rpdo_pointers: # Controlword + logger.warning( + "Controlword not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( + self.id)) - # Check if the Statusword is configured - if 0x6041 not in self.tpdo_values: - raise ValueError('Statusword not configured in this node. Unable to access node status.') - - # Set nmt state and set the DS402 not to switch on disabled - self.nmt.state = 'OPERATIONAL' - self.state = 'SWITCH ON DISABLED' + def _check_statusword_configured(self): + if 0x6041 not in self.tpdo_values: # Statusword + raise ValueError( + "Statusword not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( + self.id)) def reset_from_fault(self): """Reset node from fault and set it to Operation Enable state """ if self.state == 'FAULT': - # particular case, it resets the Fault Reset bit (rising edge 0 -> 1) + # Resets the Fault Reset bit (rising edge 0 -> 1) self.controlword = State402.CW_DISABLE_VOLTAGE - timeout = time.time() + 0.4 # 400 milliseconds - # Check if the Fault Reset bit is still = 1 - while self.statusword & (State402.SW_MASK['FAULT'][0] == State402.SW_MASK['FAULT'][1]): + timeout = time.time() + 0.4 # 400 ms + + while self.is_faulted(): if time.time() > timeout: break - time.sleep(0.01) # 10 milliseconds + time.sleep(0.01) # 10 ms self.state = 'OPERATION ENABLED' - else: - logger.info('The node its not at fault. Doing nothing!') + + def is_faulted(self): + return self.statusword & State402.SW_MASK['FAULT'][0] == State402.SW_MASK['FAULT'][1] def homing(self, timeout=30, set_new_home=True): """Function to execute the configured Homing Method on the node @@ -255,8 +259,7 @@ def homing(self, timeout=30, set_new_home=True): :return: If the homing was complet with success :rtype: bool """ - result = False - previus_opm = self.op_mode + previus_op_mode = self.op_mode self.state = 'SWITCHED ON' self.op_mode = 'HOMING' # The homing process will initialize at operation enabled @@ -278,16 +281,16 @@ def homing(self, timeout=30, set_new_home=True): if time.time() > t: raise RuntimeError('Unable to home, timeout reached') if set_new_home: - offset = self.sdo[0x6063].raw - self.sdo[0x607C].raw = offset - logger.info('Homing offset set to {0}'.format(offset)) + actual_position = self.sdo[0x6063].raw + self.sdo[0x607C].raw = actual_position # home offset (0x607C) + logger.info('Homing offset set to {0}'.format(actual_position)) logger.info('Homing mode carried out successfully.') - result = True + return True except RuntimeError as e: logger.info(str(e)) finally: - self.op_mode = previus_opm - return result + self.op_mode = previus_op_mode + return False @property def op_mode(self): @@ -316,38 +319,43 @@ def op_mode(self, mode): - 'CYCLIC SYNCHRONOUS TORQUE' - 'OPEN LOOP SCALAR MODE' - 'OPEN LOOP VECTOR MODE' - """ try: - logger.info('Changing Operation Mode to {0}'.format(mode)) - state = self.state - result = False - if not self.is_op_mode_supported(mode): - raise TypeError('Operation mode not suppported by the node.') + raise TypeError( + 'Operation mode {0} not suppported on node {1}.'.format(mode, self.id)) + + start_state = self.state if self.state == 'OPERATION ENABLED': - self.state = 'SWITCHED ON' - # to make sure the node does not move with a old value in another mode - # we clean all the target values for the modes - self.sdo[0x60FF].raw = 0.0 # target velocity - self.sdo[0x607A].raw = 0.0 # target position - self.sdo[0x6071].raw = 0.0 # target torque - # set the operation mode in an agnostic way, accessing the SDO object by ID + self.state = 'SWITCHED ON' + # ensure the node does not move with an old value + self._clear_target_values() # Shouldn't this happen before it's switched on? + + # operation mode self.sdo[0x6060].raw = OperationMode.NAME2CODE[mode] - t = time.time() + 0.5 # timeout + + timeout = time.time() + 0.5 # 500 ms while self.op_mode != mode: - if time.time() > t: - raise RuntimeError('Timeout setting the new mode of operation at node {0}.'.format(self.id)) - result = True + if time.time() > timeout: + raise RuntimeError( + "Timeout setting node {0}'s new mode of operation to {1}.".format( + self.id, mode)) + return True except SdoCommunicationError as e: logger.warning('[SDO communication error] Cause: {0}'.format(str(e))) except (RuntimeError, ValueError) as e: logger.warning('{0}'.format(str(e))) finally: - self.state = state # set to last known state - logger.info('Mode of operation of the node {n} is {m}.'.format(n=self.id , m=mode)) - return result + self.state = start_state # why? + logger.info('Set node {n} operation mode to {m}.'.format(n=self.id , m=mode)) + return False + + def _clear_target_values(self): + # [target velocity, target position, target torque] + for target_index in [0x60FF, 0x607A, 0x6071]: + if target_index in self.sdo.keys(): + self.sdo[target_index].raw = 0 def is_op_mode_supported(self, mode): """Function to check if the operation mode is supported by the node @@ -355,7 +363,7 @@ def is_op_mode_supported(self, mode): :return: If the operation mode is supported :rtype: bool """ - mode_support = (self.sdo[0x6502].raw & OperationMode.SUPPORTED[mode]) + mode_support = self.sdo[0x6502].raw & OperationMode.SUPPORTED[mode] return mode_support == OperationMode.SUPPORTED[mode] def on_TPDOs_update_callback(self, mapobject): @@ -380,11 +388,11 @@ def statusword(self): @property def controlword(self): - raise RuntimeError('This property has no getter.') + raise RuntimeError('The Controlword is write-only.') @controlword.setter def controlword(self, value): - """Helper function enabling the node to send the state using PDO or SDO objects + """Send the state using PDO or SDO objects. :param int value: State value to send in the message """ if 0x6040 in self.rpdo_pointers: @@ -396,9 +404,7 @@ def controlword(self, value): @property def state(self): """Attribute to get or set node's state as a string for the DS402 State Machine. - States of the node can be one of: - - 'NOT READY TO SWITCH ON' - 'SWITCH ON DISABLED' - 'READY TO SWITCH ON' @@ -407,54 +413,53 @@ def state(self): - 'FAULT' - 'FAULT REACTION ACTIVE' - 'QUICK STOP ACTIVE' + """ + for state, mask_val_pair in State402.SW_MASK.items(): + mask = mask_val_pair[0] + state_value = mask_val_pair[1] + masked_value = self.statusword & mask + if masked_value == state_value: + return state + return 'UNKNOWN' + @state.setter + def state(self, target_state): + """ Defines the state for the DS402 state machine States to switch to can be one of: - - 'SWITCH ON DISABLED' - 'DISABLE VOLTAGE' - 'READY TO SWITCH ON' - 'SWITCHED ON' - 'OPERATION ENABLED' - 'QUICK STOP ACTIVE' - - """ - for key, value in State402.SW_MASK.items(): - # check if the value after applying the bitmask (value[0]) - # corresponds with the value[1] to determine the current status - bitmaskvalue = self.statusword & value[0] - if bitmaskvalue == value[1]: - return key - return 'UNKNOWN' - - @state.setter - def state(self, new_state): - """ Defines the state for the DS402 state machine - :param string new_state: Target state - :param int timeout: + :param string target_state: Target state :raise RuntimeError: Occurs when the time defined to change the state is reached - :raise TypeError: Occurs when trying to execute a ilegal transition in the sate machine + :raise ValueError: Occurs when trying to execute a ilegal transition in the sate machine """ - t_to_new_state = time.time() + 8 # 800 milliseconds tiemout - while self.state != new_state: - try: - if new_state == 'OPERATION ENABLED': - next_state = State402.next_state_for_enabling(self.state) - else: - next_state = new_state - # get the code from the transition table - code = State402.TRANSITIONTABLE[ (self.state, next_state) ] - # set the control word - self.controlword = code - # timeout of 400 milliseconds to try set the next state - t_to_next_state = time.time() + 0.4 - while self.state != next_state: - if time.time() > t_to_next_state: - break - time.sleep(0.01) # 10 milliseconds of sleep - except KeyError: - raise ValueError('Illegal transition from {f} to {t}'.format(f=self.state, t=new_state)) - # check the timeout - if time.time() > t_to_new_state: + timeout = time.time() + 0.8 # 800 ms + while self.state != target_state: + next_state = self._next_state(target_state) + if _change_state(next_state): + continue + if time.time() > timeout: raise RuntimeError('Timeout when trying to change state') - time.sleep(0.01) # 10 miliseconds of sleep + time.sleep(0.01) # 10 ms + def _next_state(self, target_state): + if target_state == 'OPERATION ENABLED': + return State402.next_state_for_enabling(self.state) + else: + return target_state + + def _change_state(self, target_state): + try: + self.controlword = State402.TRANSITIONTABLE[(self.state, target_state)] + except KeyError: + raise ValueError( + 'Illegal state transition from {f} to {t}'.format(f=self.state, t=target_state)) + timeout = time.time() + 0.4 # 400 ms + while self.state != target_state: + if time.time() > timeout: + return False + time.sleep(0.01) # 10 ms + return True From f5c6ae1ef76c7299fe91efa3b1a007ba3a0d029e Mon Sep 17 00:00:00 2001 From: Sander Huijsen Date: Mon, 2 Dec 2019 14:35:48 +0800 Subject: [PATCH 005/199] In stead of assigning 0 directly to a timestamp member, make it None, then check whether it exists before doing the subtraction. This way, we can potentially use other types for the timestamp, as long as subtracting two of them result in an integer/float (meaning seconds). --- canopen/pdo/base.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index b1139d11..ecf071c3 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -174,7 +174,7 @@ def __init__(self, pdo_node, com_record, map_array): #: Current message data self.data = bytearray() #: Timestamp of last received message - self.timestamp = 0 + self.timestamp = None #: Period of receive message transmission in seconds self.period = None self.callbacks = [] @@ -268,7 +268,7 @@ def on_message(self, can_id, data, timestamp): with self.receive_condition: self.is_received = True self.data = data - self.period = timestamp - self.timestamp + self.period = timestamp - self.timestamp if self.timestamp is not None else timestamp self.timestamp = timestamp self.receive_condition.notify_all() for callback in self.callbacks: From df898c6a40674a450df045553fa39617b2bce491 Mon Sep 17 00:00:00 2001 From: Sander Huijsen Date: Mon, 2 Dec 2019 23:03:24 +0800 Subject: [PATCH 006/199] Only update period when we have received two timestamps. --- canopen/pdo/base.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index ecf071c3..4fca9ffc 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -268,7 +268,8 @@ def on_message(self, can_id, data, timestamp): with self.receive_condition: self.is_received = True self.data = data - self.period = timestamp - self.timestamp if self.timestamp is not None else timestamp + if self.timestamp is not None: + self.period = timestamp - self.timestamp self.timestamp = timestamp self.receive_condition.notify_all() for callback in self.callbacks: From 7359004241583366ef0fe823ad0ba7446caf673f Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Mon, 6 Jan 2020 19:18:43 +0100 Subject: [PATCH 007/199] Do not fail when network.notifier has not been set Related to #165 --- canopen/network.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index c533d228..01bbc290 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -244,10 +244,11 @@ def check(self): If an exception caused the thread to terminate, that exception will be raised. """ - exc = self.notifier.exception - if exc is not None: - logger.error("An error has caused receiving of messages to stop") - raise exc + if self.notifier is not None: + exc = self.notifier.exception + if exc is not None: + logger.error("An error has caused receiving of messages to stop") + raise exc def __getitem__(self, node_id): return self.nodes[node_id] From 61bc0a0874002963233d5401edf9c25fcdcea445 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Mon, 6 Jan 2020 19:51:16 +0100 Subject: [PATCH 008/199] Update CI with new Python versions --- .travis.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.travis.yml b/.travis.yml index 99347dbd..cdc01ba1 100644 --- a/.travis.yml +++ b/.travis.yml @@ -2,12 +2,12 @@ dist: xenial language: python python: - "2.7" - - "3.4" + - "3.5" - "3.7" - - "3.8-dev" + - "3.8" - "pypy3.5" install: - pip install -e . - pip install --upgrade pytest pytest-cov codacy-coverage -script: py.test -v --color=yes --cov-report xml --cov=canopen test/ +script: pytest -v --color=yes --cov-report xml --cov=canopen test/ after_script: python-codacy-coverage From 2afeefbcc68e12198160b165cd823dad84001553 Mon Sep 17 00:00:00 2001 From: DALENCON Stanislas Date: Tue, 28 Jan 2020 16:00:10 +0100 Subject: [PATCH 009/199] Add loading of DummyUsage definitions in order to map dummy data in PDO definition. --- canopen/objectdictionary/eds.py | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 8dad5e66..e07590bb 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -36,6 +36,17 @@ def import_eds(source, node_id): od.node_id = int(eds.get("DeviceComissioning", "NodeID")) for section in eds.sections(): + # Match dummy definitions + match = re.match(r"^[D|d]ummy[U|u]sage$", section) + if match is not None: + for i in range(1,8): + key = "Dummy%04d" % i + if eds.getint(section,key) == 1: + var = objectdictionary.Variable(key, i, 0) + var.data_type = i + var.access_type = "const" + od.add_object(var) + # Match indexes match = re.match(r"^[0-9A-Fa-f]{4}$", section) if match is not None: From 36560593151a30145d03b98c592b744d87cccba9 Mon Sep 17 00:00:00 2001 From: DALENCON Stanislas Date: Wed, 29 Jan 2020 08:03:41 +0100 Subject: [PATCH 010/199] Add tests and some corrections according to PR suggestions. --- canopen/objectdictionary/eds.py | 6 +++--- test/sample.eds | 2 +- test/test_eds.py | 14 ++++++++++++++ 3 files changed, 18 insertions(+), 4 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index e07590bb..d58882b7 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -37,11 +37,11 @@ def import_eds(source, node_id): for section in eds.sections(): # Match dummy definitions - match = re.match(r"^[D|d]ummy[U|u]sage$", section) + match = re.match(r"^[Dd]ummy[Uu]sage$", section) if match is not None: - for i in range(1,8): + for i in range(1, 8): key = "Dummy%04d" % i - if eds.getint(section,key) == 1: + if eds.getint(section, key) == 1: var = objectdictionary.Variable(key, i, 0) var.data_type = i var.access_type = "const" diff --git a/test/sample.eds b/test/sample.eds index f3ebd3f7..90efdd13 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -39,7 +39,7 @@ LSS_SerialNumber=0 [DummyUsage] Dummy0001=0 Dummy0002=0 -Dummy0003=0 +Dummy0003=1 Dummy0004=0 Dummy0005=0 Dummy0006=0 diff --git a/test/test_eds.py b/test/test_eds.py index 7704ab71..a308d729 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -76,3 +76,17 @@ def test_compact_subobj_parameter_name_with_percent(self): def test_sub_index_w_capital_s(self): name = self.od[0x3010][0].name self.assertEqual(name, 'Temperature') + + def test_dummy_variable(self): + var = self.od['Dummy0003'] + self.assertIsInstance(var, canopen.objectdictionary.Variable) + self.assertEqual(var.index, 0x0003) + self.assertEqual(var.subindex, 0) + self.assertEqual(var.name, 'Dummy0003') + self.assertEqual(var.data_type, canopen.objectdictionary.INTEGER16) + self.assertEqual(var.access_type, 'const') + self.assertEqual(len(var), 16) + + def test_dummy_variable_undefined(self): + with self.assertRaises(KeyError): + var_undef = self.od['Dummy0001'] From d953a37bcfc80905f4a157533d9b411805e4e6a6 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Thu, 5 Mar 2020 20:39:53 +0100 Subject: [PATCH 011/199] Clarified features in README --- README.rst | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/README.rst b/README.rst index 98435953..9aa2d6f7 100644 --- a/README.rst +++ b/README.rst @@ -11,14 +11,24 @@ The library supports Python 2.7 and 3.4+. Features -------- -* Object Dictionary from EDS -* NMT master/slave -* SDO client/server +The library is mainly meant to be used as a master. + +* NMT master +* SDO client * PDO producer/consumer -* SYNC producer/consumer -* EMCY consumer/producer +* SYNC producer +* EMCY consumer * TIME producer * LSS master +* Object Dictionary from EDS + +Incomplete support for creating slave nodes also exists. + +* SDO server +* PDO producer/consumer +* NMT slave +* EMCY producer +* Object Dictionary from EDS Installation From 3596e7080a03e2704739f970ed16bac4ce4dd81e Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Thu, 5 Mar 2020 20:40:03 +0100 Subject: [PATCH 012/199] Bump version to v1.1.0 --- canopen/version.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/version.py b/canopen/version.py index 2bcf11bf..57b9f058 100644 --- a/canopen/version.py +++ b/canopen/version.py @@ -1,2 +1,2 @@ -__version__ = "1.0.0" +__version__ = "1.1.0" From 5fa0f586ef8785b019b2bc5b0685a3dcf12ac084 Mon Sep 17 00:00:00 2001 From: Grand Joldes Date: Thu, 19 Mar 2020 11:20:02 +0800 Subject: [PATCH 013/199] Fix parsing of $NODEID to handle case differences and spaces. --- canopen/objectdictionary/eds.py | 1 + 1 file changed, 1 insertion(+) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index d58882b7..5ccd42e8 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -137,6 +137,7 @@ def _convert_variable(node_id, var_type, value): return float(value) else: # COB-ID can have a suffix of '$NODEID+' so replace this with node_id before converting + value = value.replace(" ","").upper() if '$NODEID+' in value and node_id is not None: return int(value.replace('$NODEID+', ''), 0) + node_id else: From da2add707696d41a26312ce489f5d07afa423123 Mon Sep 17 00:00:00 2001 From: Benjamin Maus Date: Tue, 7 Apr 2020 20:01:57 +0200 Subject: [PATCH 014/199] Fix missing `self.` fot checking state change in p402.py --- canopen/profiles/p402.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 310fdfbc..2ff5f417 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -439,7 +439,7 @@ def state(self, target_state): timeout = time.time() + 0.8 # 800 ms while self.state != target_state: next_state = self._next_state(target_state) - if _change_state(next_state): + if self._change_state(next_state): continue if time.time() > timeout: raise RuntimeError('Timeout when trying to change state') From c1d237c5f6ce16e5cd35c7a12acf5b892ad20651 Mon Sep 17 00:00:00 2001 From: Benjamin Maus Date: Mon, 27 Apr 2020 10:14:42 +0200 Subject: [PATCH 015/199] Add support for NO MODE in p402 to prevent KeyError when reading (#184) --- canopen/profiles/p402.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 2ff5f417..45f82452 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -96,6 +96,7 @@ def next_state_for_enabling(_from): class OperationMode(object): + NO_MODE = 0 PROFILED_POSITION = 1 VELOCITY = 2 PROFILED_VELOCITY = 3 @@ -109,6 +110,7 @@ class OperationMode(object): OPEN_LOOP_VECTOR_MODE = -2 CODE2NAME = { + NO_MODE : 'NO MODE', PROFILED_POSITION : 'PROFILED POSITION', VELOCITY : 'VELOCITY', PROFILED_VELOCITY : 'PROFILED VELOCITY', @@ -118,6 +120,7 @@ class OperationMode(object): } NAME2CODE = { + 'NO MODE' : NO_MODE, 'PROFILED POSITION' : PROFILED_POSITION, 'VELOCITY' : VELOCITY, 'PROFILED VELOCITY' : PROFILED_VELOCITY, @@ -127,6 +130,7 @@ class OperationMode(object): } SUPPORTED = { + 'NO MODE' : 0x0, 'PROFILED POSITION' : 0x1, 'VELOCITY' : 0x2, 'PROFILED VELOCITY' : 0x4, @@ -308,6 +312,7 @@ def op_mode(self, mode): :rtype: bool The modes can be: + - 'NO MODE' - 'PROFILED POSITION' - 'VELOCITY' - 'PROFILED VELOCITY' From 24e5feb9604aa8ea78306f0387118010ae7f185c Mon Sep 17 00:00:00 2001 From: tobiasht Date: Thu, 30 Apr 2020 14:25:16 +0200 Subject: [PATCH 016/199] Update profiles.rst (#185) Use the imported profile instead of getting it from the canopen module. --- doc/profiles.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/profiles.rst b/doc/profiles.rst index bd7345af..335cb6ab 100644 --- a/doc/profiles.rst +++ b/doc/profiles.rst @@ -17,7 +17,7 @@ Create a node with Node402:: import canopen from canopen.profiles.p402 import Node402 - some_node = canopen.Node402(3, 'someprofile.eds') + some_node = Node402(3, 'someprofile.eds') network = canopen.Network() network.add_node(some_node) From 8fe3932189d483efc72e0d34a9417ffbb34f5809 Mon Sep 17 00:00:00 2001 From: Paolo Teti Date: Sat, 30 May 2020 18:23:04 +0200 Subject: [PATCH 017/199] Add unit test for SYNC producer Test one-shot SYNC transmission with and without counter value. --- test/test_sync.py | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) create mode 100644 test/test_sync.py diff --git a/test/test_sync.py b/test/test_sync.py new file mode 100644 index 00000000..0321ceb6 --- /dev/null +++ b/test/test_sync.py @@ -0,0 +1,29 @@ +import unittest +import canopen + + +class TestSync(unittest.TestCase): + + def test_sync_producer(self): + network = canopen.Network() + network.connect(bustype="virtual", receive_own_messages=True) + producer = canopen.sync.SyncProducer(network) + producer.transmit() + msg = network.bus.recv(1) + network.disconnect() + self.assertEqual(msg.arbitration_id, 0x80) + self.assertEqual(msg.dlc, 0) + + def test_sync_producer_counter(self): + network = canopen.Network() + network.connect(bustype="virtual", receive_own_messages=True) + producer = canopen.sync.SyncProducer(network) + producer.transmit(2) + msg = network.bus.recv(1) + network.disconnect() + self.assertEqual(msg.arbitration_id, 0x80) + self.assertEqual(msg.dlc, 1) + self.assertEqual(msg.data, b"\x02") + +if __name__ == "__main__": + unittest.main() From ad7deb09b5158ddf89cd1bd3c0ba917d87063063 Mon Sep 17 00:00:00 2001 From: Paolo Teti Date: Tue, 2 Jun 2020 14:46:45 +0200 Subject: [PATCH 018/199] Network, avoid to raise an error if 'bus' or 'notifier' is None (#191) If 'bus' is not connected yet and for other reasons an exception is raised and some 'finally' block contains a call to disconnect() an error is raised. --- canopen/network.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index 01bbc290..70f5c361 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -119,8 +119,10 @@ def disconnect(self): for node in self.nodes.values(): if hasattr(node, "pdo"): node.pdo.stop() - self.notifier.stop() - self.bus.shutdown() + if self.notifier is not None: + self.notifier.stop() + if self.bus is not None: + self.bus.shutdown() self.bus = None self.check() From 439ee181d1bb3d97e3155de82531f9afc825cff4 Mon Sep 17 00:00:00 2001 From: bggardner Date: Tue, 2 Jun 2020 09:14:18 -0400 Subject: [PATCH 019/199] SdoClient needs ObjectDictionary argument --- canopen/objectdictionary/eds.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 5ccd42e8..fa6a4f7c 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -113,7 +113,7 @@ def import_from_node(node_id, network): :param network: network object """ # Create temporary SDO client - sdo_client = SdoClient(0x600 + node_id, 0x580 + node_id, None) + sdo_client = SdoClient(0x600 + node_id, 0x580 + node_id, objectdictionary.ObjectDictionary()) sdo_client.network = network # Subscribe to SDO responses network.subscribe(0x580 + node_id, sdo_client.on_response) From 994809cf0d7927fc66c3fcd100bd629829a527b8 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Sun, 2 Aug 2020 15:02:15 +0200 Subject: [PATCH 020/199] Allow value+$NODEID in EDS files Fixes #198 --- canopen/objectdictionary/eds.py | 6 +++--- test/sample.eds | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index fa6a4f7c..8834ff7d 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -136,10 +136,10 @@ def _convert_variable(node_id, var_type, value): elif var_type in objectdictionary.FLOAT_TYPES: return float(value) else: - # COB-ID can have a suffix of '$NODEID+' so replace this with node_id before converting + # COB-ID can contain '$NODEID+' so replace this with node_id before converting value = value.replace(" ","").upper() - if '$NODEID+' in value and node_id is not None: - return int(value.replace('$NODEID+', ''), 0) + node_id + if '$NODEID' in value and node_id is not None: + return int(re.sub(r'\+?\$NODEID\+?', '', value), 0) + node_id else: return int(value, 0) diff --git a/test/sample.eds b/test/sample.eds index 90efdd13..11c9c404 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -262,7 +262,7 @@ ObjectType=7 DataType=7 AccessType=RW PDOMapping=0 -DefaultValue=$NODEID+1280 +DefaultValue=1280+$NODEID [1403sub2] ParameterName=Transmission type RPDO 4 From 805413e5a4437ca87ffefcea3d138ad0aca26fd4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Lenard=20He=C3=9F?= <49403175+trinamic-LH@users.noreply.github.com> Date: Thu, 13 Aug 2020 14:56:55 +0200 Subject: [PATCH 021/199] profiles/p402: Fix disabled RPDO usage (#200) The list of RPDOs did not check whether the mapped RPDOs were enabled. As a result the controlword setter would try to write using a disabled RPDO which results in a timeout. --- canopen/profiles/p402.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 45f82452..f4dedb4f 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -221,10 +221,11 @@ def _init_rpdo_pointers(self): # If RPDOs have overlapping indecies, rpdo_pointers will point to # the first RPDO that has that index configured. for rpdo in self.rpdo.values(): - for obj in rpdo: - logger.debug('Configured RPDO: {0}'.format(obj.index)) - if obj.index not in self.rpdo_pointers: - self.rpdo_pointers[obj.index] = obj + if rpdo.enabled: + for obj in rpdo: + logger.debug('Configured RPDO: {0}'.format(obj.index)) + if obj.index not in self.rpdo_pointers: + self.rpdo_pointers[obj.index] = obj def _check_controlword_configured(self): if 0x6040 not in self.rpdo_pointers: # Controlword From 02bcec84283fa9cc545f375a2be36fe3933c2af9 Mon Sep 17 00:00:00 2001 From: Ruben Verhoef Date: Thu, 5 Nov 2020 08:40:09 +0100 Subject: [PATCH 022/199] [StorageLocation] Add Support for StorageLocation of EDS --- canopen/objectdictionary/__init__.py | 6 ++++-- canopen/objectdictionary/eds.py | 14 +++++++++++--- 2 files changed, 15 insertions(+), 5 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 83a20a41..a0cf137c 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -116,13 +116,14 @@ class Record(MutableMapping): #: Description for the whole record description = "" - def __init__(self, name, index): + def __init__(self, name, index, StorageLocation): #: The :class:`~canopen.ObjectDictionary` owning the record. self.parent = None #: 16-bit address of the record self.index = index #: Name of record self.name = name + self.StorageLocation = StorageLocation self.subindices = {} self.names = {} @@ -170,13 +171,14 @@ class Array(Mapping): #: Description for the whole array description = "" - def __init__(self, name, index): + def __init__(self, name, index, StorageLocation): #: The :class:`~canopen.ObjectDictionary` owning the record. self.parent = None #: 16-bit address of the array self.index = index #: Name of array self.name = name + self.StorageLocation = StorageLocation self.subindices = {} self.names = {} diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 8834ff7d..74844b70 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -59,12 +59,16 @@ def import_eds(source, node_id): # If the keyword ObjectType is missing, this is regarded as # "ObjectType=0x7" (=VAR). object_type = VAR + try: + StorageLocation = eds.get(section, "StorageLocation") + except NoOptionError: + StorageLocation = "Unknown" if object_type in (VAR, DOMAIN): var = build_variable(eds, section, node_id, index) od.add_object(var) elif object_type == ARR and eds.has_option(section, "CompactSubObj"): - arr = objectdictionary.Array(name, index) + arr = objectdictionary.Array(name, index, StorageLocation) last_subindex = objectdictionary.Variable( "Number of entries", index, 0) last_subindex.data_type = objectdictionary.UNSIGNED8 @@ -72,10 +76,10 @@ def import_eds(source, node_id): arr.add_member(build_variable(eds, section, node_id, index, 1)) od.add_object(arr) elif object_type == ARR: - arr = objectdictionary.Array(name, index) + arr = objectdictionary.Array(name, index, StorageLocation) od.add_object(arr) elif object_type == RECORD: - record = objectdictionary.Record(name, index) + record = objectdictionary.Record(name, index, StorageLocation) od.add_object(record) continue @@ -154,6 +158,10 @@ def build_variable(eds, section, node_id, index, subindex=0): """ name = eds.get(section, "ParameterName") var = objectdictionary.Variable(name, index, subindex) + try: + var.StorageLocation = eds.get(section, "StorageLocation") + except NoOptionError: + var.StorageLocation = "Unknown" var.data_type = int(eds.get(section, "DataType"), 0) var.access_type = eds.get(section, "AccessType").lower() if var.data_type > 0x1B: From 3b0b081423ccbf98f27ad9f06964d8bc814e57f7 Mon Sep 17 00:00:00 2001 From: Ruben Verhoef Date: Fri, 6 Nov 2020 08:05:59 +0100 Subject: [PATCH 023/199] Renamed `StorageLocation` to `storage_location` --- canopen/objectdictionary/__init__.py | 8 ++++---- canopen/objectdictionary/eds.py | 14 +++++++------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index a0cf137c..2cad1d50 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -116,14 +116,14 @@ class Record(MutableMapping): #: Description for the whole record description = "" - def __init__(self, name, index, StorageLocation): + def __init__(self, name, index, storage_location): #: The :class:`~canopen.ObjectDictionary` owning the record. self.parent = None #: 16-bit address of the record self.index = index #: Name of record self.name = name - self.StorageLocation = StorageLocation + self.storage_location = storage_location self.subindices = {} self.names = {} @@ -171,14 +171,14 @@ class Array(Mapping): #: Description for the whole array description = "" - def __init__(self, name, index, StorageLocation): + def __init__(self, name, index, storage_location): #: The :class:`~canopen.ObjectDictionary` owning the record. self.parent = None #: 16-bit address of the array self.index = index #: Name of array self.name = name - self.StorageLocation = StorageLocation + self.storage_location = storage_location self.subindices = {} self.names = {} diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 74844b70..87e77613 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -60,15 +60,15 @@ def import_eds(source, node_id): # "ObjectType=0x7" (=VAR). object_type = VAR try: - StorageLocation = eds.get(section, "StorageLocation") + storage_location = eds.get(section, "StorageLocation") except NoOptionError: - StorageLocation = "Unknown" + storage_location = "Unknown" if object_type in (VAR, DOMAIN): var = build_variable(eds, section, node_id, index) od.add_object(var) elif object_type == ARR and eds.has_option(section, "CompactSubObj"): - arr = objectdictionary.Array(name, index, StorageLocation) + arr = objectdictionary.Array(name, index, storage_location) last_subindex = objectdictionary.Variable( "Number of entries", index, 0) last_subindex.data_type = objectdictionary.UNSIGNED8 @@ -76,10 +76,10 @@ def import_eds(source, node_id): arr.add_member(build_variable(eds, section, node_id, index, 1)) od.add_object(arr) elif object_type == ARR: - arr = objectdictionary.Array(name, index, StorageLocation) + arr = objectdictionary.Array(name, index, storage_location) od.add_object(arr) elif object_type == RECORD: - record = objectdictionary.Record(name, index, StorageLocation) + record = objectdictionary.Record(name, index, storage_location) od.add_object(record) continue @@ -159,9 +159,9 @@ def build_variable(eds, section, node_id, index, subindex=0): name = eds.get(section, "ParameterName") var = objectdictionary.Variable(name, index, subindex) try: - var.StorageLocation = eds.get(section, "StorageLocation") + var.storage_location = eds.get(section, "StorageLocation") except NoOptionError: - var.StorageLocation = "Unknown" + var.storage_location = "Unknown" var.data_type = int(eds.get(section, "DataType"), 0) var.access_type = eds.get(section, "AccessType").lower() if var.data_type > 0x1B: From b4907ad4920553bd76b6e3ff6d861357ec4d8a83 Mon Sep 17 00:00:00 2001 From: Ruben Verhoef Date: Fri, 6 Nov 2020 08:07:02 +0100 Subject: [PATCH 024/199] Set default value of `storage_location` to `None` --- canopen/objectdictionary/eds.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 87e77613..2fc23933 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -62,7 +62,7 @@ def import_eds(source, node_id): try: storage_location = eds.get(section, "StorageLocation") except NoOptionError: - storage_location = "Unknown" + storage_location = None if object_type in (VAR, DOMAIN): var = build_variable(eds, section, node_id, index) @@ -161,7 +161,7 @@ def build_variable(eds, section, node_id, index, subindex=0): try: var.storage_location = eds.get(section, "StorageLocation") except NoOptionError: - var.storage_location = "Unknown" + var.storage_location = None var.data_type = int(eds.get(section, "DataType"), 0) var.access_type = eds.get(section, "AccessType").lower() if var.data_type > 0x1B: From bf3b19430ec40bd6c3330e60ea5d1e5cc7df2534 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Fri, 6 Nov 2020 20:17:56 +0100 Subject: [PATCH 025/199] Update README.rst --- README.rst | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/README.rst b/README.rst index 9aa2d6f7..4a1fd4b1 100644 --- a/README.rst +++ b/README.rst @@ -3,9 +3,10 @@ CANopen for Python A Python implementation of the CANopen_ standard. The aim of the project is to support the most common parts of the CiA 301 -standard in a Pythonic interface. +standard in a simple Pythonic interface. It is mainly targeted for testing and +automation tasks rather than a standard compliant master implementation. -The library supports Python 2.7 and 3.4+. +The library supports Python 3.4+. Features @@ -21,6 +22,7 @@ The library is mainly meant to be used as a master. * TIME producer * LSS master * Object Dictionary from EDS +* 402 profile support Incomplete support for creating slave nodes also exists. @@ -98,7 +100,7 @@ The :code:`n` is the PDO index (normally 1 to 4). The second form of access is f network.add_node(node) # Connect to the CAN bus - # Arguments are passed to python-can's can.interface.Bus() constructor + # Arguments are passed to python-can's can.Bus() constructor # (see https://python-can.readthedocs.io/en/latest/bus.html). network.connect() # network.connect(bustype='socketcan', channel='can0') From b52da1b013edcb7cf1e1e82e5eec67b81977fefe Mon Sep 17 00:00:00 2001 From: Ruben Verhoef Date: Mon, 9 Nov 2020 08:50:35 +0100 Subject: [PATCH 026/199] Add arr and record additional information later --- canopen/objectdictionary/__init__.py | 10 ++++++---- canopen/objectdictionary/eds.py | 9 ++++++--- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 2cad1d50..e5dd3ca5 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -116,14 +116,15 @@ class Record(MutableMapping): #: Description for the whole record description = "" - def __init__(self, name, index, storage_location): + def __init__(self, name, index): #: The :class:`~canopen.ObjectDictionary` owning the record. self.parent = None #: 16-bit address of the record self.index = index #: Name of record self.name = name - self.storage_location = storage_location + #: Storage location of index + self.storage_location = None self.subindices = {} self.names = {} @@ -171,14 +172,15 @@ class Array(Mapping): #: Description for the whole array description = "" - def __init__(self, name, index, storage_location): + def __init__(self, name, index): #: The :class:`~canopen.ObjectDictionary` owning the record. self.parent = None #: 16-bit address of the array self.index = index #: Name of array self.name = name - self.storage_location = storage_location + #: Storage location of index + self.storage_location = None self.subindices = {} self.names = {} diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 2fc23933..15b6f8e8 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -68,18 +68,21 @@ def import_eds(source, node_id): var = build_variable(eds, section, node_id, index) od.add_object(var) elif object_type == ARR and eds.has_option(section, "CompactSubObj"): - arr = objectdictionary.Array(name, index, storage_location) + arr = objectdictionary.Array(name, index) last_subindex = objectdictionary.Variable( "Number of entries", index, 0) last_subindex.data_type = objectdictionary.UNSIGNED8 arr.add_member(last_subindex) arr.add_member(build_variable(eds, section, node_id, index, 1)) + arr.storage_location = storage_location od.add_object(arr) elif object_type == ARR: - arr = objectdictionary.Array(name, index, storage_location) + arr = objectdictionary.Array(name, index) + arr.storage_location = storage_location od.add_object(arr) elif object_type == RECORD: - record = objectdictionary.Record(name, index, storage_location) + record = objectdictionary.Record(name, index) + record.storage_location = storage_location od.add_object(record) continue From eaaa71d7ad8f4481c1d5a2e3f88a42446332cd76 Mon Sep 17 00:00:00 2001 From: Ruben Verhoef Date: Mon, 9 Nov 2020 08:51:49 +0100 Subject: [PATCH 027/199] Add storage_location as member to var --- canopen/objectdictionary/__init__.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index e5dd3ca5..0dc98011 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -270,6 +270,8 @@ def __init__(self, name, index, subindex=0): self.value_descriptions = {} #: Dictionary of bitfield definitions self.bit_definitions = {} + #: Storage location of index + self.storage_location = None def __eq__(self, other): return (self.index == other.index and From 706327dff7d7f24086093e6552a1e22aaa33f46d Mon Sep 17 00:00:00 2001 From: Ruben Verhoef Date: Mon, 9 Nov 2020 12:43:10 +0100 Subject: [PATCH 028/199] Add storage_location to the __getitem__ function of Array class --- canopen/objectdictionary/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 0dc98011..25a2f37a 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -197,7 +197,7 @@ def __getitem__(self, subindex): var.parent = self for attr in ("data_type", "unit", "factor", "min", "max", "default", "access_type", "description", "value_descriptions", - "bit_definitions"): + "bit_definitions", "storage_location"): if attr in template.__dict__: var.__dict__[attr] = template.__dict__[attr] else: From 9e84aef5f37b085ea9fee8c40087709ec3f19d5a Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Mon, 9 Nov 2020 19:57:23 +0100 Subject: [PATCH 029/199] Use setuptools-scm for version and drop Python 2.7 --- canopen/__init__.py | 10 +++++++++- canopen/version.py | 2 -- doc/conf.py | 9 ++++----- setup.cfg | 2 -- setup.py | 18 ++++-------------- 5 files changed, 17 insertions(+), 24 deletions(-) delete mode 100644 canopen/version.py delete mode 100644 setup.cfg diff --git a/canopen/__init__.py b/canopen/__init__.py index 0c5db120..2fd09927 100644 --- a/canopen/__init__.py +++ b/canopen/__init__.py @@ -1,4 +1,4 @@ -from .version import __version__ +from pkg_resources import get_distribution, DistributionNotFound from .network import Network, NodeScanner from .node import RemoteNode, LocalNode from .sdo import SdoCommunicationError, SdoAbortedError @@ -6,3 +6,11 @@ from .profiles.p402 import BaseNode402 Node = RemoteNode + +try: + __version__ = get_distribution(__name__).version +except DistributionNotFound: + # package is not installed + __version__ = "unknown" + +__pypi_url__ = "https://pypi.org/project/canopen/" diff --git a/canopen/version.py b/canopen/version.py deleted file mode 100644 index 57b9f058..00000000 --- a/canopen/version.py +++ /dev/null @@ -1,2 +0,0 @@ - -__version__ = "1.1.0" diff --git a/doc/conf.py b/doc/conf.py index 45b3a685..2a1bd192 100644 --- a/doc/conf.py +++ b/doc/conf.py @@ -18,10 +18,9 @@ # import os import sys +from pkg_resources import get_distribution sys.path.insert(0, os.path.abspath('..')) -exec(open('../canopen/version.py').read()) - # -- General configuration ------------------------------------------------ # If your documentation needs a minimal Sphinx version, state it here. @@ -62,10 +61,10 @@ # |version| and |release|, also used in various other places throughout the # built documents. # -# The short X.Y version. -version = '.'.join(__version__.split('.')[0:2]) # The full version, including alpha/beta/rc tags. -release = __version__ +release = get_distribution('canopen').version +# The short X.Y version. +version = '.'.join(release.split('.')[:2]) # The language for content autogenerated by Sphinx. Refer to documentation # for a list of supported languages. diff --git a/setup.cfg b/setup.cfg deleted file mode 100644 index 2a9acf13..00000000 --- a/setup.cfg +++ /dev/null @@ -1,2 +0,0 @@ -[bdist_wheel] -universal = 1 diff --git a/setup.py b/setup.py index 49d7e8bb..eb965308 100644 --- a/setup.py +++ b/setup.py @@ -1,19 +1,13 @@ from setuptools import setup, find_packages -exec(open('canopen/version.py').read()) - description = open("README.rst").read() # Change links to stable documentation description = description.replace("/latest/", "/stable/") -# Change pip install to this exact version -description = description.replace( - "pip install canopen", - "pip install canopen==" + __version__) setup( name="canopen", url="https://github.com/christiansandberg/canopen", - version=__version__, + use_scm_version=True, packages=find_packages(), author="Christian Sandberg", author_email="christiansandberg@me.com", @@ -23,10 +17,9 @@ license="MIT", platforms=["any"], classifiers=[ - "Development Status :: 4 - Beta", + "Development Status :: 5 - Production/Stable", "License :: OSI Approved :: MIT License", "Operating System :: OS Independent", - "Programming Language :: Python :: 2", "Programming Language :: Python :: 3", "Intended Audience :: Developers", "Topic :: Scientific/Engineering" @@ -35,9 +28,6 @@ extras_require={ "db_export": ["canmatrix"] }, - include_package_data=True, - - # Tests can be run using `python setup.py test` - test_suite="nose.collector", - tests_require=["nose"] + setup_requires=["setuptools_scm"], + include_package_data=True ) From 44a9839254775f6ed7287f02874e84f7b2221ab4 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Mon, 9 Nov 2020 19:57:35 +0100 Subject: [PATCH 030/199] Use GitHub Actions --- .github/workflows/pythonpackage.yml | 32 +++++++++++++++++++++++++++++ .github/workflows/pythonpublish.yml | 31 ++++++++++++++++++++++++++++ .travis.yml | 13 ------------ 3 files changed, 63 insertions(+), 13 deletions(-) create mode 100644 .github/workflows/pythonpackage.yml create mode 100644 .github/workflows/pythonpublish.yml delete mode 100644 .travis.yml diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml new file mode 100644 index 00000000..0b6b69b7 --- /dev/null +++ b/.github/workflows/pythonpackage.yml @@ -0,0 +1,32 @@ +# This workflow will install Python dependencies, run tests and lint with a variety of Python versions +# For more information see: https://help.github.com/actions/language-and-framework-guides/using-python-with-github-actions + +name: Python package + +on: [push, pull_request] + +jobs: + build: + + runs-on: ubuntu-latest + strategy: + matrix: + python-version: [3.5, '3.x'] + + steps: + - uses: actions/checkout@v2 + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v1 + with: + python-version: ${{ matrix.python-version }} + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install pytest pytest-cov codacy-coverage + pip install -e . + - name: Test with pytest + run: | + pytest -v --cov-report xml --cov=canopen test/ + - name: Upload coverage + run: | + python-codacy-coverage diff --git a/.github/workflows/pythonpublish.yml b/.github/workflows/pythonpublish.yml new file mode 100644 index 00000000..d5f3859d --- /dev/null +++ b/.github/workflows/pythonpublish.yml @@ -0,0 +1,31 @@ +# This workflows will upload a Python Package using Twine when a release is created +# For more information see: https://help.github.com/en/actions/language-and-framework-guides/using-python-with-github-actions#publishing-to-package-registries + +name: Upload Python Package + +on: + release: + types: [created] + +jobs: + deploy: + + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v2 + - name: Set up Python + uses: actions/setup-python@v1 + with: + python-version: '3.x' + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install setuptools wheel twine + - name: Build and publish + env: + TWINE_USERNAME: ${{ secrets.PYPI_USERNAME }} + TWINE_PASSWORD: ${{ secrets.PYPI_PASSWORD }} + run: | + python setup.py sdist bdist_wheel + twine upload dist/* diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index cdc01ba1..00000000 --- a/.travis.yml +++ /dev/null @@ -1,13 +0,0 @@ -dist: xenial -language: python -python: - - "2.7" - - "3.5" - - "3.7" - - "3.8" - - "pypy3.5" -install: - - pip install -e . - - pip install --upgrade pytest pytest-cov codacy-coverage -script: pytest -v --color=yes --cov-report xml --cov=canopen test/ -after_script: python-codacy-coverage From 18a18004f9a47be699367602f54395d5f5de8ded Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Mon, 9 Nov 2020 20:08:47 +0100 Subject: [PATCH 031/199] Remove codacy coverage for now --- .github/workflows/pythonpackage.yml | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 0b6b69b7..4089ee1e 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -22,11 +22,8 @@ jobs: - name: Install dependencies run: | python -m pip install --upgrade pip - pip install pytest pytest-cov codacy-coverage + pip install pytest pip install -e . - name: Test with pytest run: | - pytest -v --cov-report xml --cov=canopen test/ - - name: Upload coverage - run: | - python-codacy-coverage + pytest -v From e9fda09caf4b3d7fe7833beade8f95067f6dc309 Mon Sep 17 00:00:00 2001 From: "andre.silva" Date: Wed, 25 Nov 2020 13:33:14 +0000 Subject: [PATCH 032/199] add eds example file --- examples/eds/e35.eds | 8857 +++++++++++++++++++++++++++++++++ examples/simple_ds402_node.py | 4 +- 2 files changed, 8859 insertions(+), 2 deletions(-) create mode 100644 examples/eds/e35.eds diff --git a/examples/eds/e35.eds b/examples/eds/e35.eds new file mode 100644 index 00000000..4978b818 --- /dev/null +++ b/examples/eds/e35.eds @@ -0,0 +1,8857 @@ +[FileInfo] +FileName=e35.eds +FileVersion=1 +FileRevision=1 +EDSVersion=402 +Description=example eds file +CreationTime=12:00AM +CreationDate=01-01-2020 +CreatedBy=Manufacturer +ModificationTime=12:34AM +ModificationDate=06-14-2017 +ModifiedBy=Manufacturer + +[DeviceInfo] +VendorName=Manufacturer +VendorNumber=001 +ProductName=example +ProductNumber=25 +RevisionNumber=295 +OrderCode=25 +Baudrate_10=1 +Baudrate_20=1 +Baudrate_50=1 +Baudrate_125=1 +Baudrate_250=1 +Baudrate_500=1 +Baudrate_800=0 +Baudrate_1000=1 +SimpleBootUpMaster=0 +SimpleBootUpSlave=1 +Granularity=8 +DynamicChannelsSupported=0 +GroupMessaging=0 +NrOfRXPDO=4 +NrOfTXPDO=4 +LSS_Supported=1 + +[DummyUsage] +Dummy0001=0 +Dummy0002=0 +Dummy0003=0 +Dummy0004=0 +Dummy0005=1 +Dummy0006=1 +Dummy0007=1 + +[Comments] +Lines=0 + +[MandatoryObjects] +SupportedObjects=3 +1=0x1000 +2=0x1001 +3=0x1018 + +[1000] +ParameterName=Device Type +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0x20192 +PDOMapping=0x0 + +[1001] +ParameterName=Error Register +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +PDOMapping=0x0 + +[1018] +SubNumber=0x5 +ParameterName=Identity Object +ObjectType=0x9 + +[1018sub0] +ParameterName=Number of Entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x4 +PDOMapping=0x0 + +[1018sub1] +ParameterName=Vendor-ID +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0xFF +PDOMapping=0x0 + +[1018sub2] +ParameterName=Product code +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0x01 +PDOMapping=0x0 + +[1018sub3] +ParameterName=Revision number +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0x01 +PDOMapping=0x0 + +[1018sub4] +ParameterName=Serial number +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 + +[ManufacturerObjects] +SupportedObjects=105 +1=0x2000 +2=0x2001 +3=0x200F +4=0x2020 +5=0x20C2 +6=0x2101 +7=0x2102 +8=0x2103 +9=0x2290 +10=0x2301 +11=0x2305 +12=0x2306 +13=0x2307 +14=0x2308 +15=0x2310 +16=0x2311 +17=0x2312 +18=0x2313 +19=0x2314 +20=0x2321 +21=0x2340 +22=0x2341 +23=0x2342 +24=0x2343 +25=0x2344 +26=0x2345 +27=0x2350 +28=0x2351 +29=0x2352 +30=0x2353 +31=0x2354 +32=0x2360 +33=0x2361 +34=0x2370 +35=0x2380 +36=0x2381 +37=0x2382 +38=0x2383 +39=0x23D0 +40=0x23D1 +41=0x23F0 +42=0x2400 +43=0x2430 +44=0x2431 +45=0x2432 +46=0x2433 +47=0x2434 +48=0x2435 +49=0x2436 +50=0x243A +51=0x2500 +52=0x2501 +53=0x2502 +54=0x2503 +55=0x2504 +56=0x2505 +57=0x2506 +58=0x2507 +59=0x2508 +60=0x2509 +61=0x250A +62=0x2510 +63=0x2600 +64=0x2601 +65=0x2602 +66=0x2603 +67=0x2610 +68=0x2611 +69=0x2700 +70=0x2701 +71=0x2702 +72=0x2A02 +73=0x2A03 +74=0x2A04 +75=0x2A05 +76=0x2A08 +77=0x2A0A +78=0x2A0B +79=0x2A10 +80=0x2A11 +81=0x2C00 +82=0x2C01 +83=0x2C02 +84=0x2C03 +85=0x2C04 +86=0x2C05 +87=0x2C06 +88=0x2C07 +89=0x2C08 +90=0x2C09 +91=0x2C0A +92=0x2C50 +93=0x2C51 +94=0x2C52 +95=0x2C55 +96=0x2D00 +97=0x2FF0 +98=0x2FF1 +99=0x2FF2 +100=0x2FF3 +101=0x2FF4 +102=0x2FF5 +103=0x2FFD +104=0x2FFE + +[2000] +SubNumber=0x9 +ParameterName=Uart configuration +ObjectType=0x8 + +[2000sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x8 +PDOMapping=0x0 + +[2000sub1] +ParameterName=Node ID +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 +LowLimit=0x1 +HighLimit=0x7F +ParameterValue=0x20 + +[2000sub2] +ParameterName=Baudrate +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2000sub3] +ParameterName=Daisy chain mode +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2000sub4] +ParameterName=Base format +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2000sub5] +ParameterName=Statusword on request +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[2000sub6] +ParameterName=CRC enable +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2000sub7] +ParameterName=Lifeguard message +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2000sub8] +ParameterName=Binary mode +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2001] +SubNumber=0x4 +ParameterName=CANopen configuration +ObjectType=0x9 + +[2001sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2001sub1] +ParameterName=Node ID +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +ParameterValue=0x20 +PDOMapping=0x0 +LowLimit=0x1 +HighLimit=0x7F + +[2001sub2] +ParameterName=Baudrate +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x8 + +[2001sub3] +ParameterName=Diagnosis Level +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x2 + +[200F] +SubNumber=0x4 +ParameterName=Communication password +ObjectType=0x8 + +[200Fsub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[200Fsub1] +ParameterName=All password +ObjectType=0x7 +DataType=0x0007 +AccessType=wo +DefaultValue=0x0 +PDOMapping=0x0 + +[200Fsub2] +ParameterName=UART password +ObjectType=0x7 +DataType=0x0007 +AccessType=wo +DefaultValue=0x0 +PDOMapping=0x0 + +[200Fsub3] +ParameterName=CANopen password +ObjectType=0x7 +DataType=0x0007 +AccessType=wo +DefaultValue=0x0 +PDOMapping=0x0 + +[2020] +ParameterName=Enable alternative frequency PWM +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[20C2] +SubNumber=0x4 +ParameterName=Driver temperature +ObjectType=0x8 + +[20C2sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[20C2sub1] +ParameterName=Actual temperature +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[20C2sub2] +ParameterName=Max user temperature +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=85000 +PDOMapping=0x0 + +[20C2sub3] +ParameterName=Min user temperature +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-20000 +PDOMapping=0x0 + +[2101] +SubNumber=0x4 +ParameterName=Bus voltage +ObjectType=0x8 + +[2101sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2101sub1] +ParameterName=DC link circuit voltage +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2101sub2] +ParameterName=Max user bus voltage +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0xEA60 +PDOMapping=0x0 + +[2101sub3] +ParameterName=Min user bus voltage +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x2EE0 +PDOMapping=0x0 + +[2102] +SubNumber=0x4 +ParameterName=Homing extra parameters +ObjectType=0x9 + +[2102sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2102sub1] +ParameterName=Total homing timeout +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x1F40 +PDOMapping=0x0 + +[2102sub2] +ParameterName=Torque threshold +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xC8 +PDOMapping=0x0 + +[2102sub3] +ParameterName=Start-up homing sensor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x9 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0xC + +[2103] +SubNumber=0x5 +ParameterName=Shunt configuration +ObjectType=0x9 + +[2103sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x4 +PDOMapping=0x0 + +[2103sub1] +ParameterName=Available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2103sub2] +ParameterName=Duty used +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x400 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x800 + +[2103sub3] +ParameterName=Hysteresis +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x64 + +[2103sub4] +ParameterName=Frequency +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 +LowLimit=0x3E8 +HighLimit=0x13880 + +[2290] +ParameterName=Drive setup status +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2301] +ParameterName=Motor pair poles +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x4 +PDOMapping=0x0 + +[2305] +SubNumber=0x6 +ParameterName=Commutation +ObjectType=0x9 + +[2305sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[2305sub1] +ParameterName=Commutation sensor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2305sub2] +ParameterName=Initial angle determination method +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x2 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x3 + +[2305sub3] +ParameterName=Actual system angle +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2305sub4] +ParameterName=Reference sensor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2305sub5] +ParameterName=Commutation angle offset +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x0 + +[2306] +SubNumber=0x4 +ParameterName=Forced alignment method +ObjectType=0x9 + +[2306sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2306sub1] +ParameterName=Process time +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[2306sub2] +ParameterName=Process current +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1F4 +PDOMapping=0x0 + +[2306sub3] +ParameterName=Process tolerance +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x5 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x64 + +[2307] +SubNumber=0x2 +ParameterName=Known alignment method +ObjectType=0x9 + +[2307sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x1 +PDOMapping=0x0 + +[2307sub1] +ParameterName=Initial rotor angle +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2308] +SubNumber=0x2 +ParameterName=Non-incremental alignment +ObjectType=0x9 + +[2308sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x1 +PDOMapping=0x0 + +[2308sub1] +ParameterName=Offset from phase A +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2310] +SubNumber=0x4 +ParameterName=Feedbacks +ObjectType=0x8 + +[2310sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2310sub1] +ParameterName=Torque sensor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2310sub2] +ParameterName=Velocity sensor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0xB + +[2310sub3] +ParameterName=Position sensor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0xC + +[2311] +ParameterName=Dig. encoder / SinCos polarity +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 +LowLimit=0 +HighLimit=1 + +[2312] +ParameterName=Dig. encoder / SinCos type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x2 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x4 + +[2313] +ParameterName=Dig. encoder / SinCos glitch filter +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x8 + +[2314] +ParameterName=Dig. encoder value +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +PDOMapping=0x1 + +[2321] +SubNumber=0x4 +ParameterName=Digital halls +ObjectType=0x9 + +[2321sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2321sub1] +ParameterName=Polarity +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2321sub2] +ParameterName=Value +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +PDOMapping=0x1 + +[2321sub3] +ParameterName=Halls step offset +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x5 + +[2340] +SubNumber=0x4 +ParameterName=Linear hall values +ObjectType=0x8 + +[2340sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2340sub1] +ParameterName=Linear hall 1 value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2340sub2] +ParameterName=Linear hall 2 value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2340sub3] +ParameterName=Linear hall 3 value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2341] +SubNumber=0x4 +ParameterName=Linear hall offsets +ObjectType=0x8 + +[2341sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2341sub1] +ParameterName=Linear hall 1 offset +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7FFF +PDOMapping=0x0 + +[2341sub2] +ParameterName=Linear hall 2 offset +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7FFF +PDOMapping=0x0 + +[2341sub3] +ParameterName=Linear hall 3 offset +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7FFF +PDOMapping=0x0 + +[2342] +SubNumber=0x4 +ParameterName=Linear hall gains +ObjectType=0x8 + +[2342sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2342sub1] +ParameterName=Linear hall 1 gain +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xFFFF +PDOMapping=0x0 + +[2342sub2] +ParameterName=Linear hall 2 gain +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xFFFF +PDOMapping=0x0 + +[2342sub3] +ParameterName=Linear hall 3 gain +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xFFFF +PDOMapping=0x0 + +[2343] +SubNumber=0x4 +ParameterName=Linear hall rotational +ObjectType=0x8 + +[2343sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2343sub1] +ParameterName=Linear hall alpha +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2343sub2] +ParameterName=Linear hall beta +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2343sub3] +ParameterName=Linear hall zero +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2344] +ParameterName=Linear hall estimated angle +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2345] +ParameterName=Linear hall polarity +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2350] +SubNumber=0x4 +ParameterName=SinCos values +ObjectType=0x8 + +[2350sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2350sub1] +ParameterName=Sinus value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2350sub2] +ParameterName=Cosinus value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2350sub3] +ParameterName=Reference value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2351] +SubNumber=0x4 +ParameterName=SinCos offsets +ObjectType=0x8 + +[2351sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2351sub1] +ParameterName=Sinus offset +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7FFF +PDOMapping=0x0 + +[2351sub2] +ParameterName=Cosinus offset +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7FFF +PDOMapping=0x0 + +[2351sub3] +ParameterName=Reference offset +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7FFF +PDOMapping=0x0 + +[2352] +SubNumber=0x4 +ParameterName=SinCos gains +ObjectType=0x8 + +[2352sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2352sub1] +ParameterName=Sinus gain +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xFFFF +PDOMapping=0x0 + +[2352sub2] +ParameterName=Cosinus gain +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xFFFF +PDOMapping=0x0 + +[2352sub3] +ParameterName=Reference gain +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xFFFF +PDOMapping=0x0 + +[2353] +ParameterName=SinCos estimated angle +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2354] +ParameterName=SinCos multiplier factor +ObjectType=0x7 +DataType=0x0003 +AccessType=rw +DefaultValue=10 +PDOMapping=0x0 +LowLimit=2 +HighLimit=10 + +[2360] +SubNumber=0x8 +ParameterName=SMO parameters +ObjectType=0x9 + +[2360sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x7 +PDOMapping=0x0 + +[2360sub1] +ParameterName=Lock time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x1F4 +PDOMapping=0x0 + +[2360sub2] +ParameterName=Open loop final speed +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x190 +PDOMapping=0x0 + +[2360sub3] +ParameterName=Open loop current +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x258 +PDOMapping=0x0 + +[2360sub4] +ParameterName=Open loop time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7D0 +PDOMapping=0x0 + +[2360sub5] +ParameterName=Open-close transition enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2360sub6] +ParameterName=SMO Gain +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x19 +PDOMapping=0x0 + +[2360sub7] +ParameterName=SMO Linear zone +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[2361] +SubNumber=0x8 +ParameterName=SMO Results +ObjectType=0x9 + +[2361sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x7 +PDOMapping=0x0 + +[2361sub1] +ParameterName=Estimated i-alpha +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2361sub2] +ParameterName=Estimated i-beta +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2361sub3] +ParameterName=Measured i-alpha +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2361sub4] +ParameterName=Measured i-beta +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2361sub5] +ParameterName=Estimated BEMF alpha +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2361sub6] +ParameterName=Estimated BEMF beta +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2361sub7] +ParameterName=Estimated theta +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2370] +SubNumber=0x8 +ParameterName=Resolver parameters +ObjectType=0x9 + +[2370sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x7 +PDOMapping=0x0 + +[2370sub1] +ParameterName=Resolver angle +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2370sub2] +ParameterName=Resolver tolerance +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0xA +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x64 + +[2370sub3] +ParameterName=Resolver pole pairs +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 +LowLimit=0x1 +HighLimit=0x30 + +[2370sub4] +ParameterName=Resolver polarity +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2370sub5] +ParameterName=Resolver adapted angle +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2370sub6] +ParameterName=Resolver error code +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x4 + +[2370sub7] +ParameterName=Resolver error filter +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0xA +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x64 + +[2380] +SubNumber=0xB +ParameterName=SSI Absolute encoder configuration +ObjectType=0x9 + +[2380sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0xa +PDOMapping=0x0 + +[2380sub1] +ParameterName=Frame type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x2 + +[2380sub2] +ParameterName=Frame size +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x19 +PDOMapping=0x0 + +[2380sub3] +ParameterName=Codification +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2380sub4] +ParameterName=Max. clock rate +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7D0 +PDOMapping=0x0 +LowLimit=0x3E8 +HighLimit=0x7D0 + +[2380sub5] +ParameterName=Single-turn bits +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0xC +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x20 + +[2380sub6] +ParameterName=Single-turn start bit +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x20 + +[2380sub7] +ParameterName=Multi-turn bits +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0xD +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x20 + +[2380sub8] +ParameterName=Multi-turn start bit +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0xC +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x20 + +[2380sub9] +ParameterName=Endianness +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2380subA] +ParameterName=Error filter +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x10 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x64 + +[2381] +ParameterName=SSI multi-turn value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2382] +ParameterName=SSI single-turn value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2383] +ParameterName=SSI polarity +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[23D0] +SubNumber=0x6 +ParameterName=Analog input feedback +ObjectType=0x9 + +[23D0sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[23D0sub1] +ParameterName=Analog input used +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[23D0sub2] +ParameterName=Analog input motion offset +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[23D0sub3] +ParameterName=Reserved +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[23D0sub4] +ParameterName=Analog input motion range +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0xFFF +PDOMapping=0x0 + +[23D0sub5] +ParameterName=Analog input polarity +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[23D1] +SubNumber=0x83 +ParameterName=Analog input feedback correction +ObjectType=0x9 + +[23D1sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x82 +PDOMapping=0x0 + +[23D1sub1] +ParameterName=Correction enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[23D1sub2] +ParameterName=Value 0 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-2000 +PDOMapping=0x0 + +[23D1sub3] +ParameterName=Value 1 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1968 +PDOMapping=0x0 + +[23D1sub4] +ParameterName=Value 2 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1937 +PDOMapping=0x0 + +[23D1sub5] +ParameterName=Value 3 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1906 +PDOMapping=0x0 + +[23D1sub6] +ParameterName=Value 4 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1875 +PDOMapping=0x0 + +[23D1sub7] +ParameterName=Value 5 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1843 +PDOMapping=0x0 + +[23D1sub8] +ParameterName=Value 6 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1812 +PDOMapping=0x0 + +[23D1sub9] +ParameterName=Value 7 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1781 +PDOMapping=0x0 + +[23D1subA] +ParameterName=Value 8 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1750 +PDOMapping=0x0 + +[23D1subB] +ParameterName=Value 9 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1718 +PDOMapping=0x0 + +[23D1subC] +ParameterName=Value 10 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1687 +PDOMapping=0x0 + +[23D1subD] +ParameterName=Value 11 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1656 +PDOMapping=0x0 + +[23D1subE] +ParameterName=Value 12 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1625 +PDOMapping=0x0 + +[23D1subF] +ParameterName=Value 13 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1593 +PDOMapping=0x0 + +[23D1sub10] +ParameterName=Value 14 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1562 +PDOMapping=0x0 + +[23D1sub11] +ParameterName=Value 15 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1531 +PDOMapping=0x0 + +[23D1sub12] +ParameterName=Value 16 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1500 +PDOMapping=0x0 + +[23D1sub13] +ParameterName=Value 17 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1468 +PDOMapping=0x0 + +[23D1sub14] +ParameterName=Value 18 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1437 +PDOMapping=0x0 + +[23D1sub15] +ParameterName=Value 19 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1406 +PDOMapping=0x0 + +[23D1sub16] +ParameterName=Value 20 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1375 +PDOMapping=0x0 + +[23D1sub17] +ParameterName=Value 21 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1343 +PDOMapping=0x0 + +[23D1sub18] +ParameterName=Value 22 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1312 +PDOMapping=0x0 + +[23D1sub19] +ParameterName=Value 23 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1281 +PDOMapping=0x0 + +[23D1sub1A] +ParameterName=Value 24 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1250 +PDOMapping=0x0 + +[23D1sub1B] +ParameterName=Value 25 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1218 +PDOMapping=0x0 + +[23D1sub1C] +ParameterName=Value 26 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1187 +PDOMapping=0x0 + +[23D1sub1D] +ParameterName=Value 27 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1156 +PDOMapping=0x0 + +[23D1sub1E] +ParameterName=Value 28 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1125 +PDOMapping=0x0 + +[23D1sub1F] +ParameterName=Value 29 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1093 +PDOMapping=0x0 + +[23D1sub20] +ParameterName=Value 30 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1062 +PDOMapping=0x0 + +[23D1sub21] +ParameterName=Value 31 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1031 +PDOMapping=0x0 + +[23D1sub22] +ParameterName=Value 32 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-1000 +PDOMapping=0x0 + +[23D1sub23] +ParameterName=Value 33 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-968 +PDOMapping=0x0 + +[23D1sub24] +ParameterName=Value 34 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-937 +PDOMapping=0x0 + +[23D1sub25] +ParameterName=Value 35 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-906 +PDOMapping=0x0 + +[23D1sub26] +ParameterName=Value 36 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-875 +PDOMapping=0x0 + +[23D1sub27] +ParameterName=Value 37 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-843 +PDOMapping=0x0 + +[23D1sub28] +ParameterName=Value 38 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-812 +PDOMapping=0x0 + +[23D1sub29] +ParameterName=Value 39 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-781 +PDOMapping=0x0 + +[23D1sub2A] +ParameterName=Value 40 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-750 +PDOMapping=0x0 + +[23D1sub2B] +ParameterName=Value 41 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-718 +PDOMapping=0x0 + +[23D1sub2C] +ParameterName=Value 42 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-687 +PDOMapping=0x0 + +[23D1sub2D] +ParameterName=Value 43 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-656 +PDOMapping=0x0 + +[23D1sub2E] +ParameterName=Value 44 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-625 +PDOMapping=0x0 + +[23D1sub2F] +ParameterName=Value 45 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-593 +PDOMapping=0x0 + +[23D1sub30] +ParameterName=Value 46 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-562 +PDOMapping=0x0 + +[23D1sub31] +ParameterName=Value 47 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-531 +PDOMapping=0x0 + +[23D1sub32] +ParameterName=Value 48 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-500 +PDOMapping=0x0 + +[23D1sub33] +ParameterName=Value 49 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-468 +PDOMapping=0x0 + +[23D1sub34] +ParameterName=Value 50 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-437 +PDOMapping=0x0 + +[23D1sub35] +ParameterName=Value 51 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-406 +PDOMapping=0x0 + +[23D1sub36] +ParameterName=Value 52 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-375 +PDOMapping=0x0 + +[23D1sub37] +ParameterName=Value 53 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-343 +PDOMapping=0x0 + +[23D1sub38] +ParameterName=Value 54 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-312 +PDOMapping=0x0 + +[23D1sub39] +ParameterName=Value 55 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-281 +PDOMapping=0x0 + +[23D1sub3A] +ParameterName=Value 56 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-250 +PDOMapping=0x0 + +[23D1sub3B] +ParameterName=Value 57 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-218 +PDOMapping=0x0 + +[23D1sub3C] +ParameterName=Value 58 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-187 +PDOMapping=0x0 + +[23D1sub3D] +ParameterName=Value 59 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-156 +PDOMapping=0x0 + +[23D1sub3E] +ParameterName=Value 60 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-125 +PDOMapping=0x0 + +[23D1sub3F] +ParameterName=Value 61 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-93 +PDOMapping=0x0 + +[23D1sub40] +ParameterName=Value 62 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-62 +PDOMapping=0x0 + +[23D1sub41] +ParameterName=Value 63 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=-31 +PDOMapping=0x0 + +[23D1sub42] +ParameterName=Value 64 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[23D1sub43] +ParameterName=Value 65 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=31 +PDOMapping=0x0 + +[23D1sub44] +ParameterName=Value 66 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=62 +PDOMapping=0x0 + +[23D1sub45] +ParameterName=Value 67 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=93 +PDOMapping=0x0 + +[23D1sub46] +ParameterName=Value 68 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=125 +PDOMapping=0x0 + +[23D1sub47] +ParameterName=Value 69 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=156 +PDOMapping=0x0 + +[23D1sub48] +ParameterName=Value 70 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=187 +PDOMapping=0x0 + +[23D1sub49] +ParameterName=Value 71 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=218 +PDOMapping=0x0 + +[23D1sub4A] +ParameterName=Value 72 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=250 +PDOMapping=0x0 + +[23D1sub4B] +ParameterName=Value 73 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=281 +PDOMapping=0x0 + +[23D1sub4C] +ParameterName=Value 74 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=312 +PDOMapping=0x0 + +[23D1sub4D] +ParameterName=Value 75 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=343 +PDOMapping=0x0 + +[23D1sub4E] +ParameterName=Value 76 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=375 +PDOMapping=0x0 + +[23D1sub4F] +ParameterName=Value 77 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=406 +PDOMapping=0x0 + +[23D1sub50] +ParameterName=Value 78 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=437 +PDOMapping=0x0 + +[23D1sub51] +ParameterName=Value 79 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=468 +PDOMapping=0x0 + +[23D1sub52] +ParameterName=Value 80 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=500 +PDOMapping=0x0 + +[23D1sub53] +ParameterName=Value 81 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=531 +PDOMapping=0x0 + +[23D1sub54] +ParameterName=Value 82 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=562 +PDOMapping=0x0 + +[23D1sub55] +ParameterName=Value 83 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=593 +PDOMapping=0x0 + +[23D1sub56] +ParameterName=Value 84 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=625 +PDOMapping=0x0 + +[23D1sub57] +ParameterName=Value 85 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=656 +PDOMapping=0x0 + +[23D1sub58] +ParameterName=Value 86 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=687 +PDOMapping=0x0 + +[23D1sub59] +ParameterName=Value 87 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=718 +PDOMapping=0x0 + +[23D1sub5A] +ParameterName=Value 88 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=750 +PDOMapping=0x0 + +[23D1sub5B] +ParameterName=Value 89 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=781 +PDOMapping=0x0 + +[23D1sub5C] +ParameterName=Value 90 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=812 +PDOMapping=0x0 + +[23D1sub5D] +ParameterName=Value 91 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=843 +PDOMapping=0x0 + +[23D1sub5E] +ParameterName=Value 92 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=875 +PDOMapping=0x0 + +[23D1sub5F] +ParameterName=Value 93 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=906 +PDOMapping=0x0 + +[23D1sub60] +ParameterName=Value 94 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=937 +PDOMapping=0x0 + +[23D1sub61] +ParameterName=Value 95 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=968 +PDOMapping=0x0 + +[23D1sub62] +ParameterName=Value 96 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1000 +PDOMapping=0x0 + +[23D1sub63] +ParameterName=Value 97 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1031 +PDOMapping=0x0 + +[23D1sub64] +ParameterName=Value 98 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1062 +PDOMapping=0x0 + +[23D1sub65] +ParameterName=Value 99 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1093 +PDOMapping=0x0 + +[23D1sub66] +ParameterName=Value 100 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1125 +PDOMapping=0x0 + +[23D1sub67] +ParameterName=Value 101 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1156 +PDOMapping=0x0 + +[23D1sub68] +ParameterName=Value 102 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1187 +PDOMapping=0x0 + +[23D1sub69] +ParameterName=Value 103 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1218 +PDOMapping=0x0 + +[23D1sub6A] +ParameterName=Value 104 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1250 +PDOMapping=0x0 + +[23D1sub6B] +ParameterName=Value 105 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1281 +PDOMapping=0x0 + +[23D1sub6C] +ParameterName=Value 106 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1312 +PDOMapping=0x0 + +[23D1sub6D] +ParameterName=Value 107 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1343 +PDOMapping=0x0 + +[23D1sub6E] +ParameterName=Value 108 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1375 +PDOMapping=0x0 + +[23D1sub6F] +ParameterName=Value 109 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1406 +PDOMapping=0x0 + +[23D1sub70] +ParameterName=Value 110 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1437 +PDOMapping=0x0 + +[23D1sub71] +ParameterName=Value 111 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1468 +PDOMapping=0x0 + +[23D1sub72] +ParameterName=Value 112 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1500 +PDOMapping=0x0 + +[23D1sub73] +ParameterName=Value 113 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1531 +PDOMapping=0x0 + +[23D1sub74] +ParameterName=Value 114 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1562 +PDOMapping=0x0 + +[23D1sub75] +ParameterName=Value 115 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1593 +PDOMapping=0x0 + +[23D1sub76] +ParameterName=Value 116 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1625 +PDOMapping=0x0 + +[23D1sub77] +ParameterName=Value 117 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1656 +PDOMapping=0x0 + +[23D1sub78] +ParameterName=Value 118 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1687 +PDOMapping=0x0 + +[23D1sub79] +ParameterName=Value 119 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1718 +PDOMapping=0x0 + +[23D1sub7A] +ParameterName=Value 120 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1750 +PDOMapping=0x0 + +[23D1sub7B] +ParameterName=Value 121 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1781 +PDOMapping=0x0 + +[23D1sub7C] +ParameterName=Value 122 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1812 +PDOMapping=0x0 + +[23D1sub7D] +ParameterName=Value 123 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1843 +PDOMapping=0x0 + +[23D1sub7E] +ParameterName=Value 124 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1875 +PDOMapping=0x0 + +[23D1sub7F] +ParameterName=Value 125 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1906 +PDOMapping=0x0 + +[23D1sub80] +ParameterName=Value 126 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1937 +PDOMapping=0x0 + +[23D1sub81] +ParameterName=Value 127 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1968 +PDOMapping=0x0 + +[23D1sub82] +ParameterName=Value 128 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=2000 +PDOMapping=0x0 + +[23F0] +SubNumber=0x4 +ParameterName=DC-Tachometer parameters +ObjectType=0x9 + +[23F0sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[23F0sub1] +ParameterName=Voltage (mV) per 1000rpm +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x208 +PDOMapping=0x0 + +[23F0sub2] +ParameterName=Analog input used +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[23F0sub3] +ParameterName=Analog input offset +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x800 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1000 + +[2400] +ParameterName=System Polarity +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2430] +ParameterName=Command reference source +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2431] +ParameterName=Local/remote control +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2432] +SubNumber=0x3 +ParameterName=Electronic gearing cmd source +ObjectType=0x8 + +[2432sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2432sub1] +ParameterName=Input gear +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1 +PDOMapping=0x0 + +[2432sub2] +ParameterName=Output gear +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1 +PDOMapping=0x0 + +[2433] +SubNumber=0x3 +ParameterName=Step and direction cmd source +ObjectType=0x8 + +[2433sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2433sub1] +ParameterName=Step Out +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[2433sub2] +ParameterName=Step In +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[2434] +SubNumber=0x5 +ParameterName=Analog input cmd source +ObjectType=0x9 + +[2434sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x4 +PDOMapping=0x0 + +[2434sub1] +ParameterName=Analog input used +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[2434sub2] +ParameterName=Analog input motion offset +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2434sub3] +ParameterName=Analog input velocity deadband +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2434sub4] +ParameterName=Analog input motion range +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1000 +PDOMapping=0x0 + +[2435] +SubNumber=0x7 +ParameterName=PWM cmd source +ObjectType=0x9 + +[2435sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x6 +PDOMapping=0x0 + +[2435sub1] +ParameterName=Mode +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2435sub2] +ParameterName=PWM input motion offset +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2435sub3] +ParameterName=PWM input velocity deadband +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2435sub4] +ParameterName=PWM input motion range +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1000 +PDOMapping=0x0 + +[2435sub5] +ParameterName=PWM duty actual +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x0 + +[2435sub6] +ParameterName=PWM period actual +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x0 + +[2436] +SubNumber=0x4 +ParameterName=Internal generator cmd source +ObjectType=0x9 + +[2436sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2436sub1] +ParameterName=Function type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x3 + +[2436sub2] +ParameterName=Amplitude +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x7FFFFFFF + +[2436sub3] +ParameterName=Frequency (10 mHz) +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xA +PDOMapping=0x0 +LowLimit=0x2 +HighLimit=0xFFFF + +[243A] +ParameterName=Internal target cmd source +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x0 + +[2500] +SubNumber=0x8 +ParameterName=Position control parameter set +ObjectType=0x8 + +[2500sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x7 +PDOMapping=0x0 + +[2500sub1] +ParameterName=Proportional constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x2710 +PDOMapping=0x0 + +[2500sub2] +ParameterName=Integral constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x5 +PDOMapping=0x0 + +[2500sub3] +ParameterName=Derivative constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x9C40 +PDOMapping=0x0 + +[2500sub4] +ParameterName=Integral antiwindup constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2500sub5] +ParameterName=Velocity feedforward constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2500sub6] +ParameterName=Acceleration feedforward constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2500sub7] +ParameterName=Integral limit +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[2501] +SubNumber=0x7 +ParameterName=Velocity control parameter set +ObjectType=0x8 + +[2501sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x6 +PDOMapping=0x0 + +[2501sub1] +ParameterName=Proportional constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0xFA0 +PDOMapping=0x0 + +[2501sub2] +ParameterName=Integral constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x32 +PDOMapping=0x0 + +[2501sub3] +ParameterName=Derivative constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2501sub4] +ParameterName=Integral antiwindup constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x186A0 +PDOMapping=0x0 + +[2501sub5] +ParameterName=Acceleration feedforward constant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2501sub6] +ParameterName=Integral limit +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[2502] +SubNumber=0x4 +ParameterName=Flux control parameter set +ObjectType=0x9 + +[2502sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2502sub1] +ParameterName=Proportional constant +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xBB8 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x7FFF + +[2502sub2] +ParameterName=Integral constant +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x12C +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x7FFF + +[2502sub3] +ParameterName=Constant scaling +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x8 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x10 + +[2503] +SubNumber=0x4 +ParameterName=Torque control parameter set +ObjectType=0x9 + +[2503sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2503sub1] +ParameterName=Proportional constant +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xBB8 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x7FFF + +[2503sub2] +ParameterName=Integral constant +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x12C +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x7FFF + +[2503sub3] +ParameterName=Constant scaling +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x8 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x10 + +[2504] +SubNumber=0x3 +ParameterName=Torque demand low pass filter +ObjectType=0x9 + +[2504sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2504sub1] +ParameterName=Filter enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2504sub2] +ParameterName=Cutoff frequency +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x64 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x5DC + +[2505] +SubNumber=0x3 +ParameterName=Torque actual low pass filter +ObjectType=0x9 + +[2505sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2505sub1] +ParameterName=Filter enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2505sub2] +ParameterName=Cutoff frequency +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x64 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x5DC + +[2506] +ParameterName=Max torque cte speed +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[2507] +SubNumber=0x6 +ParameterName=Control loops configuration +ObjectType=0x8 + +[2507sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[2507sub1] +ParameterName=Bypass torque loop +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2507sub2] +ParameterName=Position feedback openloop +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2507sub3] +ParameterName=Velocity feedback openloop +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2507sub4] +ParameterName=Torque feedback openloop +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2507sub5] +ParameterName=Velocity mode uses Position loop +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2508] +ParameterName=Torque window +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xA +PDOMapping=0x0 + +[2509] +ParameterName=Torque window time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[250A] +SubNumber=0x9 +ParameterName=Disturbance signal +ObjectType=0x9 + +[250Asub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x8 +PDOMapping=0x0 + +[250Asub1] +ParameterName=Max entries +ObjectType=0x7 +DataType=0x0006 +AccessType=const +DefaultValue=0x3E8 +PDOMapping=0x0 + +[250Asub2] +ParameterName=Filled entries +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x3E8 + +[250Asub3] +ParameterName=Entry number +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x3E8 + +[250Asub4] +ParameterName=Entry value +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +PDOMapping=0x0 + +[250Asub5] +ParameterName=Injection point +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[250Asub6] +ParameterName=Number of cycles +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[250Asub7] +ParameterName=Update rate +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[250Asub8] +ParameterName=Output value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x0 + +[2510] +ParameterName=Enable current low pass filter +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2600] +SubNumber=0x4 +ParameterName=Current readings +ObjectType=0x8 + +[2600sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2600sub1] +ParameterName=Current phase A +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2600sub2] +ParameterName=Current phase B +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2600sub3] +ParameterName=Current phase C +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2601] +SubNumber=0x3 +ParameterName=Current d-q +ObjectType=0x8 + +[2601sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2601sub1] +ParameterName=Current direct +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2601sub2] +ParameterName=Current quadrature +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2602] +SubNumber=0x4 +ParameterName=Current readings thousands +ObjectType=0x8 + +[2602sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2602sub1] +ParameterName=Current phase A +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2602sub2] +ParameterName=Current phase B +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2602sub3] +ParameterName=Current phase C +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2603] +SubNumber=0x3 +ParameterName=Current demand steppers +ObjectType=0x8 + +[2603sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2603sub1] +ParameterName=Coil 1 +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2603sub2] +ParameterName=Coil 2 +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2610] +SubNumber=0x4 +ParameterName=Voltage generated +ObjectType=0x8 + +[2610sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2610sub1] +ParameterName=Voltage phase A +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[2610sub2] +ParameterName=Voltage phase B +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[2610sub3] +ParameterName=Voltage phase C +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[2611] +SubNumber=0x3 +ParameterName=Voltage d-q +ObjectType=0x8 + +[2611sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2611sub1] +ParameterName=Voltage direct +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2611sub2] +ParameterName=Voltage quadrature +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[2700] +SubNumber=0x7 +ParameterName=Stepper parameters +ObjectType=0x9 + +[2700sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x6 +PDOMapping=0x0 + +[2700sub1] +ParameterName=Number of microsteps bits +ObjectType=0x7 +DataType=0x0005 +AccessType=rww +DefaultValue=0x2 +PDOMapping=0x1 +LowLimit=0x0 +HighLimit=0x9 + +[2700sub2] +ParameterName=Run current +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x190 +PDOMapping=0x0 + +[2700sub3] +ParameterName=Standby current +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x64 +PDOMapping=0x0 + +[2700sub4] +ParameterName=Number of steps per revolution +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xC8 +PDOMapping=0x0 + +[2700sub5] +ParameterName=Number of phases +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x2 +PDOMapping=0x0 + +[2700sub6] +ParameterName=Enhanced current mode +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2701] +SubNumber=0x7 +ParameterName=Motor parameters +ObjectType=0x9 + +[2701sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x6 +PDOMapping=0x0 + +[2701sub1] +ParameterName=Resistance phase-to-phase +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x320 +PDOMapping=0x0 + +[2701sub2] +ParameterName=Inductance phase-to-phase +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x78 +PDOMapping=0x0 + +[2701sub3] +ParameterName=Magnetic pole pitch +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[2701sub4] +ParameterName=Motor backemf constant - Kv +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2701sub5] +ParameterName=Stroke (um) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[2701sub6] +ParameterName=Motor torque constant - Km +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x67 +PDOMapping=0x0 + +[2702] +SubNumber=0x3 +ParameterName=i2t parameters +ObjectType=0x9 + +[2702sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2702sub1] +ParameterName=Peak current +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[2702sub2] +ParameterName=Peak time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[2A02] +SubNumber=0x3 +ParameterName=Digital inputs/outputs +ObjectType=0x9 + +[2A02sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2A02sub1] +ParameterName=Input polarity +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xFFFF +PDOMapping=0x0 + +[2A02sub2] +ParameterName=Output polarity +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xFFFF +PDOMapping=0x0 + +[2A03] +SubNumber=0x9 +ParameterName=Analog inputs +ObjectType=0x8 + +[2A03sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x8 +PDOMapping=0x0 + +[2A03sub1] +ParameterName=Analog input 1 value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2A03sub2] +ParameterName=Analog input 2 value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2A03sub3] +ParameterName=Analog input 3 value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2A03sub4] +ParameterName=Analog input 4 value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2A03sub5] +ParameterName=Analog input 5 value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2A03sub6] +ParameterName=Analog input 6 value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2A03sub7] +ParameterName=Analog input 7 value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2A03sub8] +ParameterName=Analog input 8 value +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[2A04] +SubNumber=0x3 +ParameterName=Analog output +ObjectType=0x8 + +[2A04sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2A04sub1] +ParameterName=Analog output 1 value (11bits) +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x0 +PDOMapping=0x1 + +[2A04sub2] +ParameterName=Analog output 2 value (16bits) +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x0 +PDOMapping=0x1 + +[2A05] +SubNumber=0x7 +ParameterName=Brake options +ObjectType=0x9 + +[2A05sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x6 +PDOMapping=0x0 + +[2A05sub1] +ParameterName=Mode +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2A05sub2] +ParameterName=Delay before release brake +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2A05sub3] +ParameterName=Delay after enable brake +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2A05sub4] +ParameterName=Duty cycle +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x7FF +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x7FF + +[2A05sub5] +ParameterName=Full release brake pulse time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2A05sub6] +ParameterName=Frequency +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 +LowLimit=0x3E8 +HighLimit=0x13880 + +[2A08] +SubNumber=0x5 +ParameterName=Analog output automatic +ObjectType=0x9 + +[2A08sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x4 +PDOMapping=0x0 + +[2A08sub1] +ParameterName=Mode enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2A08sub2] +ParameterName=Source register +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=24692 +PDOMapping=0x0 + +[2A08sub3] +ParameterName=Destination output +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 +LowLimit=0x1 +HighLimit=0x2 + +[2A08sub4] +ParameterName=Max represented value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x7FFFFFFF +PDOMapping=0x0 + +[2A0A] +SubNumber=0x6 +ParameterName=PWM Inputs +ObjectType=0x9 + +[2A0Asub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[2A0Asub1] +ParameterName=Max PWM frequency +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 + +[2A0Asub2] +ParameterName=PWM period 1 +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2A0Asub3] +ParameterName=PWM duty 1 +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2A0Asub4] +ParameterName=PWM period 2 +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2A0Asub5] +ParameterName=PWM duty 2 +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[2A0B] +SubNumber=0x6 +ParameterName=PWM Outputs +ObjectType=0x9 + +[2A0Bsub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[2A0Bsub1] +ParameterName=Max PWM frequency +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 + +[2A0Bsub2] +ParameterName=PWM period 1 +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x9C4 +PDOMapping=0x1 + +[2A0Bsub3] +ParameterName=PWM duty 1 +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x4E2 +PDOMapping=0x1 + +[2A0Bsub4] +ParameterName=PWM period 2 +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x9C4 +PDOMapping=0x1 + +[2A0Bsub5] +ParameterName=PWM duty 2 +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x4E2 +PDOMapping=0x1 + +[2A10] +SubNumber=0xB +ParameterName=GPI mapping parameter +ObjectType=0x8 + +[2A10sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0xA +PDOMapping=0x0 + +[2A10sub1] +ParameterName=GPI 1 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10sub2] +ParameterName=GPI 2 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10sub3] +ParameterName=GPI 3 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10sub4] +ParameterName=GPI 4 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10sub5] +ParameterName=GPI 5 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10sub6] +ParameterName=GPI 6 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10sub7] +ParameterName=GPI 7 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10sub8] +ParameterName=GPI 8 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10sub9] +ParameterName=HS GPI 1 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A10subA] +ParameterName=HS GPI 2 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x6 + +[2A11] +SubNumber=0xB +ParameterName=GPO mapping parameter +ObjectType=0x8 + +[2A11sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0xA +PDOMapping=0x0 + +[2A11sub1] +ParameterName=GPO 1 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2A11sub2] +ParameterName=GPO 2 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2A11sub3] +ParameterName=GPO 3 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2A11sub4] +ParameterName=GPO 4 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2A11sub5] +ParameterName=GPO 5 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2A11sub6] +ParameterName=GPO 6 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2A11sub7] +ParameterName=GPO 7 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2A11sub8] +ParameterName=GPO 8 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2A11sub9] +ParameterName=GPO 9 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x9 +PDOMapping=0x0 +LowLimit=0x9 +HighLimit=0x9 + +[2A11subA] +ParameterName=GPO 10 function +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x8 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x9 + +[2C00] +SubNumber=0x65 +ParameterName=General purpose registers +ObjectType=0x8 + +[2C00sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x64 +PDOMapping=0x0 + +[2C00sub1] +ParameterName=ACCUM +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub2] +ParameterName=W2 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub3] +ParameterName=W3 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub4] +ParameterName=W4 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub5] +ParameterName=W5 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub6] +ParameterName=W6 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub7] +ParameterName=W7 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub8] +ParameterName=W8 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub9] +ParameterName=W9 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00subA] +ParameterName=W10 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00subB] +ParameterName=W11 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00subC] +ParameterName=W12 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00subD] +ParameterName=W13 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00subE] +ParameterName=W14 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00subF] +ParameterName=W15 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub10] +ParameterName=W16 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub11] +ParameterName=W17 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub12] +ParameterName=W18 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub13] +ParameterName=W19 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub14] +ParameterName=W20 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub15] +ParameterName=W21 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub16] +ParameterName=W22 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub17] +ParameterName=W23 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub18] +ParameterName=W24 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub19] +ParameterName=W25 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub1A] +ParameterName=W26 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub1B] +ParameterName=W27 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub1C] +ParameterName=W28 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub1D] +ParameterName=W29 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub1E] +ParameterName=W30 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub1F] +ParameterName=W31 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub20] +ParameterName=W32 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub21] +ParameterName=W33 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub22] +ParameterName=W34 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub23] +ParameterName=W35 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub24] +ParameterName=W36 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub25] +ParameterName=W37 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub26] +ParameterName=W38 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub27] +ParameterName=W39 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub28] +ParameterName=W40 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub29] +ParameterName=W41 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub2A] +ParameterName=W42 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub2B] +ParameterName=W43 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub2C] +ParameterName=W44 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub2D] +ParameterName=W45 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub2E] +ParameterName=W46 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub2F] +ParameterName=W47 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub30] +ParameterName=W48 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub31] +ParameterName=W49 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub32] +ParameterName=W50 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub33] +ParameterName=W51 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub34] +ParameterName=W52 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub35] +ParameterName=W53 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub36] +ParameterName=W54 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub37] +ParameterName=W55 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub38] +ParameterName=W56 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub39] +ParameterName=W57 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub3A] +ParameterName=W58 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub3B] +ParameterName=W59 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub3C] +ParameterName=W60 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub3D] +ParameterName=W61 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub3E] +ParameterName=W62 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub3F] +ParameterName=W63 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub40] +ParameterName=W64 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub41] +ParameterName=W65 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub42] +ParameterName=W66 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub43] +ParameterName=W67 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub44] +ParameterName=W68 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub45] +ParameterName=W69 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub46] +ParameterName=W70 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub47] +ParameterName=W71 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub48] +ParameterName=W72 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub49] +ParameterName=W73 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub4A] +ParameterName=W74 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub4B] +ParameterName=W75 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub4C] +ParameterName=W76 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub4D] +ParameterName=W77 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub4E] +ParameterName=W78 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub4F] +ParameterName=W79 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub50] +ParameterName=W80 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub51] +ParameterName=W81 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub52] +ParameterName=W82 +ObjectType=0x7 +DataType=0x0004 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[2C00sub53] +ParameterName=W83 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub54] +ParameterName=W84 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub55] +ParameterName=W85 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub56] +ParameterName=W86 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub57] +ParameterName=W87 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub58] +ParameterName=W88 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub59] +ParameterName=W89 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub5A] +ParameterName=W90 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub5B] +ParameterName=W91 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub5C] +ParameterName=W92 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub5D] +ParameterName=W93 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub5E] +ParameterName=W94 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub5F] +ParameterName=W95 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub60] +ParameterName=W96 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub61] +ParameterName=W97 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub62] +ParameterName=W98 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub63] +ParameterName=W99 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C00sub64] +ParameterName=W100 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C01] +SubNumber=0x18 +ParameterName=Register commands +ObjectType=0x8 + +[2C01sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x17 +PDOMapping=0x0 + +[2C01sub1] +ParameterName=Add constant to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub2] +ParameterName=Accumulator divide constant +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub3] +ParameterName=Xor constant to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub4] +ParameterName=Accumulator multiply constant +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub5] +ParameterName=And constant to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub6] +ParameterName=Or constant to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub7] +ParameterName=Substract constant from accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub8] +ParameterName=Shift left accumulator by constant +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub9] +ParameterName=Shift right accumulator by constant +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01subA] +ParameterName=Add register to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01subB] +ParameterName=Accumulator divide register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01subC] +ParameterName=Xor register to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01subD] +ParameterName=Accumulator multiply register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01subE] +ParameterName=And register to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01subF] +ParameterName=Or register to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub10] +ParameterName=Substract register from accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub11] +ParameterName=Shift left accumulator by register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub12] +ParameterName=Shift right accumulator by register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub13] +ParameterName=Absolute accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub14] +ParameterName=Accumulator complement +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub15] +ParameterName=Write accumulator to register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub16] +ParameterName=Write register32 to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C01sub17] +ParameterName=Write register16 to accumulator +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02] +SubNumber=0x18 +ParameterName=Sequence commands +ObjectType=0x8 + +[2C02sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x17 +PDOMapping=0x0 + +[2C02sub1] +ParameterName=Do if i/o is "Off" +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub2] +ParameterName=Do if i/o is "On" +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub3] +ParameterName=End program +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub4] +ParameterName=If accumulator is below value +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub5] +ParameterName=If accumulator is higher value +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub6] +ParameterName=If accumulator is equal value +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub7] +ParameterName=If accumulator is unequal value +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub8] +ParameterName=If i/o is "Off" +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub9] +ParameterName=If i/o is "On" +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02subA] +ParameterName=If bit of accumulator is set +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02subB] +ParameterName=If bit of accumulator is clear +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02subC] +ParameterName=Repeat +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02subD] +ParameterName=Wait (miliseconds) value +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02subE] +ParameterName=Wait for Index +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02subF] +ParameterName=Wait for i/o to be "Off" +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub10] +ParameterName=Wait for i/o to be "On" +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub11] +ParameterName=If analog is below +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub12] +ParameterName=If analog is higher +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub13] +ParameterName=If accumulator is below register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub14] +ParameterName=If accumulator is higher register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub15] +ParameterName=If accumulator is equal register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub16] +ParameterName=If accumulator is unequal register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C02sub17] +ParameterName=Wait (milliseconds) register +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C03] +SubNumber=0x4 +ParameterName=Learned position +ObjectType=0x8 + +[2C03sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2C03sub1] +ParameterName=Learn current position +ObjectType=0x7 +DataType=0x0005 +AccessType=wo +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0xC7 + +[2C03sub2] +ParameterName=Learn target position +ObjectType=0x7 +DataType=0x0005 +AccessType=wo +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0xC7 + +[2C03sub3] +ParameterName=Move index table position +ObjectType=0x7 +DataType=0x0005 +AccessType=wo +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0xC7 + +[2C04] +SubNumber=0x9 +ParameterName=Macro commands +ObjectType=0x8 + +[2C04sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x8 +PDOMapping=0x0 + +[2C04sub1] +ParameterName=Macro call +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C04sub2] +ParameterName=Return from macro call +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C04sub3] +ParameterName=Macro jump +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C04sub4] +ParameterName=Reset macros +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C04sub5] +ParameterName=Jump absolute +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C04sub6] +ParameterName=Jump relative +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C04sub7] +ParameterName=Macro call interrupt +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C04sub8] +ParameterName=Unpush macro +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2C05] +SubNumber=0x5 +ParameterName=Macro access +ObjectType=0x9 + +[2C05sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x4 +PDOMapping=0x0 + +[2C05sub1] +ParameterName=Macro number +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C05sub2] +ParameterName=Macro command +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C05sub3] +ParameterName=Command +ObjectType=0x7 +DataType=0x001B +AccessType=rw +PDOMapping=0x0 + +[2C05sub4] +ParameterName=Unprotected access +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2C06] +SubNumber=0x5 +ParameterName=Timers access +ObjectType=0x8 + +[2C06sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x4 +PDOMapping=0x0 + +[2C06sub1] +ParameterName=Timer 1 (count up) value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2C06sub2] +ParameterName=Timer 2 (count up) value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2C06sub3] +ParameterName=Timer 3 (count down) value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2C06sub4] +ParameterName=Timer 4 (count down) value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2C07] +SubNumber=0xD +ParameterName=Interrupt vector +ObjectType=0x8 + +[2C07sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0xC +PDOMapping=0x0 + +[2C07sub1] +ParameterName=Interrupt 1 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07sub2] +ParameterName=Interrupt 2 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07sub3] +ParameterName=Interrupt 3 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07sub4] +ParameterName=Interrupt 4 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07sub5] +ParameterName=Interrupt 5 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07sub6] +ParameterName=Interrupt 6 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07sub7] +ParameterName=Interrupt 7 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07sub8] +ParameterName=Interrupt 8 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07sub9] +ParameterName=Interrupt 9 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07subA] +ParameterName=Interrupt 10 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07subB] +ParameterName=Interrupt 11 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C07subC] +ParameterName=Interrupt 12 vector +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C08] +SubNumber=0xD +ParameterName=Interrupt enable +ObjectType=0x8 + +[2C08sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0xC +PDOMapping=0x0 + +[2C08sub1] +ParameterName=Interrupt 1 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08sub2] +ParameterName=Interrupt 2 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08sub3] +ParameterName=Interrupt 3 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08sub4] +ParameterName=Interrupt 4 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08sub5] +ParameterName=Interrupt 5 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08sub6] +ParameterName=Interrupt 6 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08sub7] +ParameterName=Interrupt 7 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08sub8] +ParameterName=Interrupt 8 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08sub9] +ParameterName=Interrupt 9 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08subA] +ParameterName=Interrupt 10 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08subB] +ParameterName=Interrupt 11 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C08subC] +ParameterName=Interrupt 12 enabled +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x1 + +[2C09] +SubNumber=0x4 +ParameterName=Pointer access +ObjectType=0x9 + +[2C09sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2C09sub1] +ParameterName=Pointer to register +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C09sub2] +ParameterName=Content of register +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C09sub3] +ParameterName=Write content to register +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C0A] +SubNumber=0x4 +ParameterName=Macro debug +ObjectType=0x9 + +[2C0Asub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2C0Asub1] +ParameterName=Actual macro number +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=0x0 +PDOMapping=0x0 + +[2C0Asub2] +ParameterName=Actual command number +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=0x0 +PDOMapping=0x0 + +[2C0Asub3] +ParameterName=Macro status +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=0x0 +PDOMapping=0x0 + +[2C50] +SubNumber=0x4 +ParameterName=Monitor config +ObjectType=0x9 + +[2C50sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[2C50sub1] +ParameterName=Sampling rate +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0xA +PDOMapping=0x0 + +[2C50sub2] +ParameterName=Enable mode +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C50sub3] +ParameterName=Trigger Delay in samples +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C51] +SubNumber=0x8 +ParameterName=Monitor result +ObjectType=0x9 + +[2C51sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x7 +PDOMapping=0x0 + +[2C51sub1] +ParameterName=Max entry number +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +DefaultValue=0x2BC +PDOMapping=0x0 + +[2C51sub2] +ParameterName=Filled entry values +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +DefaultValue=0x0 +PDOMapping=0x0 + +[2C51sub3] +ParameterName=Entry number +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C51sub4] +ParameterName=Actual entry table 1 +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +DefaultValue=0 +PDOMapping=0x0 + +[2C51sub5] +ParameterName=Actual entry table 2 +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +DefaultValue=0 +PDOMapping=0x0 + +[2C51sub6] +ParameterName=Actual entry table 3 +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +DefaultValue=0 +PDOMapping=0x0 + +[2C51sub7] +ParameterName=Actual entry table 4 +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +DefaultValue=0 +PDOMapping=0x0 + +[2C52] +SubNumber=0x5 +ParameterName=Monitor mapping +ObjectType=0x9 + +[2C52sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x4 +PDOMapping=0x0 + +[2C52sub1] +ParameterName=Channel 1 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1617166368 +PDOMapping=0x0 + +[2C52sub2] +ParameterName=Channel 2 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1617035296 +PDOMapping=0x0 + +[2C52sub3] +ParameterName=Channel 3 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1617690656 +PDOMapping=0x0 + +[2C52sub4] +ParameterName=Channel 4 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1617625120 +PDOMapping=0x0 + +[2C55] +SubNumber=0x7 +ParameterName=Trigger 1 +ObjectType=0x9 + +[2C55sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x6 +PDOMapping=0x0 + +[2C55sub1] +ParameterName=Mode +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 +LowLimit=0x0 +HighLimit=0x5 + +[2C55sub2] +ParameterName=Source Register +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x6074 +PDOMapping=0x0 + +[2C55sub3] +ParameterName=Positive Threshold +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C55sub4] +ParameterName=Negative Threshold +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[2C55sub5] +ParameterName=Digital Input Mask +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2C55sub6] +ParameterName=Delay in samples +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2D00] +SubNumber=0x3 +ParameterName=Open loop parameters +ObjectType=0x9 + +[2D00sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[2D00sub1] +ParameterName=Target voltage +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[2D00sub2] +ParameterName=Target frequency +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x1 +PDOMapping=0x1 + +[2FF0] +SubNumber=0x3C +ParameterName=Hardware configuration +ObjectType=0x9 + +[2FF0sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3B +PDOMapping=0x0 + +[2FF0sub1] +ParameterName=Current sensing resistor value +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub2] +ParameterName=Preamplifier gain +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub3] +ParameterName=VGA available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub4] +ParameterName=Temperature sensor available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub5] +ParameterName=Max absolute temperature (mC) +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub6] +ParameterName=Min absolute temperature (mC) +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub7] +ParameterName=Vbus sensor available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub8] +ParameterName=Max absolute voltage (mV) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub9] +ParameterName=Min absolute voltage (mV) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0subA] +ParameterName=Nominal current (mA - RMS value) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0subB] +ParameterName=Peak current (mA - RMS value) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0subC] +ParameterName=Maximum peak time (100us) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0subD] +ParameterName=Maximum current (mA - peak value) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0subE] +ParameterName=Stepper in 3phases available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0subF] +ParameterName=NVM available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub10] +ParameterName=HW error available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub11] +ParameterName=Temperature sensor offset (mV) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub12] +ParameterName=Temperature sensor gain (mV/C) +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub13] +ParameterName=Vbus sensor gain +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub14] +ParameterName=Deadtime (ns) +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub15] +ParameterName=PWM frequency scale (legacy) +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub16] +ParameterName=Boostrap charge time (ms) +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub17] +ParameterName=NTC sensor available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub18] +ParameterName=NTC Rext (Ohm) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub19] +ParameterName=NTC R25 (Ohm) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub1A] +ParameterName=NTC B25 (K) +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub1B] +ParameterName=Resolver available +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub1C] +ParameterName=Node ID by HW +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub1D] +ParameterName=PWM frequency (Hz) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub1E] +ParameterName=Available digital inputs +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub1F] +ParameterName=Available digital outputs +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub20] +ParameterName=Available analog inputs +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub21] +ParameterName=Available analog outputs +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub22] +ParameterName=Commercial product ID +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub23] +ParameterName=Commercial Serial Number +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub24] +ParameterName=2 Phases Switching Scheme +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub25] +ParameterName=Driver enable in UART com. +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub26] +ParameterName=Available current sensors +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub27] +ParameterName=Digital inputs polarity mask +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub28] +ParameterName=Digital outputs polarity mask +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub29] +ParameterName=Analog reference voltage +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub2A] +ParameterName=Analog input 1-2 parameters +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub2B] +ParameterName=Analog input 3-4 parameters +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub2C] +ParameterName=Analog output 1-2 parameters +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub2D] +ParameterName=Macro parameters +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub2E] +ParameterName=Supported motor types +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub2F] +ParameterName=Supported communication interfaces +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub30] +ParameterName=Supported feedbacks +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub31] +ParameterName=PWM maximum duty cycle +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub32] +ParameterName=Current loop frequency +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub33] +ParameterName=Position/velocity loop frequency +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub34] +ParameterName=Supported command source +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub35] +ParameterName=Safe torque off input +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub36] +ParameterName=Alternative frequency PWM (Hz) +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub37] +ParameterName=Current low pass filter output +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub38] +ParameterName=Analog input 5 parameters +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub39] +ParameterName=Open Load protection input +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub3A] +ParameterName=Shunt output +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF0sub3B] +ParameterName=Brake output +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF1] +ParameterName=Hardware configuration pass +ObjectType=0x7 +DataType=0x0004 +AccessType=wo +DefaultValue=0 +PDOMapping=0x0 + +[2FF2] +ParameterName=EDS version +ObjectType=0x7 +DataType=0x0006 +AccessType=const +DefaultValue=0x11D +PDOMapping=0x0 + +[2FF3] +ParameterName=HW available registers +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF4] +SubNumber=0x5 +ParameterName=HW identification +ObjectType=0x9 + +[2FF4sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x4 +PDOMapping=0x0 + +[2FF4sub1] +ParameterName=HW Version +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF4sub2] +ParameterName=HW Variant +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0x0 + +[2FF4sub3] +ParameterName=HW programming date +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF4sub4] +ParameterName=HW configuration revision +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +PDOMapping=0x0 + +[2FF5] +ParameterName=Build number +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 + +[2FFD] +ParameterName=Maximum current range +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[2FFE] +ParameterName=Drive name +ObjectType=0x7 +DataType=0x001B +AccessType=rw +DefaultValue=0x657669724420794D +PDOMapping=0x0 + +[2FFF] +ParameterName=Reset device +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[OptionalObjects] +SupportedObjects=104 +1=0x1003 +2=0x1005 +3=0x1006 +4=0x1007 +5=0x1008 +6=0x1009 +7=0x100A +8=0x100C +9=0x100D +10=0x1010 +11=0x1011 +12=0x1014 +13=0x1017 +14=0x1200 +15=0x1400 +16=0x1401 +17=0x1402 +18=0x1403 +19=0x1600 +20=0x1601 +21=0x1602 +22=0x1603 +23=0x1800 +24=0x1801 +25=0x1802 +26=0x1803 +27=0x1A00 +28=0x1A01 +29=0x1A02 +30=0x1A03 +31=0x603F +32=0x6040 +33=0x6041 +34=0x6042 +35=0x6043 +36=0x6044 +37=0x6046 +38=0x6048 +39=0x6049 +40=0x6060 +41=0x6061 +42=0x6062 +43=0x6063 +44=0x6064 +45=0x6065 +46=0x6066 +47=0x6067 +48=0x6068 +49=0x6069 +50=0x606B +51=0x606C +52=0x606D +53=0x606E +54=0x606F +55=0x6070 +56=0x6071 +57=0x6072 +58=0x6073 +59=0x6074 +60=0x6075 +61=0x6076 +62=0x6077 +63=0x6078 +64=0x6079 +65=0x607A +66=0x607C +67=0x607D +68=0x607E +69=0x607F +70=0x6080 +71=0x6081 +72=0x6083 +73=0x6084 +74=0x6085 +75=0x6086 +76=0x6087 +77=0x6088 +78=0x608F +79=0x6090 +80=0x6091 +81=0x6092 +82=0x6098 +83=0x6099 +84=0x609A +85=0x60A8 +86=0x60A9 +87=0x60AA +88=0x60B2 +89=0x60C1 +90=0x60C2 +91=0x60C4 +92=0x60C5 +93=0x60C6 +94=0x60E0 +95=0x60E1 +96=0x60F4 +97=0x60FA +98=0x60FC +99=0x60FD +100=0x60FE +101=0x60FF +102=0x6402 +103=0x6502 +104=0x6505 + +[1003] +SubNumber=0x5 +ParameterName=Pre-defined Error Field +ObjectType=0x8 + +[1003sub0] +ParameterName=number of errors +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1003sub1] +ParameterName=standard error field +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 + +[1003sub2] +ParameterName=standard error field +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 + +[1003sub3] +ParameterName=standard error field +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 + +[1003sub4] +ParameterName=standard error field +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x0 + +[1005] +ParameterName=COB-ID SYNC +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x80 +PDOMapping=0x0 + +[1006] +ParameterName=Cycle Period +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +ParameterValue=0x1 +PDOMapping=0x0 + +[1007] +ParameterName=Sync Windows Length +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1008] +ParameterName=Device name +ObjectType=0x7 +DataType=0x0009 +AccessType=const +DefaultValue=emcl +PDOMapping=0x0 + +[1009] +ParameterName=Hardware version +ObjectType=0x7 +DataType=0x0009 +AccessType=const +DefaultValue=See PCB +PDOMapping=0x0 + +[100A] +ParameterName=Software version +ObjectType=0x7 +DataType=0x0009 +AccessType=const +DefaultValue=2.4.13 +PDOMapping=0x0 + +[100C] +ParameterName=Guard Time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +ParameterValue=0x64 +PDOMapping=0x0 + +[100D] +ParameterName=Life Time Factor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +ParameterValue=0x4 +PDOMapping=0x0 + +[1010] +SubNumber=0x4 +ParameterName=Store Parameters +ObjectType=0x8 + +[1010sub0] +ParameterName=largest supported Sub-Index +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[1010sub1] +ParameterName=save all parameters +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[1010sub2] +ParameterName=save communication parameters +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[1010sub3] +ParameterName=save application parameters +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[1011] +SubNumber=0x4 +ParameterName=Restore default parameters +ObjectType=0x8 + +[1011sub0] +ParameterName=largest supported Sub-Index +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[1011sub1] +ParameterName=restore all default para. +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[1011sub2] +ParameterName=restore comm. default para. +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[1011sub3] +ParameterName=restore app. default para. +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[1014] +ParameterName=COB-ID Emergency message +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x80 +ParameterValue=0xA0 +PDOMapping=0x0 + +[1017] +ParameterName=Producer Heartbeat Time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1200] +SubNumber=0x3 +ParameterName=SSDO +ObjectType=0x9 + +[1200sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[1200sub1] +ParameterName=COB-ID Client->Server +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=$NODEID+0x600 +ParameterValue=0x620 +PDOMapping=0x0 + +[1200sub2] +ParameterName=COB-ID Server->Client +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=$NODEID+0x580 +ParameterValue=0x5A0 +PDOMapping=0x0 + +[1400] +SubNumber=0x4 +ParameterName=RPDO 1 +ObjectType=0x9 + +[1400sub0] +ParameterName=largest subindex supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[1400sub1] +ParameterName=COB-Id used +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x200 +ParameterValue=0x220 +PDOMapping=0x0 + +[1400sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +ParameterValue=0x1 +PDOMapping=0x0 + +[1400sub3] +ParameterName=Inhibit Time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1401] +SubNumber=0x4 +ParameterName=RPDO 2 +ObjectType=0x9 + +[1401sub0] +ParameterName=largest subindex supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[1401sub1] +ParameterName=COB-ID used +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x300 +ParameterValue=0x80000320 +PDOMapping=0x0 + +[1401sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x01 +ParameterValue=0x1 +PDOMapping=0x0 + +[1401sub3] +ParameterName=Inhibit Time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1402] +SubNumber=0x4 +ParameterName=RPDO 3 +ObjectType=0x9 + +[1402sub0] +ParameterName=largest subindex supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[1402sub1] +ParameterName=COB-ID used +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x400 +ParameterValue=0x80000420 +PDOMapping=0x0 + +[1402sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +ParameterValue=0x1 +PDOMapping=0x0 + +[1402sub3] +ParameterName=Inhibit Time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1403] +SubNumber=0x4 +ParameterName=RPDO 4 +ObjectType=0x9 + +[1403sub0] +ParameterName=largest subindex supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x3 +PDOMapping=0x0 + +[1403sub1] +ParameterName=COB-ID used +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x500 +ParameterValue=0x80000520 +PDOMapping=0x0 + +[1403sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +ParameterValue=0x1 +PDOMapping=0x0 + +[1403sub3] +ParameterName=Inhibit Time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1600] +SubNumber=0x9 +ParameterName=RPDO 1 mapping parameter +ObjectType=0x9 + +[1600sub0] +ParameterName=number of mapped objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0x0 +ParameterValue=0x2 + +[1600sub1] +ParameterName=Target Velocity +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60ff0020 +PDOMapping=0x0 +ParameterValue=0x60ff0020 + +[1600sub2] +ParameterName=Control Word +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60400010 +PDOMapping=0x0 +ParameterValue=0x60400010 + +[1600sub3] +ParameterName=PDO mapping 3. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1600sub4] +ParameterName=PDO mapping 4. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1600sub5] +ParameterName=PDO mapping 5. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1600sub6] +ParameterName=PDO mapping 6. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1600sub7] +ParameterName=PDO mapping 7. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1600sub8] +ParameterName=PDO mapping 8. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1601] +SubNumber=0x9 +ParameterName=RPDO 2 mapping parameter +ObjectType=0x9 + +[1601sub0] +ParameterName=number of mapped objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +#ParameterValue=0x2 + +[1601sub1] +ParameterName=PDO mapping 1. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +#ParameterValue=0x60400010 +PDOMapping=0x0 + +[1601sub2] +ParameterName=PDO mapping 2. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +#ParameterValue=0x60600008 +PDOMapping=0x0 + +[1601sub3] +ParameterName=PDO mapping 3. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1601sub4] +ParameterName=PDO mapping 4. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1601sub5] +ParameterName=PDO mapping 5. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1601sub6] +ParameterName=PDO mapping 6. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1601sub7] +ParameterName=PDO mapping 7. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1601sub8] +ParameterName=PDO mapping 8. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1602] +SubNumber=0x9 +ParameterName=RPDO 3 mapping parameter +ObjectType=0x9 + +[1602sub0] +ParameterName=number of mapped objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +#ParameterValue=0x2 + +[1602sub1] +ParameterName=PDO mapping 1. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +#ParameterValue=0x60400010 +PDOMapping=0x0 + +[1602sub2] +ParameterName=PDO mapping 2. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +#ParameterValue=0x607A0020 +PDOMapping=0x0 + +[1602sub3] +ParameterName=PDO mapping 3. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1602sub4] +ParameterName=PDO mapping 4. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1602sub5] +ParameterName=PDO mapping 5. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1602sub6] +ParameterName=PDO mapping 6. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1602sub7] +ParameterName=PDO mapping 7. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1602sub8] +ParameterName=PDO mapping 8. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1603] +SubNumber=0x9 +ParameterName=RPDO 4 mapping parameter +ObjectType=0x9 + +[1603sub0] +ParameterName=number of mapped objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 +#ParameterValue=0x2 + +[1603sub1] +ParameterName=PDO mapping 1. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +#ParameterValue=0x60400010 +PDOMapping=0x0 + +[1603sub2] +ParameterName=PDO mapping 2. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +#ParameterValue=0x60FF0020 +PDOMapping=0x0 + +[1603sub3] +ParameterName=PDO mapping 3. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1603sub4] +ParameterName=PDO mapping 4. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1603sub5] +ParameterName=PDO mapping 5. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1603sub6] +ParameterName=PDO mapping 6. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1603sub7] +ParameterName=PDO mapping 7. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1603sub8] +ParameterName=PDO mapping 8. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1800] +SubNumber=0x5 +ParameterName=TPDO 1 +ObjectType=0x9 + +[1800sub0] +ParameterName=largest subindex supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[1800sub1] +ParameterName=COB-ID used +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x40000180 +ParameterValue=0x400001A0 +PDOMapping=0x0 + +[1800sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +ParameterValue=0x1 +PDOMapping=0x0 + +[1800sub3] +ParameterName=inhibit time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[1800sub5] +ParameterName=event timer +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1801] +SubNumber=0x5 +ParameterName=TPDO 2 +ObjectType=0x9 + +[1801sub0] +ParameterName=largest subindex supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[1801sub1] +ParameterName=COB-ID used +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x40000280 +ParameterValue=0x400002A0 +PDOMapping=0x0 + +[1801sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +ParameterValue=0x1 +PDOMapping=0x0 + +[1801sub3] +ParameterName=inhibit time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[1801sub5] +ParameterName=event timer +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1802] +SubNumber=0x5 +ParameterName=TPDO 3 +ObjectType=0x9 + +[1802sub0] +ParameterName=largest subindex supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[1802sub1] +ParameterName=COB-ID used +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x40000380 +ParameterValue=0x400003A0 +PDOMapping=0x0 + +[1802sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +ParameterValue=0x1 +PDOMapping=0x0 + +[1802sub3] +ParameterName=inhibit time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[1802sub5] +ParameterName=event timer +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1803] +SubNumber=0x5 +ParameterName=TPDO 4 +ObjectType=0x9 + +[1803sub0] +ParameterName=largest subindex supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x5 +PDOMapping=0x0 + +[1803sub1] +ParameterName=COB-ID used +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NODEID+0x40000480 +ParameterValue=0x400004A0 +PDOMapping=0x0 + +[1803sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x01 +ParameterValue=0x1 +PDOMapping=0x0 + +[1803sub3] +ParameterName=inhibit time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[1803sub5] +ParameterName=event timer +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A00] +SubNumber=0x9 +ParameterName=TPDO 1 mapping parameter +ObjectType=0x9 + +[1A00sub0] +ParameterName=number of mapped objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x2 +PDOMapping=0x0 +ParameterValue=0x2 + +[1A00sub1] +ParameterName=Velocity Actual Value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x606C0020 +PDOMapping=0x0 +ParameterValue=0x606C0020 + + +[1A00sub2] +ParameterName=Status Word +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60410010 +PDOMapping=0x0 +ParameterValue=0x60410010 + +[1A00sub3] +ParameterName=PDO mapping 3. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A00sub4] +ParameterName=PDO mapping 4. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A00sub5] +ParameterName=PDO mapping 5. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A00sub6] +ParameterName=PDO mapping 6. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A00sub7] +ParameterName=PDO mapping 7. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A00sub8] +ParameterName=PDO mapping 8. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A01] +SubNumber=0x9 +ParameterName=TPDO 2 mapping parameter +ObjectType=0x9 + +[1A01sub0] +ParameterName=number of mapped app. objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x3 +PDOMapping=0x0 +ParameterValue=0x3 + +[1A01sub1] +ParameterName=Torque Actual Value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60770010 +PDOMapping=0x0 +ParameterValue=0x60770010 + +[1A01sub2] +ParameterName=Current Actual Value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60780010 +PDOMapping=0x0 +ParameterValue=0x60780010 + +[1A01sub3] +ParameterName=DC Link circuit voltage +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60790020 +PDOMapping=0x0 +ParameterValue=0x60790020 + +[1A01sub4] +ParameterName=PDO mapping 4. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A01sub5] +ParameterName=PDO mapping 5. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A01sub6] +ParameterName=PDO mapping 6. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A01sub7] +ParameterName=PDO mapping 7. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A01sub8] +ParameterName=PDO mapping 8. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A02] +SubNumber=0x9 +ParameterName=TPDO 3 mapping parameter +ObjectType=0x9 + +[1A02sub0] +ParameterName=number of mapped app. objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x2 +PDOMapping=0x0 +ParameterValue=0x2 + +[1A02sub1] +ParameterName=Position Actual Value +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60640020 +PDOMapping=0x0 +ParameterValue=0x60640020 + +[1A02sub2] +ParameterName=Temperature +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x20c20120 +PDOMapping=0x0 +ParameterValue=0x20c20120 + +[1A02sub3] +ParameterName=PDO mapping 3. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A02sub4] +ParameterName=PDO mapping 4. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A02sub5] +ParameterName=PDO mapping 5. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A02sub6] +ParameterName=PDO mapping 6. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A02sub7] +ParameterName=PDO mapping 7. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A02sub8] +ParameterName=PDO mapping 8. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03] +SubNumber=0x9 +ParameterName=TPDO 4 mapping parameter +ObjectType=0x9 + +[1A03sub0] +ParameterName=number of mapped app. objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03sub1] +ParameterName=PDO mapping 1. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03sub2] +ParameterName=PDO mapping 2. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03sub3] +ParameterName=PDO mapping 3. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03sub4] +ParameterName=PDO mapping 4. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03sub5] +ParameterName=PDO mapping 5. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03sub6] +ParameterName=PDO mapping 6. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03sub7] +ParameterName=PDO mapping 7. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[1A03sub8] +ParameterName=PDO mapping 8. app. object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[603F] +ParameterName=Error code +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[6040] +ParameterName=Controlword +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x0 +PDOMapping=0x1 + +[6041] +ParameterName=Statusword +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0x1 + +[6042] +ParameterName=vl target velocity +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[6043] +ParameterName=vl velocity demand +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[6044] +ParameterName=vl velocity actual value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[6046] +SubNumber=0x3 +ParameterName=vl velocity min max amount +ObjectType=0x8 + +[6046sub0] +ParameterName=Highest sub-index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[6046sub1] +ParameterName=vl velocity min amount +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x64 +PDOMapping=0x0 + +[6046sub2] +ParameterName=vl velocity max amount +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x5DC +PDOMapping=0x0 + +[6048] +SubNumber=0x3 +ParameterName=vl velocity acceleration +ObjectType=0x9 + +[6048sub0] +ParameterName=Highest sub-index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[6048sub1] +ParameterName=Delta speed +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[6048sub2] +ParameterName=Delta time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[6049] +SubNumber=0x3 +ParameterName=vl velocity deceleration +ObjectType=0x9 + +[6049sub0] +ParameterName=Highest sub-index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[6049sub1] +ParameterName=Delta speed +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x3E8 +PDOMapping=0x0 + +[6049sub2] +ParameterName=Delta time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[6060] +ParameterName=Modes of operation +ObjectType=0x7 +DataType=0x0002 +AccessType=rww +DefaultValue=1 +PDOMapping=0x1 +LowLimit=-2 +HighLimit=10 + +[6061] +ParameterName=Modes of operation display +ObjectType=0x7 +DataType=0x0002 +AccessType=ro +PDOMapping=0x1 + +[6062] +ParameterName=Position demand value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[6063] +ParameterName=Position actual internal value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[6064] +ParameterName=Position actual value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[6065] +ParameterName=Following error window +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0xFFFFFFFF +ParameterValue=0x1F4 +PDOMapping=0x1 + +[6066] +ParameterName=Following error time out +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x64 +PDOMapping=0x1 + +[6067] +ParameterName=Position window +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x64 +PDOMapping=0x1 + +[6068] +ParameterName=Position window time +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0xA +PDOMapping=0x1 + +[6069] +ParameterName=Velocity sensor actual value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[606B] +ParameterName=Velocity demand value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[606C] +ParameterName=Velocity actual value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x1 + +[606D] +ParameterName=Velocity window +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x3E8 +PDOMapping=0x1 + +[606E] +ParameterName=Velocity window time +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0xA +PDOMapping=0x1 + +[606F] +ParameterName=Velocity threshold +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x3E8 +PDOMapping=0x1 + +[6070] +ParameterName=Velocity threshold time +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x64 +PDOMapping=0x1 + +[6071] +ParameterName=Target torque +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[6072] +ParameterName=Max torque +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x3E8 +PDOMapping=0x1 + +[6073] +ParameterName=Max current +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0x3E8 +PDOMapping=0x1 + +[6074] +ParameterName=Torque demand +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[6075] +ParameterName=Motor rated current +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0xBB8 +PDOMapping=0x1 + +[6076] +ParameterName=Motor rated torque +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x136 +PDOMapping=0x1 + +[6077] +ParameterName=Torque actual value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[6078] +ParameterName=Current actual value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=0x1 + +[6079] +ParameterName=DC link circuit voltage +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[607A] +ParameterName=Target position +ObjectType=0x7 +DataType=0x0004 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[607C] +ParameterName=Home offset +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0x0 + +[607D] +SubNumber=0x3 +ParameterName=Software position limit +ObjectType=0x8 + +[607Dsub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[607Dsub1] +ParameterName=Min position limit +ObjectType=0x7 +DataType=0x0004 +AccessType=rww +DefaultValue=-2147483647 +PDOMapping=0x1 + +[607Dsub2] +ParameterName=Max position limit +ObjectType=0x7 +DataType=0x0004 +AccessType=rww +DefaultValue=2147483647 +PDOMapping=0x1 + +[607E] +ParameterName=Polarity +ObjectType=0x7 +DataType=0x0005 +AccessType=rww +DefaultValue=0x0 +PDOMapping=0x1 + +[607F] +ParameterName=Max profile velocity +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x186A0 +PDOMapping=0x1 + +[6080] +ParameterName=Max motor speed +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x30D40 +PDOMapping=0x1 + +[6081] +ParameterName=Profile velocity +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x186A0 +PDOMapping=0x1 + +[6083] +ParameterName=Profile acceleration +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x186A0 +PDOMapping=0x1 +LowLimit=0x1 +HighLimit=0xFFFFFFFF + +[6084] +ParameterName=Profile deceleration +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x186A0 +PDOMapping=0x1 +LowLimit=0x1 +HighLimit=0xFFFFFFFF + +[6085] +ParameterName=Quick stop deceleration +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x30D40 +PDOMapping=0x1 + +[6086] +ParameterName=Motion profile type +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[6087] +ParameterName=Torque slope +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x2710 +PDOMapping=0x1 + +[6088] +ParameterName=Torque profile type +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[608F] +SubNumber=0x3 +ParameterName=Position encoder resolution +ObjectType=0x8 + +[608Fsub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[608Fsub1] +ParameterName=Encoder increments +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x7D0 +PDOMapping=0x1 + +[608Fsub2] +ParameterName=Motor revolutions +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x1 +PDOMapping=0x1 + +[6090] +SubNumber=0x3 +ParameterName=Velocity encoder resolution +ObjectType=0x8 + +[6090sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[6090sub1] +ParameterName=Encoder increments +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x7D0 +PDOMapping=0x1 + +[6090sub2] +ParameterName=Motor revolutions +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x1 +PDOMapping=0x1 + +[6091] +SubNumber=0x3 +ParameterName=Gear ratio +ObjectType=0x8 + +[6091sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[6091sub1] +ParameterName=Motor shaft revolutions +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[6091sub2] +ParameterName=Driving shaft revolutions +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[6092] +SubNumber=0x3 +ParameterName=Feed constant +ObjectType=0x8 + +[6092sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[6092sub1] +ParameterName=Feed +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[6092sub2] +ParameterName=Shaft revolutions +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[6098] +ParameterName=Homing method +ObjectType=0x7 +DataType=0x0002 +AccessType=rw +DefaultValue=35 +PDOMapping=0x0 + +[6099] +SubNumber=0x3 +ParameterName=Homing speeds +ObjectType=0x8 + +[6099sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[6099sub1] +ParameterName=Speed for switch search +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0xC350 +PDOMapping=0x0 + +[6099sub2] +ParameterName=Speed for zero search +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x1388 +PDOMapping=0x0 + +[609A] +ParameterName=Homing acceleration +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x186A0 +PDOMapping=0x0 + +[60A8] +ParameterName=SI unit position +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0xB50000 +PDOMapping=0x0 + +[60A9] +ParameterName=SI unit velocity +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0xB50300 +PDOMapping=0x0 + +[60AA] +ParameterName=SI unit acceleration +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0xB55700 +PDOMapping=0x0 + +[60B2] +ParameterName=Torque offset +ObjectType=0x7 +DataType=0x0004 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 +LowLimit=-32767 +HighLimit=32767 + +[60C1] +SubNumber=0x2 +ParameterName=Interpolation data record +ObjectType=0x8 + +[60C1sub0] +ParameterName=Highest sub-index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x1 +PDOMapping=0x0 + +[60C1sub1] +ParameterName=Interpolation 1st Set-point +ObjectType=0x7 +DataType=0x0004 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[60C2] +SubNumber=0x3 +ParameterName=Interpolation time period +ObjectType=0x9 + +[60C2sub0] +ParameterName=Highest sub-index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[60C2sub1] +ParameterName=Interpolation time period value +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x1 +PDOMapping=0x0 + +[60C2sub2] +ParameterName=Interpolation time index +ObjectType=0x7 +DataType=0x0002 +AccessType=rw +DefaultValue=-3 +PDOMapping=0x0 + +[60C4] +SubNumber=0x7 +ParameterName=Interpolation data configuration +ObjectType=0x9 + +[60C4sub0] +ParameterName=Highest sub-index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x6 +PDOMapping=0x0 + +[60C4sub1] +ParameterName=Maximum buffer size +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0x10 +PDOMapping=0x0 + +[60C4sub2] +ParameterName=Actual buffer size +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[60C4sub3] +ParameterName=Buffer organisation +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[60C4sub4] +ParameterName=Buffer position +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x0 +PDOMapping=0x0 + +[60C4sub5] +ParameterName=Size of data record +ObjectType=0x7 +DataType=0x0005 +AccessType=wo +DefaultValue=0x4 +PDOMapping=0x0 + +[60C4sub6] +ParameterName=Buffer clear +ObjectType=0x7 +DataType=0x0005 +AccessType=wo +DefaultValue=0x0 +PDOMapping=0x0 + +[60C5] +ParameterName=Max acceleration +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x30D40 +PDOMapping=0x1 +LowLimit=0x1 +HighLimit=0xFFFFFFFF + +[60C6] +ParameterName=Max deceleration +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x30D40 +PDOMapping=0x1 +LowLimit=0x1 +HighLimit=0xFFFFFFFF + +[60E0] +ParameterName=Positive torque limit value +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +DefaultValue=1000 +PDOMapping=0x1 + +[60E1] +ParameterName=Negative torque limit value +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +DefaultValue=-1000 +PDOMapping=0x1 + +[60F4] +ParameterName=Following error actual value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +DefaultValue=0 +PDOMapping=0x1 + +[60FA] +ParameterName=Control effort +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +DefaultValue=0 +PDOMapping=0x1 + +[60FC] +ParameterName=Position demand internal value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +DefaultValue=0 +PDOMapping=0x1 + +[60FD] +ParameterName=Digital inputs +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0x1 + +[60FE] +SubNumber=0x3 +ParameterName=Digital outputs +ObjectType=0x8 + +[60FEsub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=0x2 +PDOMapping=0x0 + +[60FEsub1] +ParameterName=Physical outputs +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x0 +PDOMapping=0x1 + +[60FEsub2] +ParameterName=Bit mask +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +DefaultValue=0x0 +PDOMapping=0x1 + +[60FF] +ParameterName=Target velocity +ObjectType=0x7 +DataType=0x0004 +AccessType=rww +DefaultValue=0 +PDOMapping=0x1 + +[6402] +ParameterName=Motor type +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +DefaultValue=0xD +PDOMapping=0x1 + +[6502] +ParameterName=Supported drive modes +ObjectType=0x7 +DataType=0x0007 +AccessType=const +DefaultValue=0x303EF +PDOMapping=0x1 + diff --git a/examples/simple_ds402_node.py b/examples/simple_ds402_node.py index ae7deab9..c99831a0 100644 --- a/examples/simple_ds402_node.py +++ b/examples/simple_ds402_node.py @@ -16,9 +16,9 @@ network.check() # Add some nodes with corresponding Object Dictionaries - node = canopen.BaseNode402(35, '/home/andre/Code/test/jupiter.eds') + node = canopen.BaseNode402(35, 'eds/e35.eds') network.add_node(node) - # network.add_node(34, '/home/andre/Code/test/jupiter.eds') + # network.add_node(34, 'eds/example34.eds') # node = network[34] # Reset network From a03d0244ce1b96fa23765d77fea57ce885a40e84 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Filipe=20Silva?= Date: Fri, 11 Dec 2020 09:51:59 +0000 Subject: [PATCH 033/199] fix naming Node402 -> BaseNode402 --- doc/profiles.rst | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/doc/profiles.rst b/doc/profiles.rst index 335cb6ab..dac3e85d 100644 --- a/doc/profiles.rst +++ b/doc/profiles.rst @@ -10,14 +10,14 @@ CiA 402 CANopen device profile for motion controllers and drives This device profile has a control state machine for controlling the behaviour of the drive. Therefore one needs to instantiate a node with the -:class:`Node402` class +:class:`BaseNode402` class -Create a node with Node402:: +Create a node with BaseNode402:: import canopen - from canopen.profiles.p402 import Node402 + from canopen.profiles.p402 import BaseNode402 - some_node = Node402(3, 'someprofile.eds') + some_node = BaseNode402(3, 'someprofile.eds') network = canopen.Network() network.add_node(some_node) @@ -35,7 +35,7 @@ The current status can be read from the device by reading the register Changes in state can only be done in the 'OPERATIONAL' state of the NmtMaster TPDO1 needs to be set up correctly. For this, run the the -`Node402.setup_402_state_machine()` method. Note that this setup +`BaseNode402.setup_402_state_machine()` method. Note that this setup routine will change only TPDO1 and automatically go to the 'OPERATIONAL' state of the NmtMaster:: @@ -55,10 +55,10 @@ by the Controlword, for example a 'FAULT' state. Therefore the :class:`PowerStateMachine` class (in similarity to the :class:`NmtMaster` class) automatically monitors state changes of the Statusword which is sent by TPDO1. The available callback on thet TPDO1 will then extract the -information and mirror the state change in the :attr:`Node402.powerstate_402` +information and mirror the state change in the :attr:`BaseNode402.powerstate_402` attribute. -Similar to the :class:`NmtMaster` class, the states of the :class:`Node402` +Similar to the :class:`NmtMaster` class, the states of the :class:`BaseNode402` class :attr:`._state` attribute can be read and set (command) by a string:: # command a state (an SDO message will be called) From 3b9171018704fba52c4f0a01f53add4dcc1209b1 Mon Sep 17 00:00:00 2001 From: David van Rijn Date: Sun, 17 Jan 2021 01:38:18 +0100 Subject: [PATCH 034/199] Added script to create debian package --- .gitignore | 1 + makedeb | 49 +++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 50 insertions(+) create mode 100755 makedeb diff --git a/.gitignore b/.gitignore index f7d264f1..fddae0e9 100644 --- a/.gitignore +++ b/.gitignore @@ -25,6 +25,7 @@ var/ *.egg-info/ .installed.cfg *.egg +build-deb/ # PyInstaller # Usually these files are written by a python script from a template diff --git a/makedeb b/makedeb new file mode 100755 index 00000000..c7da516d --- /dev/null +++ b/makedeb @@ -0,0 +1,49 @@ +#!/bin/sh + +py=python3 +name=canopen +pkgname=$py-canopen +description="CANopen stack implementation" + + +version=`git tag |grep -Eo '[0-9]+\.[0-9]+\.[0-9]+' |sort | tail -1 ` +maintainer=`git log -1 --pretty=format:'%an <%ae>'` +arch=all + +echo version: $version +echo maintainer: $maintainer + +cd $(dirname $0) +package_dir=$PWD/build-deb/${pkgname}_$version-1_all +fakeroot=$package_dir + +mkdir -p $fakeroot + +$py setup.py bdist >setup_py.log + +tar -f dist/*.tar.* -C $fakeroot -x + +mkdir -p $fakeroot/usr/lib/$py/dist-packages/ +mv -f $(find $fakeroot -name $name -type d) $fakeroot/usr/lib/python3/dist-packages/ + +cp -r $name.egg-info $fakeroot/usr/lib/python3/dist-packages/$name-$version.egg-info + +mkdir $package_dir/DEBIAN + +cat > $package_dir/DEBIAN/control < Date: Wed, 20 Jan 2021 07:19:33 +0100 Subject: [PATCH 035/199] Reading DefaultValue from EDS is wrong for data type OCTET_STRING and DOMAIN. The DefaultValue for data type OCTET_STRING and DOMAIN is formatted with two hex digits for each byte in the EDS - see corresponding CiA standard. Also the content of the default value has to end up in a bytes instance and not in a string instance. (otherwise an exception is thrown when the SDOServer tries to answer a SDO upload request for an object dictionary entry with this data type.) --- canopen/objectdictionary/eds.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 15b6f8e8..371c164f 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -138,7 +138,9 @@ def import_from_node(node_id, network): def _convert_variable(node_id, var_type, value): - if var_type in objectdictionary.DATA_TYPES: + if var_type in (objectdictionary.OCTET_STRING, objectdictionary.DOMAIN): + return bytes.fromhex(value) + elif var_type in (objectdictionary.VISIBLE_STRING, objectdictionary.UNICODE_STRING): return value elif var_type in objectdictionary.FLOAT_TYPES: return float(value) From db4e6d0aa5324d547dcd0f6d7d039d28a990e899 Mon Sep 17 00:00:00 2001 From: Bundesber <79271298+Bundesber@users.noreply.github.com> Date: Fri, 19 Feb 2021 15:59:04 +0100 Subject: [PATCH 036/199] fix for exception on multipe stop (#225) Co-authored-by: Reinhard Berlach --- canopen/nmt.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/canopen/nmt.py b/canopen/nmt.py index 96d00141..60a7f758 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -178,12 +178,14 @@ def start_node_guarding(self, period): :param float period: Period (in seconds) at which the node guarding should be advertised to the slave node. """ + if self._node_guarding_producer : self.stop_node_guarding() self._node_guarding_producer = self.network.send_periodic(0x700 + self.id, None, period, True) def stop_node_guarding(self): """Stops the node guarding mechanism.""" if self._node_guarding_producer is not None: self._node_guarding_producer.stop() + self._node_guarding_producer = None class NmtSlave(NmtBase): From 1b12c9717897c0eba2b3685eda8253dd1a8d8cbb Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Sat, 20 Feb 2021 09:33:13 +0100 Subject: [PATCH 037/199] Add support for hex node ID in DCF Fixes #221 --- canopen/objectdictionary/eds.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 371c164f..81c38adc 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -33,7 +33,7 @@ def import_eds(source, node_id): od = objectdictionary.ObjectDictionary() if eds.has_section("DeviceComissioning"): od.bitrate = int(eds.get("DeviceComissioning", "Baudrate")) * 1000 - od.node_id = int(eds.get("DeviceComissioning", "NodeID")) + od.node_id = int(eds.get("DeviceComissioning", "NodeID"), 0) for section in eds.sections(): # Match dummy definitions From ad1d93af16cc419e8ecf847489f5cdd06d498ea8 Mon Sep 17 00:00:00 2001 From: Nikos Skalkotos Date: Tue, 9 Mar 2021 19:16:05 +0200 Subject: [PATCH 038/199] Respect rtr_allowed in Pdo.Map.Save() When disabling or enabling a PDO by changing the "COB-ID used" sub-index we need to respect the value in the 30th bit. If a device does not support remote frames, an attempt to write the field will trigger an SBO abort reply. --- canopen/pdo/base.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 4fca9ffc..f0aea015 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -338,7 +338,7 @@ def save(self): """Save PDO configuration for this map using SDO.""" logger.info("Setting COB-ID 0x%X and temporarily disabling PDO", self.cob_id) - self.com_record[1].raw = self.cob_id | PDO_NOT_VALID + self.com_record[1].raw = self.cob_id | PDO_NOT_VALID | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0x0) if self.trans_type is not None: logger.info("Setting transmission type to %d", self.trans_type) self.com_record[2].raw = self.trans_type @@ -388,7 +388,8 @@ def save(self): if self.enabled: logger.info("Enabling PDO") - self.com_record[1].raw = self.cob_id + self.com_record[1].raw = self.cob_id | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0x0) + self.pdo_node.network.subscribe(self.cob_id, self.on_message) def clear(self): From f48a9425ebe36613f9aeda020043c56ca1258bbb Mon Sep 17 00:00:00 2001 From: ventussolus Date: Tue, 13 Apr 2021 20:59:56 -0500 Subject: [PATCH 039/199] Shutdown an already running periodic PDO before starting a new one --- canopen/pdo/base.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index f0aea015..97006b01 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -441,6 +441,10 @@ def start(self, period=None): :param float period: Transmission period in seconds """ + # Stop an already running transmission if we have one, otherwise we + # overwrite the reference and can lose our handle to shut it down + self.stop() + if period is not None: self.period = period From 287c1b56d888bfd7fdc7b3da3306e929ceb13f03 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Wed, 14 Apr 2021 08:13:36 +0200 Subject: [PATCH 040/199] Bump min supported Python version to 3.6 --- .github/workflows/pythonpackage.yml | 2 +- README.rst | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 4089ee1e..3efb3261 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -11,7 +11,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - python-version: [3.5, '3.x'] + python-version: [3.6, '3.x'] steps: - uses: actions/checkout@v2 diff --git a/README.rst b/README.rst index 4a1fd4b1..c3c840d9 100644 --- a/README.rst +++ b/README.rst @@ -6,7 +6,7 @@ The aim of the project is to support the most common parts of the CiA 301 standard in a simple Pythonic interface. It is mainly targeted for testing and automation tasks rather than a standard compliant master implementation. -The library supports Python 3.4+. +The library supports Python 3.6+. Features From 7883bb3383b69525ae1dbe5af65c8f5f7bdbcff0 Mon Sep 17 00:00:00 2001 From: Janis Ita Date: Thu, 3 Jun 2021 17:18:50 +0200 Subject: [PATCH 041/199] added SDO Abort if a timeout occurs when sending a SDO request --- canopen/sdo/client.py | 1 + 1 file changed, 1 insertion(+) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 44159c49..0118d0ea 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -86,6 +86,7 @@ def request_response(self, sdo_request): except SdoCommunicationError as e: retries_left -= 1 if not retries_left: + self.abort(0x5040000) raise logger.warning(str(e)) From 1f288694b4587f36ab1b4e7d758d97dabb6c4031 Mon Sep 17 00:00:00 2001 From: Janis Ita Date: Fri, 4 Jun 2021 13:11:58 +0200 Subject: [PATCH 042/199] added argument for block transfer to enable/disable CRC Support --- canopen/sdo/base.py | 4 ++-- canopen/sdo/client.py | 18 +++++++++++------- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 8f1fcb18..9cc3cf6f 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -112,7 +112,7 @@ def set_data(self, data): self.sdo_node.download(self.od.index, self.od.subindex, data, force_segment) def open(self, mode="rb", encoding="ascii", buffering=1024, size=None, - block_transfer=False): + block_transfer=False, request_crc_support=True): """Open the data stream as a file like object. :param str mode: @@ -141,4 +141,4 @@ def open(self, mode="rb", encoding="ascii", buffering=1024, size=None, A file like object. """ return self.sdo_node.open(self.od.index, self.od.subindex, mode, - encoding, buffering, size, block_transfer) + encoding, buffering, size, block_transfer, request_crc_support=request_crc_support) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 44159c49..672fb8ae 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -155,7 +155,7 @@ def download(self, index, subindex, data, force_segment=False): fp.close() def open(self, index, subindex=0, mode="rb", encoding="ascii", - buffering=1024, size=None, block_transfer=False, force_segment=False): + buffering=1024, size=None, block_transfer=False, force_segment=False, request_crc_support=True): """Open the data stream as a file like object. :param int index: @@ -192,7 +192,7 @@ def open(self, index, subindex=0, mode="rb", encoding="ascii", buffer_size = buffering if buffering > 1 else io.DEFAULT_BUFFER_SIZE if "r" in mode: if block_transfer: - raw_stream = BlockUploadStream(self, index, subindex) + raw_stream = BlockUploadStream(self, index, subindex, request_crc_support=request_crc_support) else: raw_stream = ReadableStream(self, index, subindex) if buffering: @@ -201,7 +201,7 @@ def open(self, index, subindex=0, mode="rb", encoding="ascii", return raw_stream if "w" in mode: if block_transfer: - raw_stream = BlockDownloadStream(self, index, subindex, size) + raw_stream = BlockDownloadStream(self, index, subindex, size, request_crc_support=request_crc_support) else: raw_stream = WritableStream(self, index, subindex, size, force_segment) if buffering: @@ -446,7 +446,7 @@ class BlockUploadStream(io.RawIOBase): crc_supported = False - def __init__(self, sdo_client, index, subindex=0): + def __init__(self, sdo_client, index, subindex=0, request_crc_support=True): """ :param canopen.sdo.SdoClient sdo_client: The SDO client to use for reading. @@ -466,7 +466,9 @@ def __init__(self, sdo_client, index, subindex=0): sdo_client.rx_cobid - 0x600) # Initiate Block Upload request = bytearray(8) - command = REQUEST_BLOCK_UPLOAD | INITIATE_BLOCK_TRANSFER | CRC_SUPPORTED + command = REQUEST_BLOCK_UPLOAD | INITIATE_BLOCK_TRANSFER + if request_crc_support: + command |= CRC_SUPPORTED struct.pack_into(" Date: Wed, 9 Jun 2021 07:26:07 +0200 Subject: [PATCH 043/199] added new arguments to docstrings --- canopen/sdo/base.py | 2 ++ canopen/sdo/client.py | 8 +++++++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 9cc3cf6f..9018dc23 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -136,6 +136,8 @@ def open(self, mode="rb", encoding="ascii", buffering=1024, size=None, Size of data to that will be transmitted. :param bool block_transfer: If block transfer should be used. + :param bool request_crc_support: + If crc calculation should be requested when using block transfer :returns: A file like object. diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 672fb8ae..ec993c2a 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -185,7 +185,9 @@ def open(self, index, subindex=0, mode="rb", encoding="ascii", If block transfer should be used. :param bool force_segment: Force use of segmented download regardless of data size. - + :param bool request_crc_support: + If crc calculation should be requested when using block transfer + :returns: A file like object. """ @@ -454,6 +456,8 @@ def __init__(self, sdo_client, index, subindex=0, request_crc_support=True): Object dictionary index to read from. :param int subindex: Object dictionary sub-index to read from. + :param bool request_crc_support: + If crc calculation should be requested when using block transfer """ self._done = False self.sdo_client = sdo_client @@ -608,6 +612,8 @@ def __init__(self, sdo_client, index, subindex=0, size=None, request_crc_support Object dictionary sub-index to read from. :param int size: Size of data in number of bytes if known in advance. + :param bool request_crc_support: + If crc calculation should be requested when using block transfer """ self.sdo_client = sdo_client self.size = size From 9b7fa31a2d1e61612b8053db8c910a02c086a015 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=BCnther=20Jena?= Date: Wed, 9 Jun 2021 15:40:44 +0200 Subject: [PATCH 044/199] Check writeable for SDO upload --- canopen/sdo/server.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index 894f48ef..f6d02dad 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -210,4 +210,4 @@ def download(self, index, subindex, data, force_segment=False): :raises canopen.SdoAbortedError: When node responds with an error. """ - return self._node.set_data(index, subindex, data) + return self._node.set_data(index, subindex, data, check_writable=True) From 47051d5877eed773db2b019e560205979ded65f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=BCnther=20Jena?= Date: Wed, 9 Jun 2021 21:35:23 +0200 Subject: [PATCH 045/199] implement feedback from Christian --- canopen/sdo/server.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index f6d02dad..be4d934e 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -123,7 +123,6 @@ def block_download(self, data): self.abort(0x05040001) def init_download(self, request): - # TODO: Check if writable command, index, subindex = SDO_STRUCT.unpack_from(request) self._index = index self._subindex = subindex @@ -136,7 +135,7 @@ def init_download(self, request): size = 4 - ((command >> 2) & 0x3) else: size = 4 - self.download(index, subindex, request[4:4 + size]) + self._node.set_data(index, subindex, request[4:4 + size], check_writable=True) else: logger.info("Initiating segmented download for 0x%X:%d", index, subindex) if command & SIZE_SPECIFIED: @@ -210,4 +209,4 @@ def download(self, index, subindex, data, force_segment=False): :raises canopen.SdoAbortedError: When node responds with an error. """ - return self._node.set_data(index, subindex, data, check_writable=True) + return self._node.set_data(index, subindex, data) From d2276b20b6aa6e5c07e3ee766e9ecc3b653320b2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=BCnther=20Jena?= Date: Wed, 9 Jun 2021 22:02:01 +0200 Subject: [PATCH 046/199] insert TODO comment --- canopen/sdo/server.py | 1 + 1 file changed, 1 insertion(+) diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index be4d934e..746f43a3 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -123,6 +123,7 @@ def block_download(self, data): self.abort(0x05040001) def init_download(self, request): + # TODO: Check if writable (now would fail on end of segmented downloads) command, index, subindex = SDO_STRUCT.unpack_from(request) self._index = index self._subindex = subindex From 657062aeb6634e5be33c3766777feb67e098822d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 2 Aug 2021 13:51:45 +0200 Subject: [PATCH 047/199] DS402 code cleanup (#245) * ds402: Define additional operation mode constants. Add the missing CYCLIC_SYNCHRONOUS_... modes to the mapping dicts, including the supported mode bit flags. * ds402: Use monotonic clock for timeouts. The value returned from time.time() can go backwards between multiple calls, so time.monotonic() is the recommended way for checking timeouts. * ds402: Make timeout values configurable. Move all timing-related magic numbers to class-level constants and use those for timeout calculations and sleep() calls. That allows the library user to override the defaults on a per-node basis if needed, by just setting the same attribute on the object. And it's cleaner code without magic numbers. * ds402: Code cleanup: whitespace and indentation. * ds402: Clean up list formatting and style. Consistently format constant definitions, especially constant mappings: * Write Controlword commands with for hex digits (16 bits). * Same for Supported Drive Modes flags (only 16 of 32 bits). * Move colon directly after key in dicts and align values consistently. Fixes lots of flake8 errors. * Always include trailing comma in multi-line sequences. * Use tuples instead of lists for constant definitions. They don't need to be mutable. * ds402: Use tuple unpacking for simplified bitmask code. Apply the same pattern whenever the Statusword is checked for a specific bit pattern. --- canopen/profiles/p402.py | 219 +++++++++++++++++++++------------------ 1 file changed, 118 insertions(+), 101 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index f4dedb4f..d3d75b17 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -6,53 +6,54 @@ logger = logging.getLogger(__name__) + class State402(object): # Controlword (0x6040) commands - CW_OPERATION_ENABLED = 0x0F - CW_SHUTDOWN = 0x06 - CW_SWITCH_ON = 0x07 - CW_QUICK_STOP = 0x02 - CW_DISABLE_VOLTAGE = 0x00 - CW_SWITCH_ON_DISABLED = 0x80 + CW_OPERATION_ENABLED = 0x000F + CW_SHUTDOWN = 0x0006 + CW_SWITCH_ON = 0x0007 + CW_QUICK_STOP = 0x0002 + CW_DISABLE_VOLTAGE = 0x0000 + CW_SWITCH_ON_DISABLED = 0x0080 CW_CODE_COMMANDS = { - CW_SWITCH_ON_DISABLED : 'SWITCH ON DISABLED', - CW_DISABLE_VOLTAGE : 'DISABLE VOLTAGE', - CW_SHUTDOWN : 'READY TO SWITCH ON', - CW_SWITCH_ON : 'SWITCHED ON', - CW_OPERATION_ENABLED : 'OPERATION ENABLED', - CW_QUICK_STOP : 'QUICK STOP ACTIVE' + CW_SWITCH_ON_DISABLED: 'SWITCH ON DISABLED', + CW_DISABLE_VOLTAGE: 'DISABLE VOLTAGE', + CW_SHUTDOWN: 'READY TO SWITCH ON', + CW_SWITCH_ON: 'SWITCHED ON', + CW_OPERATION_ENABLED: 'OPERATION ENABLED', + CW_QUICK_STOP: 'QUICK STOP ACTIVE', } CW_COMMANDS_CODE = { - 'SWITCH ON DISABLED' : CW_SWITCH_ON_DISABLED, - 'DISABLE VOLTAGE' : CW_DISABLE_VOLTAGE, - 'READY TO SWITCH ON' : CW_SHUTDOWN, - 'SWITCHED ON' : CW_SWITCH_ON, - 'OPERATION ENABLED' : CW_OPERATION_ENABLED, - 'QUICK STOP ACTIVE' : CW_QUICK_STOP + 'SWITCH ON DISABLED': CW_SWITCH_ON_DISABLED, + 'DISABLE VOLTAGE': CW_DISABLE_VOLTAGE, + 'READY TO SWITCH ON': CW_SHUTDOWN, + 'SWITCHED ON': CW_SWITCH_ON, + 'OPERATION ENABLED': CW_OPERATION_ENABLED, + 'QUICK STOP ACTIVE': CW_QUICK_STOP, } # Statusword 0x6041 bitmask and values in the list in the dictionary value SW_MASK = { - 'NOT READY TO SWITCH ON': [0x4F, 0x00], - 'SWITCH ON DISABLED' : [0x4F, 0x40], - 'READY TO SWITCH ON' : [0x6F, 0x21], - 'SWITCHED ON' : [0x6F, 0x23], - 'OPERATION ENABLED' : [0x6F, 0x27], - 'FAULT' : [0x4F, 0x08], - 'FAULT REACTION ACTIVE' : [0x4F, 0x0F], - 'QUICK STOP ACTIVE' : [0x6F, 0x07] + 'NOT READY TO SWITCH ON': (0x4F, 0x00), + 'SWITCH ON DISABLED': (0x4F, 0x40), + 'READY TO SWITCH ON': (0x6F, 0x21), + 'SWITCHED ON': (0x6F, 0x23), + 'OPERATION ENABLED': (0x6F, 0x27), + 'FAULT': (0x4F, 0x08), + 'FAULT REACTION ACTIVE': (0x4F, 0x0F), + 'QUICK STOP ACTIVE': (0x6F, 0x07), } # Transition path to get to the 'OPERATION ENABLED' state NEXTSTATE2ENABLE = { - ('START') : 'NOT READY TO SWITCH ON', - ('FAULT', 'NOT READY TO SWITCH ON') : 'SWITCH ON DISABLED', - ('SWITCH ON DISABLED') : 'READY TO SWITCH ON', - ('READY TO SWITCH ON') : 'SWITCHED ON', - ('SWITCHED ON', 'QUICK STOP ACTIVE', 'OPERATION ENABLED') : 'OPERATION ENABLED', - ('FAULT REACTION ACTIVE') : 'FAULT' + ('START'): 'NOT READY TO SWITCH ON', + ('FAULT', 'NOT READY TO SWITCH ON'): 'SWITCH ON DISABLED', + ('SWITCH ON DISABLED'): 'READY TO SWITCH ON', + ('READY TO SWITCH ON'): 'SWITCHED ON', + ('SWITCHED ON', 'QUICK STOP ACTIVE', 'OPERATION ENABLED'): 'OPERATION ENABLED', + ('FAULT REACTION ACTIVE'): 'FAULT' } # Tansition table from the DS402 State Machine @@ -110,35 +111,45 @@ class OperationMode(object): OPEN_LOOP_VECTOR_MODE = -2 CODE2NAME = { - NO_MODE : 'NO MODE', - PROFILED_POSITION : 'PROFILED POSITION', - VELOCITY : 'VELOCITY', - PROFILED_VELOCITY : 'PROFILED VELOCITY', - PROFILED_TORQUE : 'PROFILED TORQUE', - HOMING : 'HOMING', - INTERPOLATED_POSITION : 'INTERPOLATED POSITION' + NO_MODE: 'NO MODE', + PROFILED_POSITION: 'PROFILED POSITION', + VELOCITY: 'VELOCITY', + PROFILED_VELOCITY: 'PROFILED VELOCITY', + PROFILED_TORQUE: 'PROFILED TORQUE', + HOMING: 'HOMING', + INTERPOLATED_POSITION: 'INTERPOLATED POSITION', + CYCLIC_SYNCHRONOUS_POSITION: 'CYCLIC SYNCHRONOUS POSITION', + CYCLIC_SYNCHRONOUS_VELOCITY: 'CYCLIC SYNCHRONOUS VELOCITY', + CYCLIC_SYNCHRONOUS_TORQUE: 'CYCLIC SYNCHRONOUS TORQUE', } NAME2CODE = { - 'NO MODE' : NO_MODE, - 'PROFILED POSITION' : PROFILED_POSITION, - 'VELOCITY' : VELOCITY, - 'PROFILED VELOCITY' : PROFILED_VELOCITY, - 'PROFILED TORQUE' : PROFILED_TORQUE, - 'HOMING' : HOMING, - 'INTERPOLATED POSITION' : INTERPOLATED_POSITION + 'NO MODE': NO_MODE, + 'PROFILED POSITION': PROFILED_POSITION, + 'VELOCITY': VELOCITY, + 'PROFILED VELOCITY': PROFILED_VELOCITY, + 'PROFILED TORQUE': PROFILED_TORQUE, + 'HOMING': HOMING, + 'INTERPOLATED POSITION': INTERPOLATED_POSITION, + 'CYCLIC SYNCHRONOUS POSITION': CYCLIC_SYNCHRONOUS_POSITION, + 'CYCLIC SYNCHRONOUS VELOCITY': CYCLIC_SYNCHRONOUS_VELOCITY, + 'CYCLIC SYNCHRONOUS TORQUE': CYCLIC_SYNCHRONOUS_TORQUE, } SUPPORTED = { - 'NO MODE' : 0x0, - 'PROFILED POSITION' : 0x1, - 'VELOCITY' : 0x2, - 'PROFILED VELOCITY' : 0x4, - 'PROFILED TORQUE' : 0x8, - 'HOMING' : 0x20, - 'INTERPOLATED POSITION' : 0x40 + 'NO MODE': 0x0000, + 'PROFILED POSITION': 0x0001, + 'VELOCITY': 0x0002, + 'PROFILED VELOCITY': 0x0004, + 'PROFILED TORQUE': 0x0008, + 'HOMING': 0x0020, + 'INTERPOLATED POSITION': 0x0040, + 'CYCLIC SYNCHRONOUS POSITION': 0x0080, + 'CYCLIC SYNCHRONOUS VELOCITY': 0x0100, + 'CYCLIC SYNCHRONOUS TORQUE': 0x0200, } + class Homing(object): CW_START = 0x10 CW_HALT = 0x100 @@ -154,23 +165,23 @@ class Homing(object): HM_NO_HOMING_OPERATION = 0 HM_ON_THE_NEGATIVE_LIMIT_SWITCH_AND_INDEX_PULSE = 1 HM_ON_THE_POSITIVE_LIMIT_SWITCH_AND_INDEX_PULSE = 2 - HM_ON_THE_POSITIVE_HOME_SWITCH_AND_INDEX_PULSE = [3, 4] - HM_ON_THE_NEGATIVE_HOME_SWITCH_AND_INDEX_PULSE = [5, 6] + HM_ON_THE_POSITIVE_HOME_SWITCH_AND_INDEX_PULSE = (3, 4) + HM_ON_THE_NEGATIVE_HOME_SWITCH_AND_INDEX_PULSE = (5, 6) HM_ON_THE_NEGATIVE_LIMIT_SWITCH = 17 HM_ON_THE_POSITIVE_LIMIT_SWITCH = 18 - HM_ON_THE_POSITIVE_HOME_SWITCH = [19, 20] - HM_ON_THE_NEGATIVE_HOME_SWITCH = [21, 22] + HM_ON_THE_POSITIVE_HOME_SWITCH = (19, 20) + HM_ON_THE_NEGATIVE_HOME_SWITCH = (21, 22) HM_ON_NEGATIVE_INDEX_PULSE = 33 HM_ON_POSITIVE_INDEX_PULSE = 34 HM_ON_CURRENT_POSITION = 35 STATES = { - 'IN PROGRESS' : [0x3400, 0x0000], - 'INTERRUPTED' : [0x3400, 0x0400], - 'ATTAINED' : [0x3400, 0x1000], - 'TARGET REACHED' : [0x3400, 0x1400], - 'ERROR VELOCITY IS NOT ZERO' : [0x3400, 0x2000], - 'ERROR VELOCITY IS ZERO' : [0x3400, 0x2400] + 'IN PROGRESS': (0x3400, 0x0000), + 'INTERRUPTED': (0x3400, 0x0400), + 'ATTAINED': (0x3400, 0x1000), + 'TARGET REACHED': (0x3400, 0x1400), + 'ERROR VELOCITY IS NOT ZERO': (0x3400, 0x2000), + 'ERROR VELOCITY IS ZERO': (0x3400, 0x2400), } @@ -185,10 +196,17 @@ class BaseNode402(RemoteNode): :type object_dictionary: :class:`str`, :class:`canopen.ObjectDictionary` """ + TIMEOUT_RESET_FAULT = 0.4 # seconds + TIMEOUT_SWITCH_OP_MODE = 0.5 # seconds + TIMEOUT_SWITCH_STATE_FINAL = 0.8 # seconds + TIMEOUT_SWITCH_STATE_SINGLE = 0.4 # seconds + INTERVAL_CHECK_STATE = 0.01 # seconds + TIMEOUT_HOMING_DEFAULT = 30 # seconds + def __init__(self, node_id, object_dictionary): super(BaseNode402, self).__init__(node_id, object_dictionary) - self.tpdo_values = dict() # { index: TPDO_value } - self.rpdo_pointers = dict() # { index: RPDO_pointer } + self.tpdo_values = dict() # { index: TPDO_value } + self.rpdo_pointers = dict() # { index: RPDO_pointer } def setup_402_state_machine(self): """Configure the state machine by searching for a TPDO that has the @@ -204,7 +222,7 @@ def setup_402_state_machine(self): self.state = 'SWITCH ON DISABLED' # Why change state? def setup_pdos(self): - self.pdo.read() # TPDO and RPDO configurations + self.pdo.read() # TPDO and RPDO configurations self._init_tpdo_values() self._init_rpdo_pointers() @@ -218,7 +236,7 @@ def _init_tpdo_values(self): self.tpdo_values[obj.index] = 0 def _init_rpdo_pointers(self): - # If RPDOs have overlapping indecies, rpdo_pointers will point to + # If RPDOs have overlapping indecies, rpdo_pointers will point to # the first RPDO that has that index configured. for rpdo in self.rpdo.values(): if rpdo.enabled: @@ -228,13 +246,13 @@ def _init_rpdo_pointers(self): self.rpdo_pointers[obj.index] = obj def _check_controlword_configured(self): - if 0x6040 not in self.rpdo_pointers: # Controlword + if 0x6040 not in self.rpdo_pointers: # Controlword logger.warning( "Controlword not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( self.id)) def _check_statusword_configured(self): - if 0x6041 not in self.tpdo_values: # Statusword + if 0x6041 not in self.tpdo_values: # Statusword raise ValueError( "Statusword not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( self.id)) @@ -245,18 +263,18 @@ def reset_from_fault(self): if self.state == 'FAULT': # Resets the Fault Reset bit (rising edge 0 -> 1) self.controlword = State402.CW_DISABLE_VOLTAGE - timeout = time.time() + 0.4 # 400 ms - + timeout = time.monotonic() + self.TIMEOUT_RESET_FAULT while self.is_faulted(): - if time.time() > timeout: + if time.monotonic() > timeout: break - time.sleep(0.01) # 10 ms + time.sleep(self.INTERVAL_CHECK_STATE) self.state = 'OPERATION ENABLED' - + def is_faulted(self): - return self.statusword & State402.SW_MASK['FAULT'][0] == State402.SW_MASK['FAULT'][1] + bitmask, bits = State402.SW_MASK['FAULT'] + return self.statusword & bitmask == bits - def homing(self, timeout=30, set_new_home=True): + def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, set_new_home=True): """Function to execute the configured Homing Method on the node :param int timeout: Timeout value (default: 30) :param bool set_new_home: Defines if the node should set the home offset @@ -271,23 +289,24 @@ def homing(self, timeout=30, set_new_home=True): self.state = 'OPERATION ENABLED' homingstatus = 'IN PROGRESS' self.controlword = State402.CW_OPERATION_ENABLED | Homing.CW_START - t = time.time() + timeout + t = time.monotonic() + timeout try: while homingstatus not in ('TARGET REACHED', 'ATTAINED'): for key, value in Homing.STATES.items(): - # check if the value after applying the bitmask (value[0]) - # corresponds with the value[1] to determine the current status - bitmaskvalue = self.statusword & value[0] - if bitmaskvalue == value[1]: + # check if the Statusword after applying the bitmask + # corresponds with the needed bits to determine the current status + bitmask, bits = value + if self.statusword & bitmask == bits: homingstatus = key - if homingstatus in ('INTERRUPTED', 'ERROR VELOCITY IS NOT ZERO', 'ERROR VELOCITY IS ZERO'): - raise RuntimeError ('Unable to home. Reason: {0}'.format(homingstatus)) - time.sleep(0.001) - if time.time() > t: + if homingstatus in ('INTERRUPTED', 'ERROR VELOCITY IS NOT ZERO', + 'ERROR VELOCITY IS ZERO'): + raise RuntimeError('Unable to home. Reason: {0}'.format(homingstatus)) + time.sleep(self.INTERVAL_CHECK_STATE) + if time.monotonic() > t: raise RuntimeError('Unable to home, timeout reached') if set_new_home: actual_position = self.sdo[0x6063].raw - self.sdo[0x607C].raw = actual_position # home offset (0x607C) + self.sdo[0x607C].raw = actual_position # Home Offset logger.info('Homing offset set to {0}'.format(actual_position)) logger.info('Homing mode carried out successfully.') return True @@ -334,16 +353,16 @@ def op_mode(self, mode): start_state = self.state if self.state == 'OPERATION ENABLED': - self.state = 'SWITCHED ON' + self.state = 'SWITCHED ON' # ensure the node does not move with an old value self._clear_target_values() # Shouldn't this happen before it's switched on? # operation mode self.sdo[0x6060].raw = OperationMode.NAME2CODE[mode] - timeout = time.time() + 0.5 # 500 ms + timeout = time.monotonic() + self.TIMEOUT_SWITCH_OP_MODE while self.op_mode != mode: - if time.time() > timeout: + if time.monotonic() > timeout: raise RuntimeError( "Timeout setting node {0}'s new mode of operation to {1}.".format( self.id, mode)) @@ -354,7 +373,7 @@ def op_mode(self, mode): logger.warning('{0}'.format(str(e))) finally: self.state = start_state # why? - logger.info('Set node {n} operation mode to {m}.'.format(n=self.id , m=mode)) + logger.info('Set node {n} operation mode to {m}.'.format(n=self.id, m=mode)) return False def _clear_target_values(self): @@ -421,10 +440,8 @@ def state(self): - 'QUICK STOP ACTIVE' """ for state, mask_val_pair in State402.SW_MASK.items(): - mask = mask_val_pair[0] - state_value = mask_val_pair[1] - masked_value = self.statusword & mask - if masked_value == state_value: + bitmask, bits = mask_val_pair + if self.statusword & bitmask == bits: return state return 'UNKNOWN' @@ -442,14 +459,14 @@ def state(self, target_state): :raise RuntimeError: Occurs when the time defined to change the state is reached :raise ValueError: Occurs when trying to execute a ilegal transition in the sate machine """ - timeout = time.time() + 0.8 # 800 ms + timeout = time.monotonic() + self.TIMEOUT_SWITCH_STATE_FINAL while self.state != target_state: next_state = self._next_state(target_state) if self._change_state(next_state): - continue - if time.time() > timeout: + continue + if time.monotonic() > timeout: raise RuntimeError('Timeout when trying to change state') - time.sleep(0.01) # 10 ms + time.sleep(self.INTERVAL_CHECK_STATE) def _next_state(self, target_state): if target_state == 'OPERATION ENABLED': @@ -463,9 +480,9 @@ def _change_state(self, target_state): except KeyError: raise ValueError( 'Illegal state transition from {f} to {t}'.format(f=self.state, t=target_state)) - timeout = time.time() + 0.4 # 400 ms + timeout = time.monotonic() + self.TIMEOUT_SWITCH_STATE_SINGLE while self.state != target_state: - if time.time() > timeout: + if time.monotonic() > timeout: return False - time.sleep(0.01) # 10 ms + time.sleep(self.INTERVAL_CHECK_STATE) return True From 509f5533e8a1ffeb6bd9bdbf41ffc81f63b75224 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 2 Aug 2021 13:53:48 +0200 Subject: [PATCH 048/199] DS402: Cache supported operation modes (#247) * ds402: Cache supported operation modes. Requesting the same immutable OD object on each change of operation mode takes quite some time to process. Introduce a local cache member variable in order to avoid requesting more than once. * ds402: Log message about cache operation mode support. --- canopen/profiles/p402.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index d3d75b17..c5f8eb3a 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -388,8 +388,13 @@ def is_op_mode_supported(self, mode): :return: If the operation mode is supported :rtype: bool """ - mode_support = self.sdo[0x6502].raw & OperationMode.SUPPORTED[mode] - return mode_support == OperationMode.SUPPORTED[mode] + if not hasattr(self, '_op_mode_support'): + # Cache value only on first lookup, this object should never change. + self._op_mode_support = self.sdo[0x6502].raw + logger.info('Caching node {n} supported operation modes 0x{m:04X}'.format( + n=self.id, m=self._op_mode_support)) + bits = OperationMode.SUPPORTED[mode] + return self._op_mode_support & bits == bits def on_TPDOs_update_callback(self, mapobject): """This function receives a map object. From 179022cd870118f8f9ae714b9bc465af98758aec Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 2 Aug 2021 14:38:47 +0200 Subject: [PATCH 049/199] ds402: Support checking the homing status. (#248) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Implement a new method BaseNode402.is_homed() which will switch to the corresponding operation mode HOMING and then examine the Statusword for the homing status bits. This allows to skip the homing procedure in case the drive controller still knows its position, but e.g. the Python application was restarted. Co-authored-by: André Filipe Silva --- canopen/profiles/p402.py | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index c5f8eb3a..dd3ac9eb 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -274,6 +274,21 @@ def is_faulted(self): bitmask, bits = State402.SW_MASK['FAULT'] return self.statusword & bitmask == bits + def is_homed(self, restore_op_mode=False): + """Switch to homing mode and determine its status.""" + previous_op_mode = self.op_mode + if previous_op_mode != 'HOMING': + logger.info('Switch to HOMING from %s', previous_op_mode) + self.op_mode = 'HOMING' + homingstatus = None + for key, value in Homing.STATES.items(): + bitmask, bits = value + if self.statusword & bitmask == bits: + homingstatus = key + if restore_op_mode: + self.op_mode = previous_op_mode + return homingstatus in ('TARGET REACHED', 'ATTAINED') + def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, set_new_home=True): """Function to execute the configured Homing Method on the node :param int timeout: Timeout value (default: 30) From 1f456a469f4708790fb62f0e4fc02d2e76d77e95 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Fri, 6 Aug 2021 14:32:19 +0200 Subject: [PATCH 050/199] Separate subscription from the PDO's read() and save() methods. Normally one needs to call read() or save() on a single pdo (or the node's whole PDO collection) in order to receive any such objects from the network. That however requires quite a few SDO exchanges to make sure the node's PDO configuration matches the parameters configured in the object. For applications where the PDO configuration is stored persistently in the node (e.g. device EEPROM), doing this SDO exchange can be skipped entirely if the application programmer takes care to mirror the same configuration in the python-canopen objects. Another use case is reconnecting to a node for which the same python-canopen script previously ran and the PDO configuration is still known to be valid. Factor out a new method subscribe() from read() and save() to offer doing only that last part via the public API. Adapt the log message and make sure it is logged in read() as well. --- canopen/pdo/base.py | 26 +++++++++++++++++++++++--- 1 file changed, 23 insertions(+), 3 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 97006b01..f5f65192 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -59,6 +59,17 @@ def save(self): for pdo_map in self.map.values(): pdo_map.save() + def subscribe(self): + """Register the node's PDOs for reception on the network. + + This normally happens when the PDO configuration is read from + or saved to the node. Use this method to avoid the SDO flood + associated with read() or save(), if the local PDO setup is + known to match what's stored on the node. + """ + for pdo_map in self.map.values(): + pdo_map.subscribe() + def export(self, filename): """Export current configuration to a database file. @@ -331,8 +342,7 @@ def read(self): if index and size: self.add_variable(index, subindex, size) - if self.enabled: - self.pdo_node.network.subscribe(self.cob_id, self.on_message) + self.subscribe() def save(self): """Save PDO configuration for this map using SDO.""" @@ -387,9 +397,19 @@ def save(self): self._update_data_size() if self.enabled: - logger.info("Enabling PDO") self.com_record[1].raw = self.cob_id | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0x0) + self.subscribe() + + def subscribe(self): + """Register the PDO for reception on the network. + This normally happens when the PDO configuration is read from + or saved to the node. Use this method to avoid the SDO flood + associated with read() or save(), if the local PDO setup is + known to match what's stored on the node. + """ + if self.enabled: + logger.info("Subscribing to enabled PDO 0x%X on the network", self.cob_id) self.pdo_node.network.subscribe(self.cob_id, self.on_message) def clear(self): From e3c0432e834505439019b6fd37c1fc93c731d816 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Fri, 6 Aug 2021 14:55:55 +0200 Subject: [PATCH 051/199] Fix some docstrings on the PDO classes. Follow the standard docstring conventions and rephrase the description of RPDO and TPDO classes which is really long for a single summary line. No more docstring errors are reported by the flake8 checker on this file. --- canopen/pdo/__init__.py | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/canopen/pdo/__init__.py b/canopen/pdo/__init__.py index 5d8a3ba4..a08b3ccc 100644 --- a/canopen/pdo/__init__.py +++ b/canopen/pdo/__init__.py @@ -8,7 +8,8 @@ class PDO(PdoBase): - """PDO Class for backwards compatibility + """PDO Class for backwards compatibility. + :param rpdo: RPDO object holding the Receive PDO mappings :param tpdo: TPDO object holding the Transmit PDO mappings """ @@ -27,9 +28,11 @@ def __init__(self, node, rpdo, tpdo): class RPDO(PdoBase): - """PDO specialization for the Receive PDO enabling the transfer of data from the master to the node. + """Receive PDO to transfer data from somewhere to the represented node. + Properties 0x1400 to 0x1403 | Mapping 0x1600 to 0x1603. - :param object node: Parent node for this object.""" + :param object node: Parent node for this object. + """ def __init__(self, node): super(RPDO, self).__init__(node) @@ -38,8 +41,10 @@ def __init__(self, node): def stop(self): """Stop transmission of all RPDOs. + :raise TypeError: Exception is thrown if the node associated with the PDO does not - support this function""" + support this function. + """ if isinstance(self.node, canopen.RemoteNode): for pdo in self.map.values(): pdo.stop() @@ -48,8 +53,11 @@ def stop(self): class TPDO(PdoBase): - """PDO specialization for the Transmit PDO enabling the transfer of data from the node to the master. - Properties 0x1800 to 0x1803 | Mapping 0x1A00 to 0x1A03.""" + """Transmit PDO to broadcast data from the represented node to the network. + + Properties 0x1800 to 0x1803 | Mapping 0x1A00 to 0x1A03. + :param object node: Parent node for this object. + """ def __init__(self, node): super(TPDO, self).__init__(node) @@ -58,8 +66,10 @@ def __init__(self, node): def stop(self): """Stop transmission of all TPDOs. + :raise TypeError: Exception is thrown if the node associated with the PDO does not - support this function""" + support this function. + """ if isinstance(canopen.LocalNode, self.node): for pdo in self.map.values(): pdo.stop() From 7ff48b152ff2472e13ea27fe3059a37424f7149d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Wed, 11 Aug 2021 09:47:30 +0200 Subject: [PATCH 052/199] p402: Remove return value from property setter. Such a return value cannot be used sensibly, because assignments to the property don't have a return value in Python. --- canopen/profiles/p402.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index dd3ac9eb..195ca035 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -343,8 +343,6 @@ def op_mode(self): def op_mode(self, mode): """Function to define the operation mode of the node :param string mode: Mode to define. - :return: Return if the operation mode was set with success or not - :rtype: bool The modes can be: - 'NO MODE' @@ -381,7 +379,6 @@ def op_mode(self, mode): raise RuntimeError( "Timeout setting node {0}'s new mode of operation to {1}.".format( self.id, mode)) - return True except SdoCommunicationError as e: logger.warning('[SDO communication error] Cause: {0}'.format(str(e))) except (RuntimeError, ValueError) as e: @@ -389,7 +386,6 @@ def op_mode(self, mode): finally: self.state = start_state # why? logger.info('Set node {n} operation mode to {m}.'.format(n=self.id, m=mode)) - return False def _clear_target_values(self): # [target velocity, target position, target torque] From 475d22ceaf85d9e18ab0b7a8769070d19ecfafe1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Wed, 11 Aug 2021 10:53:20 +0200 Subject: [PATCH 053/199] doc: Include generated API documentation for the BaseNode402 class. --- doc/profiles.rst | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/doc/profiles.rst b/doc/profiles.rst index dac3e85d..1047c7f9 100644 --- a/doc/profiles.rst +++ b/doc/profiles.rst @@ -85,3 +85,10 @@ Available commands - 'SWITCHED ON' - 'OPERATION ENABLED' - 'QUICK STOP ACTIVE' + + +API +``` + +.. autoclass:: canopen.profiles.p402.BaseNode402 + :members: From 4263f85b3b8c7cddc3b09128cf8bbc1189945018 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Wed, 11 Aug 2021 12:44:05 +0200 Subject: [PATCH 054/199] DS402: Clean up docstrings. Follow PEP-257 regarding overall formatting. Fix typos. Fix incorrect usage of Sphinx directives (:return: does not take an inline type as :param: does). Standardize on :raises: directive. Fix wrapping to eliminate Sphinx warnings. Add missing parameter and return documentation for is_homed(). Move all property documentation to the getter functions, where Python expects it and where it is not ignored by Sphinx. Fix incorrectly documented return types. Improve some descriptions that were unclear (to me). --- canopen/profiles/p402.py | 120 +++++++++++++++++++++------------------ 1 file changed, 66 insertions(+), 54 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 195ca035..923e0331 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -87,9 +87,11 @@ class State402(object): @staticmethod def next_state_for_enabling(_from): - """Returns the next state needed for reach the state Operation Enabled - :param string target: Target state - :return string: Next target to chagne + """Return the next state needed for reach the state Operation Enabled. + + :param string target: Target state. + :return: Next target to change. + :rtype: str """ for cond, next_state in State402.NEXTSTATE2ENABLE.items(): if _from in cond: @@ -209,10 +211,10 @@ def __init__(self, node_id, object_dictionary): self.rpdo_pointers = dict() # { index: RPDO_pointer } def setup_402_state_machine(self): - """Configure the state machine by searching for a TPDO that has the - StatusWord mapped. - :raise ValueError: If the the node can't find a Statusword configured - in the any of the TPDOs + """Configure the state machine by searching for a TPDO that has the StatusWord mapped. + + :raises ValueError: + If the the node can't find a Statusword configured in the any of the TPDOs. """ self.nmt.state = 'PRE-OPERATIONAL' # Why is this necessary? self.setup_pdos() @@ -258,8 +260,7 @@ def _check_statusword_configured(self): self.id)) def reset_from_fault(self): - """Reset node from fault and set it to Operation Enable state - """ + """Reset node from fault and set it to Operation Enable state.""" if self.state == 'FAULT': # Resets the Fault Reset bit (rising edge 0 -> 1) self.controlword = State402.CW_DISABLE_VOLTAGE @@ -275,7 +276,12 @@ def is_faulted(self): return self.statusword & bitmask == bits def is_homed(self, restore_op_mode=False): - """Switch to homing mode and determine its status.""" + """Switch to homing mode and determine its status. + + :param bool restore_op_mode: Switch back to the previous operation mode when done. + :return: If the status indicates successful homing. + :rtype: bool + """ previous_op_mode = self.op_mode if previous_op_mode != 'HOMING': logger.info('Switch to HOMING from %s', previous_op_mode) @@ -290,11 +296,13 @@ def is_homed(self, restore_op_mode=False): return homingstatus in ('TARGET REACHED', 'ATTAINED') def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, set_new_home=True): - """Function to execute the configured Homing Method on the node - :param int timeout: Timeout value (default: 30) - :param bool set_new_home: Defines if the node should set the home offset - object (0x607C) to the current position after the homing procedure (default: true) - :return: If the homing was complete with success + """Execute the configured Homing method on the node. + + :param int timeout: Timeout value (default: 30). + :param bool set_new_home: + Defines if the node should set the home offset object (0x607C) to the current + position after the homing procedure (default: true). + :return: If the homing was complete with success. :rtype: bool """ previus_op_mode = self.op_mode @@ -333,18 +341,11 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, set_new_home=True): @property def op_mode(self): - """ - :return: Return the operation mode stored in the object 0x6061 through SDO - :rtype: int - """ - return OperationMode.CODE2NAME[self.sdo[0x6061].raw] + """The node's Operation Mode stored in the object 0x6061. - @op_mode.setter - def op_mode(self, mode): - """Function to define the operation mode of the node - :param string mode: Mode to define. + Uses SDO to access the current value. The modes are passed as one of the + following strings: - The modes can be: - 'NO MODE' - 'PROFILED POSITION' - 'VELOCITY' @@ -357,7 +358,14 @@ def op_mode(self, mode): - 'CYCLIC SYNCHRONOUS TORQUE' - 'OPEN LOOP SCALAR MODE' - 'OPEN LOOP VECTOR MODE' + + :raises TypeError: When setting a mode not advertised as supported by the node. + :raises RuntimeError: If the switch is not confirmed within the configured timeout. """ + return OperationMode.CODE2NAME[self.sdo[0x6061].raw] + + @op_mode.setter + def op_mode(self, mode): try: if not self.is_op_mode_supported(mode): raise TypeError( @@ -394,9 +402,13 @@ def _clear_target_values(self): self.sdo[target_index].raw = 0 def is_op_mode_supported(self, mode): - """Function to check if the operation mode is supported by the node - :param int mode: Operation mode - :return: If the operation mode is supported + """Check if the operation mode is supported by the node. + + The object listing the supported modes is retrieved once using SDO, then cached + for later checks. + + :param str mode: Same format as the :attr:`op_mode` property. + :return: If the operation mode is supported. :rtype: bool """ if not hasattr(self, '_op_mode_support'): @@ -408,18 +420,20 @@ def is_op_mode_supported(self, mode): return self._op_mode_support & bits == bits def on_TPDOs_update_callback(self, mapobject): - """This function receives a map object. - this map object is then used for changing the - :param mapobject: :class: `canopen.objectdictionary.Variable` + """Cache updated values from a TPDO received from this node. + + :param mapobject: The received PDO message. + :type mapobject: canopen.pdo.Map """ for obj in mapobject: self.tpdo_values[obj.index] = obj.raw @property def statusword(self): - """Returns the last read value of the Statusword (0x6041) from the device. - If the the object 0x6041 is not configured in any TPDO it will fallback to the SDO mechanism - and try to tget the value. + """Return the last read value of the Statusword (0x6041) from the device. + + If the the object 0x6041 is not configured in any TPDO it will fall back to the + SDO mechanism and try to get the value. """ try: return self.tpdo_values[0x6041] @@ -429,13 +443,15 @@ def statusword(self): @property def controlword(self): + """Send a state change command using PDO or SDO. + + :param int value: Controlword value to set. + :raises RuntimeError: Read access to the controlword is not intended. + """ raise RuntimeError('The Controlword is write-only.') @controlword.setter def controlword(self, value): - """Send the state using PDO or SDO objects. - :param int value: State value to send in the message - """ if 0x6040 in self.rpdo_pointers: self.rpdo_pointers[0x6040].raw = value self.rpdo_pointers[0x6040].pdo_parent.transmit() @@ -444,16 +460,24 @@ def controlword(self, value): @property def state(self): - """Attribute to get or set node's state as a string for the DS402 State Machine. - States of the node can be one of: - - 'NOT READY TO SWITCH ON' + """Manipulate current state of the DS402 State Machine on the node. + + Uses the last received Statusword value for read access, and manipulates the + :attr:`controlword` for changing states. The states are passed as one of the + following strings: + + - 'NOT READY TO SWITCH ON' (cannot be switched to deliberately) - 'SWITCH ON DISABLED' - 'READY TO SWITCH ON' - 'SWITCHED ON' - 'OPERATION ENABLED' - - 'FAULT' - - 'FAULT REACTION ACTIVE' + - 'FAULT' (cannot be switched to deliberately) + - 'FAULT REACTION ACTIVE' (cannot be switched to deliberately) - 'QUICK STOP ACTIVE' + - 'DISABLE VOLTAGE' (only as a command when writing) + + :raises RuntimeError: If the switch is not confirmed within the configured timeout. + :raises ValueError: Trying to execute a illegal transition in the state machine. """ for state, mask_val_pair in State402.SW_MASK.items(): bitmask, bits = mask_val_pair @@ -463,18 +487,6 @@ def state(self): @state.setter def state(self, target_state): - """ Defines the state for the DS402 state machine - States to switch to can be one of: - - 'SWITCH ON DISABLED' - - 'DISABLE VOLTAGE' - - 'READY TO SWITCH ON' - - 'SWITCHED ON' - - 'OPERATION ENABLED' - - 'QUICK STOP ACTIVE' - :param string target_state: Target state - :raise RuntimeError: Occurs when the time defined to change the state is reached - :raise ValueError: Occurs when trying to execute a ilegal transition in the sate machine - """ timeout = time.monotonic() + self.TIMEOUT_SWITCH_STATE_FINAL while self.state != target_state: next_state = self._next_state(target_state) From 282b2e32a42e18d3c009baf5032ca33d9a4e9482 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 12 Aug 2021 09:42:55 +0200 Subject: [PATCH 055/199] Fix typo. --- canopen/profiles/p402.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 923e0331..f822e1b9 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -432,8 +432,8 @@ def on_TPDOs_update_callback(self, mapobject): def statusword(self): """Return the last read value of the Statusword (0x6041) from the device. - If the the object 0x6041 is not configured in any TPDO it will fall back to the - SDO mechanism and try to get the value. + If the object 0x6041 is not configured in any TPDO it will fall back to the SDO + mechanism and try to get the value. """ try: return self.tpdo_values[0x6041] From 00041724a9a35e95d72f77eb39ab98ede22d5e4d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 12 Aug 2021 09:48:49 +0200 Subject: [PATCH 056/199] Fix wrong type name for parameter. "string" is not a Python type, but "str" is. --- canopen/profiles/p402.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index f822e1b9..c5d0d504 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -89,7 +89,7 @@ class State402(object): def next_state_for_enabling(_from): """Return the next state needed for reach the state Operation Enabled. - :param string target: Target state. + :param str target: Target state. :return: Next target to change. :rtype: str """ From 4e4bc90f78965124fa0e45ff2d2ba83d3706eb1c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 12 Aug 2021 10:56:21 +0200 Subject: [PATCH 057/199] Fix typo. --- canopen/profiles/p402.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index c5d0d504..f5233ea4 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -214,7 +214,7 @@ def setup_402_state_machine(self): """Configure the state machine by searching for a TPDO that has the StatusWord mapped. :raises ValueError: - If the the node can't find a Statusword configured in the any of the TPDOs. + If the the node can't find a Statusword configured in any of the TPDOs. """ self.nmt.state = 'PRE-OPERATIONAL' # Why is this necessary? self.setup_pdos() From 4b95870ebf0a435ceed38fd4778abcb0305c3eb4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 18:49:19 +0200 Subject: [PATCH 058/199] ds402: Skip explicit change to SWITCHED ON state. (#249) The BaseNode402.homing() method tries to enter state SWITCHED ON upon entry. That's unnecessary, the application should handle these transitions. But more importantly, it actually fails in many cases, namely if the previous state is SWITCH ON DISABLED, the default power-up state of most devices. There is an automatic way to reach OPERATION ENABLED over multiple intermediate steps, but the library does not know how to reach SWITCHED ON from any other state than OPERATION ENABLED or READY TO SWITCH ON. In addition, setting the op_mode property will already change to SWITCHED ON only if coming from OPERATION ENABLED (which is usually a good idea to avoid unexpected movement). Note that switching the operation mode to HOMING is actually safe in any power state. --- canopen/profiles/p402.py | 1 - 1 file changed, 1 deletion(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index f5233ea4..b0fc090f 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -306,7 +306,6 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, set_new_home=True): :rtype: bool """ previus_op_mode = self.op_mode - self.state = 'SWITCHED ON' self.op_mode = 'HOMING' # The homing process will initialize at operation enabled self.state = 'OPERATION ENABLED' From 8e9ccd665053d99a17bbd84597f64d8a12257e06 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 18:51:41 +0200 Subject: [PATCH 059/199] ds402: Remove set_new_home functionality from BaseNode402.homing(). (#250) The homing() method will try to manipulate the Home Offset (0x607C) parameter by default. That's not the way the parameter is intended to work. After a successful homing procedure, the drive should set the Actual Position (0x6063) to the Home Offset (0x607C) by itself. By default that is zero, so the selected reference switch flank will mark the new zero position. The library's default behavior here is backwards, and can only work with absolute position encoders. The whole point of homing is to find a physical reference and align the logical coordinate system to it. Trying to determine the desired offset from the value which an unreferenced encoder had at the physical reference point actually destroys that logical alignment. The functionality of set_new_home=True is trivial to do from the application, so remove it completely from homing(). --- canopen/profiles/p402.py | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index b0fc090f..804ec576 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -295,13 +295,10 @@ def is_homed(self, restore_op_mode=False): self.op_mode = previous_op_mode return homingstatus in ('TARGET REACHED', 'ATTAINED') - def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, set_new_home=True): + def homing(self, timeout=TIMEOUT_HOMING_DEFAULT): """Execute the configured Homing method on the node. :param int timeout: Timeout value (default: 30). - :param bool set_new_home: - Defines if the node should set the home offset object (0x607C) to the current - position after the homing procedure (default: true). :return: If the homing was complete with success. :rtype: bool """ @@ -326,10 +323,6 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, set_new_home=True): time.sleep(self.INTERVAL_CHECK_STATE) if time.monotonic() > t: raise RuntimeError('Unable to home, timeout reached') - if set_new_home: - actual_position = self.sdo[0x6063].raw - self.sdo[0x607C].raw = actual_position # Home Offset - logger.info('Homing offset set to {0}'.format(actual_position)) logger.info('Homing mode carried out successfully.') return True except RuntimeError as e: From 8523a686479a8a294a97e067fc3444ac869792e9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 18:54:51 +0200 Subject: [PATCH 060/199] DS402: Minimize side-effects of operation mode switching (ref #244) (#251) * ds402: Keep target values on operation mode change. As the comment already stated, clearing the target values should possibly happen before switching to the OPERATION ENABLED state, to avoid unexpected movements. So doing that when actually leaving that state is mostly useless. Some legitimate use cases even require switching the operation mode while in OPERATION ENABLED, e.g. switching between Profile Position and Profile Velocity. This change does not allow that, but at the very least will avoid the need to reset target values again. * ds402: Keep power state on operation mode change. Some legitimate use cases require switching the operation mode while in OPERATION ENABLED, e.g. switching between Profile Position and Profile Velocity. If an application or specific controller needs the transition from OPERATION ENABLED to SWITCHED ON during operation mode changes, that should be handled outside this library, and is easy enough to do. On the other hand, having it inside the op_mode setter prevents the above mentioned use-case. * ds402: Improve logging in op_mode setter. Do not generate a log message about the changed operation mode when it actually failed. Use a consistent style for the TypeError message formatting. --- canopen/profiles/p402.py | 15 ++------------- 1 file changed, 2 insertions(+), 13 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 804ec576..34763a21 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -361,31 +361,20 @@ def op_mode(self, mode): try: if not self.is_op_mode_supported(mode): raise TypeError( - 'Operation mode {0} not suppported on node {1}.'.format(mode, self.id)) - - start_state = self.state - - if self.state == 'OPERATION ENABLED': - self.state = 'SWITCHED ON' - # ensure the node does not move with an old value - self._clear_target_values() # Shouldn't this happen before it's switched on? - + 'Operation mode {m} not suppported on node {n}.'.format(n=self.id, m=mode)) # operation mode self.sdo[0x6060].raw = OperationMode.NAME2CODE[mode] - timeout = time.monotonic() + self.TIMEOUT_SWITCH_OP_MODE while self.op_mode != mode: if time.monotonic() > timeout: raise RuntimeError( "Timeout setting node {0}'s new mode of operation to {1}.".format( self.id, mode)) + logger.info('Set node {n} operation mode to {m}.'.format(n=self.id, m=mode)) except SdoCommunicationError as e: logger.warning('[SDO communication error] Cause: {0}'.format(str(e))) except (RuntimeError, ValueError) as e: logger.warning('{0}'.format(str(e))) - finally: - self.state = start_state # why? - logger.info('Set node {n} operation mode to {m}.'.format(n=self.id, m=mode)) def _clear_target_values(self): # [target velocity, target position, target torque] From ebad5da3285a2386be4030f2f58e2d0837a6e3da Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 19:07:19 +0200 Subject: [PATCH 061/199] DS402: Increase delay to check status on homing start. (#252) * ds402: Increase delay to check status on homing start. The Statusword is examined immediately after setting the Controlword command to start homing. That is very likely to fail because of the round-trip time until the Statusword is actually updated from a TPDO. To work around that, the delay between each check of the Statusword should be moved before the actual comparison, and its default value increased. Introduce a new constant TIMEOUT_CHECK_HOMING to configure that with a default value of 100 ms. This replaces the previously used INTERVAL_CHECK_STATE which is only 10 ms by default. An even better solution would be to wait for the Statusword to be updated by a received PDO, but that would be much more complex. * Apply interval to is_homed() method as well. Same problem as in the homing() method, PDO updates of the Statusword need at least one SYNC / PDO cycle duration. * Factor out common _homing_status() method. Move the common code from is_homed() and homing() to a method for internal use. Add a comment why the delay is necessary and how it should possibly be replaced by an RPDO reception check. Should the latter be implemented, there will be only one place to change it. --- canopen/profiles/p402.py | 27 +++++++++++++++------------ 1 file changed, 15 insertions(+), 12 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 34763a21..bb84ec8d 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -204,6 +204,7 @@ class BaseNode402(RemoteNode): TIMEOUT_SWITCH_STATE_SINGLE = 0.4 # seconds INTERVAL_CHECK_STATE = 0.01 # seconds TIMEOUT_HOMING_DEFAULT = 30 # seconds + INTERVAL_CHECK_HOMING = 0.1 # seconds def __init__(self, node_id, object_dictionary): super(BaseNode402, self).__init__(node_id, object_dictionary) @@ -275,6 +276,18 @@ def is_faulted(self): bitmask, bits = State402.SW_MASK['FAULT'] return self.statusword & bitmask == bits + def _homing_status(self): + """Interpret the current Statusword bits as homing state string.""" + # Wait to make sure an RPDO was received. Should better check for reception + # instead of this hard-coded delay, but at least it can be configured per node. + time.sleep(self.INTERVAL_CHECK_HOMING) + status = None + for key, value in Homing.STATES.items(): + bitmask, bits = value + if self.statusword & bitmask == bits: + status = key + return status + def is_homed(self, restore_op_mode=False): """Switch to homing mode and determine its status. @@ -286,11 +299,7 @@ def is_homed(self, restore_op_mode=False): if previous_op_mode != 'HOMING': logger.info('Switch to HOMING from %s', previous_op_mode) self.op_mode = 'HOMING' - homingstatus = None - for key, value in Homing.STATES.items(): - bitmask, bits = value - if self.statusword & bitmask == bits: - homingstatus = key + homingstatus = self._homing_status() if restore_op_mode: self.op_mode = previous_op_mode return homingstatus in ('TARGET REACHED', 'ATTAINED') @@ -311,16 +320,10 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT): t = time.monotonic() + timeout try: while homingstatus not in ('TARGET REACHED', 'ATTAINED'): - for key, value in Homing.STATES.items(): - # check if the Statusword after applying the bitmask - # corresponds with the needed bits to determine the current status - bitmask, bits = value - if self.statusword & bitmask == bits: - homingstatus = key + homingstatus = self._homing_status() if homingstatus in ('INTERRUPTED', 'ERROR VELOCITY IS NOT ZERO', 'ERROR VELOCITY IS ZERO'): raise RuntimeError('Unable to home. Reason: {0}'.format(homingstatus)) - time.sleep(self.INTERVAL_CHECK_STATE) if time.monotonic() > t: raise RuntimeError('Unable to home, timeout reached') logger.info('Homing mode carried out successfully.') From 1a0ebd72be4311291654c8bc5172763e339102a4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Silva?= Date: Mon, 16 Aug 2021 18:16:03 +0100 Subject: [PATCH 062/199] Revert "DS402: Increase delay to check status on homing start. (#252)" This reverts commit ebad5da3285a2386be4030f2f58e2d0837a6e3da. Will merge instead the PR #257 with cumulative changes --- canopen/profiles/p402.py | 27 ++++++++++++--------------- 1 file changed, 12 insertions(+), 15 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index bb84ec8d..34763a21 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -204,7 +204,6 @@ class BaseNode402(RemoteNode): TIMEOUT_SWITCH_STATE_SINGLE = 0.4 # seconds INTERVAL_CHECK_STATE = 0.01 # seconds TIMEOUT_HOMING_DEFAULT = 30 # seconds - INTERVAL_CHECK_HOMING = 0.1 # seconds def __init__(self, node_id, object_dictionary): super(BaseNode402, self).__init__(node_id, object_dictionary) @@ -276,18 +275,6 @@ def is_faulted(self): bitmask, bits = State402.SW_MASK['FAULT'] return self.statusword & bitmask == bits - def _homing_status(self): - """Interpret the current Statusword bits as homing state string.""" - # Wait to make sure an RPDO was received. Should better check for reception - # instead of this hard-coded delay, but at least it can be configured per node. - time.sleep(self.INTERVAL_CHECK_HOMING) - status = None - for key, value in Homing.STATES.items(): - bitmask, bits = value - if self.statusword & bitmask == bits: - status = key - return status - def is_homed(self, restore_op_mode=False): """Switch to homing mode and determine its status. @@ -299,7 +286,11 @@ def is_homed(self, restore_op_mode=False): if previous_op_mode != 'HOMING': logger.info('Switch to HOMING from %s', previous_op_mode) self.op_mode = 'HOMING' - homingstatus = self._homing_status() + homingstatus = None + for key, value in Homing.STATES.items(): + bitmask, bits = value + if self.statusword & bitmask == bits: + homingstatus = key if restore_op_mode: self.op_mode = previous_op_mode return homingstatus in ('TARGET REACHED', 'ATTAINED') @@ -320,10 +311,16 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT): t = time.monotonic() + timeout try: while homingstatus not in ('TARGET REACHED', 'ATTAINED'): - homingstatus = self._homing_status() + for key, value in Homing.STATES.items(): + # check if the Statusword after applying the bitmask + # corresponds with the needed bits to determine the current status + bitmask, bits = value + if self.statusword & bitmask == bits: + homingstatus = key if homingstatus in ('INTERRUPTED', 'ERROR VELOCITY IS NOT ZERO', 'ERROR VELOCITY IS ZERO'): raise RuntimeError('Unable to home. Reason: {0}'.format(homingstatus)) + time.sleep(self.INTERVAL_CHECK_STATE) if time.monotonic() > t: raise RuntimeError('Unable to home, timeout reached') logger.info('Homing mode carried out successfully.') From c161ab3931a6312ce27bffc96b79f4a70386464a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 19:27:58 +0200 Subject: [PATCH 063/199] DS402: Allow handling the operation mode via PDO. (#257) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * pdo: Document relation between start() and the period attribute. * pdo: Add a property to check if period updates are transmitted. * p402: Skip sending the controlword RPDO if configured with a period. Transmitting the RPDO only makes sense if the value takes effect immediately. If there is already a cyclic task configured, or the transmission type configuration requires a SYNC to be sent for the change to apply, there is no sense in sending the PDO automatically in the controlword setter. * p402: Use RPDO to set the operation mode if possible. Fall back to the previous behavior using SDO if the relevant object 0x6060 is not mapped to an RPDO. * p402: Use TPDO to get the operation mode if possible. Fall back to the previous behavior using SDO if the relevant object 0x6061 is not mapped to a TPDO. The property getter still blocks until an up-to-date value was received, by waiting for the respective TPDO up to a configurable timeout of 0.2 seconds by default. If the TPDO does not look like it will be transmitted regularly (from its is_periodic property), the method will not block and just return the last received TPDO's value. A lookup cache tpdo_pointers is added to keep track of the needed pdo.Map instance, analog to the rpdo_pointers. * p402: Improve documentation on PDO tracking dicts. Consistently use empty dict literal for initialization. Provide more useful comments about the expected contents. * p402: Check PDO configuration for the Operation Mode objects. Switching operation modes for several drives simultaneously must be done via PDO. There is still a fallback mechanism via SDO, but a warning should be issued when that is about to be used. Co-authored-by: André Filipe Silva --- canopen/pdo/base.py | 25 +++++++++++++++++++++++-- canopen/profiles/p402.py | 37 ++++++++++++++++++++++++++++++++----- 2 files changed, 55 insertions(+), 7 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index f5f65192..63a0053e 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -186,7 +186,8 @@ def __init__(self, pdo_node, com_record, map_array): self.data = bytearray() #: Timestamp of last received message self.timestamp = None - #: Period of receive message transmission in seconds + #: Period of receive message transmission in seconds. + #: Set explicitly or using the :meth:`start()` method. self.period = None self.callbacks = [] self.receive_condition = threading.Condition() @@ -273,6 +274,23 @@ def name(self): node_id = self.cob_id & 0x7F return "%sPDO%d_node%d" % (direction, map_id, node_id) + @property + def is_periodic(self): + """Indicate whether PDO updates will be transferred regularly. + + If some external mechanism is used to transmit the PDO regularly, its cycle time + should be written to the :attr:`period` member for this property to work. + """ + if self.period is not None: + # Configured from start() or externally + return True + elif self.trans_type is not None and self.trans_type <= 0xF0: + # TPDOs will be transmitted on SYNC, RPDOs need a SYNC to apply, so + # assume that the SYNC service is active. + return True + # Unknown transmission type, assume non-periodic + return False + def on_message(self, can_id, data, timestamp): is_transmitting = self._task is not None if can_id == self.cob_id and not is_transmitting: @@ -459,7 +477,10 @@ def transmit(self): def start(self, period=None): """Start periodic transmission of message in a background thread. - :param float period: Transmission period in seconds + :param float period: + Transmission period in seconds. Can be omitted if :attr:`period` has been set + on the object before. + :raises ValueError: When neither the argument nor the :attr:`period` is given. """ # Stop an already running transmission if we have one, otherwise we # overwrite the reference and can lose our handle to shut it down diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 34763a21..044d45c4 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -202,13 +202,15 @@ class BaseNode402(RemoteNode): TIMEOUT_SWITCH_OP_MODE = 0.5 # seconds TIMEOUT_SWITCH_STATE_FINAL = 0.8 # seconds TIMEOUT_SWITCH_STATE_SINGLE = 0.4 # seconds + TIMEOUT_CHECK_TPDO = 0.2 # seconds INTERVAL_CHECK_STATE = 0.01 # seconds TIMEOUT_HOMING_DEFAULT = 30 # seconds def __init__(self, node_id, object_dictionary): super(BaseNode402, self).__init__(node_id, object_dictionary) - self.tpdo_values = dict() # { index: TPDO_value } - self.rpdo_pointers = dict() # { index: RPDO_pointer } + self.tpdo_values = {} # { index: value from last received TPDO } + self.tpdo_pointers = {} # { index: pdo.Map instance } + self.rpdo_pointers = {} # { index: pdo.Map instance } def setup_402_state_machine(self): """Configure the state machine by searching for a TPDO that has the StatusWord mapped. @@ -220,6 +222,7 @@ def setup_402_state_machine(self): self.setup_pdos() self._check_controlword_configured() self._check_statusword_configured() + self._check_op_mode_configured() self.nmt.state = 'OPERATIONAL' self.state = 'SWITCH ON DISABLED' # Why change state? @@ -236,6 +239,7 @@ def _init_tpdo_values(self): logger.debug('Configured TPDO: {0}'.format(obj.index)) if obj.index not in self.tpdo_values: self.tpdo_values[obj.index] = 0 + self.tpdo_pointers[obj.index] = obj def _init_rpdo_pointers(self): # If RPDOs have overlapping indecies, rpdo_pointers will point to @@ -259,6 +263,16 @@ def _check_statusword_configured(self): "Statusword not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( self.id)) + def _check_op_mode_configured(self): + if 0x6060 not in self.rpdo_pointers: # Operation Mode + logger.warning( + "Operation Mode not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( + self.id)) + if 0x6061 not in self.tpdo_values: # Operation Mode Display + logger.warning( + "Operation Mode Display not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( + self.id)) + def reset_from_fault(self): """Reset node from fault and set it to Operation Enable state.""" if self.state == 'FAULT': @@ -335,7 +349,7 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT): def op_mode(self): """The node's Operation Mode stored in the object 0x6061. - Uses SDO to access the current value. The modes are passed as one of the + Uses SDO or PDO to access the current value. The modes are passed as one of the following strings: - 'NO MODE' @@ -354,7 +368,18 @@ def op_mode(self): :raises TypeError: When setting a mode not advertised as supported by the node. :raises RuntimeError: If the switch is not confirmed within the configured timeout. """ - return OperationMode.CODE2NAME[self.sdo[0x6061].raw] + try: + pdo = self.tpdo_pointers[0x6061].pdo_parent + if pdo.is_periodic: + timestamp = pdo.wait_for_reception(timeout=self.TIMEOUT_CHECK_TPDO) + if timestamp is None: + raise RuntimeError("Timeout getting node {0}'s mode of operation.".format( + self.id)) + code = self.tpdo_values[0x6061] + except KeyError: + logger.warning('The object 0x6061 is not a configured TPDO, fallback to SDO') + code = self.sdo[0x6061].raw + return OperationMode.CODE2NAME[code] @op_mode.setter def op_mode(self, mode): @@ -435,7 +460,9 @@ def controlword(self): def controlword(self, value): if 0x6040 in self.rpdo_pointers: self.rpdo_pointers[0x6040].raw = value - self.rpdo_pointers[0x6040].pdo_parent.transmit() + pdo = self.rpdo_pointers[0x6040].pdo_parent + if not pdo.is_periodic: + pdo.transmit() else: self.sdo[0x6040].raw = value From e5355f4911e58d6e673f256faeae805c2c2f4466 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 19:33:15 +0200 Subject: [PATCH 064/199] p402: Make HOMING_TIMEOUT_DEFAULT configurable per instance. (#258) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit When the HOMING_TIMEOUT_DEFAULT class attribute is overridden as an object attribute, the argument default value definition in homing() still uses the old value from the class attribute. Check the argument and apply the default value at runtime to pick up the updated default timeout if the argument is omitted. Co-authored-by: André Filipe Silva --- canopen/profiles/p402.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 044d45c4..bf8b0791 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -316,6 +316,8 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT): :return: If the homing was complete with success. :rtype: bool """ + if timeout is None: + timeout = self.TIMEOUT_HOMING_DEFAULT previus_op_mode = self.op_mode self.op_mode = 'HOMING' # The homing process will initialize at operation enabled @@ -335,7 +337,7 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT): 'ERROR VELOCITY IS ZERO'): raise RuntimeError('Unable to home. Reason: {0}'.format(homingstatus)) time.sleep(self.INTERVAL_CHECK_STATE) - if time.monotonic() > t: + if timeout and time.monotonic() > t: raise RuntimeError('Unable to home, timeout reached') logger.info('Homing mode carried out successfully.') return True From 7c5e4ceaecfeea0193777e9c4655c2e77b5c2f84 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 19:36:10 +0200 Subject: [PATCH 065/199] DS402: Simplify setup procedure. (#259) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * p402: Do not switch any states during setup_402_state_machine(). Reading the PDO configuration is possible in OPERATIONAL or PRE-OPERATIONAL states, so switching that is unnecessary. The application should be responsible to handle such transitions, and the library function should be usable without disturbing the application logic. Changing the DS402 state machine to SWITCH ON DISABLED is also not necessary. The drive may be in whatever state from a previous usage, and then the change to SWITCH ON DISABLED may even trigger an exception because there is no way to reach it directly. So this transition should also be the application's responsibility. * p402: Check NMT state before reading PDO configuration. SDOs are allowed in all but the STOPPED state. That would lead to a timeout and an SdoCommunicationError exception. Checking the NMT state here raises an exception without a timeout involved. * p402: Make reading the PDO configuration optional during setup. If the application already configured the PDOs and called .save() on the pdo.Maps object, there is no sense in reading everything back again in the setup_pdos() method. Provide an optional argument to disable that behavior. A call to subscribe to the PDOs from the network is added because that side-effect of pdo.read() is necessary for the TPDO callback to work. * p402: Allow skipping PDO upload from setup_402_state_machine(). Add an optional argument which is simply passed down to setup_pdos() to choose whether reading the PDO configuration is necessary. * Fix DS402 documentation to match the implementation. Besides the changes regarding setup_402_state_machine(), there were numerous errors where the documentation talks about nonexistent or differently named attributes. Also fix the description regaring what the method actually does. It won't configure the TPDO1 to contain the Statusword, but only check the PDO configuration for Statusword and Controlword presence. Co-authored-by: André Filipe Silva --- canopen/profiles/p402.py | 25 +++++++++++++++++-------- doc/profiles.rst | 30 ++++++++++++++++-------------- 2 files changed, 33 insertions(+), 22 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index bf8b0791..f12e6176 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -212,22 +212,31 @@ def __init__(self, node_id, object_dictionary): self.tpdo_pointers = {} # { index: pdo.Map instance } self.rpdo_pointers = {} # { index: pdo.Map instance } - def setup_402_state_machine(self): + def setup_402_state_machine(self, read_pdos=True): """Configure the state machine by searching for a TPDO that has the StatusWord mapped. + :param bool read_pdos: Upload current PDO configuration from node. :raises ValueError: If the the node can't find a Statusword configured in any of the TPDOs. """ - self.nmt.state = 'PRE-OPERATIONAL' # Why is this necessary? - self.setup_pdos() + self.setup_pdos(read_pdos) self._check_controlword_configured() self._check_statusword_configured() - self._check_op_mode_configured() - self.nmt.state = 'OPERATIONAL' - self.state = 'SWITCH ON DISABLED' # Why change state? - def setup_pdos(self): - self.pdo.read() # TPDO and RPDO configurations + def setup_pdos(self, upload=True): + """Find the relevant PDO configuration to handle the state machine. + + :param bool upload: + Retrieve up-to-date configuration via SDO. If False, the node's mappings must + already be configured in the object, matching the drive's settings. + :raises AssertionError: + When the node's NMT state disallows SDOs for reading the PDO configuration. + """ + if upload: + assert self.nmt.state in 'PRE-OPERATIONAL', 'OPERATIONAL' + self.pdo.read() # TPDO and RPDO configurations + else: + self.pdo.subscribe() # Get notified on reception, usually a side-effect of read() self._init_tpdo_values() self._init_rpdo_pointers() diff --git a/doc/profiles.rst b/doc/profiles.rst index 1047c7f9..1ef5ab58 100644 --- a/doc/profiles.rst +++ b/doc/profiles.rst @@ -34,10 +34,13 @@ The current status can be read from the device by reading the register 0x6041, which is called the "Statusword". Changes in state can only be done in the 'OPERATIONAL' state of the NmtMaster -TPDO1 needs to be set up correctly. For this, run the the -`BaseNode402.setup_402_state_machine()` method. Note that this setup -routine will change only TPDO1 and automatically go to the 'OPERATIONAL' state -of the NmtMaster:: +PDOs with the Controlword and Statusword mapped need to be set up correctly, +which is the default configuration of most DS402-compatible drives. To make +them accessible to the state machine implementation, run the the +`BaseNode402.setup_402_state_machine()` method. Note that this setup routine +will read the current PDO configuration by default, causing some SDO traffic. +That works only in the 'OPERATIONAL' or 'PRE-OPERATIONAL' states of the +:class:`NmtMaster`:: # run the setup routine for TPDO1 and it's callback some_node.setup_402_state_machine() @@ -50,21 +53,20 @@ Write Controlword and read Statusword:: # Read the state of the Statusword some_node.sdo[0x6041].raw -During operation the state can change to states which cannot be commanded -by the Controlword, for example a 'FAULT' state. -Therefore the :class:`PowerStateMachine` class (in similarity to the :class:`NmtMaster` -class) automatically monitors state changes of the Statusword which is sent -by TPDO1. The available callback on thet TPDO1 will then extract the -information and mirror the state change in the :attr:`BaseNode402.powerstate_402` -attribute. +During operation the state can change to states which cannot be commanded by the +Controlword, for example a 'FAULT' state. Therefore the :class:`BaseNode402` +class (in similarity to :class:`NmtMaster`) automatically monitors state changes +of the Statusword which is sent by TPDO. The available callback on that TPDO +will then extract the information and mirror the state change in the +:attr:`BaseNode402.state` attribute. Similar to the :class:`NmtMaster` class, the states of the :class:`BaseNode402` -class :attr:`._state` attribute can be read and set (command) by a string:: +class :attr:`.state` attribute can be read and set (command) by a string:: # command a state (an SDO message will be called) - some_node.powerstate_402.state = 'SWITCHED ON' + some_node.state = 'SWITCHED ON' # read the current state - some_node.powerstate_402.state = 'SWITCHED ON' + some_node.state = 'SWITCHED ON' Available states: From b2ef201b4a53820de38ba79cf093379d6f997169 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 19:37:24 +0200 Subject: [PATCH 066/199] Small change in NMT log message and FIXME comment for DS402. (#260) * nmt: Include node ID in state change message. These log messages can get rather confusing with more nodes involved. * p402: Add FIXME about the messed up logic in reset_from_fault(). That method does not work as intended. Until a fix is ready, at least explain what goes wrong in a code comment. --- canopen/nmt.py | 4 ++-- canopen/profiles/p402.py | 2 ++ 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/canopen/nmt.py b/canopen/nmt.py index 60a7f758..f7a5d305 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -68,8 +68,8 @@ def send_command(self, code): """ if code in COMMAND_TO_STATE: new_state = COMMAND_TO_STATE[code] - logger.info("Changing NMT state from %s to %s", - NMT_STATES[self._state], NMT_STATES[new_state]) + logger.info("Changing NMT state on node %d from %s to %s", + self.id, NMT_STATES[self._state], NMT_STATES[new_state]) self._state = new_state @property diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index f12e6176..faa5f25e 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -287,6 +287,8 @@ def reset_from_fault(self): if self.state == 'FAULT': # Resets the Fault Reset bit (rising edge 0 -> 1) self.controlword = State402.CW_DISABLE_VOLTAGE + # FIXME! The rising edge happens with the transitions toward OPERATION + # ENABLED below, but until then the loop will always reach the timeout! timeout = time.monotonic() + self.TIMEOUT_RESET_FAULT while self.is_faulted(): if time.monotonic() > timeout: From 7462d0bf06f77b7b50bc81d90a2babfd5e21065b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 19:41:56 +0200 Subject: [PATCH 067/199] DS402: Restore operation mode after homing only on explicit request. (#262) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * ds402: Remove set_new_home functionality from BaseNode402.homing(). The homing() method will try to manipulate the Home Offset (0x607C) parameter by default. That's not the way the parameter is intended to work. After a successful homing procedure, the drive should set the Actual Position (0x6063) to the Home Offset (0x607C) by itself. By default that is zero, so the selected reference switch flank will mark the new zero position. The library's default behavior here is backwards, and can only work with absolute position encoders. The whole point of homing is to find a physical reference and align the logical coordinate system to it. Trying to determine the desired offset from the value which an unreferenced encoder had at the physical reference point actually destroys that logical alignment. The functionality of set_new_home=True is trivial to do from the application, so remove it completely from homing(). * ds402: Restore operation mode after homing only on explicit request. Add a new parameter restore_op_mode which defaults to False, and skip changing back to the previous mode unless it is explicitly enabled by passing True. Note that most applications will decide on the needed mode after homing and therefore do not need this behavior, hence the new default. Co-authored-by: André Filipe Silva --- canopen/profiles/p402.py | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index faa5f25e..2c17149a 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -320,16 +320,18 @@ def is_homed(self, restore_op_mode=False): self.op_mode = previous_op_mode return homingstatus in ('TARGET REACHED', 'ATTAINED') - def homing(self, timeout=TIMEOUT_HOMING_DEFAULT): + def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, restore_op_mode=False): """Execute the configured Homing method on the node. :param int timeout: Timeout value (default: 30). + :param bool restore_op_mode: + Switch back to the previous operation mode after homing (default: no). :return: If the homing was complete with success. :rtype: bool """ - if timeout is None: - timeout = self.TIMEOUT_HOMING_DEFAULT - previus_op_mode = self.op_mode + if restore_op_mode: + previous_op_mode = self.op_mode + self.state = 'SWITCHED ON' self.op_mode = 'HOMING' # The homing process will initialize at operation enabled self.state = 'OPERATION ENABLED' @@ -355,7 +357,8 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT): except RuntimeError as e: logger.info(str(e)) finally: - self.op_mode = previus_op_mode + if restore_op_mode: + self.op_mode = previous_op_mode return False @property From 0d2b4b622e0ff1a17c2cc9b8d1ea2de6c93425c1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 16 Aug 2021 20:00:58 +0200 Subject: [PATCH 068/199] DS402: Replace delay loops with waiting for TPDO reception. (#263) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * ds402: Increase delay to check status on homing start. The Statusword is examined immediately after setting the Controlword command to start homing. That is very likely to fail because of the round-trip time until the Statusword is actually updated from a TPDO. To work around that, the delay between each check of the Statusword should be moved before the actual comparison, and its default value increased. Introduce a new constant TIMEOUT_CHECK_HOMING to configure that with a default value of 100 ms. This replaces the previously used INTERVAL_CHECK_STATE which is only 10 ms by default. An even better solution would be to wait for the Statusword to be updated by a received PDO, but that would be much more complex. * Apply interval to is_homed() method as well. Same problem as in the homing() method, PDO updates of the Statusword need at least one SYNC / PDO cycle duration. * Factor out common _homing_status() method. Move the common code from is_homed() and homing() to a method for internal use. Add a comment why the delay is necessary and how it should possibly be replaced by an RPDO reception check. Should the latter be implemented, there will be only one place to change it. * p402: Add blocking method check_statusword(). In contrast to the property getter, this method will not simply return the cached last value, but actually wait for an updated TPDO reception. If no TPDO is configured, or it is not expected periodically, the usual statusword getter takes over and returns either the last received value or queries via SDO as a fallback. The timeout for receiving a TPDO can be configured individually per call, defaulting to 0.2 seconds (TIMEOUT_CHECK_TPDO). * p402: Wait for TPDO instead of timed statusword checking. Several methods loop around waiting for some expected statusword value, usually calling time.sleep() with the INTERVAL_CHECK_STATE or INTERVAL_CHECK_HOMING constants. Replace that with a call to check_statusword(), which will only block until the TPDO is received. This allows for possibly shorter delays, because the delay can be cut short when the TPDO arrives in between. But rate limiting the checking loops is still achieved through the blocking behavior of check_statusword(). If no TPDO is configured, the statusword will fall back to checking via SDO, which will also result in periodic checks, but only rate limited by the SDO round-trip time. Anyway this is not a recommended mode of operation, as the warning in _check_statusword_configured() points out. * p402: Fix wrong reports of INTERRUPTED homing procedure. While the statusword checks work properly now, there is no delay anymore to make sure the controlword RPDO which starts the homing procedure is already received before we start checking the homing status. So the first reading might easily return INTERRUPTED, meaning that the controlword change has just not been applied yet. Add one extra call for check_statusword() to wait for one extra cycle in case of periodic transmissions. In effect, the success checking logic starts looking at the second received statusword after setting the controlword. Co-authored-by: André Filipe Silva --- canopen/profiles/p402.py | 58 ++++++++++++++++++++++++++++------------ 1 file changed, 41 insertions(+), 17 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 2c17149a..87d8948c 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -293,13 +293,24 @@ def reset_from_fault(self): while self.is_faulted(): if time.monotonic() > timeout: break - time.sleep(self.INTERVAL_CHECK_STATE) + self.check_statusword() self.state = 'OPERATION ENABLED' def is_faulted(self): bitmask, bits = State402.SW_MASK['FAULT'] return self.statusword & bitmask == bits + def _homing_status(self): + """Interpret the current Statusword bits as homing state string.""" + # Wait to make sure a TPDO was received + self.check_statusword() + status = None + for key, value in Homing.STATES.items(): + bitmask, bits = value + if self.statusword & bitmask == bits: + status = key + return status + def is_homed(self, restore_op_mode=False): """Switch to homing mode and determine its status. @@ -310,12 +321,8 @@ def is_homed(self, restore_op_mode=False): previous_op_mode = self.op_mode if previous_op_mode != 'HOMING': logger.info('Switch to HOMING from %s', previous_op_mode) - self.op_mode = 'HOMING' - homingstatus = None - for key, value in Homing.STATES.items(): - bitmask, bits = value - if self.statusword & bitmask == bits: - homingstatus = key + self.op_mode = 'HOMING' # blocks until confirmed + homingstatus = self._homing_status() if restore_op_mode: self.op_mode = previous_op_mode return homingstatus in ('TARGET REACHED', 'ATTAINED') @@ -335,17 +342,14 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, restore_op_mode=False): self.op_mode = 'HOMING' # The homing process will initialize at operation enabled self.state = 'OPERATION ENABLED' - homingstatus = 'IN PROGRESS' - self.controlword = State402.CW_OPERATION_ENABLED | Homing.CW_START + homingstatus = 'UNKNOWN' + self.controlword = State402.CW_OPERATION_ENABLED | Homing.CW_START # does not block + # Wait for one extra cycle, to make sure the controlword was received + self.check_statusword() t = time.monotonic() + timeout try: while homingstatus not in ('TARGET REACHED', 'ATTAINED'): - for key, value in Homing.STATES.items(): - # check if the Statusword after applying the bitmask - # corresponds with the needed bits to determine the current status - bitmask, bits = value - if self.statusword & bitmask == bits: - homingstatus = key + homingstatus = self._homing_status() if homingstatus in ('INTERRUPTED', 'ERROR VELOCITY IS NOT ZERO', 'ERROR VELOCITY IS ZERO'): raise RuntimeError('Unable to home. Reason: {0}'.format(homingstatus)) @@ -463,6 +467,26 @@ def statusword(self): logger.warning('The object 0x6041 is not a configured TPDO, fallback to SDO') return self.sdo[0x6041].raw + def check_statusword(self, timeout=None): + """Report an up-to-date reading of the statusword (0x6041) from the device. + + If the TPDO with the statusword is configured as periodic, this method blocks + until one was received. Otherwise, it uses the SDO fallback of the ``statusword`` + property. + + :param timeout: Maximum time in seconds to wait for TPDO reception. + :raises RuntimeError: Occurs when the given timeout expires without a TPDO. + :return: Updated value of the ``statusword`` property. + :rtype: int + """ + if 0x6041 in self.tpdo_pointers: + pdo = self.tpdo_pointers[0x6041].pdo_parent + if pdo.is_periodic: + timestamp = pdo.wait_for_reception(timeout or self.TIMEOUT_CHECK_TPDO) + if timestamp is None: + raise RuntimeError('Timeout waiting for updated statusword') + return self.statusword + @property def controlword(self): """Send a state change command using PDO or SDO. @@ -518,7 +542,7 @@ def state(self, target_state): continue if time.monotonic() > timeout: raise RuntimeError('Timeout when trying to change state') - time.sleep(self.INTERVAL_CHECK_STATE) + self.check_statusword() def _next_state(self, target_state): if target_state == 'OPERATION ENABLED': @@ -536,5 +560,5 @@ def _change_state(self, target_state): while self.state != target_state: if time.monotonic() > timeout: return False - time.sleep(self.INTERVAL_CHECK_STATE) + self.check_statusword() return True From 33f7af33230bc49f5756c561f9b6800accc95895 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 17 Aug 2021 09:50:31 +0200 Subject: [PATCH 069/199] DS402: Fix merge errors. (#265) * ds402: Skip explicit change to SWITCHED ON state. The BaseNode402.homing() method tries to enter state SWITCHED ON upon entry. That's unnecessary, the application should handle these transitions. But more importantly, it actually fails in many cases, namely if the previous state is SWITCH ON DISABLED, the default power-up state of most devices. There is an automatic way to reach OPERATION ENABLED over multiple intermediate steps, but the library does not know how to reach SWITCHED ON from any other state than OPERATION ENABLED or READY TO SWITCH ON. In addition, setting the op_mode property will already change to SWITCHED ON only if coming from OPERATION ENABLED (which is usually a good idea to avoid unexpected movement). Note that switching the operation mode to HOMING is actually safe in any power state. * p402: Make HOMING_TIMEOUT_DEFAULT configurable per instance. When the HOMING_TIMEOUT_DEFAULT class attribute is overridden as an object attribute, the argument default value definition in homing() still uses the old value from the class attribute. Check the argument and apply the default value at runtime to pick up the updated default timeout if the argument is omitted. * ds402: Increase delay to check status on homing start. The Statusword is examined immediately after setting the Controlword command to start homing. That is very likely to fail because of the round-trip time until the Statusword is actually updated from a TPDO. To work around that, the delay between each check of the Statusword should be moved before the actual comparison, and its default value increased. Introduce a new constant TIMEOUT_CHECK_HOMING to configure that with a default value of 100 ms. This replaces the previously used INTERVAL_CHECK_STATE which is only 10 ms by default. An even better solution would be to wait for the Statusword to be updated by a received PDO, but that would be much more complex. * p402: Wait for TPDO instead of timed statusword checking. Several methods loop around waiting for some expected statusword value, usually calling time.sleep() with the INTERVAL_CHECK_STATE or INTERVAL_CHECK_HOMING constants. Replace that with a call to check_statusword(), which will only block until the TPDO is received. This allows for possibly shorter delays, because the delay can be cut short when the TPDO arrives in between. But rate limiting the checking loops is still achieved through the blocking behavior of check_statusword(). If no TPDO is configured, the statusword will fall back to checking via SDO, which will also result in periodic checks, but only rate limited by the SDO round-trip time. Anyway this is not a recommended mode of operation, as the warning in _check_statusword_configured() points out. * p402: Use RPDO to set the operation mode if possible. Fall back to the previous behavior using SDO if the relevant object 0x6060 is not mapped to an RPDO. * p402: Check PDO configuration for the Operation Mode objects. Switching operation modes for several drives simultaneously must be done via PDO. There is still a fallback mechanism via SDO, but a warning should be issued when that is about to be used. --- canopen/profiles/p402.py | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 87d8948c..f4fc0874 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -203,7 +203,6 @@ class BaseNode402(RemoteNode): TIMEOUT_SWITCH_STATE_FINAL = 0.8 # seconds TIMEOUT_SWITCH_STATE_SINGLE = 0.4 # seconds TIMEOUT_CHECK_TPDO = 0.2 # seconds - INTERVAL_CHECK_STATE = 0.01 # seconds TIMEOUT_HOMING_DEFAULT = 30 # seconds def __init__(self, node_id, object_dictionary): @@ -222,6 +221,7 @@ def setup_402_state_machine(self, read_pdos=True): self.setup_pdos(read_pdos) self._check_controlword_configured() self._check_statusword_configured() + self._check_op_mode_configured() def setup_pdos(self, upload=True): """Find the relevant PDO configuration to handle the state machine. @@ -327,18 +327,19 @@ def is_homed(self, restore_op_mode=False): self.op_mode = previous_op_mode return homingstatus in ('TARGET REACHED', 'ATTAINED') - def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, restore_op_mode=False): + def homing(self, timeout=None, restore_op_mode=False): """Execute the configured Homing method on the node. - :param int timeout: Timeout value (default: 30). + :param int timeout: Timeout value (default: 30, zero to disable). :param bool restore_op_mode: Switch back to the previous operation mode after homing (default: no). :return: If the homing was complete with success. :rtype: bool """ + if timeout is None: + timeout = self.TIMEOUT_HOMING_DEFAULT if restore_op_mode: previous_op_mode = self.op_mode - self.state = 'SWITCHED ON' self.op_mode = 'HOMING' # The homing process will initialize at operation enabled self.state = 'OPERATION ENABLED' @@ -353,7 +354,6 @@ def homing(self, timeout=TIMEOUT_HOMING_DEFAULT, restore_op_mode=False): if homingstatus in ('INTERRUPTED', 'ERROR VELOCITY IS NOT ZERO', 'ERROR VELOCITY IS ZERO'): raise RuntimeError('Unable to home. Reason: {0}'.format(homingstatus)) - time.sleep(self.INTERVAL_CHECK_STATE) if timeout and time.monotonic() > t: raise RuntimeError('Unable to home, timeout reached') logger.info('Homing mode carried out successfully.') @@ -407,8 +407,14 @@ def op_mode(self, mode): if not self.is_op_mode_supported(mode): raise TypeError( 'Operation mode {m} not suppported on node {n}.'.format(n=self.id, m=mode)) - # operation mode - self.sdo[0x6060].raw = OperationMode.NAME2CODE[mode] + # Update operation mode in RPDO if possible, fall back to SDO + if 0x6060 in self.rpdo_pointers: + self.rpdo_pointers[0x6060].raw = OperationMode.NAME2CODE[mode] + pdo = self.rpdo_pointers[0x6060].pdo_parent + if not pdo.is_periodic: + pdo.transmit() + else: + self.sdo[0x6060].raw = OperationMode.NAME2CODE[mode] timeout = time.monotonic() + self.TIMEOUT_SWITCH_OP_MODE while self.op_mode != mode: if time.monotonic() > timeout: From 5202d1e31128c35218b5bf5b2167a390fa67dd91 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 13 Sep 2021 12:32:20 +0200 Subject: [PATCH 070/199] DS402: Fix logic errors in the power state machine and generalize it. (#264) * p402: Forbid transitions to states which only the drive can enter. The NOT READY TO SWITCH ON and FAULT REACTION ACTIVE states can only be reached if the drive encounters an error or is still busy with its self-testing. Raise an exception in case these states are requested via the property. In extension, only the drive can trigger a transition to the FAULT state, so that is never valid as an end goal requested by the user. * p402: Add a test script to check DS402 State Machine transitions. Go through all possible target states and display where the next_state_for_enabling() function would lead to based on the original state. Mark transitions which can happen directly because they are in the TRANSITIONTABLE. * p402: Extend test script to check the actual implementation. Mock up a BaseNode402 object and compare the _next_state() behavior to the simple lookups from the underlying transition tables. * p402: Simplify check for intermediate states. Don't special case the OPERATION ENABLED state, as the mechanism formulated for it is actually usable for almost all states. Instead, check whether there is a direct transition and return that immediately before consulting next_state_for_enabling(). * p402: Rename NEXTSTATE2ENABLE to generalize it. The goal is to provide automatic transition paths for any state, not only OPERATION ENABLED. Reflect that in the naming, without changing the actual logic yet. * p402: Adjust automatic state transition paths. As there is a direct transition from QUICK STOP ACTIVE to OPERATION ENABLED, remove that from the transition paths. Instead go through the SWITCH ON DISABLED state, closing the cycle to make it work for anything between SWITCH ON DISABLED and OPERATION ENABLED. Also remove the self-reference OPERATION ENABLED to itself, which is useless. The whole state changing code will only be called if the target state and the current state do not match. * p402: Remove two illegal transitions from the state table. Transitions 7 and 10 are duplicated and certainly wrong in the quickstop context. The only transition toward QUICK STOP ACTIVE is from OPERATION ENABLED. * Move test_p402_states script to a subdirectory and add a docstring. --- canopen/profiles/p402.py | 35 ++++++++++++-------- canopen/profiles/tools/test_p402_states.py | 37 ++++++++++++++++++++++ 2 files changed, 59 insertions(+), 13 deletions(-) create mode 100644 canopen/profiles/tools/test_p402_states.py diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index f4fc0874..a3a97160 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -46,14 +46,14 @@ class State402(object): 'QUICK STOP ACTIVE': (0x6F, 0x07), } - # Transition path to get to the 'OPERATION ENABLED' state - NEXTSTATE2ENABLE = { + # Transition path to reach and state without a direct transition + NEXTSTATE2ANY = { ('START'): 'NOT READY TO SWITCH ON', - ('FAULT', 'NOT READY TO SWITCH ON'): 'SWITCH ON DISABLED', + ('FAULT', 'NOT READY TO SWITCH ON', 'QUICK STOP ACTIVE'): 'SWITCH ON DISABLED', ('SWITCH ON DISABLED'): 'READY TO SWITCH ON', ('READY TO SWITCH ON'): 'SWITCHED ON', - ('SWITCHED ON', 'QUICK STOP ACTIVE', 'OPERATION ENABLED'): 'OPERATION ENABLED', - ('FAULT REACTION ACTIVE'): 'FAULT' + ('SWITCHED ON'): 'OPERATION ENABLED', + ('FAULT REACTION ACTIVE'): 'FAULT', } # Tansition table from the DS402 State Machine @@ -78,22 +78,25 @@ class State402(object): ('SWITCHED ON', 'OPERATION ENABLED'): CW_OPERATION_ENABLED, # transition 4 ('QUICK STOP ACTIVE', 'OPERATION ENABLED'): CW_OPERATION_ENABLED, # transition 16 # quickstop --------------------------------------------------------------------------- - ('READY TO SWITCH ON', 'QUICK STOP ACTIVE'): CW_QUICK_STOP, # transition 7 - ('SWITCHED ON', 'QUICK STOP ACTIVE'): CW_QUICK_STOP, # transition 10 ('OPERATION ENABLED', 'QUICK STOP ACTIVE'): CW_QUICK_STOP, # transition 11 # fault ------------------------------------------------------------------------------- ('FAULT', 'SWITCH ON DISABLED'): CW_SWITCH_ON_DISABLED, # transition 15 } @staticmethod - def next_state_for_enabling(_from): - """Return the next state needed for reach the state Operation Enabled. + def next_state_indirect(_from): + """Return the next state needed to reach any state indirectly. + + The chosen path always points toward the OPERATION ENABLED state, except when + coming from QUICK STOP ACTIVE. In that case, it will cycle through SWITCH ON + DISABLED first, as there would have been a direct transition if the opposite was + desired. :param str target: Target state. :return: Next target to change. :rtype: str """ - for cond, next_state in State402.NEXTSTATE2ENABLE.items(): + for cond, next_state in State402.NEXTSTATE2ANY.items(): if _from in cond: return next_state @@ -551,10 +554,16 @@ def state(self, target_state): self.check_statusword() def _next_state(self, target_state): - if target_state == 'OPERATION ENABLED': - return State402.next_state_for_enabling(self.state) - else: + if target_state in ('NOT READY TO SWITCH ON', + 'FAULT REACTION ACTIVE', + 'FAULT'): + raise ValueError( + 'Target state {} cannot be entered programmatically'.format(target_state)) + from_state = self.state + if (from_state, target_state) in State402.TRANSITIONTABLE: return target_state + else: + return State402.next_state_indirect(from_state) def _change_state(self, target_state): try: diff --git a/canopen/profiles/tools/test_p402_states.py b/canopen/profiles/tools/test_p402_states.py new file mode 100644 index 00000000..39f085f5 --- /dev/null +++ b/canopen/profiles/tools/test_p402_states.py @@ -0,0 +1,37 @@ +"""Verification script to diagnose automatic state transitions. + +This is meant to be run for verifying changes to the DS402 power state +machine code. For each target state, it just lists the next +intermediate state which would be set automatically, depending on the +assumed current state. +""" + +from canopen.objectdictionary import ObjectDictionary +from canopen.profiles.p402 import State402, BaseNode402 + + +if __name__ == '__main__': + n = BaseNode402(1, ObjectDictionary()) + + for target_state in State402.SW_MASK: + print('\n--- Target =', target_state, '---') + for from_state in State402.SW_MASK: + if target_state == from_state: + continue + if (from_state, target_state) in State402.TRANSITIONTABLE: + print('direct:\t{} -> {}'.format(from_state, target_state)) + else: + next_state = State402.next_state_indirect(from_state) + if not next_state: + print('FAIL:\t{} -> {}'.format(from_state, next_state)) + else: + print('\t{} -> {} ...'.format(from_state, next_state)) + + try: + while from_state != target_state: + n.tpdo_values[0x6041] = State402.SW_MASK[from_state][1] + next_state = n._next_state(target_state) + print('\t\t-> {}'.format(next_state)) + from_state = next_state + except ValueError: + print('\t\t-> disallowed!') From ff8b5ca9593862bde260f97299243b626238e7fa Mon Sep 17 00:00:00 2001 From: Kristian Sloth Lauszus Date: Mon, 13 Sep 2021 12:36:39 +0200 Subject: [PATCH 071/199] Do not raise an exception in "_check_statusword_configured" just log it as a warning (#268) --- canopen/profiles/p402.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index a3a97160..b8b9254a 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -271,7 +271,7 @@ def _check_controlword_configured(self): def _check_statusword_configured(self): if 0x6041 not in self.tpdo_values: # Statusword - raise ValueError( + logger.warning( "Statusword not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( self.id)) From cacc4193a528c9057b29895ae90293f4f3e7074e Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Sat, 2 Oct 2021 22:23:13 +0200 Subject: [PATCH 072/199] Add type annotations --- canopen/emcy.py | 26 +++--- canopen/network.py | 99 ++++++++++++--------- canopen/nmt.py | 39 +++++---- canopen/node/base.py | 10 ++- canopen/node/local.py | 22 +++-- canopen/node/remote.py | 15 +++- canopen/objectdictionary/__init__.py | 126 ++++++++++++++------------- canopen/pdo/base.py | 93 ++++++++++---------- canopen/sdo/base.py | 62 ++++++++----- canopen/sdo/client.py | 23 +++-- canopen/sdo/exceptions.py | 2 +- canopen/sdo/server.py | 23 +++-- canopen/sync.py | 13 +-- canopen/timestamp.py | 3 +- canopen/variable.py | 37 ++++---- doc/conf.py | 1 + 16 files changed, 342 insertions(+), 252 deletions(-) diff --git a/canopen/emcy.py b/canopen/emcy.py index afb52dde..8964262e 100644 --- a/canopen/emcy.py +++ b/canopen/emcy.py @@ -2,6 +2,7 @@ import logging import threading import time +from typing import Callable, List, Optional # Error code, error register, vendor specific data EMCY_STRUCT = struct.Struct(" "EmcyError": """Wait for a new EMCY to arrive. - :param int emcy_code: EMCY code to wait for - :param float timeout: Max time in seconds to wait + :param emcy_code: EMCY code to wait for + :param timeout: Max time in seconds to wait :return: The EMCY exception object or None if timeout - :rtype: canopen.emcy.EmcyError """ end_time = time.time() + timeout while True: @@ -79,15 +81,15 @@ def wait(self, emcy_code=None, timeout=10): class EmcyProducer(object): - def __init__(self, cob_id): + def __init__(self, cob_id: int): self.network = None self.cob_id = cob_id - def send(self, code, register=0, data=b""): + def send(self, code: int, register: int = 0, data: bytes = b""): payload = EMCY_STRUCT.pack(code, register, data) self.network.send_message(self.cob_id, payload) - def reset(self, register=0, data=b""): + def reset(self, register: int = 0, data: bytes = b""): payload = EMCY_STRUCT.pack(0, register, data) self.network.send_message(self.cob_id, payload) @@ -111,7 +113,7 @@ class EmcyError(Exception): (0xFF00, 0xFF00, "Device Specific") ] - def __init__(self, code, register, data, timestamp): + def __init__(self, code: int, register: int, data: bytes, timestamp: float): #: EMCY code self.code = code #: Error register @@ -121,7 +123,7 @@ def __init__(self, code, register, data, timestamp): #: Timestamp of message self.timestamp = timestamp - def get_desc(self): + def get_desc(self) -> str: for code, mask, description in self.DESCRIPTIONS: if self.code & mask == code: return description diff --git a/canopen/network.py b/canopen/network.py index 70f5c361..04acda18 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -4,7 +4,7 @@ from collections import MutableMapping import logging import threading -import struct +from typing import Callable, Dict, Iterable, List, Optional, Union try: import can @@ -22,9 +22,12 @@ from .nmt import NmtMaster from .lss import LssMaster from .objectdictionary.eds import import_from_node +from .objectdictionary import ObjectDictionary logger = logging.getLogger(__name__) +Callback = Callable[[int, bytearray, float], None] + class Network(MutableMapping): """Representation of one CAN bus containing one or more nodes.""" @@ -43,8 +46,8 @@ def __init__(self, bus=None): #: Includes at least MessageListener. self.listeners = [MessageListener(self)] self.notifier = None - self.nodes = {} - self.subscribers = {} + self.nodes: Dict[int, Union[RemoteNode, LocalNode]] = {} + self.subscribers: Dict[int, List[Callback]] = {} self.send_lock = threading.Lock() self.sync = SyncProducer(self) self.time = TimeProducer(self) @@ -55,10 +58,10 @@ def __init__(self, bus=None): self.lss.network = self self.subscribe(self.lss.LSS_RX_COBID, self.lss.on_message_received) - def subscribe(self, can_id, callback): + def subscribe(self, can_id: int, callback: Callback) -> None: """Listen for messages with a specific CAN ID. - :param int can_id: + :param can_id: The CAN ID to listen for. :param callback: Function to call when message is received. @@ -67,7 +70,7 @@ def subscribe(self, can_id, callback): if callback not in self.subscribers[can_id]: self.subscribers[can_id].append(callback) - def unsubscribe(self, can_id, callback=None): + def unsubscribe(self, can_id, callback=None) -> None: """Stop listening for message. :param int can_id: @@ -81,7 +84,7 @@ def unsubscribe(self, can_id, callback=None): else: self.subscribers[can_id].remove(callback) - def connect(self, *args, **kwargs): + def connect(self, *args, **kwargs) -> "Network": """Connect to CAN bus using python-can. Arguments are passed directly to :class:`can.BusABC`. Typically these @@ -111,7 +114,7 @@ def connect(self, *args, **kwargs): self.notifier = can.Notifier(self.bus, self.listeners, 1) return self - def disconnect(self): + def disconnect(self) -> None: """Disconnect from the CAN bus. Must be overridden in a subclass if a custom interface is used. @@ -132,7 +135,12 @@ def __enter__(self): def __exit__(self, type, value, traceback): self.disconnect() - def add_node(self, node, object_dictionary=None, upload_eds=False): + def add_node( + self, + node: Union[int, RemoteNode, LocalNode], + object_dictionary: Union[str, ObjectDictionary, None] = None, + upload_eds: bool = False, + ) -> RemoteNode: """Add a remote node to the network. :param node: @@ -142,12 +150,11 @@ def add_node(self, node, object_dictionary=None, upload_eds=False): Can be either a string for specifying the path to an Object Dictionary file or a :class:`canopen.ObjectDictionary` object. - :param bool upload_eds: + :param upload_eds: Set ``True`` if EDS file should be uploaded from 0x1021. :return: The Node object that was added. - :rtype: canopen.RemoteNode """ if isinstance(node, int): if upload_eds: @@ -157,7 +164,11 @@ def add_node(self, node, object_dictionary=None, upload_eds=False): self[node.id] = node return node - def create_node(self, node, object_dictionary=None): + def create_node( + self, + node: int, + object_dictionary: Union[str, ObjectDictionary, None] = None, + ) -> LocalNode: """Create a local node in the network. :param node: @@ -169,14 +180,13 @@ def create_node(self, node, object_dictionary=None): :return: The Node object that was added. - :rtype: canopen.LocalNode """ if isinstance(node, int): node = LocalNode(node, object_dictionary) self[node.id] = node return node - def send_message(self, can_id, data, remote=False): + def send_message(self, can_id: int, data: bytes, remote: bool = False) -> None: """Send a raw CAN message to the network. This method may be overridden in a subclass if you need to integrate @@ -203,35 +213,36 @@ def send_message(self, can_id, data, remote=False): self.bus.send(msg) self.check() - def send_periodic(self, can_id, data, period, remote=False): + def send_periodic( + self, can_id: int, data: bytes, period: float, remote: bool = False + ) -> "PeriodicMessageTask": """Start sending a message periodically. - :param int can_id: + :param can_id: CAN-ID of the message :param data: Data to be transmitted (anything that can be converted to bytes) - :param float period: + :param period: Seconds between each message - :param bool remote: + :param remote: indicates if the message frame is a remote request to the slave node :return: An task object with a ``.stop()`` method to stop the transmission - :rtype: canopen.network.PeriodicMessageTask """ return PeriodicMessageTask(can_id, data, period, self.bus, remote) - def notify(self, can_id, data, timestamp): + def notify(self, can_id: int, data: bytearray, timestamp: float) -> None: """Feed incoming message to this library. If a custom interface is used, this function must be called for each message read from the CAN bus. - :param int can_id: + :param can_id: CAN-ID of the message - :param bytearray data: + :param data: Data part of the message (0 - 8 bytes) - :param float timestamp: + :param timestamp: Timestamp of the message, preferably as a Unix timestamp """ if can_id in self.subscribers: @@ -240,7 +251,7 @@ def notify(self, can_id, data, timestamp): callback(can_id, data, timestamp) self.scanner.on_message_received(can_id) - def check(self): + def check(self) -> None: """Check that no fatal error has occurred in the receiving thread. If an exception caused the thread to terminate, that exception will be @@ -252,22 +263,22 @@ def check(self): logger.error("An error has caused receiving of messages to stop") raise exc - def __getitem__(self, node_id): + def __getitem__(self, node_id: int) -> Union[RemoteNode, LocalNode]: return self.nodes[node_id] - def __setitem__(self, node_id, node): + def __setitem__(self, node_id: int, node: Union[RemoteNode, LocalNode]): assert node_id == node.id self.nodes[node_id] = node node.associate_network(self) - def __delitem__(self, node_id): + def __delitem__(self, node_id: int): self.nodes[node_id].remove_network() del self.nodes[node_id] - def __iter__(self): + def __iter__(self) -> Iterable[int]: return iter(self.nodes) - def __len__(self): + def __len__(self) -> int: return len(self.nodes) @@ -277,13 +288,20 @@ class PeriodicMessageTask(object): CyclicSendTask """ - def __init__(self, can_id, data, period, bus, remote=False): - """ - :param int can_id: + def __init__( + self, + can_id: int, + data: bytes, + period: float, + bus, + remote: bool = False, + ): + """ + :param can_id: CAN-ID of the message :param data: Data to be transmitted (anything that can be converted to bytes) - :param float period: + :param period: Seconds between each message :param can.BusABC bus: python-can bus to use for transmission @@ -303,7 +321,7 @@ def stop(self): """Stop transmission""" self._task.stop() - def update(self, data): + def update(self, data: bytes) -> None: """Update data of message :param data: @@ -323,11 +341,11 @@ def update(self, data): class MessageListener(Listener): """Listens for messages on CAN bus and feeds them to a Network instance. - :param canopen.Network network: + :param network: The network to notify on new messages. """ - def __init__(self, network): + def __init__(self, network: Network): self.network = network def on_message_received(self, msg): @@ -359,12 +377,12 @@ class NodeScanner(object): SERVICES = (0x700, 0x580, 0x180, 0x280, 0x380, 0x480, 0x80) - def __init__(self, network=None): + def __init__(self, network: Optional[Network] = None): self.network = network #: A :class:`list` of nodes discovered - self.nodes = [] + self.nodes: List[int] = [] - def on_message_received(self, can_id): + def on_message_received(self, can_id: int): service = can_id & 0x780 node_id = can_id & 0x7F if node_id not in self.nodes and node_id != 0 and service in self.SERVICES: @@ -374,11 +392,10 @@ def reset(self): """Clear list of found nodes.""" self.nodes = [] - def search(self, limit=127): + def search(self, limit: int = 127) -> None: """Search for nodes by sending SDO requests to all node IDs.""" if self.network is None: raise RuntimeError("A Network is required to do active scanning") sdo_req = b"\x40\x00\x10\x00\x00\x00\x00\x00" for node_id in range(1, limit + 1): self.network.send_message(0x600 + node_id, sdo_req) - diff --git a/canopen/nmt.py b/canopen/nmt.py index f7a5d305..09963de0 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -2,6 +2,7 @@ import logging import struct import time +from typing import Callable, Optional from .network import CanError @@ -44,7 +45,7 @@ class NmtBase(object): the current state using the heartbeat protocol. """ - def __init__(self, node_id): + def __init__(self, node_id: int): self.id = node_id self.network = None self._state = 0 @@ -60,10 +61,10 @@ def on_command(self, can_id, data, timestamp): NMT_STATES[new_state], NMT_STATES[self._state]) self._state = new_state - def send_command(self, code): + def send_command(self, code: int): """Send an NMT command code to the node. - :param int code: + :param code: NMT command code. """ if code in COMMAND_TO_STATE: @@ -73,7 +74,7 @@ def send_command(self, code): self._state = new_state @property - def state(self): + def state(self) -> str: """Attribute to get or set node's state as a string. Can be one of: @@ -93,7 +94,7 @@ def state(self): return self._state @state.setter - def state(self, new_state): + def state(self, new_state: str): if new_state in NMT_COMMANDS: code = NMT_COMMANDS[new_state] else: @@ -105,12 +106,12 @@ def state(self, new_state): class NmtMaster(NmtBase): - def __init__(self, node_id): + def __init__(self, node_id: int): super(NmtMaster, self).__init__(node_id) self._state_received = None self._node_guarding_producer = None #: Timestamp of last heartbeat message - self.timestamp = None + self.timestamp: Optional[float] = None self.state_update = threading.Condition() self._callbacks = [] @@ -131,10 +132,10 @@ def on_heartbeat(self, can_id, data, timestamp): self._state_received = new_state self.state_update.notify_all() - def send_command(self, code): + def send_command(self, code: int): """Send an NMT command code to the node. - :param int code: + :param code: NMT command code. """ super(NmtMaster, self).send_command(code) @@ -142,7 +143,7 @@ def send_command(self, code): "Sending NMT command 0x%X to node %d", code, self.id) self.network.send_message(0, [code, self.id]) - def wait_for_heartbeat(self, timeout=10): + def wait_for_heartbeat(self, timeout: float = 10): """Wait until a heartbeat message is received.""" with self.state_update: self._state_received = None @@ -151,7 +152,7 @@ def wait_for_heartbeat(self, timeout=10): raise NmtError("No boot-up or heartbeat received") return self.state - def wait_for_bootup(self, timeout=10): + def wait_for_bootup(self, timeout: float = 10) -> None: """Wait until a boot-up message is received.""" end_time = time.time() + timeout while True: @@ -164,7 +165,7 @@ def wait_for_bootup(self, timeout=10): if self._state_received == 0: break - def add_hearbeat_callback(self, callback): + def add_hearbeat_callback(self, callback: Callable[[int], None]): """Add function to be called on heartbeat reception. :param callback: @@ -172,10 +173,10 @@ def add_hearbeat_callback(self, callback): """ self._callbacks.append(callback) - def start_node_guarding(self, period): + def start_node_guarding(self, period: float): """Starts the node guarding mechanism. - :param float period: + :param period: Period (in seconds) at which the node guarding should be advertised to the slave node. """ if self._node_guarding_producer : self.stop_node_guarding() @@ -193,7 +194,7 @@ class NmtSlave(NmtBase): Handles the NMT state and handles heartbeat NMT service. """ - def __init__(self, node_id, local_node): + def __init__(self, node_id: int, local_node): super(NmtSlave, self).__init__(node_id) self._send_task = None self._heartbeat_time_ms = 0 @@ -203,10 +204,10 @@ def on_command(self, can_id, data, timestamp): super(NmtSlave, self).on_command(can_id, data, timestamp) self.update_heartbeat() - def send_command(self, code): + def send_command(self, code: int) -> None: """Send an NMT command code to the node. - :param int code: + :param code: NMT command code. """ old_state = self._state @@ -232,10 +233,10 @@ def on_write(self, index, data, **kwargs): else: self.start_heartbeat(hearbeat_time) - def start_heartbeat(self, heartbeat_time_ms): + def start_heartbeat(self, heartbeat_time_ms: int): """Start the hearbeat service. - :param int hearbeat_time + :param hearbeat_time The heartbeat time in ms. If the heartbeat time is 0 the heartbeating will not start. """ diff --git a/canopen/node/base.py b/canopen/node/base.py index 9df02e43..d87e5517 100644 --- a/canopen/node/base.py +++ b/canopen/node/base.py @@ -1,18 +1,22 @@ +from typing import TextIO, Union from .. import objectdictionary class BaseNode(object): """A CANopen node. - :param int node_id: + :param node_id: Node ID (set to None or 0 if specified by object dictionary) :param object_dictionary: Object dictionary as either a path to a file, an ``ObjectDictionary`` or a file like object. - :type object_dictionary: :class:`str`, :class:`canopen.ObjectDictionary` """ - def __init__(self, node_id, object_dictionary): + def __init__( + self, + node_id: int, + object_dictionary: Union[objectdictionary.ObjectDictionary, str, TextIO], + ): self.network = None if not isinstance(object_dictionary, diff --git a/canopen/node/local.py b/canopen/node/local.py index 8eee9420..ecce2dff 100644 --- a/canopen/node/local.py +++ b/canopen/node/local.py @@ -1,5 +1,5 @@ import logging -import struct +from typing import Dict, Union from .base import BaseNode from ..sdo import SdoServer, SdoAbortedError @@ -13,10 +13,14 @@ class LocalNode(BaseNode): - def __init__(self, node_id, object_dictionary): + def __init__( + self, + node_id: int, + object_dictionary: Union[objectdictionary.ObjectDictionary, str], + ): super(LocalNode, self).__init__(node_id, object_dictionary) - self.data_store = {} + self.data_store: Dict[int, Dict[int, bytes]] = {} self._read_callbacks = [] self._write_callbacks = [] @@ -55,7 +59,9 @@ def add_read_callback(self, callback): def add_write_callback(self, callback): self._write_callbacks.append(callback) - def get_data(self, index, subindex, check_readable=False): + def get_data( + self, index: int, subindex: int, check_readable: bool = False + ) -> bytes: obj = self._find_object(index, subindex) if check_readable and not obj.readable: @@ -82,7 +88,13 @@ def get_data(self, index, subindex, check_readable=False): logger.info("Resource unavailable for 0x%X:%d", index, subindex) raise SdoAbortedError(0x060A0023) - def set_data(self, index, subindex, data, check_writable=False): + def set_data( + self, + index: int, + subindex: int, + data: bytes, + check_writable: bool = False, + ) -> None: obj = self._find_object(index, subindex) if check_writable and not obj.writable: diff --git a/canopen/node/remote.py b/canopen/node/remote.py index 5a531868..864ffeb3 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -1,4 +1,5 @@ import logging +from typing import Union, TextIO from ..sdo import SdoClient from ..nmt import NmtMaster @@ -9,24 +10,30 @@ import canopen +from canopen import objectdictionary + logger = logging.getLogger(__name__) class RemoteNode(BaseNode): """A CANopen remote node. - :param int node_id: + :param node_id: Node ID (set to None or 0 if specified by object dictionary) :param object_dictionary: Object dictionary as either a path to a file, an ``ObjectDictionary`` or a file like object. - :param bool load_od: + :param load_od: Enable the Object Dictionary to be sent trough SDO's to the remote node at startup. - :type object_dictionary: :class:`str`, :class:`canopen.ObjectDictionary` """ - def __init__(self, node_id, object_dictionary, load_od=False): + def __init__( + self, + node_id: int, + object_dictionary: Union[objectdictionary.ObjectDictionary, str, TextIO], + load_od: bool = False, + ): super(RemoteNode, self).__init__(node_id, object_dictionary) #: Enable WORKAROUND for reversed PDO mapping entries diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 25a2f37a..b66f8fc3 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -2,6 +2,7 @@ Object Dictionary module """ import struct +from typing import Dict, Iterable, List, Optional, TextIO, Union try: from collections.abc import MutableMapping, Mapping except ImportError: @@ -13,7 +14,10 @@ logger = logging.getLogger(__name__) -def import_od(source, node_id=None): +def import_od( + source: Union[str, TextIO, None], + node_id: Optional[int] = None, +) -> "ObjectDictionary": """Parse an EDS, DCF, or EPF file. :param source: @@ -21,7 +25,6 @@ def import_od(source, node_id=None): :return: An Object Dictionary instance. - :rtype: canopen.ObjectDictionary """ if source is None: return ObjectDictionary() @@ -52,11 +55,13 @@ def __init__(self): self.indices = {} self.names = {} #: Default bitrate if specified by file - self.bitrate = None + self.bitrate: Optional[int] = None #: Node ID if specified by file - self.node_id = None + self.node_id: Optional[int] = None - def __getitem__(self, index): + def __getitem__( + self, index: Union[int, str] + ) -> Union["Array", "Record", "Variable"]: """Get object from object dictionary by name or index.""" item = self.names.get(index) or self.indices.get(index) if item is None: @@ -64,25 +69,27 @@ def __getitem__(self, index): raise KeyError("%s was not found in Object Dictionary" % name) return item - def __setitem__(self, index, obj): + def __setitem__( + self, index: Union[int, str], obj: Union["Array", "Record", "Variable"] + ): assert index == obj.index or index == obj.name self.add_object(obj) - def __delitem__(self, index): + def __delitem__(self, index: Union[int, str]): obj = self[index] del self.indices[obj.index] del self.names[obj.name] - def __iter__(self): + def __iter__(self) -> Iterable[int]: return iter(sorted(self.indices)) - def __len__(self): + def __len__(self) -> int: return len(self.indices) - def __contains__(self, index): + def __contains__(self, index: Union[int, str]): return index in self.names or index in self.indices - def add_object(self, obj): + def add_object(self, obj: Union["Array", "Record", "Variable"]) -> None: """Add object to the object dictionary. :param obj: @@ -95,11 +102,12 @@ def add_object(self, obj): self.indices[obj.index] = obj self.names[obj.name] = obj - def get_variable(self, index, subindex=0): + def get_variable( + self, index: Union[int, str], subindex: int = 0 + ) -> Optional["Variable"]: """Get the variable object at specified index (and subindex if applicable). :return: Variable if found, else `None` - :rtype: canopen.objectdictionary.Variable """ obj = self.get(index) if isinstance(obj, Variable): @@ -116,9 +124,9 @@ class Record(MutableMapping): #: Description for the whole record description = "" - def __init__(self, name, index): + def __init__(self, name: str, index: int): #: The :class:`~canopen.ObjectDictionary` owning the record. - self.parent = None + self.parent: Optional[ObjectDictionary] = None #: 16-bit address of the record self.index = index #: Name of record @@ -128,34 +136,34 @@ def __init__(self, name, index): self.subindices = {} self.names = {} - def __getitem__(self, subindex): + def __getitem__(self, subindex: Union[int, str]) -> "Variable": item = self.names.get(subindex) or self.subindices.get(subindex) if item is None: raise KeyError("Subindex %s was not found" % subindex) return item - def __setitem__(self, subindex, var): + def __setitem__(self, subindex: Union[int, str], var: "Variable"): assert subindex == var.subindex self.add_member(var) - def __delitem__(self, subindex): + def __delitem__(self, subindex: Union[int, str]): var = self[subindex] del self.subindices[var.subindex] del self.names[var.name] - def __len__(self): + def __len__(self) -> int: return len(self.subindices) - def __iter__(self): + def __iter__(self) -> Iterable[int]: return iter(sorted(self.subindices)) - def __contains__(self, subindex): + def __contains__(self, subindex: Union[int, str]) -> bool: return subindex in self.names or subindex in self.subindices - def __eq__(self, other): + def __eq__(self, other: "Record") -> bool: return self.index == other.index - def add_member(self, variable): + def add_member(self, variable: "Variable") -> None: """Adds a :class:`~canopen.objectdictionary.Variable` to the record.""" variable.parent = self self.subindices[variable.subindex] = variable @@ -172,7 +180,7 @@ class Array(Mapping): #: Description for the whole array description = "" - def __init__(self, name, index): + def __init__(self, name: str, index: int): #: The :class:`~canopen.ObjectDictionary` owning the record. self.parent = None #: 16-bit address of the array @@ -184,7 +192,7 @@ def __init__(self, name, index): self.subindices = {} self.names = {} - def __getitem__(self, subindex): + def __getitem__(self, subindex: Union[int, str]) -> "Variable": var = self.names.get(subindex) or self.subindices.get(subindex) if var is not None: # This subindex is defined @@ -204,16 +212,16 @@ def __getitem__(self, subindex): raise KeyError("Could not find subindex %r" % subindex) return var - def __len__(self): + def __len__(self) -> int: return len(self.subindices) - def __iter__(self): + def __iter__(self) -> Iterable[int]: return iter(sorted(self.subindices)) - def __eq__(self, other): + def __eq__(self, other: "Array") -> bool: return self.index == other.index - def add_member(self, variable): + def add_member(self, variable: "Variable") -> None: """Adds a :class:`~canopen.objectdictionary.Variable` to the record.""" variable.parent = self self.subindices[variable.subindex] = variable @@ -237,7 +245,7 @@ class Variable(object): REAL64: struct.Struct(" bool: return (self.index == other.index and self.subindex == other.subindex) - def __len__(self): + def __len__(self) -> int: if self.data_type in self.STRUCT_TYPES: return self.STRUCT_TYPES[self.data_type].size * 8 else: return 8 @property - def writable(self): + def writable(self) -> bool: return "w" in self.access_type @property - def readable(self): + def readable(self) -> bool: return "r" in self.access_type or self.access_type == "const" - def add_value_description(self, value, descr): + def add_value_description(self, value: int, descr: str) -> None: """Associate a value with a string description. - :param int value: Value to describe - :param str desc: Description of value + :param value: Value to describe + :param desc: Description of value """ self.value_descriptions[value] = descr - def add_bit_definition(self, name, bits): + def add_bit_definition(self, name: str, bits: List[int]) -> None: """Associate bit(s) with a string description. - :param str name: Name of bit(s) - :param list bits: List of bits as integers + :param name: Name of bit(s) + :param bits: List of bits as integers """ self.bit_definitions[name] = bits - def decode_raw(self, data): + def decode_raw(self, data: bytes) -> Union[int, float, str, bytes, bytearray]: if self.data_type == VISIBLE_STRING: return data.rstrip(b"\x00").decode("ascii", errors="ignore") elif self.data_type == UNICODE_STRING: @@ -324,7 +332,7 @@ def decode_raw(self, data): # Just return the data as is return data - def encode_raw(self, value): + def encode_raw(self, value: Union[int, float, str, bytes, bytearray]) -> bytes: if isinstance(value, (bytes, bytearray)): return value elif self.data_type == VISIBLE_STRING: @@ -355,18 +363,18 @@ def encode_raw(self, value): "Do not know how to encode %r to data type %Xh" % ( value, self.data_type)) - def decode_phys(self, value): + def decode_phys(self, value: int) -> Union[int, bool, float, str, bytes]: if self.data_type in INTEGER_TYPES: value *= self.factor return value - def encode_phys(self, value): + def encode_phys(self, value: Union[int, bool, float, str, bytes]) -> int: if self.data_type in INTEGER_TYPES: value /= self.factor value = int(round(value)) return value - def decode_desc(self, value): + def decode_desc(self, value: int) -> str: if not self.value_descriptions: raise ObjectDictionaryError("No value descriptions exist") elif value not in self.value_descriptions: @@ -375,7 +383,7 @@ def decode_desc(self, value): else: return self.value_descriptions[value] - def encode_desc(self, desc): + def encode_desc(self, desc: str) -> int: if not self.value_descriptions: raise ObjectDictionaryError("No value descriptions exist") else: @@ -386,7 +394,7 @@ def encode_desc(self, desc): error_text = "No value corresponds to '%s'. Valid values are: %s" raise ValueError(error_text % (desc, valid_values)) - def decode_bits(self, value, bits): + def decode_bits(self, value: int, bits: List[int]) -> int: try: bits = self.bit_definitions[bits] except (TypeError, KeyError): @@ -396,7 +404,7 @@ def decode_bits(self, value, bits): mask |= 1 << bit return (value & mask) >> min(bits) - def encode_bits(self, original_value, bits, bit_value): + def encode_bits(self, original_value: int, bits: List[int], bit_value: int): try: bits = self.bit_definitions[bits] except (TypeError, KeyError): diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 63a0053e..c11eeaae 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -1,5 +1,6 @@ import threading import math +from typing import Callable, Dict, Iterable, List, Optional, Union try: from collections.abc import Mapping except ImportError: @@ -127,14 +128,14 @@ def stop(self): class Maps(Mapping): """A collection of transmit or receive maps.""" - def __init__(self, com_offset, map_offset, pdo_node, cob_base=None): + def __init__(self, com_offset, map_offset, pdo_node: PdoBase, cob_base=None): """ :param com_offset: :param map_offset: :param pdo_node: :param cob_base: """ - self.maps = {} + self.maps: Dict[int, "Map"] = {} for map_no in range(512): if com_offset + map_no in pdo_node.node.object_dictionary: new_map = Map( @@ -146,13 +147,13 @@ def __init__(self, com_offset, map_offset, pdo_node, cob_base=None): new_map.predefined_cob_id = cob_base + map_no * 0x100 + pdo_node.node.id self.maps[map_no + 1] = new_map - def __getitem__(self, key): + def __getitem__(self, key: int) -> "Map": return self.maps[key] - def __iter__(self): + def __iter__(self) -> Iterable[int]: return iter(self.maps) - def __len__(self): + def __len__(self) -> int: return len(self.maps) @@ -164,34 +165,34 @@ def __init__(self, pdo_node, com_record, map_array): self.com_record = com_record self.map_array = map_array #: If this map is valid - self.enabled = False + self.enabled: bool = False #: COB-ID for this PDO - self.cob_id = None + self.cob_id: Optional[int] = None #: Default COB-ID if this PDO is part of the pre-defined connection set - self.predefined_cob_id = None + self.predefined_cob_id: Optional[int] = None #: Is the remote transmit request (RTR) allowed for this PDO - self.rtr_allowed = True + self.rtr_allowed: bool = True #: Transmission type (0-255) - self.trans_type = None + self.trans_type: Optional[int] = None #: Inhibit Time (optional) (in 100us) - self.inhibit_time = None + self.inhibit_time: Optional[int] = None #: Event timer (optional) (in ms) - self.event_timer = None + self.event_timer: Optional[int] = None #: Ignores SYNC objects up to this SYNC counter value (optional) - self.sync_start_value = None + self.sync_start_value: Optional[int] = None #: List of variables mapped to this PDO - self.map = [] - self.length = 0 + self.map: List["Variable"] = [] + self.length: int = 0 #: Current message data self.data = bytearray() #: Timestamp of last received message - self.timestamp = None + self.timestamp: Optional[float] = None #: Period of receive message transmission in seconds. #: Set explicitly or using the :meth:`start()` method. - self.period = None + self.period: Optional[float] = None self.callbacks = [] self.receive_condition = threading.Condition() - self.is_received = False + self.is_received: bool = False self._task = None def __getitem_by_index(self, value): @@ -214,7 +215,7 @@ def __getitem_by_name(self, value): raise KeyError('{0} not found in map. Valid entries are {1}'.format( value, ', '.join(valid_values))) - def __getitem__(self, key): + def __getitem__(self, key: Union[int, str]) -> "Variable": var = None if isinstance(key, int): # there is a maximum available of 8 slots per PDO map @@ -229,10 +230,10 @@ def __getitem__(self, key): var = self.__getitem_by_name(key) return var - def __iter__(self): + def __iter__(self) -> Iterable["Variable"]: return iter(self.map) - def __len__(self): + def __len__(self) -> int: return len(self.map) def _get_variable(self, index, subindex): @@ -257,7 +258,7 @@ def _update_data_size(self): self.data = bytearray(int(math.ceil(self.length / 8.0))) @property - def name(self): + def name(self) -> str: """A descriptive name of the PDO. Examples: @@ -275,7 +276,7 @@ def name(self): return "%sPDO%d_node%d" % (direction, map_id, node_id) @property - def is_periodic(self): + def is_periodic(self) -> bool: """Indicate whether PDO updates will be transferred regularly. If some external mechanism is used to transmit the PDO regularly, its cycle time @@ -304,7 +305,7 @@ def on_message(self, can_id, data, timestamp): for callback in self.callbacks: callback(self) - def add_callback(self, callback): + def add_callback(self, callback: Callable[["Map"], None]) -> None: """Add a callback which will be called on receive. :param callback: @@ -313,7 +314,7 @@ def add_callback(self, callback): """ self.callbacks.append(callback) - def read(self): + def read(self) -> None: """Read PDO configuration for this map using SDO.""" cob_id = self.com_record[1].raw self.cob_id = cob_id & 0x1FFFFFFF @@ -362,7 +363,7 @@ def read(self): self.subscribe() - def save(self): + def save(self) -> None: """Save PDO configuration for this map using SDO.""" logger.info("Setting COB-ID 0x%X and temporarily disabling PDO", self.cob_id) @@ -418,7 +419,7 @@ def save(self): self.com_record[1].raw = self.cob_id | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0x0) self.subscribe() - def subscribe(self): + def subscribe(self) -> None: """Register the PDO for reception on the network. This normally happens when the PDO configuration is read from @@ -430,21 +431,23 @@ def subscribe(self): logger.info("Subscribing to enabled PDO 0x%X on the network", self.cob_id) self.pdo_node.network.subscribe(self.cob_id, self.on_message) - def clear(self): + def clear(self) -> None: """Clear all variables from this map.""" self.map = [] self.length = 0 - def add_variable(self, index, subindex=0, length=None): + def add_variable( + self, + index: Union[str, int], + subindex: Union[str, int] = 0, + length: Optional[int] = None, + ) -> "Variable": """Add a variable from object dictionary as the next entry. :param index: Index of variable as name or number :param subindex: Sub-index of variable as name or number - :param int length: Size of data in number of bits - :type index: :class:`str` or :class:`int` - :type subindex: :class:`str` or :class:`int` + :param length: Size of data in number of bits :return: Variable that was added - :rtype: canopen.pdo.Variable """ try: var = self._get_variable(index, subindex) @@ -470,14 +473,14 @@ def add_variable(self, index, subindex=0, length=None): logger.warning("Max size of PDO exceeded (%d > 64)", self.length) return var - def transmit(self): + def transmit(self) -> None: """Transmit the message once.""" self.pdo_node.network.send_message(self.cob_id, self.data) - def start(self, period=None): + def start(self, period: Optional[float] = None) -> None: """Start periodic transmission of message in a background thread. - :param float period: + :param period: Transmission period in seconds. Can be omitted if :attr:`period` has been set on the object before. :raises ValueError: When neither the argument nor the :attr:`period` is given. @@ -496,30 +499,29 @@ def start(self, period=None): self._task = self.pdo_node.network.send_periodic( self.cob_id, self.data, self.period) - def stop(self): + def stop(self) -> None: """Stop transmission.""" if self._task is not None: self._task.stop() self._task = None - def update(self): + def update(self) -> None: """Update periodic message with new data.""" if self._task is not None: self._task.update(self.data) - def remote_request(self): + def remote_request(self) -> None: """Send a remote request for the transmit PDO. Silently ignore if not allowed. """ if self.enabled and self.rtr_allowed: self.pdo_node.network.send_message(self.cob_id, None, remote=True) - def wait_for_reception(self, timeout=10): + def wait_for_reception(self, timeout: float = 10) -> float: """Wait for the next transmit PDO. :param float timeout: Max time to wait in seconds. :return: Timestamp of message received or None if timeout. - :rtype: float """ with self.receive_condition: self.is_received = False @@ -530,7 +532,7 @@ def wait_for_reception(self, timeout=10): class Variable(variable.Variable): """One object dictionary variable mapped to a PDO.""" - def __init__(self, od): + def __init__(self, od: objectdictionary.Variable): #: PDO object that is associated with this Variable Object self.pdo_parent = None #: Location of variable in the message in bits @@ -538,11 +540,10 @@ def __init__(self, od): self.length = len(od) variable.Variable.__init__(self, od) - def get_data(self): + def get_data(self) -> bytes: """Reads the PDO variable from the last received message. :return: Variable value as :class:`bytes`. - :rtype: bytes """ byte_offset, bit_offset = divmod(self.offset, 8) @@ -566,10 +567,10 @@ def get_data(self): return data - def set_data(self, data): + def set_data(self, data: bytes): """Set for the given variable the PDO data. - :param bytes data: Value for the PDO variable in the PDO message as :class:`bytes`. + :param data: Value for the PDO variable in the PDO message. """ byte_offset, bit_offset = divmod(self.offset, 8) logger.debug("Updating %s to %s in %s", diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 9018dc23..3c3d0bbe 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -1,4 +1,5 @@ import binascii +from typing import Iterable, Union try: from collections.abc import Mapping except ImportError: @@ -26,13 +27,18 @@ class SdoBase(Mapping): #: The CRC algorithm used for block transfers crc_cls = CrcXmodem - def __init__(self, rx_cobid, tx_cobid, od): + def __init__( + self, + rx_cobid: int, + tx_cobid: int, + od: objectdictionary.ObjectDictionary, + ): """ - :param int rx_cobid: + :param rx_cobid: COB-ID that the server receives on (usually 0x600 + node ID) - :param int tx_cobid: + :param tx_cobid: COB-ID that the server responds with (usually 0x580 + node ID) - :param canopen.ObjectDictionary od: + :param od: Object Dictionary to use for communication """ self.rx_cobid = rx_cobid @@ -40,7 +46,9 @@ def __init__(self, rx_cobid, tx_cobid, od): self.network = None self.od = od - def __getitem__(self, index): + def __getitem__( + self, index: Union[str, int] + ) -> Union["Variable", "Array", "Record"]: entry = self.od[index] if isinstance(entry, objectdictionary.Variable): return Variable(self, entry) @@ -49,65 +57,77 @@ def __getitem__(self, index): elif isinstance(entry, objectdictionary.Record): return Record(self, entry) - def __iter__(self): + def __iter__(self) -> Iterable[int]: return iter(self.od) - def __len__(self): + def __len__(self) -> int: return len(self.od) - def __contains__(self, key): + def __contains__(self, key: Union[int, str]) -> bool: return key in self.od + def upload(self, index: int, subindex: int) -> bytes: + raise NotImplementedError() + + def download( + self, + index: int, + subindex: int, + data: bytes, + force_segment: bool = False, + ) -> None: + raise NotImplementedError() + class Record(Mapping): - def __init__(self, sdo_node, od): + def __init__(self, sdo_node: SdoBase, od: objectdictionary.ObjectDictionary): self.sdo_node = sdo_node self.od = od - def __getitem__(self, subindex): + def __getitem__(self, subindex: Union[int, str]) -> "Variable": return Variable(self.sdo_node, self.od[subindex]) - def __iter__(self): + def __iter__(self) -> Iterable[int]: return iter(self.od) - def __len__(self): + def __len__(self) -> int: return len(self.od) - def __contains__(self, subindex): + def __contains__(self, subindex: Union[int, str]) -> bool: return subindex in self.od class Array(Mapping): - def __init__(self, sdo_node, od): + def __init__(self, sdo_node: SdoBase, od: objectdictionary.ObjectDictionary): self.sdo_node = sdo_node self.od = od - def __getitem__(self, subindex): + def __getitem__(self, subindex: Union[int, str]) -> "Variable": return Variable(self.sdo_node, self.od[subindex]) - def __iter__(self): + def __iter__(self) -> Iterable[int]: return iter(range(1, len(self) + 1)) - def __len__(self): + def __len__(self) -> int: return self[0].raw - def __contains__(self, subindex): + def __contains__(self, subindex: int) -> bool: return 0 <= subindex <= len(self) class Variable(variable.Variable): """Access object dictionary variable values using SDO protocol.""" - def __init__(self, sdo_node, od): + def __init__(self, sdo_node: SdoBase, od: objectdictionary.ObjectDictionary): self.sdo_node = sdo_node variable.Variable.__init__(self, od) - def get_data(self): + def get_data(self) -> bytes: return self.sdo_node.upload(self.od.index, self.od.subindex) - def set_data(self, data): + def set_data(self, data: bytes): force_segment = self.od.data_type == objectdictionary.DOMAIN self.sdo_node.download(self.od.index, self.od.subindex, data, force_segment) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 86a36365..0ed083e4 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -99,16 +99,15 @@ def abort(self, abort_code=0x08000000): self.send_request(request) logger.error("Transfer aborted by client with code 0x{:08X}".format(abort_code)) - def upload(self, index, subindex): + def upload(self, index: int, subindex: int) -> bytes: """May be called to make a read operation without an Object Dictionary. - :param int index: + :param index: Index of object to read. - :param int subindex: + :param subindex: Sub-index of object to read. :return: A data object. - :rtype: bytes :raises canopen.SdoCommunicationError: On unexpected response or timeout. @@ -133,16 +132,22 @@ def upload(self, index, subindex): data = data[0:size] return data - def download(self, index, subindex, data, force_segment=False): + def download( + self, + index: int, + subindex: int, + data: bytes, + force_segment: bool = False, + ) -> None: """May be called to make a write operation without an Object Dictionary. - :param int index: + :param index: Index of object to write. - :param int subindex: + :param subindex: Sub-index of object to write. - :param bytes data: + :param data: Data to be written. - :param bool force_segment: + :param force_segment: Force use of segmented transfer regardless of data size. :raises canopen.SdoCommunicationError: diff --git a/canopen/sdo/exceptions.py b/canopen/sdo/exceptions.py index 2276273a..515b4086 100644 --- a/canopen/sdo/exceptions.py +++ b/canopen/sdo/exceptions.py @@ -44,7 +44,7 @@ class SdoAbortedError(SdoError): 0x08000024: "No data available", } - def __init__(self, code): + def __init__(self, code: int): #: Abort code self.code = code diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index 746f43a3..7986e1fa 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -181,30 +181,35 @@ def abort(self, abort_code=0x08000000): self.send_response(data) # logger.error("Transfer aborted with code 0x{:08X}".format(abort_code)) - def upload(self, index, subindex): + def upload(self, index: int, subindex: int) -> bytes: """May be called to make a read operation without an Object Dictionary. - :param int index: + :param index: Index of object to read. - :param int subindex: + :param subindex: Sub-index of object to read. :return: A data object. - :rtype: bytes :raises canopen.SdoAbortedError: When node responds with an error. """ return self._node.get_data(index, subindex) - def download(self, index, subindex, data, force_segment=False): - """May be called to make a write operation without an Object Dictionary. + def download( + self, + index: int, + subindex: int, + data: bytes, + force_segment: bool = False, + ): + """May be called to make a write operation without an Object Dictionary. - :param int index: + :param index: Index of object to write. - :param int subindex: + :param subindex: Sub-index of object to write. - :param bytes data: + :param data: Data to be written. :raises canopen.SdoAbortedError: diff --git a/canopen/sync.py b/canopen/sync.py index 3619cfff..32248279 100644 --- a/canopen/sync.py +++ b/canopen/sync.py @@ -1,5 +1,8 @@ +from typing import Optional + + class SyncProducer(object): """Transmits a SYNC message periodically.""" @@ -8,22 +11,22 @@ class SyncProducer(object): def __init__(self, network): self.network = network - self.period = None + self.period: Optional[float] = None self._task = None - def transmit(self, count=None): + def transmit(self, count: Optional[int] = None): """Send out a SYNC message once. - :param int count: + :param count: Counter to add in message. """ data = [count] if count is not None else [] self.network.send_message(self.cob_id, data) - def start(self, period=None): + def start(self, period: Optional[float] = None): """Start periodic transmission of SYNC message in a background thread. - :param float period: + :param period: Period of SYNC message in seconds. """ if period is not None: diff --git a/canopen/timestamp.py b/canopen/timestamp.py index 8215affc..e96f7576 100644 --- a/canopen/timestamp.py +++ b/canopen/timestamp.py @@ -1,5 +1,6 @@ import time import struct +from typing import Optional # 1 Jan 1984 OFFSET = 441763200 @@ -18,7 +19,7 @@ class TimeProducer(object): def __init__(self, network): self.network = network - def transmit(self, timestamp=None): + def transmit(self, timestamp: Optional[float] = None): """Send out the TIME message once. :param float timestamp: diff --git a/canopen/variable.py b/canopen/variable.py index edb977c3..2357d162 100644 --- a/canopen/variable.py +++ b/canopen/variable.py @@ -1,4 +1,5 @@ import logging +from typing import Union try: from collections.abc import Mapping except ImportError: @@ -11,7 +12,7 @@ class Variable(object): - def __init__(self, od): + def __init__(self, od: objectdictionary.Variable): self.od = od #: Description of this variable from Object Dictionary, overridable self.name = od.name @@ -24,23 +25,23 @@ def __init__(self, od): #: Holds a local, overridable copy of the Object Subindex self.subindex = od.subindex - def get_data(self): + def get_data(self) -> bytes: raise NotImplementedError("Variable is not readable") - def set_data(self, data): + def set_data(self, data: bytes): raise NotImplementedError("Variable is not writable") @property - def data(self): + def data(self) -> bytes: """Byte representation of the object as :class:`bytes`.""" return self.get_data() @data.setter - def data(self, data): + def data(self, data: bytes): self.set_data(data) @property - def raw(self): + def raw(self) -> Union[int, bool, float, str, bytes]: """Raw representation of the object. This table lists the translations between object dictionary data types @@ -81,14 +82,14 @@ def raw(self): return value @raw.setter - def raw(self, value): + def raw(self, value: Union[int, bool, float, str, bytes]): logger.debug("Writing %s (0x%X:%d) = %r", self.name, self.index, self.subindex, value) self.data = self.od.encode_raw(value) @property - def phys(self): + def phys(self) -> Union[int, bool, float, str, bytes]: """Physical value scaled with some factor (defaults to 1). On object dictionaries that support specifying a factor, this can be @@ -101,26 +102,26 @@ def phys(self): return value @phys.setter - def phys(self, value): + def phys(self, value: Union[int, bool, float, str, bytes]): self.raw = self.od.encode_phys(value) @property - def desc(self): + def desc(self) -> str: """Converts to and from a description of the value as a string.""" value = self.od.decode_desc(self.raw) logger.debug("Description is '%s'", value) return value @desc.setter - def desc(self, desc): + def desc(self, desc: str): self.raw = self.od.encode_desc(desc) @property - def bits(self): + def bits(self) -> "Bits": """Access bits using integers, slices, or bit descriptions.""" return Bits(self) - def read(self, fmt="raw"): + def read(self, fmt: str = "raw") -> Union[int, bool, float, str, bytes]: """Alternative way of reading using a function instead of attributes. May be useful for asynchronous reading. @@ -141,7 +142,9 @@ def read(self, fmt="raw"): elif fmt == "desc": return self.desc - def write(self, value, fmt="raw"): + def write( + self, value: Union[int, bool, float, str, bytes], fmt: str = "raw" + ) -> None: """Alternative way of writing using a function instead of attributes. May be useful for asynchronous writing. @@ -162,7 +165,7 @@ def write(self, value, fmt="raw"): class Bits(Mapping): - def __init__(self, variable): + def __init__(self, variable: Variable): self.variable = variable self.read() @@ -176,10 +179,10 @@ def _get_bits(key): bits = key return bits - def __getitem__(self, key): + def __getitem__(self, key) -> int: return self.variable.od.decode_bits(self.raw, self._get_bits(key)) - def __setitem__(self, key, value): + def __setitem__(self, key, value: int): self.raw = self.variable.od.encode_bits( self.raw, self._get_bits(key), value) self.write() diff --git a/doc/conf.py b/doc/conf.py index 2a1bd192..3f865400 100644 --- a/doc/conf.py +++ b/doc/conf.py @@ -33,6 +33,7 @@ extensions = [ 'sphinx.ext.autodoc', 'sphinx.ext.intersphinx', + 'sphinx_autodoc_typehints', 'sphinx.ext.viewcode', ] From c46228f9cf2d2661166d68e7175f3e8b99064194 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Sun, 10 Oct 2021 20:12:30 +0200 Subject: [PATCH 073/199] Use PEP 517 for packaging --- .gitignore | 1 + canopen/__init__.py | 10 ++++------ pyproject.toml | 6 ++++++ setup.cfg | 23 +++++++++++++++++++++++ setup.py | 34 ++-------------------------------- 5 files changed, 36 insertions(+), 38 deletions(-) create mode 100644 pyproject.toml create mode 100644 setup.cfg diff --git a/.gitignore b/.gitignore index fddae0e9..89ebba91 100644 --- a/.gitignore +++ b/.gitignore @@ -26,6 +26,7 @@ var/ .installed.cfg *.egg build-deb/ +_version.py # PyInstaller # Usually these files are written by a python script from a template diff --git a/canopen/__init__.py b/canopen/__init__.py index 2fd09927..69ec15bf 100644 --- a/canopen/__init__.py +++ b/canopen/__init__.py @@ -1,16 +1,14 @@ -from pkg_resources import get_distribution, DistributionNotFound from .network import Network, NodeScanner from .node import RemoteNode, LocalNode from .sdo import SdoCommunicationError, SdoAbortedError from .objectdictionary import import_od, ObjectDictionary, ObjectDictionaryError from .profiles.p402 import BaseNode402 - -Node = RemoteNode - try: - __version__ = get_distribution(__name__).version -except DistributionNotFound: + from ._version import version as __version__ +except ImportError: # package is not installed __version__ = "unknown" +Node = RemoteNode + __pypi_url__ = "https://pypi.org/project/canopen/" diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 00000000..403805fb --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,6 @@ +[build-system] +requires = ["setuptools>=45", "wheel", "setuptools_scm>=6.2"] +build-backend = "setuptools.build_meta" + +[tool.setuptools_scm] +write_to = "canopen/_version.py" diff --git a/setup.cfg b/setup.cfg new file mode 100644 index 00000000..ca6253b5 --- /dev/null +++ b/setup.cfg @@ -0,0 +1,23 @@ +[metadata] +name = canopen +description = CANopen stack implementation +long_description = file: README.rst +project_urls = + Documentation = http://canopen.readthedocs.io/en/stable/ + Source Code = https://github.com/christiansandberg/canopen +author = Christian Sandberg +author_email = christiansandberg@me.com +classifier = + Development Status :: 5 - Production/Stable + License :: OSI Approved :: MIT License + Operating System :: OS Independent + Programming Language :: Python :: 3 :: Only + Intended Audience :: Developers + Topic :: Scientific/Engineering + +[options] +packages = find: +python_requires = >=3.6 +install_requires = + python-can >= 3.0.0 +include_package_data = True diff --git a/setup.py b/setup.py index eb965308..60684932 100644 --- a/setup.py +++ b/setup.py @@ -1,33 +1,3 @@ -from setuptools import setup, find_packages +from setuptools import setup -description = open("README.rst").read() -# Change links to stable documentation -description = description.replace("/latest/", "/stable/") - -setup( - name="canopen", - url="https://github.com/christiansandberg/canopen", - use_scm_version=True, - packages=find_packages(), - author="Christian Sandberg", - author_email="christiansandberg@me.com", - description="CANopen stack implementation", - keywords="CAN CANopen", - long_description=description, - license="MIT", - platforms=["any"], - classifiers=[ - "Development Status :: 5 - Production/Stable", - "License :: OSI Approved :: MIT License", - "Operating System :: OS Independent", - "Programming Language :: Python :: 3", - "Intended Audience :: Developers", - "Topic :: Scientific/Engineering" - ], - install_requires=["python-can>=3.0.0"], - extras_require={ - "db_export": ["canmatrix"] - }, - setup_requires=["setuptools_scm"], - include_package_data=True -) +setup() From 0f13cfb7c2c0bfbabf364bc20c3057eab9537332 Mon Sep 17 00:00:00 2001 From: David van Rijn Date: Tue, 12 Oct 2021 19:48:08 +0200 Subject: [PATCH 074/199] Export Eds or Dcf (#254) --- .gitignore | 3 + canopen/__init__.py | 2 +- canopen/objectdictionary/__init__.py | 60 +++++++ canopen/objectdictionary/eds.py | 252 ++++++++++++++++++++++++++- makedeb | 14 +- test/sample.eds | 7 +- test/test_eds.py | 74 +++++++- 7 files changed, 399 insertions(+), 13 deletions(-) diff --git a/.gitignore b/.gitignore index 89ebba91..e8507cc0 100644 --- a/.gitignore +++ b/.gitignore @@ -70,3 +70,6 @@ target/ \.project \.pydevproject + +*.kdev4 +*.kate-swp diff --git a/canopen/__init__.py b/canopen/__init__.py index 69ec15bf..a63ecb83 100644 --- a/canopen/__init__.py +++ b/canopen/__init__.py @@ -1,7 +1,7 @@ from .network import Network, NodeScanner from .node import RemoteNode, LocalNode from .sdo import SdoCommunicationError, SdoAbortedError -from .objectdictionary import import_od, ObjectDictionary, ObjectDictionaryError +from .objectdictionary import import_od, export_od, ObjectDictionary, ObjectDictionaryError from .profiles.p402 import BaseNode402 try: from ._version import version as __version__ diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index b66f8fc3..2a2f9e92 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -14,6 +14,41 @@ logger = logging.getLogger(__name__) +def export_od(od, dest:Union[str,TextIO,None]=None, doc_type:Optional[str]=None): + """ Export :class: ObjectDictionary to a file. + + :param od: + :class: ObjectDictionary object to be exported + :param dest: + export destination. filename, or file-like object or None. + if None, the document is returned as string + :param doc_type: type of document to export. + If a filename is given for dest, this default to the file extension. + Otherwise, this defaults to "eds" + :rtype: str or None + """ + + doctypes = {"eds", "dcf"} + if type(dest) is str: + if doc_type is None: + for t in doctypes: + if dest.endswith(f".{t}"): + doc_type = t + break + + if doc_type is None: + doc_type = "eds" + dest = open(dest, 'w') + assert doc_type in doctypes + + if doc_type == "eds": + from . import eds + return eds.export_eds(od, dest) + elif doc_type == "dcf": + from . import eds + return eds.export_dcf(od, dest) + + def import_od( source: Union[str, TextIO, None], node_id: Optional[int] = None, @@ -54,10 +89,13 @@ class ObjectDictionary(MutableMapping): def __init__(self): self.indices = {} self.names = {} + self.comments = "" #: Default bitrate if specified by file self.bitrate: Optional[int] = None #: Node ID if specified by file self.node_id: Optional[int] = None + #: Some information about the device + self.device_information = DeviceInformation() def __getitem__( self, index: Union[int, str] @@ -280,6 +318,9 @@ def __init__(self, name: str, index: int, subindex: int = 0): self.bit_definitions: Dict[str, List[int]] = {} #: Storage location of index self.storage_location = None + #: Can this variable be mapped to a PDO + self.pdo_mappable = False + def __eq__(self, other: "Variable") -> bool: return (self.index == other.index and @@ -418,5 +459,24 @@ def encode_bits(self, original_value: int, bits: List[int], bit_value: int): return temp +class DeviceInformation: + def __init__(self): + self.allowed_baudrates = set() + self.vendor_name:Optional[str] = None + self.vendor_number:Optional[int] = None + self.product_name:Optional[str] = None + self.product_number:Optional[int] = None + self.revision_number:Optional[int] = None + self.order_code:Optional[str] = None + self.simple_boot_up_master:Optional[bool] = None + self.simple_boot_up_slave:Optional[bool] = None + self.granularity:Optional[int] = None + self.dynamic_channels_supported:Optional[bool] = None + self.group_messaging:Optional[bool] = None + self.nr_of_RXPDO:Optional[bool] = None + self.nr_of_TXPDO:Optional[bool] = None + self.LSS_supported:Optional[bool] = None + + class ObjectDictionaryError(Exception): """Unsupported operation with the current Object Dictionary.""" diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 81c38adc..10f7599d 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -11,6 +11,7 @@ logger = logging.getLogger(__name__) +# Object type. Don't confuse with Data type DOMAIN = 2 VAR = 7 ARR = 8 @@ -19,6 +20,7 @@ def import_eds(source, node_id): eds = RawConfigParser() + eds.optionxform = str if hasattr(source, "read"): fp = source else: @@ -31,6 +33,57 @@ def import_eds(source, node_id): eds.readfp(fp) fp.close() od = objectdictionary.ObjectDictionary() + + if eds.has_section("FileInfo"): + od.__edsFileInfo = { + opt: eds.get("FileInfo", opt) + for opt in eds.options("FileInfo") + } + + if eds.has_section("Comments"): + linecount = eds.getint("Comments", "Lines") + od.comments = '\n'.join([ + eds.get("Comments", "Line%i" % line) + for line in range(1, linecount+1) + ]) + + if not eds.has_section("DeviceInfo"): + logger.warn("eds file does not have a DeviceInfo section. This section is mandatory") + else: + for rate in [10, 20, 50, 125, 250, 500, 800, 1000]: + baudPossible = int( + eds.get("DeviceInfo", "Baudrate_%i" % rate, fallback='0'), 0) + if baudPossible != 0: + od.device_information.allowed_baudrates.add(rate*1000) + + for t, eprop, odprop in [ + (str, "VendorName", "vendor_name"), + (int, "VendorNumber", "vendor_number"), + (str, "ProductName", "product_name"), + (int, "ProductNumber", "product_number"), + (int, "RevisionNumber", "revision_number"), + (str, "OrderCode", "order_code"), + (bool, "SimpleBootUpMaster", "simple_boot_up_master"), + (bool, "SimpleBootUpSlave", "simple_boot_up_slave"), + (bool, "Granularity", "granularity"), + (bool, "DynamicChannelsSupported", "dynamic_channels_supported"), + (bool, "GroupMessaging", "group_messaging"), + (int, "NrOfRXPDO", "nr_of_RXPDO"), + (int, "NrOfTXPDO", "nr_of_TXPDO"), + (bool, "LSS_Supported", "LSS_supported"), + ]: + try: + if t in (int, bool): + setattr(od.device_information, odprop, + t(int(eds.get("DeviceInfo", eprop), 0)) + ) + elif t is str: + setattr(od.device_information, odprop, + eds.get("DeviceInfo", eprop) + ) + except NoOptionError: + pass + if eds.has_section("DeviceComissioning"): od.bitrate = int(eds.get("DeviceComissioning", "Baudrate")) * 1000 od.node_id = int(eds.get("DeviceComissioning", "NodeID"), 0) @@ -146,13 +199,26 @@ def _convert_variable(node_id, var_type, value): return float(value) else: # COB-ID can contain '$NODEID+' so replace this with node_id before converting - value = value.replace(" ","").upper() + value = value.replace(" ", "").upper() if '$NODEID' in value and node_id is not None: return int(re.sub(r'\+?\$NODEID\+?', '', value), 0) + node_id else: return int(value, 0) +def _revert_variable(var_type, value): + if value is None: + return None + if var_type in (objectdictionary.OCTET_STRING, objectdictionary.DOMAIN): + return bytes.hex(value) + elif var_type in (objectdictionary.VISIBLE_STRING, objectdictionary.UNICODE_STRING): + return value + elif var_type in objectdictionary.FLOAT_TYPES: + return value + else: + return "0x%02X" % value + + def build_variable(eds, section, node_id, index, subindex=0): """Creates a object dictionary entry. :param eds: String stream of the eds file @@ -181,6 +247,8 @@ def build_variable(eds, section, node_id, index, subindex=0): # Assume DOMAIN to force application to interpret the byte data var.data_type = objectdictionary.DOMAIN + var.pdo_mappable = bool(int(eds.get(section, "PDOMapping", fallback="0"), 0)) + if eds.has_option(section, "LowLimit"): try: var.min = int(eds.get(section, "LowLimit"), 0) @@ -193,11 +261,13 @@ def build_variable(eds, section, node_id, index, subindex=0): pass if eds.has_option(section, "DefaultValue"): try: + var.default_raw = eds.get(section, "DefaultValue") var.default = _convert_variable(node_id, var.data_type, eds.get(section, "DefaultValue")) except ValueError: pass if eds.has_option(section, "ParameterValue"): try: + var.value_raw = eds.get(section, "ParameterValue") var.value = _convert_variable(node_id, var.data_type, eds.get(section, "ParameterValue")) except ValueError: pass @@ -211,3 +281,183 @@ def copy_variable(eds, section, subindex, src_var): var.name = name var.subindex = subindex return var + + +def export_dcf(od, dest=None, fileInfo={}): + return export_eds(od, dest, fileInfo, True) + + +def export_eds(od, dest=None, file_info={}, device_commisioning=False): + def export_object(obj, eds): + if type(obj) is objectdictionary.Variable: + return export_variable(obj, eds) + if type(obj) is objectdictionary.Record: + return export_record(obj, eds) + if type(obj) is objectdictionary.Array: + return export_array(obj, eds) + + def export_common(var, eds, section): + eds.add_section(section) + eds.set(section, "ParameterName", var.name) + if var.storage_location: + eds.set(section, "StorageLocation", var.storage_location) + + def export_variable(var, eds): + if type(var.parent) is objectdictionary.ObjectDictionary: + # top level variable + section = "%04X" % var.index + else: + # nested variable + section = "%04Xsub%X" % (var.index, var.subindex) + + export_common(var, eds, section) + eds.set(section, "ObjectType", "0x%X" % VAR) + if var.data_type: + eds.set(section, "DataType", "0x%04X" % var.data_type) + if var.access_type: + eds.set(section, "AccessType", var.access_type) + + if getattr(var, 'default_raw', None) is not None: + eds.set(section, "DefaultValue", var.default_raw) + elif getattr(var, 'default', None) is not None: + eds.set(section, "DefaultValue", _revert_variable( + var.data_type, var.default)) + + if device_commisioning: + if getattr(var, 'value_raw', None) is not None: + eds.set(section, "ParameterValue", var.value_raw) + elif getattr(var, 'value', None) is not None: + eds.set(section, "ParameterValue", + _revert_variable(var.data_type, var.default)) + + eds.set(section, "DataType", "0x%04X" % var.data_type) + eds.set(section, "PDOMapping", hex(var.pdo_mappable)) + + if getattr(var, 'min', None) is not None: + eds.set(section, "LowLimit", var.min) + if getattr(var, 'max', None) is not None: + eds.set(section, "HighLimit", var.max) + + def export_record(var, eds): + section = "%04X" % var.index + export_common(var, eds, section) + eds.set(section, "SubNumber", "0x%X" % len(var.subindices)) + ot = RECORD if type(var) is objectdictionary.Record else ARR + eds.set(section, "ObjectType", "0x%X" % ot) + for i in var: + export_variable(var[i], eds) + + export_array = export_record + + eds = RawConfigParser() + # both disables lowercasing, and allows int keys + eds.optionxform = str + + from datetime import datetime as dt + defmtime = dt.utcnow() + + try: + # only if eds was loaded by us + origFileInfo = od.__edsFileInfo + except AttributeError: + origFileInfo = { + # just set some defaults + "CreationDate": defmtime.strftime("%m-%d-%Y"), + "CreationTime": defmtime.strftime("%I:%m%p"), + "EdsVersion": 4.2, + } + + file_info.setdefault("ModificationDate", defmtime.strftime("%m-%d-%Y")) + file_info.setdefault("ModificationTime", defmtime.strftime("%I:%m%p")) + for k, v in origFileInfo.items(): + file_info.setdefault(k, v) + + eds.add_section("FileInfo") + for k, v in file_info.items(): + eds.set("FileInfo", k, v) + + eds.add_section("DeviceInfo") + for eprop, odprop in [ + ("VendorName", "vendor_name"), + ("VendorNumber", "vendor_number"), + ("ProductName", "product_name"), + ("ProductNumber", "product_number"), + ("RevisionNumber", "revision_number"), + ("OrderCode", "order_code"), + ("SimpleBootUpMaster", "simple_boot_up_master"), + ("SimpleBootUpSlave", "simple_boot_up_slave"), + ("Granularity", "granularity"), + ("DynamicChannelsSupported", "dynamic_channels_supported"), + ("GroupMessaging", "group_messaging"), + ("NrOfRXPDO", "nr_of_RXPDO"), + ("NrOfTXPDO", "nr_of_TXPDO"), + ("LSS_Supported", "LSS_supported"), + ]: + val = getattr(od.device_information, odprop, None) + if type(val) is None: + continue + elif type(val) is str: + eds.set("DeviceInfo", eprop, val) + elif type(val) in (int, bool): + eds.set("DeviceInfo", eprop, int(val)) + + # we are also adding out of spec baudrates here. + for rate in od.device_information.allowed_baudrates.union( + {10e3, 20e3, 50e3, 125e3, 250e3, 500e3, 800e3, 1000e3}): + eds.set( + "DeviceInfo", "Baudrate_%i" % (rate/1000), + int(rate in od.device_information.allowed_baudrates)) + + if device_commisioning and (od.bitrate or od.node_id): + eds.add_section("DeviceComissioning") + if od.bitrate: + eds.set("DeviceComissioning", "Baudrate", int(od.bitrate / 1000)) + if od.node_id: + eds.set("DeviceComissioning", "NodeID", int(od.node_id)) + + eds.add_section("Comments") + i = 0 + for line in od.comments.splitlines(): + i += 1 + eds.set("Comments", "Line%i" % i, line) + eds.set("Comments", "Lines", i) + + eds.add_section("DummyUsage") + for i in range(1, 8): + key = "Dummy%04d" % i + eds.set("DummyUsage", key, 1 if (key in od) else 0) + + def mandatory_indices(x): + return x in {0x1000, 0x1001, 0x1018} + + def manufacturer_idices(x): + return x in range(0x2000, 0x6000) + + def optional_indices(x): + return all(( + x > 0x1001, + not mandatory_indices(x), + not manufacturer_idices(x), + )) + + supported_mantatory_indices = list(filter(mandatory_indices, od)) + supported_optional_indices = list(filter(optional_indices, od)) + supported_manufacturer_indices = list(filter(manufacturer_idices, od)) + + def add_list(section, list): + eds.add_section(section) + eds.set(section, "SupportedObjects", len(list)) + for i in range(0, len(list)): + eds.set(section, (i + 1), "0x%04X" % list[i]) + for index in list: + export_object(od[index], eds) + + add_list("MandatoryObjects", supported_mantatory_indices) + add_list("OptionalObjects", supported_optional_indices) + add_list("ManufacturerObjects", supported_manufacturer_indices) + + if not dest: + import sys + dest = sys.stdout + + eds.write(dest, False) diff --git a/makedeb b/makedeb index c7da516d..591ffc11 100755 --- a/makedeb +++ b/makedeb @@ -1,11 +1,10 @@ #!/bin/sh py=python3 -name=canopen -pkgname=$py-canopen +name='canopen' +pkgname=$py-$name description="CANopen stack implementation" - version=`git tag |grep -Eo '[0-9]+\.[0-9]+\.[0-9]+' |sort | tail -1 ` maintainer=`git log -1 --pretty=format:'%an <%ae>'` arch=all @@ -19,14 +18,13 @@ fakeroot=$package_dir mkdir -p $fakeroot -$py setup.py bdist >setup_py.log - -tar -f dist/*.tar.* -C $fakeroot -x +$py setup.py bdist_wheel >setup_py.log mkdir -p $fakeroot/usr/lib/$py/dist-packages/ -mv -f $(find $fakeroot -name $name -type d) $fakeroot/usr/lib/python3/dist-packages/ +unzip dist/*.whl -d $fakeroot/usr/lib/python3/dist-packages/ -cp -r $name.egg-info $fakeroot/usr/lib/python3/dist-packages/$name-$version.egg-info +# deploy extra files +#cp -r install/* $fakeroot/ mkdir $package_dir/DEBIAN diff --git a/test/sample.eds b/test/sample.eds index 11c9c404..b01a9ee5 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -20,7 +20,7 @@ BaudRate_500=1 BaudRate_800=0 BaudRate_1000=1 SimpleBootUpMaster=0 -SimpleBootUpSlave=0 +SimpleBootUpSlave=1 Granularity=8 DynamicChannelsSupported=0 CompactPDO=0 @@ -46,7 +46,10 @@ Dummy0006=0 Dummy0007=0 [Comments] -Lines=0 +Lines=3 +Line1=|-------------| +Line2=| Don't panic | +Line3=|-------------| [MandatoryObjects] SupportedObjects=3 diff --git a/test/test_eds.py b/test/test_eds.py index a308d729..6df65285 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -4,7 +4,6 @@ EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') - class TestEDS(unittest.TestCase): def setUp(self): @@ -90,3 +89,76 @@ def test_dummy_variable(self): def test_dummy_variable_undefined(self): with self.assertRaises(KeyError): var_undef = self.od['Dummy0001'] + + def test_comments(self): + self.assertEqual(self.od.comments, +""" +|-------------| +| Don't panic | +|-------------| +""".strip() + ) + + + def test_export_eds(self): + import tempfile + for doctype in {"eds", "dcf"}: + with tempfile.NamedTemporaryFile(suffix="."+doctype, mode="w+") as tempeds: + print("exporting %s to " % doctype + tempeds.name) + canopen.export_od(self.od, tempeds, doc_type=doctype) + tempeds.flush() + exported_od = canopen.import_od(tempeds.name) + + for index in exported_od: + self.assertIn(exported_od[index].name, self.od) + self.assertIn(index , self.od) + + for index in self.od: + if index < 0x0008: + # ignore dummies + continue + self.assertIn(self.od[index].name, exported_od) + self.assertIn(index , exported_od) + + actual_object = exported_od[index] + expected_object = self.od[index] + self.assertEqual(type(actual_object), type(expected_object)) + self.assertEqual(actual_object.name, expected_object.name) + + if type(actual_object) is canopen.objectdictionary.Variable: + expected_vars = [expected_object] + actual_vars = [actual_object ] + else : + expected_vars = [expected_object[idx] for idx in expected_object] + actual_vars = [actual_object [idx] for idx in actual_object] + + for prop in [ + "allowed_baudrates", + "vendor_name", + "vendor_number", + "product_name", + "product_number", + "revision_number", + "order_code", + "simple_boot_up_master", + "simple_boot_up_slave", + "granularity", + "dynamic_channels_supported", + "group_messaging", + "nr_of_RXPDO", + "nr_of_TXPDO", + "LSS_supported", + ]: + self.assertEqual(getattr(self.od.device_information, prop), getattr(exported_od.device_information, prop), f"prop {prop!r} mismatch on DeviceInfo") + + + for evar,avar in zip(expected_vars,actual_vars): + self. assertEqual(getattr(avar, "data_type" , None) , getattr(evar,"data_type" ,None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) + self. assertEqual(getattr(avar, "default_raw", None) , getattr(evar,"default_raw",None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) + self. assertEqual(getattr(avar, "min" , None) , getattr(evar,"min" ,None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) + self. assertEqual(getattr(avar, "max" , None) , getattr(evar,"max" ,None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) + if doctype == "dcf": + self.assertEqual(getattr(avar, "value" , None) , getattr(evar,"value" ,None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) + + self.assertEqual(self.od.comments, exported_od.comments) + From 1ea906d3fb6ecc73b25505015c07717d6b9069bc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Wed, 10 Nov 2021 16:41:09 +0100 Subject: [PATCH 075/199] p402: Fix missing fallback behavior in check_statusword(). (#277) The docstring for BaseNode402.check_statusword() promises it will fall back to SDO if the TPDO is not configured as periodic. However, that actually only happens when there is no TPDO for the Statusword at all. Fix that small detail, as the code using this function relies on getting an up-to-date value and on the implicit throttling caused by the SDO round-trip time. --- canopen/profiles/p402.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index b8b9254a..12ccdd3b 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -477,9 +477,9 @@ def statusword(self): return self.sdo[0x6041].raw def check_statusword(self, timeout=None): - """Report an up-to-date reading of the statusword (0x6041) from the device. + """Report an up-to-date reading of the Statusword (0x6041) from the device. - If the TPDO with the statusword is configured as periodic, this method blocks + If the TPDO with the Statusword is configured as periodic, this method blocks until one was received. Otherwise, it uses the SDO fallback of the ``statusword`` property. @@ -494,6 +494,8 @@ def check_statusword(self, timeout=None): timestamp = pdo.wait_for_reception(timeout or self.TIMEOUT_CHECK_TPDO) if timestamp is None: raise RuntimeError('Timeout waiting for updated statusword') + else: + return self.sdo[0x6041].raw return self.statusword @property From 99bb97b9dd37b6b96acdf711cc7a713f1f782851 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Wed, 10 Nov 2021 16:42:34 +0100 Subject: [PATCH 076/199] eds: Fix exception in comment parsing with hexadecimal line count. (#279) Inside an EDS file's [Comments] section, the Lines attribute may be expressed as a hexadecimal number prefixed with 0x. The ConfigParser.getint() method however does not support such a format. Switch to the default int() constructor with a base=0 argument to enable auto-detection of this condition. The same is done for basically every other numeric value in the EDS importer. --- canopen/objectdictionary/eds.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 10f7599d..fa1933af 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -41,7 +41,7 @@ def import_eds(source, node_id): } if eds.has_section("Comments"): - linecount = eds.getint("Comments", "Lines") + linecount = int(eds.get("Comments", "Lines"), 0) od.comments = '\n'.join([ eds.get("Comments", "Line%i" % line) for line in range(1, linecount+1) From 52131ea168ee989bc7a98031ccc1612cbd5e652d Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Sat, 20 Nov 2021 13:17:24 +0100 Subject: [PATCH 077/199] GH: Update to PEP 517 build process --- .github/workflows/pythonpublish.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/pythonpublish.yml b/.github/workflows/pythonpublish.yml index d5f3859d..420d032a 100644 --- a/.github/workflows/pythonpublish.yml +++ b/.github/workflows/pythonpublish.yml @@ -21,11 +21,11 @@ jobs: - name: Install dependencies run: | python -m pip install --upgrade pip - pip install setuptools wheel twine + pip install setuptools wheel build twine - name: Build and publish env: TWINE_USERNAME: ${{ secrets.PYPI_USERNAME }} TWINE_PASSWORD: ${{ secrets.PYPI_PASSWORD }} run: | - python setup.py sdist bdist_wheel + python -m build twine upload dist/* From a83a6b83b1589f493b2205042ae114053d26f61e Mon Sep 17 00:00:00 2001 From: Henrik Brix Andersen Date: Wed, 1 Dec 2021 20:40:44 +0100 Subject: [PATCH 078/199] Add instructions for running the unit tests. (#280) --- README.rst | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/README.rst b/README.rst index c3c840d9..bdf66701 100644 --- a/README.rst +++ b/README.rst @@ -51,6 +51,10 @@ it in `develop mode`_:: $ cd canopen $ pip install -e . +Unit tests can be run using the pytest_ framework:: + + $ pip install pytest + $ pytest -v Documentation ------------- @@ -165,3 +169,4 @@ logging_ level: .. _Sphinx: http://www.sphinx-doc.org/ .. _develop mode: https://packaging.python.org/distributing/#working-in-development-mode .. _logging: https://docs.python.org/3/library/logging.html +.. _pytest: https://docs.pytest.org/ From 89bc634e352124bf48e1fdaba7c49253af389f0b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Valmantas=20Palik=C5=A1a?= Date: Wed, 22 Dec 2021 00:13:55 +0200 Subject: [PATCH 079/199] Fix canmatrix export (#287) Broken with canmatrix >= 0.9. --- canopen/pdo/base.py | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index c11eeaae..1685de62 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -88,8 +88,7 @@ def export(self, filename): if pdo_map.cob_id is None: continue frame = canmatrix.Frame(pdo_map.name, - Id=pdo_map.cob_id, - extended=0) + arbitration_id=pdo_map.cob_id) for var in pdo_map.map: is_signed = var.od.data_type in objectdictionary.SIGNED_TYPES is_float = var.od.data_type in objectdictionary.FLOAT_TYPES @@ -103,8 +102,8 @@ def export(self, filename): name = name.replace(" ", "_") name = name.replace(".", "_") signal = canmatrix.Signal(name, - startBit=var.offset, - signalSize=var.length, + start_bit=var.offset, + size=var.length, is_signed=is_signed, is_float=is_float, factor=var.od.factor, @@ -113,9 +112,9 @@ def export(self, filename): unit=var.od.unit) for value, desc in var.od.value_descriptions.items(): signal.addValues(value, desc) - frame.addSignal(signal) - frame.calcDLC() - db.frames.addFrame(frame) + frame.add_signal(signal) + frame.calc_dlc() + db.add_frame(frame) formats.dumpp({"": db}, filename) return db From a142fb583f236e0ea3c561af32f72ab1c423b95b Mon Sep 17 00:00:00 2001 From: Henrik Brix Andersen Date: Thu, 6 Jan 2022 16:12:24 +0100 Subject: [PATCH 080/199] Add 'relative' property for COB-ID vars relative to the node-ID (#281) --- canopen/objectdictionary/__init__.py | 2 ++ canopen/objectdictionary/eds.py | 2 ++ test/test_eds.py | 6 ++++++ 3 files changed, 10 insertions(+) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 2a2f9e92..f900f71c 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -304,6 +304,8 @@ def __init__(self, name: str, index: int, subindex: int = 0): self.max: Optional[int] = None #: Default value at start-up self.default: Optional[int] = None + #: Is the default value relative to the node-ID (only applies to COB-IDs) + self.relative = False #: The value of this variable stored in the object dictionary self.value: Optional[int] = None #: Data type according to the standard as an :class:`int` diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index fa1933af..afd94159 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -262,6 +262,8 @@ def build_variable(eds, section, node_id, index, subindex=0): if eds.has_option(section, "DefaultValue"): try: var.default_raw = eds.get(section, "DefaultValue") + if '$NODEID' in var.default_raw: + var.relative = True var.default = _convert_variable(node_id, var.data_type, eds.get(section, "DefaultValue")) except ValueError: pass diff --git a/test/test_eds.py b/test/test_eds.py index 6df65285..e5f6c89e 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -26,6 +26,12 @@ def test_variable(self): self.assertEqual(var.data_type, canopen.objectdictionary.UNSIGNED16) self.assertEqual(var.access_type, 'rw') self.assertEqual(var.default, 0) + self.assertFalse(var.relative) + + def test_relative_variable(self): + var = self.od['Receive PDO 0 Communication Parameter']['COB-ID use by RPDO 1'] + self.assertTrue(var.relative) + self.assertEqual(var.default, 512 + self.od.node_id) def test_record(self): record = self.od['Identity object'] From 60f064e55ab36142eac503456a9a894ac98bec9c Mon Sep 17 00:00:00 2001 From: Sudlav <101553227+Sudlav@users.noreply.github.com> Date: Wed, 16 Mar 2022 21:56:47 +0100 Subject: [PATCH 081/199] Corrected casing of BaudRate_xx keywords in DeviceInfo section of EDS files (#303) Co-authored-by: Andreas Valdusson --- canopen/objectdictionary/eds.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index afd94159..de4db99d 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -52,7 +52,7 @@ def import_eds(source, node_id): else: for rate in [10, 20, 50, 125, 250, 500, 800, 1000]: baudPossible = int( - eds.get("DeviceInfo", "Baudrate_%i" % rate, fallback='0'), 0) + eds.get("DeviceInfo", "BaudRate_%i" % rate, fallback='0'), 0) if baudPossible != 0: od.device_information.allowed_baudrates.add(rate*1000) @@ -407,7 +407,7 @@ def export_record(var, eds): for rate in od.device_information.allowed_baudrates.union( {10e3, 20e3, 50e3, 125e3, 250e3, 500e3, 800e3, 1000e3}): eds.set( - "DeviceInfo", "Baudrate_%i" % (rate/1000), + "DeviceInfo", "BaudRate_%i" % (rate/1000), int(rate in od.device_information.allowed_baudrates)) if device_commisioning and (od.bitrate or od.node_id): From 3d57a1c817d06634fcb57818fc7b5d5441908a99 Mon Sep 17 00:00:00 2001 From: Sudlav <101553227+Sudlav@users.noreply.github.com> Date: Fri, 18 Mar 2022 01:04:33 +0100 Subject: [PATCH 082/199] Making sure the FileInfo section is copied from the imported EDS to the exported EDS (#304) Co-authored-by: Andreas Valdusson --- canopen/objectdictionary/eds.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index de4db99d..0d0ffb7e 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -369,10 +369,10 @@ def export_record(var, eds): "EdsVersion": 4.2, } - file_info.setdefault("ModificationDate", defmtime.strftime("%m-%d-%Y")) - file_info.setdefault("ModificationTime", defmtime.strftime("%I:%m%p")) - for k, v in origFileInfo.items(): - file_info.setdefault(k, v) + file_info.setdefault("ModificationDate", defmtime.strftime("%m-%d-%Y")) + file_info.setdefault("ModificationTime", defmtime.strftime("%I:%m%p")) + for k, v in origFileInfo.items(): + file_info.setdefault(k, v) eds.add_section("FileInfo") for k, v in file_info.items(): From 074cbbc4d4c2c7803dc1e0151f6f534dbe44efc8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Filipe=20Silva?= Date: Fri, 18 Mar 2022 00:07:54 +0000 Subject: [PATCH 083/199] change missing Baudrate to BaudRate Following the changes done #304, #305 --- canopen/objectdictionary/eds.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 0d0ffb7e..872df234 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -85,7 +85,7 @@ def import_eds(source, node_id): pass if eds.has_section("DeviceComissioning"): - od.bitrate = int(eds.get("DeviceComissioning", "Baudrate")) * 1000 + od.bitrate = int(eds.get("DeviceComissioning", "BaudRate")) * 1000 od.node_id = int(eds.get("DeviceComissioning", "NodeID"), 0) for section in eds.sections(): @@ -413,7 +413,7 @@ def export_record(var, eds): if device_commisioning and (od.bitrate or od.node_id): eds.add_section("DeviceComissioning") if od.bitrate: - eds.set("DeviceComissioning", "Baudrate", int(od.bitrate / 1000)) + eds.set("DeviceComissioning", "BaudRate", int(od.bitrate / 1000)) if od.node_id: eds.set("DeviceComissioning", "NodeID", int(od.node_id)) From b3f67c1243d61a6816ae1f955ae3679306d85819 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Silva?= Date: Fri, 18 Mar 2022 00:34:53 +0000 Subject: [PATCH 084/199] fix: change Baudrate to BaudRate missing on .eds files the missing change on sample.eds was preventing the tests from running --- examples/eds/e35.eds | 20 ++++++++++---------- test/sample.eds | 2 +- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/examples/eds/e35.eds b/examples/eds/e35.eds index 4978b818..bf0baff0 100644 --- a/examples/eds/e35.eds +++ b/examples/eds/e35.eds @@ -18,14 +18,14 @@ ProductName=example ProductNumber=25 RevisionNumber=295 OrderCode=25 -Baudrate_10=1 -Baudrate_20=1 -Baudrate_50=1 -Baudrate_125=1 -Baudrate_250=1 -Baudrate_500=1 -Baudrate_800=0 -Baudrate_1000=1 +BaudRate_10=1 +BaudRate_20=1 +BaudRate_50=1 +BaudRate_125=1 +BaudRate_250=1 +BaudRate_500=1 +BaudRate_800=0 +BaudRate_1000=1 SimpleBootUpMaster=0 SimpleBootUpSlave=1 Granularity=8 @@ -243,7 +243,7 @@ HighLimit=0x7F ParameterValue=0x20 [2000sub2] -ParameterName=Baudrate +ParameterName=BaudRate ObjectType=0x7 DataType=0x0005 AccessType=rw @@ -324,7 +324,7 @@ LowLimit=0x1 HighLimit=0x7F [2001sub2] -ParameterName=Baudrate +ParameterName=BaudRate ObjectType=0x7 DataType=0x0005 AccessType=rw diff --git a/test/sample.eds b/test/sample.eds index b01a9ee5..bea6b9c3 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -32,7 +32,7 @@ LSS_Supported=0 [DeviceComissioning] NodeID=2 NodeName=Some name -Baudrate=500 +BaudRate=500 NetNumber=0 LSS_SerialNumber=0 From 33908247b1020975784062558e2e0174f4f7a52a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Filipe=20Silva?= Date: Thu, 28 Apr 2022 15:37:59 +0100 Subject: [PATCH 085/199] fix eds file example with valid VendorNumber #313 `ValueError: invalid literal for int() with base 0: '001'` The error happens while trying to parse DeviceInfo >> VendorNumber with leading zeros --- examples/eds/e35.eds | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/eds/e35.eds b/examples/eds/e35.eds index bf0baff0..17b24879 100644 --- a/examples/eds/e35.eds +++ b/examples/eds/e35.eds @@ -13,7 +13,7 @@ ModifiedBy=Manufacturer [DeviceInfo] VendorName=Manufacturer -VendorNumber=001 +VendorNumber=101 ProductName=example ProductNumber=25 RevisionNumber=295 From c7ad0a822a20a765f0fc7c43be0f4450b7a536ef Mon Sep 17 00:00:00 2001 From: Clark Willison Date: Mon, 23 May 2022 06:10:07 -0700 Subject: [PATCH 086/199] network: fix broken link to python-can readthedocs in docstring (#319) --- canopen/network.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/network.py b/canopen/network.py index 04acda18..00c21cf0 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -94,7 +94,7 @@ def connect(self, *args, **kwargs) -> "Network": Backend specific channel for the CAN interface. :param str bustype: Name of the interface. See - `python-can manual `__ + `python-can manual `__ for full list of supported interfaces. :param int bitrate: Bitrate in bit/s. From e3829fc4f0fe1fb0193c1f40ac2544195c942393 Mon Sep 17 00:00:00 2001 From: Samuel Lee <54152208+samsamfire@users.noreply.github.com> Date: Mon, 8 Aug 2022 21:34:28 +0200 Subject: [PATCH 087/199] Adding retransmit functionnality to sdo block download (#324) --- canopen/sdo/client.py | 38 +++++++++++++++++++++++++++++++++----- 1 file changed, 33 insertions(+), 5 deletions(-) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 0ed083e4..7e0f58bf 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -628,6 +628,8 @@ def __init__(self, sdo_client, index, subindex=0, size=None, request_crc_support self._seqno = 0 self._crc = sdo_client.crc_cls() self._last_bytes_sent = 0 + self._current_block = [] + self._retransmitting = False command = REQUEST_BLOCK_DOWNLOAD | INITIATE_BLOCK_TRANSFER if request_crc_support: command |= CRC_SUPPORTED @@ -708,7 +710,10 @@ def send(self, b, end=False): request[1:len(b) + 1] = b self.sdo_client.send_request(request) self.pos += len(b) - if self.crc_supported: + # Add the sent data to the current block buffer + self._current_block.append(b) + # Don't calculate crc if retransmitting + if self.crc_supported and not self._retransmitting: # Calculate CRC self._crc.process(b) if self._seqno >= self._blksize: @@ -731,14 +736,37 @@ def _block_ack(self): raise SdoCommunicationError("Server did not respond with a " "block download response") if ackseq != self._blksize: - self.sdo_client.abort(0x05040003) - raise SdoCommunicationError( - ("%d of %d sequences were received. " - "Retransmission is not supported yet.") % (ackseq, self._blksize)) + # Sequence error, try to retransmit + self._retransmit(ackseq, blksize) + # We should be back in sync + return + # Clear the current block buffer + self._current_block = [] logger.debug("All %d sequences were received successfully", ackseq) logger.debug("Server requested a block size of %d", blksize) self._blksize = blksize self._seqno = 0 + + def _retransmit(self, ackseq, blksize): + """Retransmit the failed block""" + logger.info(("%d of %d sequences were received. " + "Will start retransmission") % (ackseq, self._blksize)) + # Sub blocks betwen ackseq and end of corrupted block need to be resent + # Get the part of the block to resend + block = self._current_block[ackseq:] + # Go back to correct position in stream + self.pos = self.pos - (len(block) * 7) + # Reset the _current_block before starting the retransmission + self._current_block = [] + # Reset _seqno and update blksize + self._seqno = 0 + self._blksize = blksize + # We are retransmitting + self._retransmitting = True + # Resend the block + for b in block: + self.write(b) + self._retransmitting = False def close(self): """Closes the stream.""" From 62eb145920146386c3e0d024f7ddad52fdb18f97 Mon Sep 17 00:00:00 2001 From: Mark Truttmann <50853333+mtru32@users.noreply.github.com> Date: Mon, 24 Oct 2022 19:30:16 -0500 Subject: [PATCH 088/199] Fix Typo (#332) Assuming this should be through instead of trough --- canopen/node/remote.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/node/remote.py b/canopen/node/remote.py index 864ffeb3..5aca17ff 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -24,7 +24,7 @@ class RemoteNode(BaseNode): Object dictionary as either a path to a file, an ``ObjectDictionary`` or a file like object. :param load_od: - Enable the Object Dictionary to be sent trough SDO's to the remote + Enable the Object Dictionary to be sent through SDO's to the remote node at startup. """ From 559274fe5eecd8564c3a49330c21f9583fcdcaac Mon Sep 17 00:00:00 2001 From: Mihail Emelyanov Date: Sat, 19 Nov 2022 02:18:35 +0500 Subject: [PATCH 089/199] Fix typo (#334) --- canopen/lss.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/canopen/lss.py b/canopen/lss.py index d77f528f..d375e852 100644 --- a/canopen/lss.py +++ b/canopen/lss.py @@ -248,7 +248,7 @@ def fast_scan(self): :return: True if a slave is found. False if there is no candidate. - list is the LSS identities [vendor_id, product_code, revision_number, seerial_number] + list is the LSS identities [vendor_id, product_code, revision_number, serial_number] :rtype: bool, list """ lss_id = [0] * 4 @@ -265,21 +265,21 @@ def fast_scan(self): if not self.__send_fast_scan_message(lss_id[lss_sub], lss_bit_check, lss_sub, lss_next): lss_id[lss_sub] |= 1< Date: Sun, 11 Dec 2022 19:41:45 +0100 Subject: [PATCH 090/199] Check data length sdo server (#338) --- canopen/node/local.py | 6 ++++++ test/test_local.py | 10 ++++++++++ 2 files changed, 16 insertions(+) diff --git a/canopen/node/local.py b/canopen/node/local.py index ecce2dff..9e0a80b3 100644 --- a/canopen/node/local.py +++ b/canopen/node/local.py @@ -100,6 +100,12 @@ def set_data( if check_writable and not obj.writable: raise SdoAbortedError(0x06010002) + # Check length matches type (length of od variable is in bits) + if obj.data_type in objectdictionary.NUMBER_TYPES and ( + not 8 * len(data) == len(obj) + ): + raise SdoAbortedError(0x06070010) + # Try callbacks for callback in self._write_callbacks: callback(index=index, subindex=subindex, od=obj, data=data) diff --git a/test/test_local.py b/test/test_local.py index aed3a28c..f4119d44 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -71,6 +71,16 @@ def test_expedited_download(self): value = self.local_node.sdo[0x2004].raw self.assertEqual(value, 0xfeff) + def test_expedited_download_wrong_datatype(self): + # Try to write 32 bit in integer16 type + with self.assertRaises(canopen.SdoAbortedError) as error: + self.remote_node.sdo.download(0x2001, 0x0, bytes([10, 10, 10, 10])) + self.assertEqual(error.exception.code, 0x06070010) + # Try to write normal 16 bit word, should be ok + self.remote_node.sdo.download(0x2001, 0x0, bytes([10, 10])) + value = self.remote_node.sdo.upload(0x2001, 0x0) + self.assertEqual(value, bytes([10, 10])) + def test_segmented_download(self): self.remote_node.sdo[0x2000].raw = "Another cool device" value = self.local_node.sdo[0x2000].data From a59cc243d4947df487aeba739ff6ae2e280cf033 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Tue, 3 Jan 2023 15:18:48 +0100 Subject: [PATCH 091/199] Remove testing of older Python versions --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 3efb3261..2962fc69 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -11,7 +11,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - python-version: [3.6, '3.x'] + python-version: ['3.x'] steps: - uses: actions/checkout@v2 From 862147c21b7b297f505c158e34d3aad246bc6bb6 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Tue, 3 Jan 2023 15:42:18 +0100 Subject: [PATCH 092/199] Update GitHub workflows --- .github/workflows/pythonpackage.yml | 13 +++++++---- .github/workflows/pythonpublish.yml | 34 ++++++++++++++++++----------- 2 files changed, 30 insertions(+), 17 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 2962fc69..fd81104e 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -1,22 +1,27 @@ # This workflow will install Python dependencies, run tests and lint with a variety of Python versions -# For more information see: https://help.github.com/actions/language-and-framework-guides/using-python-with-github-actions +# For more information see: https://docs.github.com/en/actions/automating-builds-and-tests/building-and-testing-python name: Python package -on: [push, pull_request] +on: + push: + branches: [ "master" ] + pull_request: + branches: [ "master" ] jobs: build: runs-on: ubuntu-latest strategy: + fail-fast: false matrix: python-version: ['3.x'] steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - name: Set up Python ${{ matrix.python-version }} - uses: actions/setup-python@v1 + uses: actions/setup-python@v3 with: python-version: ${{ matrix.python-version }} - name: Install dependencies diff --git a/.github/workflows/pythonpublish.yml b/.github/workflows/pythonpublish.yml index 420d032a..bdaab28a 100644 --- a/.github/workflows/pythonpublish.yml +++ b/.github/workflows/pythonpublish.yml @@ -1,11 +1,19 @@ -# This workflows will upload a Python Package using Twine when a release is created -# For more information see: https://help.github.com/en/actions/language-and-framework-guides/using-python-with-github-actions#publishing-to-package-registries +# This workflow will upload a Python Package using Twine when a release is created +# For more information see: https://docs.github.com/en/actions/automating-builds-and-tests/building-and-testing-python#publishing-to-package-registries + +# This workflow uses actions that are not certified by GitHub. +# They are provided by a third-party and are governed by +# separate terms of service, privacy policy, and support +# documentation. name: Upload Python Package on: release: - types: [created] + types: [published] + +permissions: + contents: read jobs: deploy: @@ -13,19 +21,19 @@ jobs: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - name: Set up Python - uses: actions/setup-python@v1 + uses: actions/setup-python@v3 with: python-version: '3.x' - name: Install dependencies run: | python -m pip install --upgrade pip - pip install setuptools wheel build twine - - name: Build and publish - env: - TWINE_USERNAME: ${{ secrets.PYPI_USERNAME }} - TWINE_PASSWORD: ${{ secrets.PYPI_PASSWORD }} - run: | - python -m build - twine upload dist/* + pip install build + - name: Build package + run: python -m build + - name: Publish package + uses: pypa/gh-action-pypi-publish@27b31702a0e7fc50959f5ad993c78deac1bdfc29 + with: + user: __token__ + password: ${{ secrets.PYPI_API_TOKEN }} From 52fbafbaad7cf6d6edea2a2aaae39c9c78f1c892 Mon Sep 17 00:00:00 2001 From: Christian Sandberg Date: Tue, 3 Jan 2023 16:09:09 +0100 Subject: [PATCH 093/199] Fix Readthedocs --- .readthedocs.yaml | 25 +++++++++++++++++++++++++ doc/requirements.txt | 2 ++ 2 files changed, 27 insertions(+) create mode 100644 .readthedocs.yaml create mode 100644 doc/requirements.txt diff --git a/.readthedocs.yaml b/.readthedocs.yaml new file mode 100644 index 00000000..81bb6b50 --- /dev/null +++ b/.readthedocs.yaml @@ -0,0 +1,25 @@ +# .readthedocs.yaml +# Read the Docs configuration file +# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details + +version: 2 + +build: + os: ubuntu-22.04 + tools: + python: "3" + +# Build documentation in the docs/ directory with Sphinx +sphinx: + configuration: doc/conf.py + +# If using Sphinx, optionally build your docs in additional formats such as PDF +# formats: +# - pdf + +# Optionally declare the Python requirements required to build your docs +python: + install: + - method: pip + path: . + - requirements: doc/requirements.txt diff --git a/doc/requirements.txt b/doc/requirements.txt new file mode 100644 index 00000000..2ca4275e --- /dev/null +++ b/doc/requirements.txt @@ -0,0 +1,2 @@ +sphinx +sphinx-autodoc-typehints From fd226e3b8c7fe09f933ed10cc42bec8c085366aa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Frieder=20Sch=C3=BCler?= Date: Fri, 24 Feb 2023 16:52:51 +0100 Subject: [PATCH 094/199] Fixed HighLimit and LowLimit for SIGNED values in EDS (#345) * Fixed incorrect min (LowLImit) and max (HighLimit) values when using signed integer types. * Fixed min/max for non-signed datatypes and added tests * Removed type hints --- canopen/objectdictionary/eds.py | 42 +++++++++++++-- test/sample.eds | 36 +++++++++++++ test/test_eds.py | 92 ++++++++++++++++++++------------- 3 files changed, 128 insertions(+), 42 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 872df234..c1c54d78 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -1,7 +1,9 @@ -import re -import io -import logging import copy +import logging +import re + +from canopen.objectdictionary import datatypes + try: from configparser import RawConfigParser, NoOptionError, NoSectionError except ImportError: @@ -190,6 +192,28 @@ def import_from_node(node_id, network): return od +def _calc_bit_length(data_type): + if data_type == datatypes.INTEGER8: + return 8 + elif data_type == datatypes.INTEGER16: + return 16 + elif data_type == datatypes.INTEGER32: + return 32 + elif data_type == datatypes.INTEGER64: + return 64 + else: + raise ValueError(f"Invalid data_type '{data_type}', expecting a signed integer data_type.") + + +def _signed_int_from_hex(hex_str, bit_length): + number = int(hex_str, 0) + limit = ((1 << bit_length - 1) - 1) + if number > limit: + return limit - number + else: + return number + + def _convert_variable(node_id, var_type, value): if var_type in (objectdictionary.OCTET_STRING, objectdictionary.DOMAIN): return bytes.fromhex(value) @@ -251,12 +275,20 @@ def build_variable(eds, section, node_id, index, subindex=0): if eds.has_option(section, "LowLimit"): try: - var.min = int(eds.get(section, "LowLimit"), 0) + min_string = eds.get(section, "LowLimit") + if var.data_type in objectdictionary.SIGNED_TYPES: + var.min = _signed_int_from_hex(min_string, _calc_bit_length(var.data_type)) + else: + var.min = int(min_string, 0) except ValueError: pass if eds.has_option(section, "HighLimit"): try: - var.max = int(eds.get(section, "HighLimit"), 0) + max_string = eds.get(section, "HighLimit") + if var.data_type in objectdictionary.SIGNED_TYPES: + var.max = _signed_int_from_hex(max_string, _calc_bit_length(var.data_type)) + else: + var.max = int(max_string, 0) except ValueError: pass if eds.has_option(section, "DefaultValue"): diff --git a/test/sample.eds b/test/sample.eds index bea6b9c3..671a559e 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -902,3 +902,39 @@ DataType=0x0008 AccessType=ro DefaultValue=0 PDOMapping=1 + +[3020] +ParameterName=INTEGER8 only positive values +ObjectType=0x7 +DataType=0x02 +AccessType=rw +HighLimit=0x7F +LowLimit=0x00 +PDOMapping=0 + +[3021] +ParameterName=UNSIGNED8 value range +2 to +10 +ObjectType=0x7 +DataType=0x05 +AccessType=rw +HighLimit=0x0A +LowLimit=0x02 +PDOMapping=0 + +[3030] +ParameterName=INTEGER32 only negative values +ObjectType=0x7 +DataType=0x04 +AccessType=rw +HighLimit=0x00000000 +LowLimit=0xFFFFFFFF +PDOMapping=0 + +[3040] +ParameterName=INTEGER64 value range -10 to +10 +ObjectType=0x7 +DataType=0x15 +AccessType=rw +HighLimit=0x000000000000000A +LowLimit=0x8000000000000009 +PDOMapping=0 diff --git a/test/test_eds.py b/test/test_eds.py index e5f6c89e..2a6d5098 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -4,6 +4,7 @@ EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') + class TestEDS(unittest.TestCase): def setUp(self): @@ -47,6 +48,20 @@ def test_record(self): self.assertEqual(var.data_type, canopen.objectdictionary.UNSIGNED32) self.assertEqual(var.access_type, 'ro') + def test_record_with_limits(self): + int8 = self.od[0x3020] + self.assertEqual(int8.min, 0) + self.assertEqual(int8.max, 127) + uint8 = self.od[0x3021] + self.assertEqual(uint8.min, 2) + self.assertEqual(uint8.max, 10) + int32 = self.od[0x3030] + self.assertEqual(int32.min, -2147483648) + self.assertEqual(int32.max, 0) + int64 = self.od[0x3040] + self.assertEqual(int64.min, -10) + self.assertEqual(int64.max, +10) + def test_array_compact_subobj(self): array = self.od[0x1003] self.assertIsInstance(array, canopen.objectdictionary.Array) @@ -98,18 +113,16 @@ def test_dummy_variable_undefined(self): def test_comments(self): self.assertEqual(self.od.comments, -""" + """ |-------------| | Don't panic | |-------------| -""".strip() - ) - +""".strip()) def test_export_eds(self): import tempfile for doctype in {"eds", "dcf"}: - with tempfile.NamedTemporaryFile(suffix="."+doctype, mode="w+") as tempeds: + with tempfile.NamedTemporaryFile(suffix="." + doctype, mode="w+") as tempeds: print("exporting %s to " % doctype + tempeds.name) canopen.export_od(self.od, tempeds, doc_type=doctype) tempeds.flush() @@ -117,54 +130,59 @@ def test_export_eds(self): for index in exported_od: self.assertIn(exported_od[index].name, self.od) - self.assertIn(index , self.od) + self.assertIn(index, self.od) for index in self.od: if index < 0x0008: # ignore dummies continue self.assertIn(self.od[index].name, exported_od) - self.assertIn(index , exported_od) + self.assertIn(index, exported_od) - actual_object = exported_od[index] - expected_object = self.od[index] + actual_object = exported_od[index] + expected_object = self.od[index] self.assertEqual(type(actual_object), type(expected_object)) self.assertEqual(actual_object.name, expected_object.name) if type(actual_object) is canopen.objectdictionary.Variable: expected_vars = [expected_object] - actual_vars = [actual_object ] - else : + actual_vars = [actual_object] + else: expected_vars = [expected_object[idx] for idx in expected_object] - actual_vars = [actual_object [idx] for idx in actual_object] + actual_vars = [actual_object[idx] for idx in actual_object] for prop in [ - "allowed_baudrates", - "vendor_name", - "vendor_number", - "product_name", - "product_number", - "revision_number", - "order_code", - "simple_boot_up_master", - "simple_boot_up_slave", - "granularity", - "dynamic_channels_supported", - "group_messaging", - "nr_of_RXPDO", - "nr_of_TXPDO", - "LSS_supported", + "allowed_baudrates", + "vendor_name", + "vendor_number", + "product_name", + "product_number", + "revision_number", + "order_code", + "simple_boot_up_master", + "simple_boot_up_slave", + "granularity", + "dynamic_channels_supported", + "group_messaging", + "nr_of_RXPDO", + "nr_of_TXPDO", + "LSS_supported", ]: - self.assertEqual(getattr(self.od.device_information, prop), getattr(exported_od.device_information, prop), f"prop {prop!r} mismatch on DeviceInfo") - - - for evar,avar in zip(expected_vars,actual_vars): - self. assertEqual(getattr(avar, "data_type" , None) , getattr(evar,"data_type" ,None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) - self. assertEqual(getattr(avar, "default_raw", None) , getattr(evar,"default_raw",None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) - self. assertEqual(getattr(avar, "min" , None) , getattr(evar,"min" ,None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) - self. assertEqual(getattr(avar, "max" , None) , getattr(evar,"max" ,None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) + self.assertEqual(getattr(self.od.device_information, prop), + getattr(exported_od.device_information, prop), + f"prop {prop!r} mismatch on DeviceInfo") + + for evar, avar in zip(expected_vars, actual_vars): + self.assertEqual(getattr(avar, "data_type", None), getattr(evar, "data_type", None), + " mismatch on %04X:%X" % (evar.index, evar.subindex)) + self.assertEqual(getattr(avar, "default_raw", None), getattr(evar, "default_raw", None), + " mismatch on %04X:%X" % (evar.index, evar.subindex)) + self.assertEqual(getattr(avar, "min", None), getattr(evar, "min", None), + " mismatch on %04X:%X" % (evar.index, evar.subindex)) + self.assertEqual(getattr(avar, "max", None), getattr(evar, "max", None), + " mismatch on %04X:%X" % (evar.index, evar.subindex)) if doctype == "dcf": - self.assertEqual(getattr(avar, "value" , None) , getattr(evar,"value" ,None) , " mismatch on %04X:%X"%(evar.index, evar.subindex)) + self.assertEqual(getattr(avar, "value", None), getattr(evar, "value", None), + " mismatch on %04X:%X" % (evar.index, evar.subindex)) self.assertEqual(self.od.comments, exported_od.comments) - From 64772dc45cfdfd924f6de0bb6d58b66a5d0c1fba Mon Sep 17 00:00:00 2001 From: Alflanker94 <61652913+Alflanker94@users.noreply.github.com> Date: Thu, 2 Mar 2023 06:51:22 +0100 Subject: [PATCH 095/199] Update profiles.rst (#348) --- doc/profiles.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/profiles.rst b/doc/profiles.rst index 1ef5ab58..9fdc1d29 100644 --- a/doc/profiles.rst +++ b/doc/profiles.rst @@ -66,7 +66,7 @@ class :attr:`.state` attribute can be read and set (command) by a string:: # command a state (an SDO message will be called) some_node.state = 'SWITCHED ON' # read the current state - some_node.state = 'SWITCHED ON' + some_node.state Available states: From 5efd42181f01daa94af80540027d038938251699 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Mon, 3 Apr 2023 08:11:38 +0200 Subject: [PATCH 096/199] Change type() into isinstance() (#357) --- canopen/objectdictionary/__init__.py | 2 +- canopen/objectdictionary/eds.py | 16 ++++++++-------- test/test_eds.py | 2 +- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index f900f71c..225c3f25 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -29,7 +29,7 @@ def export_od(od, dest:Union[str,TextIO,None]=None, doc_type:Optional[str]=None) """ doctypes = {"eds", "dcf"} - if type(dest) is str: + if isinstance(dest, str): if doc_type is None: for t in doctypes: if dest.endswith(f".{t}"): diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index c1c54d78..f6fdd2b8 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -323,11 +323,11 @@ def export_dcf(od, dest=None, fileInfo={}): def export_eds(od, dest=None, file_info={}, device_commisioning=False): def export_object(obj, eds): - if type(obj) is objectdictionary.Variable: + if isinstance(obj, objectdictionary.Variable): return export_variable(obj, eds) - if type(obj) is objectdictionary.Record: + if isinstance(obj, objectdictionary.Record): return export_record(obj, eds) - if type(obj) is objectdictionary.Array: + if isinstance(obj, objectdictionary.Array): return export_array(obj, eds) def export_common(var, eds, section): @@ -337,7 +337,7 @@ def export_common(var, eds, section): eds.set(section, "StorageLocation", var.storage_location) def export_variable(var, eds): - if type(var.parent) is objectdictionary.ObjectDictionary: + if isinstance(var.parent, objectdictionary.ObjectDictionary): # top level variable section = "%04X" % var.index else: @@ -376,7 +376,7 @@ def export_record(var, eds): section = "%04X" % var.index export_common(var, eds, section) eds.set(section, "SubNumber", "0x%X" % len(var.subindices)) - ot = RECORD if type(var) is objectdictionary.Record else ARR + ot = RECORD if isinstance(var, objectdictionary.Record) else ARR eds.set(section, "ObjectType", "0x%X" % ot) for i in var: export_variable(var[i], eds) @@ -428,11 +428,11 @@ def export_record(var, eds): ("LSS_Supported", "LSS_supported"), ]: val = getattr(od.device_information, odprop, None) - if type(val) is None: + if val is None: continue - elif type(val) is str: + elif isinstance(val, str): eds.set("DeviceInfo", eprop, val) - elif type(val) in (int, bool): + elif isinstance(val, (int, bool)): eds.set("DeviceInfo", eprop, int(val)) # we are also adding out of spec baudrates here. diff --git a/test/test_eds.py b/test/test_eds.py index 2a6d5098..c34df381 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -144,7 +144,7 @@ def test_export_eds(self): self.assertEqual(type(actual_object), type(expected_object)) self.assertEqual(actual_object.name, expected_object.name) - if type(actual_object) is canopen.objectdictionary.Variable: + if isinstance(actual_object, canopen.objectdictionary.Variable): expected_vars = [expected_object] actual_vars = [actual_object] else: From 61294f9b5e8b085490df138cfef0472c47398e77 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Wed, 5 Apr 2023 08:09:15 +0200 Subject: [PATCH 097/199] Remove use of object (#361) --- canopen/emcy.py | 4 ++-- canopen/lss.py | 2 +- canopen/network.py | 7 ++++--- canopen/nmt.py | 2 +- canopen/node/base.py | 2 +- canopen/objectdictionary/__init__.py | 2 +- canopen/pdo/base.py | 2 +- canopen/profiles/p402.py | 6 +++--- canopen/sdo/base.py | 2 +- canopen/sync.py | 2 +- canopen/timestamp.py | 2 +- canopen/variable.py | 2 +- 12 files changed, 18 insertions(+), 17 deletions(-) diff --git a/canopen/emcy.py b/canopen/emcy.py index 8964262e..118ede4f 100644 --- a/canopen/emcy.py +++ b/canopen/emcy.py @@ -10,7 +10,7 @@ logger = logging.getLogger(__name__) -class EmcyConsumer(object): +class EmcyConsumer: def __init__(self): #: Log of all received EMCYs for this node @@ -79,7 +79,7 @@ def wait( return emcy -class EmcyProducer(object): +class EmcyProducer: def __init__(self, cob_id: int): self.network = None diff --git a/canopen/lss.py b/canopen/lss.py index d375e852..9dee3147 100644 --- a/canopen/lss.py +++ b/canopen/lss.py @@ -65,7 +65,7 @@ ] -class LssMaster(object): +class LssMaster: """The Master of Layer Setting Services""" LSS_TX_COBID = 0x7E5 diff --git a/canopen/network.py b/canopen/network.py index 00c21cf0..51137b22 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -13,8 +13,9 @@ except ImportError: # Do not fail if python-can is not installed can = None - Listener = object CanError = Exception + class Listener: + """ Dummy listener """ from .node import RemoteNode, LocalNode from .sync import SyncProducer @@ -282,7 +283,7 @@ def __len__(self) -> int: return len(self.nodes) -class PeriodicMessageTask(object): +class PeriodicMessageTask: """ Task object to transmit a message periodically using python-can's CyclicSendTask @@ -359,7 +360,7 @@ def on_message_received(self, msg): logger.error(str(e)) -class NodeScanner(object): +class NodeScanner: """Observes which nodes are present on the bus. Listens for the following messages: diff --git a/canopen/nmt.py b/canopen/nmt.py index 09963de0..7a718d5d 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -39,7 +39,7 @@ } -class NmtBase(object): +class NmtBase: """ Can set the state of the node it controls using NMT commands and monitor the current state using the heartbeat protocol. diff --git a/canopen/node/base.py b/canopen/node/base.py index d87e5517..29d298e6 100644 --- a/canopen/node/base.py +++ b/canopen/node/base.py @@ -2,7 +2,7 @@ from .. import objectdictionary -class BaseNode(object): +class BaseNode: """A CANopen node. :param node_id: diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 225c3f25..793b8c4c 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -266,7 +266,7 @@ def add_member(self, variable: "Variable") -> None: self.names[variable.name] = variable -class Variable(object): +class Variable: """Simple variable.""" STRUCT_TYPES = { diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 1685de62..d7160738 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -156,7 +156,7 @@ def __len__(self) -> int: return len(self.maps) -class Map(object): +class Map: """One message which can have up to 8 bytes of variables mapped.""" def __init__(self, pdo_node, com_record, map_array): diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 12ccdd3b..915621d7 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -7,7 +7,7 @@ logger = logging.getLogger(__name__) -class State402(object): +class State402: # Controlword (0x6040) commands CW_OPERATION_ENABLED = 0x000F CW_SHUTDOWN = 0x0006 @@ -101,7 +101,7 @@ def next_state_indirect(_from): return next_state -class OperationMode(object): +class OperationMode: NO_MODE = 0 PROFILED_POSITION = 1 VELOCITY = 2 @@ -155,7 +155,7 @@ class OperationMode(object): } -class Homing(object): +class Homing: CW_START = 0x10 CW_HALT = 0x100 diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 3c3d0bbe..622eed14 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -9,7 +9,7 @@ from .. import variable -class CrcXmodem(object): +class CrcXmodem: """Mimics CrcXmodem from crccheck.""" def __init__(self): diff --git a/canopen/sync.py b/canopen/sync.py index 32248279..6e583b04 100644 --- a/canopen/sync.py +++ b/canopen/sync.py @@ -3,7 +3,7 @@ from typing import Optional -class SyncProducer(object): +class SyncProducer: """Transmits a SYNC message periodically.""" #: COB-ID of the SYNC message diff --git a/canopen/timestamp.py b/canopen/timestamp.py index e96f7576..f3004da2 100644 --- a/canopen/timestamp.py +++ b/canopen/timestamp.py @@ -10,7 +10,7 @@ TIME_OF_DAY_STRUCT = struct.Struct(" Date: Thu, 6 Apr 2023 19:25:50 +0200 Subject: [PATCH 098/199] Use with contexts for opens (#356) --- canopen/objectdictionary/__init__.py | 4 ++++ canopen/objectdictionary/eds.py | 10 +++++--- canopen/sdo/client.py | 13 +++++------ doc/sdo.rst | 34 ++++++++++++---------------- test/test_eds.py | 3 ++- test/test_local.py | 10 ++++---- test/test_sdo.py | 19 +++++++--------- 7 files changed, 48 insertions(+), 45 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 793b8c4c..70816515 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -48,6 +48,10 @@ def export_od(od, dest:Union[str,TextIO,None]=None, doc_type:Optional[str]=None) from . import eds return eds.export_dcf(od, dest) + # If dest is opened in this fn, it should be closed + if type(dest) is str: + dest.close() + def import_od( source: Union[str, TextIO, None], diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index f6fdd2b8..c595ed66 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -33,7 +33,11 @@ def import_eds(source, node_id): except AttributeError: # Python 2 eds.readfp(fp) - fp.close() + finally: + # Only close object if opened in this fn + if not hasattr(source, "read"): + fp.close() + od = objectdictionary.ObjectDictionary() if eds.has_section("FileInfo"): @@ -181,8 +185,8 @@ def import_from_node(node_id, network): network.subscribe(0x580 + node_id, sdo_client.on_response) # Create file like object for Store EDS variable try: - eds_fp = sdo_client.open(0x1021, 0, "rt") - od = import_eds(eds_fp, node_id) + with sdo_client.open(0x1021, 0, "rt") as eds_fp: + od = import_eds(eds_fp, node_id) except Exception as e: logger.error("No object dictionary could be loaded for node %d: %s", node_id, e) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 7e0f58bf..7faa103a 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -114,9 +114,9 @@ def upload(self, index: int, subindex: int) -> bytes: :raises canopen.SdoAbortedError: When node responds with an error. """ - fp = self.open(index, subindex, buffering=0) - size = fp.size - data = fp.read() + with self.open(index, subindex, buffering=0) as fp: + size = fp.size + data = fp.read() if size is None: # Node did not specify how many bytes to use # Try to find out using Object Dictionary @@ -155,10 +155,9 @@ def download( :raises canopen.SdoAbortedError: When node responds with an error. """ - fp = self.open(index, subindex, "wb", buffering=7, size=len(data), - force_segment=force_segment) - fp.write(data) - fp.close() + with self.open(index, subindex, "wb", buffering=7, size=len(data), + force_segment=force_segment) as fp: + fp.write(data) def open(self, index, subindex=0, mode="rb", encoding="ascii", buffering=1024, size=None, block_transfer=False, force_segment=False, request_crc_support=True): diff --git a/doc/sdo.rst b/doc/sdo.rst index bfc78c25..c0db4ca5 100644 --- a/doc/sdo.rst +++ b/doc/sdo.rst @@ -72,14 +72,11 @@ Variables can be opened as readable or writable file objects which can be useful when dealing with large amounts of data:: # Open the Store EDS variable as a file like object - infile = node.sdo[0x1021].open('r', encoding='ascii') - # Open a file for writing to - outfile = open('out.eds', 'w', encoding='ascii') - # Iteratively read lines from node and write to file - outfile.writelines(infile) - # Clean-up - infile.close() - outfile.close() + with node.sdo[0x1021].open('r', encoding='ascii') as infile, + open('out.eds', 'w', encoding='ascii') as outfile: + + # Iteratively read lines from node and write to file + outfile.writelines(infile) Most APIs accepting file objects should also be able to accept this. @@ -88,17 +85,16 @@ server supports it. This is done through the file object interface:: FIRMWARE_PATH = '/path/to/firmware.bin' FILESIZE = os.path.getsize(FIRMWARE_PATH) - infile = open(FIRMWARE_PATH, 'rb') - outfile = node.sdo['Firmware'].open('wb', size=FILESIZE, block_transfer=True) - - # Iteratively transfer data without having to read all into memory - while True: - data = infile.read(1024) - if not data: - break - outfile.write(data) - infile.close() - outfile.close() + + with open(FIRMWARE_PATH, 'rb') as infile, + node.sdo['Firmware'].open('wb', size=FILESIZE, block_transfer=True) as outfile: + + # Iteratively transfer data without having to read all into memory + while True: + data = infile.read(1024) + if not data: + break + outfile.write(data) .. warning:: Block transfer is still in experimental stage! diff --git a/test/test_eds.py b/test/test_eds.py index c34df381..4977dc10 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -15,7 +15,8 @@ def test_load_nonexisting_file(self): canopen.import_od('/path/to/wrong_file.eds') def test_load_file_object(self): - od = canopen.import_od(open(EDS_PATH)) + with open(EDS_PATH) as fp: + od = canopen.import_od(fp) self.assertTrue(len(od) > 0) def test_variable(self): diff --git a/test/test_local.py b/test/test_local.py index f4119d44..493cef1b 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -40,7 +40,8 @@ def test_expedited_upload(self): def test_block_upload_switch_to_expedite_upload(self): with self.assertRaises(canopen.SdoCommunicationError) as context: - self.remote_node.sdo[0x1008].open('r', block_transfer=True) + with self.remote_node.sdo[0x1008].open('r', block_transfer=True) as fp: + pass # We get this since the sdo client don't support the switch # from block upload to expedite upload self.assertEqual("Unexpected response 0x41", str(context.exception)) @@ -48,9 +49,10 @@ def test_block_upload_switch_to_expedite_upload(self): def test_block_download_not_supported(self): data = b"TEST DEVICE" with self.assertRaises(canopen.SdoAbortedError) as context: - self.remote_node.sdo[0x1008].open('wb', - size=len(data), - block_transfer=True) + with self.remote_node.sdo[0x1008].open('wb', + size=len(data), + block_transfer=True) as fp: + pass self.assertEqual(context.exception.code, 0x05040001) def test_expedited_upload_default_value_visible_string(self): diff --git a/test/test_sdo.py b/test/test_sdo.py index 67115499..c0ba086b 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -110,10 +110,9 @@ def test_block_download(self): (RX, b'\xa1\x00\x00\x00\x00\x00\x00\x00') ] data = b'A really really long string...' - fp = self.network[2].sdo['Writable string'].open( - 'wb', size=len(data), block_transfer=True) - fp.write(data) - fp.close() + with self.network[2].sdo['Writable string'].open( + 'wb', size=len(data), block_transfer=True) as fp: + fp.write(data) def test_block_upload(self): self.data = [ @@ -128,9 +127,8 @@ def test_block_upload(self): (RX, b'\xc9\x40\xe1\x00\x00\x00\x00\x00'), (TX, b'\xa1\x00\x00\x00\x00\x00\x00\x00') ] - fp = self.network[2].sdo[0x1008].open('r', block_transfer=True) - data = fp.read() - fp.close() + with self.network[2].sdo[0x1008].open('r', block_transfer=True) as fp: + data = fp.read() self.assertEqual(data, 'Tiny Node - Mega Domains !') def test_writable_file(self): @@ -144,10 +142,9 @@ def test_writable_file(self): (TX, b'\x0f\x00\x00\x00\x00\x00\x00\x00'), (RX, b'\x20\x00\x20\x00\x00\x00\x00\x00') ] - fp = self.network[2].sdo['Writable string'].open('wb') - fp.write(b'1234') - fp.write(b'56789') - fp.close() + with self.network[2].sdo['Writable string'].open('wb') as fp: + fp.write(b'1234') + fp.write(b'56789') self.assertTrue(fp.closed) # Write on closed file with self.assertRaises(ValueError): From 9cdfe9b476f3b265d08b9fbb4a1fd4537c19f54a Mon Sep 17 00:00:00 2001 From: Samuel Lee <54152208+samsamfire@users.noreply.github.com> Date: Sat, 8 Apr 2023 19:24:08 +0100 Subject: [PATCH 099/199] - Remove old callbacks if re-adding a node with the same id (#342) --- canopen/network.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/canopen/network.py b/canopen/network.py index 51137b22..e348324c 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -269,6 +269,9 @@ def __getitem__(self, node_id: int) -> Union[RemoteNode, LocalNode]: def __setitem__(self, node_id: int, node: Union[RemoteNode, LocalNode]): assert node_id == node.id + if node_id in self.nodes: + # Remove old callbacks + self.nodes[node_id].remove_network() self.nodes[node_id] = node node.associate_network(self) From 9e303f22967efc1dac34fcaa91864681e6b0a0a6 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Sat, 8 Apr 2023 20:43:25 +0200 Subject: [PATCH 100/199] Import cleanups (#362) * Use absolute `canopen` instead of relative imports * Ensure canopen imports after system imports * Fix isinstance bug in TPDO.stop() * Change const from objectdictionary.* to datatypes.* in objectdictionary.eds.py for consistency * Save typing by using ObjectDictionary instead of objectdictionary.ObjectDictionary --- canopen/__init__.py | 12 +++++------ canopen/network.py | 14 ++++++------- canopen/nmt.py | 2 -- canopen/node/__init__.py | 4 ++-- canopen/node/base.py | 10 ++++------ canopen/node/local.py | 15 +++++++------- canopen/node/remote.py | 22 +++++++++----------- canopen/objectdictionary/__init__.py | 10 +++++----- canopen/objectdictionary/eds.py | 30 ++++++++++++++-------------- canopen/objectdictionary/epf.py | 4 +++- canopen/pdo/__init__.py | 11 +++++----- canopen/pdo/base.py | 6 +++--- canopen/profiles/p402.py | 5 +++-- canopen/sdo/__init__.py | 8 ++++---- canopen/sdo/base.py | 13 ++++++------ canopen/sdo/client.py | 13 ++++++------ canopen/sdo/server.py | 6 +++--- canopen/sync.py | 2 -- canopen/variable.py | 2 +- 19 files changed, 91 insertions(+), 98 deletions(-) diff --git a/canopen/__init__.py b/canopen/__init__.py index a63ecb83..ee5ff7b5 100644 --- a/canopen/__init__.py +++ b/canopen/__init__.py @@ -1,10 +1,10 @@ -from .network import Network, NodeScanner -from .node import RemoteNode, LocalNode -from .sdo import SdoCommunicationError, SdoAbortedError -from .objectdictionary import import_od, export_od, ObjectDictionary, ObjectDictionaryError -from .profiles.p402 import BaseNode402 +from canopen.network import Network, NodeScanner +from canopen.node import RemoteNode, LocalNode +from canopen.sdo import SdoCommunicationError, SdoAbortedError +from canopen.objectdictionary import import_od, export_od, ObjectDictionary, ObjectDictionaryError +from canopen.profiles.p402 import BaseNode402 try: - from ._version import version as __version__ + from canopen._version import version as __version__ except ImportError: # package is not installed __version__ = "unknown" diff --git a/canopen/network.py b/canopen/network.py index e348324c..7768795d 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -17,13 +17,13 @@ class Listener: """ Dummy listener """ -from .node import RemoteNode, LocalNode -from .sync import SyncProducer -from .timestamp import TimeProducer -from .nmt import NmtMaster -from .lss import LssMaster -from .objectdictionary.eds import import_from_node -from .objectdictionary import ObjectDictionary +from canopen.node import RemoteNode, LocalNode +from canopen.sync import SyncProducer +from canopen.timestamp import TimeProducer +from canopen.nmt import NmtMaster +from canopen.lss import LssMaster +from canopen.objectdictionary.eds import import_from_node +from canopen.objectdictionary import ObjectDictionary logger = logging.getLogger(__name__) diff --git a/canopen/nmt.py b/canopen/nmt.py index 7a718d5d..98d8ea25 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -4,8 +4,6 @@ import time from typing import Callable, Optional -from .network import CanError - logger = logging.getLogger(__name__) NMT_STATES = { diff --git a/canopen/node/__init__.py b/canopen/node/__init__.py index 98bc707b..31fed19e 100644 --- a/canopen/node/__init__.py +++ b/canopen/node/__init__.py @@ -1,2 +1,2 @@ -from .remote import RemoteNode -from .local import LocalNode +from canopen.node.remote import RemoteNode +from canopen.node.local import LocalNode diff --git a/canopen/node/base.py b/canopen/node/base.py index 29d298e6..bf72d959 100644 --- a/canopen/node/base.py +++ b/canopen/node/base.py @@ -1,5 +1,5 @@ from typing import TextIO, Union -from .. import objectdictionary +from canopen.objectdictionary import ObjectDictionary, import_od class BaseNode: @@ -15,14 +15,12 @@ class BaseNode: def __init__( self, node_id: int, - object_dictionary: Union[objectdictionary.ObjectDictionary, str, TextIO], + object_dictionary: Union[ObjectDictionary, str, TextIO], ): self.network = None - if not isinstance(object_dictionary, - objectdictionary.ObjectDictionary): - object_dictionary = objectdictionary.import_od( - object_dictionary, node_id) + if not isinstance(object_dictionary, ObjectDictionary): + object_dictionary = import_od(object_dictionary, node_id) self.object_dictionary = object_dictionary self.id = node_id or self.object_dictionary.node_id diff --git a/canopen/node/local.py b/canopen/node/local.py index 9e0a80b3..b36cf3eb 100644 --- a/canopen/node/local.py +++ b/canopen/node/local.py @@ -1,12 +1,13 @@ import logging from typing import Dict, Union -from .base import BaseNode -from ..sdo import SdoServer, SdoAbortedError -from ..pdo import PDO, TPDO, RPDO -from ..nmt import NmtSlave -from ..emcy import EmcyProducer -from .. import objectdictionary +from canopen.node.base import BaseNode +from canopen.sdo import SdoServer, SdoAbortedError +from canopen.pdo import PDO, TPDO, RPDO +from canopen.nmt import NmtSlave +from canopen.emcy import EmcyProducer +from canopen.objectdictionary import ObjectDictionary +from canopen import objectdictionary logger = logging.getLogger(__name__) @@ -16,7 +17,7 @@ class LocalNode(BaseNode): def __init__( self, node_id: int, - object_dictionary: Union[objectdictionary.ObjectDictionary, str], + object_dictionary: Union[ObjectDictionary, str], ): super(LocalNode, self).__init__(node_id, object_dictionary) diff --git a/canopen/node/remote.py b/canopen/node/remote.py index 5aca17ff..8e4025d7 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -1,16 +1,12 @@ import logging from typing import Union, TextIO -from ..sdo import SdoClient -from ..nmt import NmtMaster -from ..emcy import EmcyConsumer -from ..pdo import TPDO, RPDO, PDO -from ..objectdictionary import Record, Array, Variable -from .base import BaseNode - -import canopen - -from canopen import objectdictionary +from canopen.sdo import SdoClient, SdoCommunicationError, SdoAbortedError +from canopen.nmt import NmtMaster +from canopen.emcy import EmcyConsumer +from canopen.pdo import TPDO, RPDO, PDO +from canopen.objectdictionary import Record, Array, Variable, ObjectDictionary +from canopen.node.base import BaseNode logger = logging.getLogger(__name__) @@ -31,7 +27,7 @@ class RemoteNode(BaseNode): def __init__( self, node_id: int, - object_dictionary: Union[objectdictionary.ObjectDictionary, str, TextIO], + object_dictionary: Union[ObjectDictionary, str, TextIO], load_od: bool = False, ): super(RemoteNode, self).__init__(node_id, object_dictionary) @@ -138,9 +134,9 @@ def __load_configuration_helper(self, index, subindex, name, value): index=index, name=name, value=value))) - except canopen.SdoCommunicationError as e: + except SdoCommunicationError as e: logger.warning(str(e)) - except canopen.SdoAbortedError as e: + except SdoAbortedError as e: # WORKAROUND for broken implementations: the SDO is set but the error # "Attempt to write a read-only object" is raised any way. if e.code != 0x06010002: diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 70816515..3c608126 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -9,7 +9,7 @@ from collections import MutableMapping, Mapping import logging -from .datatypes import * +from canopen.objectdictionary.datatypes import * logger = logging.getLogger(__name__) @@ -42,10 +42,10 @@ def export_od(od, dest:Union[str,TextIO,None]=None, doc_type:Optional[str]=None) assert doc_type in doctypes if doc_type == "eds": - from . import eds + from canopen.objectdictionary import eds return eds.export_eds(od, dest) elif doc_type == "dcf": - from . import eds + from canopen.objectdictionary import eds return eds.export_dcf(od, dest) # If dest is opened in this fn, it should be closed @@ -78,10 +78,10 @@ def import_od( filename = source suffix = filename[filename.rfind("."):].lower() if suffix in (".eds", ".dcf"): - from . import eds + from canopen.objectdictionary import eds return eds.import_eds(source, node_id) elif suffix == ".epf": - from . import epf + from canopen.objectdictionary import epf return epf.import_epf(source) else: raise NotImplementedError("No support for this format") diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index c595ed66..aa83db0c 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -2,13 +2,13 @@ import logging import re -from canopen.objectdictionary import datatypes - try: from configparser import RawConfigParser, NoOptionError, NoSectionError except ImportError: from ConfigParser import RawConfigParser, NoOptionError, NoSectionError + from canopen import objectdictionary +from canopen.objectdictionary import ObjectDictionary, datatypes from canopen.sdo import SdoClient logger = logging.getLogger(__name__) @@ -38,7 +38,7 @@ def import_eds(source, node_id): if not hasattr(source, "read"): fp.close() - od = objectdictionary.ObjectDictionary() + od = ObjectDictionary() if eds.has_section("FileInfo"): od.__edsFileInfo = { @@ -130,7 +130,7 @@ def import_eds(source, node_id): arr = objectdictionary.Array(name, index) last_subindex = objectdictionary.Variable( "Number of entries", index, 0) - last_subindex.data_type = objectdictionary.UNSIGNED8 + last_subindex.data_type = datatypes.UNSIGNED8 arr.add_member(last_subindex) arr.add_member(build_variable(eds, section, node_id, index, 1)) arr.storage_location = storage_location @@ -179,7 +179,7 @@ def import_from_node(node_id, network): :param network: network object """ # Create temporary SDO client - sdo_client = SdoClient(0x600 + node_id, 0x580 + node_id, objectdictionary.ObjectDictionary()) + sdo_client = SdoClient(0x600 + node_id, 0x580 + node_id, ObjectDictionary()) sdo_client.network = network # Subscribe to SDO responses network.subscribe(0x580 + node_id, sdo_client.on_response) @@ -219,11 +219,11 @@ def _signed_int_from_hex(hex_str, bit_length): def _convert_variable(node_id, var_type, value): - if var_type in (objectdictionary.OCTET_STRING, objectdictionary.DOMAIN): + if var_type in (datatypes.OCTET_STRING, datatypes.DOMAIN): return bytes.fromhex(value) - elif var_type in (objectdictionary.VISIBLE_STRING, objectdictionary.UNICODE_STRING): + elif var_type in (datatypes.VISIBLE_STRING, datatypes.UNICODE_STRING): return value - elif var_type in objectdictionary.FLOAT_TYPES: + elif var_type in datatypes.FLOAT_TYPES: return float(value) else: # COB-ID can contain '$NODEID+' so replace this with node_id before converting @@ -237,11 +237,11 @@ def _convert_variable(node_id, var_type, value): def _revert_variable(var_type, value): if value is None: return None - if var_type in (objectdictionary.OCTET_STRING, objectdictionary.DOMAIN): + if var_type in (datatypes.OCTET_STRING, datatypes.DOMAIN): return bytes.hex(value) - elif var_type in (objectdictionary.VISIBLE_STRING, objectdictionary.UNICODE_STRING): + elif var_type in (datatypes.VISIBLE_STRING, datatypes.UNICODE_STRING): return value - elif var_type in objectdictionary.FLOAT_TYPES: + elif var_type in datatypes.FLOAT_TYPES: return value else: return "0x%02X" % value @@ -273,14 +273,14 @@ def build_variable(eds, section, node_id, index, subindex=0): except NoSectionError: logger.warning("%s has an unknown or unsupported data type (%X)", name, var.data_type) # Assume DOMAIN to force application to interpret the byte data - var.data_type = objectdictionary.DOMAIN + var.data_type = datatypes.DOMAIN var.pdo_mappable = bool(int(eds.get(section, "PDOMapping", fallback="0"), 0)) if eds.has_option(section, "LowLimit"): try: min_string = eds.get(section, "LowLimit") - if var.data_type in objectdictionary.SIGNED_TYPES: + if var.data_type in datatypes.SIGNED_TYPES: var.min = _signed_int_from_hex(min_string, _calc_bit_length(var.data_type)) else: var.min = int(min_string, 0) @@ -289,7 +289,7 @@ def build_variable(eds, section, node_id, index, subindex=0): if eds.has_option(section, "HighLimit"): try: max_string = eds.get(section, "HighLimit") - if var.data_type in objectdictionary.SIGNED_TYPES: + if var.data_type in datatypes.SIGNED_TYPES: var.max = _signed_int_from_hex(max_string, _calc_bit_length(var.data_type)) else: var.max = int(max_string, 0) @@ -341,7 +341,7 @@ def export_common(var, eds, section): eds.set(section, "StorageLocation", var.storage_location) def export_variable(var, eds): - if isinstance(var.parent, objectdictionary.ObjectDictionary): + if isinstance(var.parent, ObjectDictionary): # top level variable section = "%04X" % var.index else: diff --git a/canopen/objectdictionary/epf.py b/canopen/objectdictionary/epf.py index 5cef4058..8bfc513a 100644 --- a/canopen/objectdictionary/epf.py +++ b/canopen/objectdictionary/epf.py @@ -3,7 +3,9 @@ except ImportError: import xml.etree.ElementTree as etree import logging + from canopen import objectdictionary +from canopen.objectdictionary import ObjectDictionary logger = logging.getLogger(__name__) @@ -32,7 +34,7 @@ def import_epf(epf): The Object Dictionary. :rtype: canopen.ObjectDictionary """ - od = objectdictionary.ObjectDictionary() + od = ObjectDictionary() if etree.iselement(epf): tree = epf else: diff --git a/canopen/pdo/__init__.py b/canopen/pdo/__init__.py index a08b3ccc..d47ec693 100644 --- a/canopen/pdo/__init__.py +++ b/canopen/pdo/__init__.py @@ -1,8 +1,7 @@ -from .base import PdoBase, Maps, Map, Variable - import logging -import itertools -import canopen + +from canopen import node +from canopen.pdo.base import PdoBase, Maps, Map, Variable logger = logging.getLogger(__name__) @@ -45,7 +44,7 @@ def stop(self): :raise TypeError: Exception is thrown if the node associated with the PDO does not support this function. """ - if isinstance(self.node, canopen.RemoteNode): + if isinstance(self.node, node.RemoteNode): for pdo in self.map.values(): pdo.stop() else: @@ -70,7 +69,7 @@ def stop(self): :raise TypeError: Exception is thrown if the node associated with the PDO does not support this function. """ - if isinstance(canopen.LocalNode, self.node): + if isinstance(self.node, node.LocalNode): for pdo in self.map.values(): pdo.stop() else: diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index d7160738..086a0774 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -8,9 +8,9 @@ import logging import binascii -from ..sdo import SdoAbortedError -from .. import objectdictionary -from .. import variable +from canopen.sdo import SdoAbortedError +from canopen import objectdictionary +from canopen import variable PDO_NOT_VALID = 1 << 31 RTR_NOT_ALLOWED = 1 << 30 diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 915621d7..2e5fb133 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -1,8 +1,9 @@ # inspired by the NmtMaster code import logging import time -from ..node import RemoteNode -from ..sdo import SdoCommunicationError + +from canopen.node import RemoteNode +from canopen.sdo import SdoCommunicationError logger = logging.getLogger(__name__) diff --git a/canopen/sdo/__init__.py b/canopen/sdo/__init__.py index b395d0fd..160affd3 100644 --- a/canopen/sdo/__init__.py +++ b/canopen/sdo/__init__.py @@ -1,4 +1,4 @@ -from .base import Variable, Record, Array -from .client import SdoClient -from .server import SdoServer -from .exceptions import SdoAbortedError, SdoCommunicationError +from canopen.sdo.base import Variable, Record, Array +from canopen.sdo.client import SdoClient +from canopen.sdo.server import SdoServer +from canopen.sdo.exceptions import SdoAbortedError, SdoCommunicationError diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 622eed14..25d3d60c 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -5,8 +5,9 @@ except ImportError: from collections import Mapping -from .. import objectdictionary -from .. import variable +from canopen import objectdictionary +from canopen.objectdictionary import ObjectDictionary +from canopen import variable class CrcXmodem: @@ -31,7 +32,7 @@ def __init__( self, rx_cobid: int, tx_cobid: int, - od: objectdictionary.ObjectDictionary, + od: ObjectDictionary, ): """ :param rx_cobid: @@ -81,7 +82,7 @@ def download( class Record(Mapping): - def __init__(self, sdo_node: SdoBase, od: objectdictionary.ObjectDictionary): + def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.sdo_node = sdo_node self.od = od @@ -100,7 +101,7 @@ def __contains__(self, subindex: Union[int, str]) -> bool: class Array(Mapping): - def __init__(self, sdo_node: SdoBase, od: objectdictionary.ObjectDictionary): + def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.sdo_node = sdo_node self.od = od @@ -120,7 +121,7 @@ def __contains__(self, subindex: int) -> bool: class Variable(variable.Variable): """Access object dictionary variable values using SDO protocol.""" - def __init__(self, sdo_node: SdoBase, od: objectdictionary.ObjectDictionary): + def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.sdo_node = sdo_node variable.Variable.__init__(self, od) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 7faa103a..21517717 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -7,12 +7,11 @@ except ImportError: import Queue as queue -from ..network import CanError -from .. import objectdictionary - -from .base import SdoBase -from .constants import * -from .exceptions import * +from canopen.network import CanError +from canopen import objectdictionary +from canopen.sdo.base import SdoBase +from canopen.sdo.constants import * +from canopen.sdo.exceptions import * logger = logging.getLogger(__name__) @@ -192,7 +191,7 @@ def open(self, index, subindex=0, mode="rb", encoding="ascii", Force use of segmented download regardless of data size. :param bool request_crc_support: If crc calculation should be requested when using block transfer - + :returns: A file like object. """ diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index 7986e1fa..e9574feb 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -1,8 +1,8 @@ import logging -from .base import SdoBase -from .constants import * -from .exceptions import * +from canopen.sdo.base import SdoBase +from canopen.sdo.constants import * +from canopen.sdo.exceptions import * logger = logging.getLogger(__name__) diff --git a/canopen/sync.py b/canopen/sync.py index 6e583b04..d3734512 100644 --- a/canopen/sync.py +++ b/canopen/sync.py @@ -1,5 +1,3 @@ - - from typing import Optional diff --git a/canopen/variable.py b/canopen/variable.py index 2abfa2ab..c7924e51 100644 --- a/canopen/variable.py +++ b/canopen/variable.py @@ -5,7 +5,7 @@ except ImportError: from collections import Mapping -from . import objectdictionary +from canopen import objectdictionary logger = logging.getLogger(__name__) From e8807b87e69902840f459279ce38e330b069f53d Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Sat, 8 Apr 2023 20:45:19 +0200 Subject: [PATCH 101/199] Fix pytest on windows (#364) (#365) * Fix pytest on windows (#364) * Slack test even more for WIndows --- setup.cfg | 6 ++++++ test/test_eds.py | 15 +++++++++------ test/test_network.py | 5 ++++- 3 files changed, 19 insertions(+), 7 deletions(-) diff --git a/setup.cfg b/setup.cfg index ca6253b5..7d33e805 100644 --- a/setup.cfg +++ b/setup.cfg @@ -21,3 +21,9 @@ python_requires = >=3.6 install_requires = python-can >= 3.0.0 include_package_data = True + +[tool:pytest] +testpaths = + test +filterwarnings = + ignore::DeprecationWarning diff --git a/test/test_eds.py b/test/test_eds.py index 4977dc10..5edd8d86 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -122,12 +122,15 @@ def test_comments(self): def test_export_eds(self): import tempfile - for doctype in {"eds", "dcf"}: - with tempfile.NamedTemporaryFile(suffix="." + doctype, mode="w+") as tempeds: - print("exporting %s to " % doctype + tempeds.name) - canopen.export_od(self.od, tempeds, doc_type=doctype) - tempeds.flush() - exported_od = canopen.import_od(tempeds.name) + from pathlib import Path + with tempfile.TemporaryDirectory() as tempdir: + for doctype in {"eds", "dcf"}: + tempfile = str(Path(tempdir, "test." + doctype)) + with open(tempfile, "w+") as tempeds: + print("exporting %s to " % doctype + tempeds.name) + canopen.export_od(self.od, tempeds, doc_type=doctype) + + exported_od = canopen.import_od(tempfile) for index in exported_od: self.assertIn(exported_od[index].name, self.od) diff --git a/test/test_network.py b/test/test_network.py index e89ae4dd..04129271 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -59,7 +59,10 @@ def test_send_perodic(self): task = self.network.send_periodic(0x123, [1, 2, 3], 0.01) time.sleep(0.1) - self.assertTrue(9 <= bus.queue.qsize() <= 11) + # FIXME: This test is a little fragile, as the number of elements + # depends on the timing of the machine. + print("Queue size: %s" % (bus.queue.qsize(),)) + self.assertTrue(9 <= bus.queue.qsize() <= 13) msg = bus.recv(0) self.assertIsNotNone(msg) self.assertSequenceEqual(msg.data, [1, 2, 3]) From 2f42ec69e71f1183f67367433d69ed4091d4ffc7 Mon Sep 17 00:00:00 2001 From: Joep Date: Mon, 29 May 2023 22:17:05 +0200 Subject: [PATCH 102/199] Enable inline comments when reading files (#380) --- canopen/objectdictionary/eds.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index aa83db0c..d9f06e97 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -21,7 +21,7 @@ def import_eds(source, node_id): - eds = RawConfigParser() + eds = RawConfigParser(inline_comment_prefixes=(';',)) eds.optionxform = str if hasattr(source, "read"): fp = source From 2d5d6d369efe1f1cdbd2a4e6ae4fd997d2845c62 Mon Sep 17 00:00:00 2001 From: Marco Date: Wed, 30 Aug 2023 07:36:13 +0100 Subject: [PATCH 103/199] Feature/eds parse factor and description (#378) --- canopen/objectdictionary/eds.py | 23 ++++++++++++++++++++++ test/sample.eds | 34 +++++++++++++++++++++++++++++++++ test/test_eds.py | 12 ++++++++++++ 3 files changed, 69 insertions(+) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index d9f06e97..187b5135 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -309,6 +309,22 @@ def build_variable(eds, section, node_id, index, subindex=0): var.value = _convert_variable(node_id, var.data_type, eds.get(section, "ParameterValue")) except ValueError: pass + # Factor, Description and Unit are not standard according to the CANopen specifications, but they are implemented in the python canopen package, so we can at least try to use them + if eds.has_option(section, "Factor"): + try: + var.factor = float(eds.get(section, "Factor")) + except ValueError: + pass + if eds.has_option(section, "Description"): + try: + var.description = eds.get(section, "Description") + except ValueError: + pass + if eds.has_option(section, "Unit"): + try: + var.unit = eds.get(section, "Unit") + except ValueError: + pass return var @@ -376,6 +392,13 @@ def export_variable(var, eds): if getattr(var, 'max', None) is not None: eds.set(section, "HighLimit", var.max) + if getattr(var, 'description', '') != '': + eds.set(section, "Description", var.description) + if getattr(var, 'factor', 1) != 1: + eds.set(section, "Factor", var.factor) + if getattr(var, 'unit', '') != '': + eds.set(section, "Unit", var.unit) + def export_record(var, eds): section = "%04X" % var.index export_common(var, eds, section) diff --git a/test/sample.eds b/test/sample.eds index 671a559e..2267ff55 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -938,3 +938,37 @@ AccessType=rw HighLimit=0x000000000000000A LowLimit=0x8000000000000009 PDOMapping=0 + + +[3050] +ParameterName=EDS file extensions +SubNumber=0x7 +ObjectType=0x9 + +[3050sub0] +ParameterName=Highest subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=0x02 +PDOMapping=0x0 + +[3050sub1] +ParameterName=FactorAndDescription +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x0 +Factor=0.1 +Description=This is the a test description +Unit=mV + +[3050sub2] +ParameterName=Error Factor and No Description +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=0x0 +Factor=ERROR +Description= +Unit= diff --git a/test/test_eds.py b/test/test_eds.py index 5edd8d86..17674d45 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -111,6 +111,18 @@ def test_dummy_variable(self): def test_dummy_variable_undefined(self): with self.assertRaises(KeyError): var_undef = self.od['Dummy0001'] + + def test_reading_factor(self): + var = self.od['EDS file extensions']['FactorAndDescription'] + self.assertEqual(var.factor, 0.1) + self.assertEqual(var.description, "This is the a test description") + self.assertEqual(var.unit,'mV') + var2 = self.od['EDS file extensions']['Error Factor and No Description'] + self.assertEqual(var2.description, '') + self.assertEqual(var2.factor, 1) + self.assertEqual(var2.unit, '') + + def test_comments(self): self.assertEqual(self.od.comments, From 3585837c482bae2dc0aadd7726fe5608c03163e8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Frieder=20Sch=C3=BCler?= Date: Fri, 1 Sep 2023 21:36:42 +0200 Subject: [PATCH 104/199] Correct signed_int_from_hex implementation (#394) * fixed signed_int_from_hex method and eds tests. added full unit tests for method. * Fixed testdata, missing import and hex-prefix in string conversion. --- canopen/objectdictionary/eds.py | 7 +++--- test/sample.eds | 7 +++--- test/test_eds.py | 41 ++++++++++++++++++++++++++++++++- 3 files changed, 47 insertions(+), 8 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 187b5135..16ed22c1 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -211,9 +211,10 @@ def _calc_bit_length(data_type): def _signed_int_from_hex(hex_str, bit_length): number = int(hex_str, 0) - limit = ((1 << bit_length - 1) - 1) - if number > limit: - return limit - number + max_value = (1 << (bit_length - 1)) - 1 + + if number > max_value: + return number - (1 << bit_length) else: return number diff --git a/test/sample.eds b/test/sample.eds index 2267ff55..b88ff75b 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -926,8 +926,8 @@ ParameterName=INTEGER32 only negative values ObjectType=0x7 DataType=0x04 AccessType=rw -HighLimit=0x00000000 -LowLimit=0xFFFFFFFF +HighLimit=0xFFFFFFFF +LowLimit=0x80000000 PDOMapping=0 [3040] @@ -936,10 +936,9 @@ ObjectType=0x7 DataType=0x15 AccessType=rw HighLimit=0x000000000000000A -LowLimit=0x8000000000000009 +LowLimit=0xFFFFFFFFFFFFFFF6 PDOMapping=0 - [3050] ParameterName=EDS file extensions SubNumber=0x7 diff --git a/test/test_eds.py b/test/test_eds.py index 17674d45..50629234 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -1,12 +1,44 @@ import os import unittest import canopen +from canopen.objectdictionary.eds import _signed_int_from_hex EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') class TestEDS(unittest.TestCase): + test_data = { + "int8": [ + {"hex_str": "7F", "bit_length": 8, "expected": 127}, + {"hex_str": "80", "bit_length": 8, "expected": -128}, + {"hex_str": "FF", "bit_length": 8, "expected": -1}, + {"hex_str": "00", "bit_length": 8, "expected": 0}, + {"hex_str": "01", "bit_length": 8, "expected": 1} + ], + "int16": [ + {"hex_str": "7FFF", "bit_length": 16, "expected": 32767}, + {"hex_str": "8000", "bit_length": 16, "expected": -32768}, + {"hex_str": "FFFF", "bit_length": 16, "expected": -1}, + {"hex_str": "0000", "bit_length": 16, "expected": 0}, + {"hex_str": "0001", "bit_length": 16, "expected": 1} + ], + "int32": [ + {"hex_str": "7FFFFFFF", "bit_length": 32, "expected": 2147483647}, + {"hex_str": "80000000", "bit_length": 32, "expected": -2147483648}, + {"hex_str": "FFFFFFFF", "bit_length": 32, "expected": -1}, + {"hex_str": "00000000", "bit_length": 32, "expected": 0}, + {"hex_str": "00000001", "bit_length": 32, "expected": 1} + ], + "int64": [ + {"hex_str": "7FFFFFFFFFFFFFFF", "bit_length": 64, "expected": 9223372036854775807}, + {"hex_str": "8000000000000000", "bit_length": 64, "expected": -9223372036854775808}, + {"hex_str": "FFFFFFFFFFFFFFFF", "bit_length": 64, "expected": -1}, + {"hex_str": "0000000000000000", "bit_length": 64, "expected": 0}, + {"hex_str": "0000000000000001", "bit_length": 64, "expected": 1} + ] + } + def setUp(self): self.od = canopen.import_od(EDS_PATH, 2) @@ -58,11 +90,18 @@ def test_record_with_limits(self): self.assertEqual(uint8.max, 10) int32 = self.od[0x3030] self.assertEqual(int32.min, -2147483648) - self.assertEqual(int32.max, 0) + self.assertEqual(int32.max, -1) int64 = self.od[0x3040] self.assertEqual(int64.min, -10) self.assertEqual(int64.max, +10) + def test_signed_int_from_hex(self): + for data_type, test_cases in self.test_data.items(): + for test_case in test_cases: + with self.subTest(data_type=data_type, test_case=test_case): + result = _signed_int_from_hex('0x' + test_case["hex_str"], test_case["bit_length"]) + self.assertEqual(result, test_case["expected"]) + def test_array_compact_subobj(self): array = self.od[0x1003] self.assertIsInstance(array, canopen.objectdictionary.Array) From 0285f582beb344de708ce8308274a99bc04988a1 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Fri, 1 Sep 2023 21:49:49 +0200 Subject: [PATCH 105/199] Rename Variable, Record and Array (#363) (#368) To create better distinction between the different Variable, Record and Array types used for different purposes. Helps development, as IDE/linters often only display base name of class. --- canopen/node/local.py | 2 +- canopen/node/remote.py | 8 ++-- canopen/objectdictionary/__init__.py | 62 +++++++++++++++------------- canopen/objectdictionary/eds.py | 24 +++++------ canopen/objectdictionary/epf.py | 6 +-- canopen/pdo/__init__.py | 5 ++- canopen/pdo/base.py | 30 ++++++++------ canopen/sdo/__init__.py | 5 ++- canopen/sdo/base.py | 34 ++++++++------- canopen/variable.py | 6 +-- doc/od.rst | 14 +++---- doc/pdo.rst | 8 ++-- doc/sdo.rst | 20 ++++----- test/test_eds.py | 14 +++---- test/test_od.py | 40 +++++++++--------- 15 files changed, 150 insertions(+), 128 deletions(-) diff --git a/canopen/node/local.py b/canopen/node/local.py index b36cf3eb..de3e23b9 100644 --- a/canopen/node/local.py +++ b/canopen/node/local.py @@ -120,7 +120,7 @@ def _find_object(self, index, subindex): # Index does not exist raise SdoAbortedError(0x06020000) obj = self.object_dictionary[index] - if not isinstance(obj, objectdictionary.Variable): + if not isinstance(obj, objectdictionary.ODVariable): # Group or array if subindex not in obj: # Subindex does not exist diff --git a/canopen/node/remote.py b/canopen/node/remote.py index 8e4025d7..07462422 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -5,7 +5,7 @@ from canopen.nmt import NmtMaster from canopen.emcy import EmcyConsumer from canopen.pdo import TPDO, RPDO, PDO -from canopen.objectdictionary import Record, Array, Variable, ObjectDictionary +from canopen.objectdictionary import ODRecord, ODArray, ODVariable, ObjectDictionary from canopen.node.base import BaseNode logger = logging.getLogger(__name__) @@ -148,10 +148,10 @@ def __load_configuration_helper(self, index, subindex, name, value): def load_configuration(self): ''' Load the configuration of the node from the object dictionary.''' for obj in self.object_dictionary.values(): - if isinstance(obj, Record) or isinstance(obj, Array): + if isinstance(obj, ODRecord) or isinstance(obj, ODArray): for subobj in obj.values(): - if isinstance(subobj, Variable) and subobj.writable and (subobj.value is not None): + if isinstance(subobj, ODVariable) and subobj.writable and (subobj.value is not None): self.__load_configuration_helper(subobj.index, subobj.subindex, subobj.name, subobj.value) - elif isinstance(obj, Variable) and obj.writable and (obj.value is not None): + elif isinstance(obj, ODVariable) and obj.writable and (obj.value is not None): self.__load_configuration_helper(obj.index, None, obj.name, obj.value) self.pdo.read() # reads the new configuration from the driver diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 3c608126..066a069c 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -103,7 +103,7 @@ def __init__(self): def __getitem__( self, index: Union[int, str] - ) -> Union["Array", "Record", "Variable"]: + ) -> Union["ODArray", "ODRecord", "ODVariable"]: """Get object from object dictionary by name or index.""" item = self.names.get(index) or self.indices.get(index) if item is None: @@ -112,7 +112,7 @@ def __getitem__( return item def __setitem__( - self, index: Union[int, str], obj: Union["Array", "Record", "Variable"] + self, index: Union[int, str], obj: Union["ODArray", "ODRecord", "ODVariable"] ): assert index == obj.index or index == obj.name self.add_object(obj) @@ -131,14 +131,14 @@ def __len__(self) -> int: def __contains__(self, index: Union[int, str]): return index in self.names or index in self.indices - def add_object(self, obj: Union["Array", "Record", "Variable"]) -> None: + def add_object(self, obj: Union["ODArray", "ODRecord", "ODVariable"]) -> None: """Add object to the object dictionary. :param obj: Should be either one of - :class:`~canopen.objectdictionary.Variable`, - :class:`~canopen.objectdictionary.Record`, or - :class:`~canopen.objectdictionary.Array`. + :class:`~canopen.objectdictionary.ODVariable`, + :class:`~canopen.objectdictionary.ODRecord`, or + :class:`~canopen.objectdictionary.ODArray`. """ obj.parent = self self.indices[obj.index] = obj @@ -146,20 +146,20 @@ def add_object(self, obj: Union["Array", "Record", "Variable"]) -> None: def get_variable( self, index: Union[int, str], subindex: int = 0 - ) -> Optional["Variable"]: + ) -> Optional["ODVariable"]: """Get the variable object at specified index (and subindex if applicable). - :return: Variable if found, else `None` + :return: ODVariable if found, else `None` """ obj = self.get(index) - if isinstance(obj, Variable): + if isinstance(obj, ODVariable): return obj - elif isinstance(obj, (Record, Array)): + elif isinstance(obj, (ODRecord, ODArray)): return obj.get(subindex) -class Record(MutableMapping): - """Groups multiple :class:`~canopen.objectdictionary.Variable` objects using +class ODRecord(MutableMapping): + """Groups multiple :class:`~canopen.objectdictionary.ODVariable` objects using subindices. """ @@ -178,13 +178,13 @@ def __init__(self, name: str, index: int): self.subindices = {} self.names = {} - def __getitem__(self, subindex: Union[int, str]) -> "Variable": + def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": item = self.names.get(subindex) or self.subindices.get(subindex) if item is None: raise KeyError("Subindex %s was not found" % subindex) return item - def __setitem__(self, subindex: Union[int, str], var: "Variable"): + def __setitem__(self, subindex: Union[int, str], var: "ODVariable"): assert subindex == var.subindex self.add_member(var) @@ -202,18 +202,18 @@ def __iter__(self) -> Iterable[int]: def __contains__(self, subindex: Union[int, str]) -> bool: return subindex in self.names or subindex in self.subindices - def __eq__(self, other: "Record") -> bool: + def __eq__(self, other: "ODRecord") -> bool: return self.index == other.index - def add_member(self, variable: "Variable") -> None: - """Adds a :class:`~canopen.objectdictionary.Variable` to the record.""" + def add_member(self, variable: "ODVariable") -> None: + """Adds a :class:`~canopen.objectdictionary.ODVariable` to the record.""" variable.parent = self self.subindices[variable.subindex] = variable self.names[variable.name] = variable -class Array(Mapping): - """An array of :class:`~canopen.objectdictionary.Variable` objects using +class ODArray(Mapping): + """An array of :class:`~canopen.objectdictionary.ODVariable` objects using subindices. Actual length of array must be read from the node using SDO. @@ -234,7 +234,7 @@ def __init__(self, name: str, index: int): self.subindices = {} self.names = {} - def __getitem__(self, subindex: Union[int, str]) -> "Variable": + def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": var = self.names.get(subindex) or self.subindices.get(subindex) if var is not None: # This subindex is defined @@ -243,7 +243,7 @@ def __getitem__(self, subindex: Union[int, str]) -> "Variable": # Create a new variable based on first array item template = self.subindices[1] name = "%s_%x" % (template.name, subindex) - var = Variable(name, self.index, subindex) + var = ODVariable(name, self.index, subindex) var.parent = self for attr in ("data_type", "unit", "factor", "min", "max", "default", "access_type", "description", "value_descriptions", @@ -260,17 +260,17 @@ def __len__(self) -> int: def __iter__(self) -> Iterable[int]: return iter(sorted(self.subindices)) - def __eq__(self, other: "Array") -> bool: + def __eq__(self, other: "ODArray") -> bool: return self.index == other.index - def add_member(self, variable: "Variable") -> None: - """Adds a :class:`~canopen.objectdictionary.Variable` to the record.""" + def add_member(self, variable: "ODVariable") -> None: + """Adds a :class:`~canopen.objectdictionary.ODVariable` to the record.""" variable.parent = self self.subindices[variable.subindex] = variable self.names[variable.name] = variable -class Variable: +class ODVariable: """Simple variable.""" STRUCT_TYPES = { @@ -289,8 +289,8 @@ class Variable: def __init__(self, name: str, index: int, subindex: int = 0): #: The :class:`~canopen.ObjectDictionary`, - #: :class:`~canopen.objectdictionary.Record` or - #: :class:`~canopen.objectdictionary.Array` owning the variable + #: :class:`~canopen.objectdictionary.ODRecord` or + #: :class:`~canopen.objectdictionary.ODArray` owning the variable self.parent = None #: 16-bit address of the object in the dictionary self.index = index @@ -328,7 +328,7 @@ def __init__(self, name: str, index: int, subindex: int = 0): self.pdo_mappable = False - def __eq__(self, other: "Variable") -> bool: + def __eq__(self, other: "ODVariable") -> bool: return (self.index == other.index and self.subindex == other.subindex) @@ -486,3 +486,9 @@ def __init__(self): class ObjectDictionaryError(Exception): """Unsupported operation with the current Object Dictionary.""" + + +# Compatibility for old names +Record = ODRecord +Array = ODArray +Variable = ODVariable diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 16ed22c1..73a7eaeb 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -101,7 +101,7 @@ def import_eds(source, node_id): for i in range(1, 8): key = "Dummy%04d" % i if eds.getint(section, key) == 1: - var = objectdictionary.Variable(key, i, 0) + var = objectdictionary.ODVariable(key, i, 0) var.data_type = i var.access_type = "const" od.add_object(var) @@ -127,8 +127,8 @@ def import_eds(source, node_id): var = build_variable(eds, section, node_id, index) od.add_object(var) elif object_type == ARR and eds.has_option(section, "CompactSubObj"): - arr = objectdictionary.Array(name, index) - last_subindex = objectdictionary.Variable( + arr = objectdictionary.ODArray(name, index) + last_subindex = objectdictionary.ODVariable( "Number of entries", index, 0) last_subindex.data_type = datatypes.UNSIGNED8 arr.add_member(last_subindex) @@ -136,11 +136,11 @@ def import_eds(source, node_id): arr.storage_location = storage_location od.add_object(arr) elif object_type == ARR: - arr = objectdictionary.Array(name, index) + arr = objectdictionary.ODArray(name, index) arr.storage_location = storage_location od.add_object(arr) elif object_type == RECORD: - record = objectdictionary.Record(name, index) + record = objectdictionary.ODRecord(name, index) record.storage_location = storage_location od.add_object(record) @@ -152,8 +152,8 @@ def import_eds(source, node_id): index = int(match.group(1), 16) subindex = int(match.group(2), 16) entry = od[index] - if isinstance(entry, (objectdictionary.Record, - objectdictionary.Array)): + if isinstance(entry, (objectdictionary.ODRecord, + objectdictionary.ODArray)): var = build_variable(eds, section, node_id, index, subindex) entry.add_member(var) @@ -257,7 +257,7 @@ def build_variable(eds, section, node_id, index, subindex=0): :param subindex: Subindex of the CANOpen object (if presente, else 0) """ name = eds.get(section, "ParameterName") - var = objectdictionary.Variable(name, index, subindex) + var = objectdictionary.ODVariable(name, index, subindex) try: var.storage_location = eds.get(section, "StorageLocation") except NoOptionError: @@ -344,11 +344,11 @@ def export_dcf(od, dest=None, fileInfo={}): def export_eds(od, dest=None, file_info={}, device_commisioning=False): def export_object(obj, eds): - if isinstance(obj, objectdictionary.Variable): + if isinstance(obj, objectdictionary.ODVariable): return export_variable(obj, eds) - if isinstance(obj, objectdictionary.Record): + if isinstance(obj, objectdictionary.ODRecord): return export_record(obj, eds) - if isinstance(obj, objectdictionary.Array): + if isinstance(obj, objectdictionary.ODArray): return export_array(obj, eds) def export_common(var, eds, section): @@ -404,7 +404,7 @@ def export_record(var, eds): section = "%04X" % var.index export_common(var, eds, section) eds.set(section, "SubNumber", "0x%X" % len(var.subindices)) - ot = RECORD if isinstance(var, objectdictionary.Record) else ARR + ot = RECORD if isinstance(var, objectdictionary.ODRecord) else ARR eds.set(section, "ObjectType", "0x%X" % ot) for i in var: export_variable(var[i], eds) diff --git a/canopen/objectdictionary/epf.py b/canopen/objectdictionary/epf.py index 8bfc513a..f884b659 100644 --- a/canopen/objectdictionary/epf.py +++ b/canopen/objectdictionary/epf.py @@ -61,7 +61,7 @@ def import_epf(epf): od.add_object(var) elif len(parameters) == 2 and parameters[1].get("ObjectType") == "ARRAY": # Array - arr = objectdictionary.Array(name, index) + arr = objectdictionary.ODArray(name, index) for par_tree in parameters: var = build_variable(par_tree) arr.add_member(var) @@ -71,7 +71,7 @@ def import_epf(epf): od.add_object(arr) else: # Complex record - record = objectdictionary.Record(name, index) + record = objectdictionary.ODRecord(name, index) for par_tree in parameters: var = build_variable(par_tree) record.add_member(var) @@ -89,7 +89,7 @@ def build_variable(par_tree): name = par_tree.get("SymbolName") data_type = par_tree.get("DataType") - par = objectdictionary.Variable(name, index, subindex) + par = objectdictionary.ODVariable(name, index, subindex) factor = par_tree.get("Factor", "1") par.factor = int(factor) if factor.isdigit() else float(factor) unit = par_tree.get("Unit") diff --git a/canopen/pdo/__init__.py b/canopen/pdo/__init__.py index d47ec693..46396e30 100644 --- a/canopen/pdo/__init__.py +++ b/canopen/pdo/__init__.py @@ -1,7 +1,10 @@ import logging from canopen import node -from canopen.pdo.base import PdoBase, Maps, Map, Variable +from canopen.pdo.base import PdoBase, Maps + +# Compatibility +from .base import Variable logger = logging.getLogger(__name__) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 086a0774..bb166e7a 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -180,7 +180,7 @@ def __init__(self, pdo_node, com_record, map_array): #: Ignores SYNC objects up to this SYNC counter value (optional) self.sync_start_value: Optional[int] = None #: List of variables mapped to this PDO - self.map: List["Variable"] = [] + self.map: List["PdoVariable"] = [] self.length: int = 0 #: Current message data self.data = bytearray() @@ -214,7 +214,7 @@ def __getitem_by_name(self, value): raise KeyError('{0} not found in map. Valid entries are {1}'.format( value, ', '.join(valid_values))) - def __getitem__(self, key: Union[int, str]) -> "Variable": + def __getitem__(self, key: Union[int, str]) -> "PdoVariable": var = None if isinstance(key, int): # there is a maximum available of 8 slots per PDO map @@ -229,7 +229,7 @@ def __getitem__(self, key: Union[int, str]) -> "Variable": var = self.__getitem_by_name(key) return var - def __iter__(self) -> Iterable["Variable"]: + def __iter__(self) -> Iterable["PdoVariable"]: return iter(self.map) def __len__(self) -> int: @@ -237,9 +237,9 @@ def __len__(self) -> int: def _get_variable(self, index, subindex): obj = self.pdo_node.node.object_dictionary[index] - if isinstance(obj, (objectdictionary.Record, objectdictionary.Array)): + if isinstance(obj, (objectdictionary.ODRecord, objectdictionary.ODArray)): obj = obj[subindex] - var = Variable(obj) + var = PdoVariable(obj) var.pdo_parent = self return var @@ -248,8 +248,8 @@ def _fill_map(self, needed): logger.info("Filling up fixed-length mapping array") while len(self.map) < needed: # Generate a dummy mapping for an invalid object with zero length. - obj = objectdictionary.Variable('Dummy', 0, 0) - var = Variable(obj) + obj = objectdictionary.ODVariable('Dummy', 0, 0) + var = PdoVariable(obj) var.length = 0 self.map.append(var) @@ -440,13 +440,13 @@ def add_variable( index: Union[str, int], subindex: Union[str, int] = 0, length: Optional[int] = None, - ) -> "Variable": + ) -> "PdoVariable": """Add a variable from object dictionary as the next entry. :param index: Index of variable as name or number :param subindex: Sub-index of variable as name or number :param length: Size of data in number of bits - :return: Variable that was added + :return: PdoVariable that was added """ try: var = self._get_variable(index, subindex) @@ -528,11 +528,11 @@ def wait_for_reception(self, timeout: float = 10) -> float: return self.timestamp if self.is_received else None -class Variable(variable.Variable): +class PdoVariable(variable.Variable): """One object dictionary variable mapped to a PDO.""" - def __init__(self, od: objectdictionary.Variable): - #: PDO object that is associated with this Variable Object + def __init__(self, od: objectdictionary.ODVariable): + #: PDO object that is associated with this ODVariable Object self.pdo_parent = None #: Location of variable in the message in bits self.offset = None @@ -542,7 +542,7 @@ def __init__(self, od: objectdictionary.Variable): def get_data(self) -> bytes: """Reads the PDO variable from the last received message. - :return: Variable value as :class:`bytes`. + :return: PdoVariable value as :class:`bytes`. """ byte_offset, bit_offset = divmod(self.offset, 8) @@ -598,3 +598,7 @@ def set_data(self, data: bytes): self.pdo_parent.data[byte_offset:byte_offset + len(data)] = data self.pdo_parent.update() + + +# For compatibility +Variable = PdoVariable diff --git a/canopen/sdo/__init__.py b/canopen/sdo/__init__.py index 160affd3..775a8c4e 100644 --- a/canopen/sdo/__init__.py +++ b/canopen/sdo/__init__.py @@ -1,4 +1,7 @@ -from canopen.sdo.base import Variable, Record, Array +from canopen.sdo.base import SdoVariable, SdoRecord, SdoArray from canopen.sdo.client import SdoClient from canopen.sdo.server import SdoServer from canopen.sdo.exceptions import SdoAbortedError, SdoCommunicationError + +# Compatibility +from .base import Variable, Record, Array diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 25d3d60c..85cfe4e9 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -49,14 +49,14 @@ def __init__( def __getitem__( self, index: Union[str, int] - ) -> Union["Variable", "Array", "Record"]: + ) -> Union["SdoVariable", "SdoArray", "SdoRecord"]: entry = self.od[index] - if isinstance(entry, objectdictionary.Variable): - return Variable(self, entry) - elif isinstance(entry, objectdictionary.Array): - return Array(self, entry) - elif isinstance(entry, objectdictionary.Record): - return Record(self, entry) + if isinstance(entry, objectdictionary.ODVariable): + return SdoVariable(self, entry) + elif isinstance(entry, objectdictionary.ODArray): + return SdoArray(self, entry) + elif isinstance(entry, objectdictionary.ODRecord): + return SdoRecord(self, entry) def __iter__(self) -> Iterable[int]: return iter(self.od) @@ -80,14 +80,14 @@ def download( raise NotImplementedError() -class Record(Mapping): +class SdoRecord(Mapping): def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.sdo_node = sdo_node self.od = od - def __getitem__(self, subindex: Union[int, str]) -> "Variable": - return Variable(self.sdo_node, self.od[subindex]) + def __getitem__(self, subindex: Union[int, str]) -> "SdoVariable": + return SdoVariable(self.sdo_node, self.od[subindex]) def __iter__(self) -> Iterable[int]: return iter(self.od) @@ -99,14 +99,14 @@ def __contains__(self, subindex: Union[int, str]) -> bool: return subindex in self.od -class Array(Mapping): +class SdoArray(Mapping): def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.sdo_node = sdo_node self.od = od - def __getitem__(self, subindex: Union[int, str]) -> "Variable": - return Variable(self.sdo_node, self.od[subindex]) + def __getitem__(self, subindex: Union[int, str]) -> "SdoVariable": + return SdoVariable(self.sdo_node, self.od[subindex]) def __iter__(self) -> Iterable[int]: return iter(range(1, len(self) + 1)) @@ -118,7 +118,7 @@ def __contains__(self, subindex: int) -> bool: return 0 <= subindex <= len(self) -class Variable(variable.Variable): +class SdoVariable(variable.Variable): """Access object dictionary variable values using SDO protocol.""" def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): @@ -165,3 +165,9 @@ def open(self, mode="rb", encoding="ascii", buffering=1024, size=None, """ return self.sdo_node.open(self.od.index, self.od.subindex, mode, encoding, buffering, size, block_transfer, request_crc_support=request_crc_support) + + +# For compatibility +Record = SdoRecord +Array = SdoArray +Variable = SdoVariable diff --git a/canopen/variable.py b/canopen/variable.py index c7924e51..e8687660 100644 --- a/canopen/variable.py +++ b/canopen/variable.py @@ -12,12 +12,12 @@ class Variable: - def __init__(self, od: objectdictionary.Variable): + def __init__(self, od: objectdictionary.ODVariable): self.od = od #: Description of this variable from Object Dictionary, overridable self.name = od.name - if isinstance(od.parent, (objectdictionary.Record, - objectdictionary.Array)): + if isinstance(od.parent, (objectdictionary.ODRecord, + objectdictionary.ODArray)): # Include the parent object's name for subentries self.name = od.parent.name + "." + od.name #: Holds a local, overridable copy of the Object Index diff --git a/doc/od.rst b/doc/od.rst index 043dce01..6e7eb3b5 100644 --- a/doc/od.rst +++ b/doc/od.rst @@ -40,7 +40,7 @@ Here is an example where the entire object dictionary gets printed out:: node = network.add_node(6, 'od.eds') for obj in node.object_dictionary.values(): print('0x%X: %s' % (obj.index, obj.name)) - if isinstance(obj, canopen.objectdictionary.Record): + if isinstance(obj, canopen.objectdictionary.ODRecord): for subobj in obj.values(): print(' %d: %s' % (subobj.subindex, subobj.name)) @@ -79,7 +79,7 @@ API Return a list of objects (records, arrays and variables). -.. autoclass:: canopen.objectdictionary.Variable +.. autoclass:: canopen.objectdictionary.ODVariable :members: .. describe:: len(var) @@ -91,12 +91,12 @@ API Return ``True`` if the variables have the same index and subindex. -.. autoclass:: canopen.objectdictionary.Record +.. autoclass:: canopen.objectdictionary.ODRecord :members: .. describe:: record[subindex] - Return the :class:`~canopen.objectdictionary.Variable` for the specified + Return the :class:`~canopen.objectdictionary.ODVariable` for the specified subindex (as int) or name (as string). .. describe:: iter(record) @@ -118,15 +118,15 @@ API .. method:: values() - Return a list of :class:`~canopen.objectdictionary.Variable` in the record. + Return a list of :class:`~canopen.objectdictionary.ODVariable` in the record. -.. autoclass:: canopen.objectdictionary.Array +.. autoclass:: canopen.objectdictionary.ODArray :members: .. describe:: array[subindex] - Return the :class:`~canopen.objectdictionary.Variable` for the specified + Return the :class:`~canopen.objectdictionary.ODVariable` for the specified subindex (as int) or name (as string). This will work for all subindexes between 1 and 255. If the requested subindex has not been specified in the object dictionary, it will be diff --git a/doc/pdo.rst b/doc/pdo.rst index 9a7c027b..05e1e94d 100644 --- a/doc/pdo.rst +++ b/doc/pdo.rst @@ -106,22 +106,22 @@ API .. describe:: map[name] - Return the :class:`canopen.pdo.Variable` for the variable specified as + Return the :class:`canopen.pdo.PdoVariable` for the variable specified as ``"Group.Variable"`` or ``"Variable"`` or as a position starting at 0. .. describe:: iter(map) - Return an iterator of the :class:`canopen.pdo.Variable` entries in the map. + Return an iterator of the :class:`canopen.pdo.PdoVariable` entries in the map. .. describe:: len(map) Return the number of variables in the map. -.. autoclass:: canopen.pdo.Variable +.. autoclass:: canopen.pdo.PdoVariable :members: :inherited-members: .. py:attribute:: od - The :class:`canopen.objectdictionary.Variable` associated with this object. + The :class:`canopen.objectdictionary.ODVariable` associated with this object. diff --git a/doc/sdo.rst b/doc/sdo.rst index c0db4ca5..7b06118e 100644 --- a/doc/sdo.rst +++ b/doc/sdo.rst @@ -163,25 +163,25 @@ API Return a list of objects (records, arrays and variables). -.. autoclass:: canopen.sdo.Variable +.. autoclass:: canopen.sdo.SdoVariable :members: :inherited-members: .. py:attribute:: od - The :class:`canopen.objectdictionary.Variable` associated with this object. + The :class:`canopen.objectdictionary.ODVariable` associated with this object. -.. autoclass:: canopen.sdo.Record +.. autoclass:: canopen.sdo.SdoRecord :members: .. py:attribute:: od - The :class:`canopen.objectdictionary.Record` associated with this object. + The :class:`canopen.objectdictionary.ODRecord` associated with this object. .. describe:: record[subindex] - Return the :class:`canopen.sdo.Variable` for the specified subindex + Return the :class:`canopen.sdo.SdoVariable` for the specified subindex (as int) or name (as string). .. describe:: iter(record) @@ -199,19 +199,19 @@ API .. method:: values() - Return a list of :class:`canopen.sdo.Variable` in the record. + Return a list of :class:`canopen.sdo.SdoVariable` in the record. -.. autoclass:: canopen.sdo.Array +.. autoclass:: canopen.sdo.SdoArray :members: .. py:attribute:: od - The :class:`canopen.objectdictionary.Array` associated with this object. + The :class:`canopen.objectdictionary.ODArray` associated with this object. .. describe:: array[subindex] - Return the :class:`canopen.sdo.Variable` for the specified subindex + Return the :class:`canopen.sdo.SdoVariable` for the specified subindex (as int) or name (as string). .. describe:: iter(array) @@ -234,7 +234,7 @@ API .. method:: values() - Return a list of :class:`canopen.sdo.Variable` in the array. + Return a list of :class:`canopen.sdo.SdoVariable` in the array. This will make a SDO read operation on subindex 0 in order to get the actual length of the array. diff --git a/test/test_eds.py b/test/test_eds.py index 50629234..a3923709 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -53,7 +53,7 @@ def test_load_file_object(self): def test_variable(self): var = self.od['Producer heartbeat time'] - self.assertIsInstance(var, canopen.objectdictionary.Variable) + self.assertIsInstance(var, canopen.objectdictionary.ODVariable) self.assertEqual(var.index, 0x1017) self.assertEqual(var.subindex, 0) self.assertEqual(var.name, 'Producer heartbeat time') @@ -69,12 +69,12 @@ def test_relative_variable(self): def test_record(self): record = self.od['Identity object'] - self.assertIsInstance(record, canopen.objectdictionary.Record) + self.assertIsInstance(record, canopen.objectdictionary.ODRecord) self.assertEqual(len(record), 5) self.assertEqual(record.index, 0x1018) self.assertEqual(record.name, 'Identity object') var = record['Vendor-ID'] - self.assertIsInstance(var, canopen.objectdictionary.Variable) + self.assertIsInstance(var, canopen.objectdictionary.ODVariable) self.assertEqual(var.name, 'Vendor-ID') self.assertEqual(var.index, 0x1018) self.assertEqual(var.subindex, 1) @@ -104,11 +104,11 @@ def test_signed_int_from_hex(self): def test_array_compact_subobj(self): array = self.od[0x1003] - self.assertIsInstance(array, canopen.objectdictionary.Array) + self.assertIsInstance(array, canopen.objectdictionary.ODArray) self.assertEqual(array.index, 0x1003) self.assertEqual(array.name, 'Pre-defined error field') var = array[5] - self.assertIsInstance(var, canopen.objectdictionary.Variable) + self.assertIsInstance(var, canopen.objectdictionary.ODVariable) self.assertEqual(var.name, 'Pre-defined error field_5') self.assertEqual(var.index, 0x1003) self.assertEqual(var.subindex, 5) @@ -139,7 +139,7 @@ def test_sub_index_w_capital_s(self): def test_dummy_variable(self): var = self.od['Dummy0003'] - self.assertIsInstance(var, canopen.objectdictionary.Variable) + self.assertIsInstance(var, canopen.objectdictionary.ODVariable) self.assertEqual(var.index, 0x0003) self.assertEqual(var.subindex, 0) self.assertEqual(var.name, 'Dummy0003') @@ -199,7 +199,7 @@ def test_export_eds(self): self.assertEqual(type(actual_object), type(expected_object)) self.assertEqual(actual_object.name, expected_object.name) - if isinstance(actual_object, canopen.objectdictionary.Variable): + if isinstance(actual_object, canopen.objectdictionary.ODVariable): expected_vars = [expected_object] actual_vars = [actual_object] else: diff --git a/test/test_od.py b/test/test_od.py index 794df05c..fe90dc13 100644 --- a/test/test_od.py +++ b/test/test_od.py @@ -5,7 +5,7 @@ class TestDataConversions(unittest.TestCase): def test_boolean(self): - var = od.Variable("Test BOOLEAN", 0x1000) + var = od.ODVariable("Test BOOLEAN", 0x1000) var.data_type = od.BOOLEAN self.assertEqual(var.decode_raw(b"\x01"), True) self.assertEqual(var.decode_raw(b"\x00"), False) @@ -13,25 +13,25 @@ def test_boolean(self): self.assertEqual(var.encode_raw(False), b"\x00") def test_unsigned8(self): - var = od.Variable("Test UNSIGNED8", 0x1000) + var = od.ODVariable("Test UNSIGNED8", 0x1000) var.data_type = od.UNSIGNED8 self.assertEqual(var.decode_raw(b"\xff"), 255) self.assertEqual(var.encode_raw(254), b"\xfe") def test_unsigned16(self): - var = od.Variable("Test UNSIGNED16", 0x1000) + var = od.ODVariable("Test UNSIGNED16", 0x1000) var.data_type = od.UNSIGNED16 self.assertEqual(var.decode_raw(b"\xfe\xff"), 65534) self.assertEqual(var.encode_raw(65534), b"\xfe\xff") def test_unsigned32(self): - var = od.Variable("Test UNSIGNED32", 0x1000) + var = od.ODVariable("Test UNSIGNED32", 0x1000) var.data_type = od.UNSIGNED32 self.assertEqual(var.decode_raw(b"\xfc\xfd\xfe\xff"), 4294901244) self.assertEqual(var.encode_raw(4294901244), b"\xfc\xfd\xfe\xff") def test_integer8(self): - var = od.Variable("Test INTEGER8", 0x1000) + var = od.ODVariable("Test INTEGER8", 0x1000) var.data_type = od.INTEGER8 self.assertEqual(var.decode_raw(b"\xff"), -1) self.assertEqual(var.decode_raw(b"\x7f"), 127) @@ -39,7 +39,7 @@ def test_integer8(self): self.assertEqual(var.encode_raw(127), b"\x7f") def test_integer16(self): - var = od.Variable("Test INTEGER16", 0x1000) + var = od.ODVariable("Test INTEGER16", 0x1000) var.data_type = od.INTEGER16 self.assertEqual(var.decode_raw(b"\xfe\xff"), -2) self.assertEqual(var.decode_raw(b"\x01\x00"), 1) @@ -47,13 +47,13 @@ def test_integer16(self): self.assertEqual(var.encode_raw(1), b"\x01\x00") def test_integer32(self): - var = od.Variable("Test INTEGER32", 0x1000) + var = od.ODVariable("Test INTEGER32", 0x1000) var.data_type = od.INTEGER32 self.assertEqual(var.decode_raw(b"\xfe\xff\xff\xff"), -2) self.assertEqual(var.encode_raw(-2), b"\xfe\xff\xff\xff") def test_visible_string(self): - var = od.Variable("Test VISIBLE_STRING", 0x1000) + var = od.ODVariable("Test VISIBLE_STRING", 0x1000) var.data_type = od.VISIBLE_STRING self.assertEqual(var.decode_raw(b"abcdefg"), "abcdefg") self.assertEqual(var.decode_raw(b"zero terminated\x00"), "zero terminated") @@ -63,7 +63,7 @@ def test_visible_string(self): class TestAlternativeRepresentations(unittest.TestCase): def test_phys(self): - var = od.Variable("Test INTEGER16", 0x1000) + var = od.ODVariable("Test INTEGER16", 0x1000) var.data_type = od.INTEGER16 var.factor = 0.1 @@ -71,7 +71,7 @@ def test_phys(self): self.assertEqual(var.encode_phys(-0.1), -1) def test_desc(self): - var = od.Variable("Test UNSIGNED8", 0x1000) + var = od.ODVariable("Test UNSIGNED8", 0x1000) var.data_type = od.UNSIGNED8 var.add_value_description(0, "Value 0") var.add_value_description(1, "Value 1") @@ -82,7 +82,7 @@ def test_desc(self): self.assertEqual(var.encode_desc("Value 1"), 1) def test_bits(self): - var = od.Variable("Test UNSIGNED8", 0x1000) + var = od.ODVariable("Test UNSIGNED8", 0x1000) var.data_type = od.UNSIGNED8 var.add_bit_definition("BIT 0", [0]) var.add_bit_definition("BIT 2 and 3", [2, 3]) @@ -99,15 +99,15 @@ class TestObjectDictionary(unittest.TestCase): def test_add_variable(self): test_od = od.ObjectDictionary() - var = od.Variable("Test Variable", 0x1000) + var = od.ODVariable("Test Variable", 0x1000) test_od.add_object(var) self.assertEqual(test_od["Test Variable"], var) self.assertEqual(test_od[0x1000], var) def test_add_record(self): test_od = od.ObjectDictionary() - record = od.Record("Test Record", 0x1001) - var = od.Variable("Test Subindex", 0x1001, 1) + record = od.ODRecord("Test Record", 0x1001) + var = od.ODVariable("Test Subindex", 0x1001, 1) record.add_member(var) test_od.add_object(record) self.assertEqual(test_od["Test Record"], record) @@ -116,8 +116,8 @@ def test_add_record(self): def test_add_array(self): test_od = od.ObjectDictionary() - array = od.Array("Test Array", 0x1002) - array.add_member(od.Variable("Last subindex", 0x1002, 0)) + array = od.ODArray("Test Array", 0x1002) + array.add_member(od.ODVariable("Last subindex", 0x1002, 0)) test_od.add_object(array) self.assertEqual(test_od["Test Array"], array) self.assertEqual(test_od[0x1002], array) @@ -126,12 +126,12 @@ def test_add_array(self): class TestArray(unittest.TestCase): def test_subindexes(self): - array = od.Array("Test Array", 0x1000) - last_subindex = od.Variable("Last subindex", 0x1000, 0) + array = od.ODArray("Test Array", 0x1000) + last_subindex = od.ODVariable("Last subindex", 0x1000, 0) last_subindex.data_type = od.UNSIGNED8 array.add_member(last_subindex) - array.add_member(od.Variable("Test Variable", 0x1000, 1)) - array.add_member(od.Variable("Test Variable 2", 0x1000, 2)) + array.add_member(od.ODVariable("Test Variable", 0x1000, 1)) + array.add_member(od.ODVariable("Test Variable 2", 0x1000, 2)) self.assertEqual(array[0].name, "Last subindex") self.assertEqual(array[1].name, "Test Variable") self.assertEqual(array[2].name, "Test Variable 2") From 54180545d06d8173a0589d95d01bfc75415658dd Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Fri, 1 Sep 2023 21:52:43 +0200 Subject: [PATCH 106/199] Implement reading PDO from OD (#273) (#370) --- canopen/pdo/base.py | 26 ++++++++++++++++---------- 1 file changed, 16 insertions(+), 10 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index bb166e7a..ffe6dc32 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -50,10 +50,10 @@ def __getitem__(self, key): def __len__(self): return len(self.map) - def read(self): + def read(self, from_od=False): """Read PDO configuration from node using SDO.""" for pdo_map in self.map.values(): - pdo_map.read() + pdo_map.read(from_od=from_od) def save(self): """Save PDO configuration to node using SDO.""" @@ -313,43 +313,49 @@ def add_callback(self, callback: Callable[["Map"], None]) -> None: """ self.callbacks.append(callback) - def read(self) -> None: + def read(self, from_od=False) -> None: """Read PDO configuration for this map using SDO.""" - cob_id = self.com_record[1].raw + + def _raw_from(param): + if from_od: + return param.od.default + return param.raw + + cob_id = _raw_from(self.com_record[1]) self.cob_id = cob_id & 0x1FFFFFFF logger.info("COB-ID is 0x%X", self.cob_id) self.enabled = cob_id & PDO_NOT_VALID == 0 logger.info("PDO is %s", "enabled" if self.enabled else "disabled") self.rtr_allowed = cob_id & RTR_NOT_ALLOWED == 0 logger.info("RTR is %s", "allowed" if self.rtr_allowed else "not allowed") - self.trans_type = self.com_record[2].raw + self.trans_type = _raw_from(self.com_record[2]) logger.info("Transmission type is %d", self.trans_type) if self.trans_type >= 254: try: - self.inhibit_time = self.com_record[3].raw + self.inhibit_time = _raw_from(self.com_record[3]) except (KeyError, SdoAbortedError) as e: logger.info("Could not read inhibit time (%s)", e) else: logger.info("Inhibit time is set to %d ms", self.inhibit_time) try: - self.event_timer = self.com_record[5].raw + self.event_timer = _raw_from(self.com_record[5]) except (KeyError, SdoAbortedError) as e: logger.info("Could not read event timer (%s)", e) else: logger.info("Event timer is set to %d ms", self.event_timer) try: - self.sync_start_value = self.com_record[6].raw + self.sync_start_value = _raw_from(self.com_record[6]) except (KeyError, SdoAbortedError) as e: logger.info("Could not read SYNC start value (%s)", e) else: logger.info("SYNC start value is set to %d ms", self.sync_start_value) self.clear() - nof_entries = self.map_array[0].raw + nof_entries = _raw_from(self.map_array[0]) for subindex in range(1, nof_entries + 1): - value = self.map_array[subindex].raw + value = _raw_from(self.map_array[subindex]) index = value >> 16 subindex = (value >> 8) & 0xFF size = value & 0xFF From 6f9f06eb4a2d8989583e35ec0d4b34d7705726d0 Mon Sep 17 00:00:00 2001 From: Carl Ljungholm Date: Sun, 17 Sep 2023 10:26:42 +0200 Subject: [PATCH 107/199] Use smaller of response size and size in OD (#395) --- canopen/sdo/client.py | 27 ++++++++++++++------------- 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 21517717..370aab72 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -114,21 +114,22 @@ def upload(self, index: int, subindex: int) -> bytes: When node responds with an error. """ with self.open(index, subindex, buffering=0) as fp: - size = fp.size + response_size = fp.size data = fp.read() - if size is None: - # Node did not specify how many bytes to use - # Try to find out using Object Dictionary - var = self.od.get_variable(index, subindex) - if var is not None: - # Found a matching variable in OD - # If this is a data type (string, domain etc) the size is - # unknown anyway so keep the data as is - if var.data_type not in objectdictionary.DATA_TYPES: - # Get the size in bytes for this variable - size = len(var) // 8 + + # If size is available through variable in OD, then use the smaller of the two sizes. + # Some devices send U32/I32 even if variable is smaller in OD + var = self.od.get_variable(index, subindex) + if var is not None: + # Found a matching variable in OD + # If this is a data type (string, domain etc) the size is + # unknown anyway so keep the data as is + if var.data_type not in objectdictionary.DATA_TYPES: + # Get the size in bytes for this variable + var_size = len(var) // 8 + if response_size is None or var_size < response_size: # Truncate the data to specified size - data = data[0:size] + data = data[0:var_size] return data def download( From ba4fa0c337e1d8df1800788f4a778be162302663 Mon Sep 17 00:00:00 2001 From: Pavel Gostev <73311144+vongostev@users.noreply.github.com> Date: Tue, 14 Nov 2023 23:29:49 +0300 Subject: [PATCH 108/199] Support of custom can.Bus implementations to the Network class (#404) --- canopen/network.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index 7768795d..0f9c9327 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -33,7 +33,7 @@ class Listener: class Network(MutableMapping): """Representation of one CAN bus containing one or more nodes.""" - def __init__(self, bus=None): + def __init__(self, bus: can.BusABC | None = None): """ :param can.BusABC bus: A python-can bus instance to re-use. @@ -110,7 +110,8 @@ def connect(self, *args, **kwargs) -> "Network": if node.object_dictionary.bitrate: kwargs["bitrate"] = node.object_dictionary.bitrate break - self.bus = can.interface.Bus(*args, **kwargs) + if self.bus is None: + self.bus = can.Bus(*args, **kwargs) logger.info("Connected to '%s'", self.bus.channel_info) self.notifier = can.Notifier(self.bus, self.listeners, 1) return self From 36900b1358271dcb254f3e7fef441de90537e4c3 Mon Sep 17 00:00:00 2001 From: raffi-g <42327873+raffi-g@users.noreply.github.com> Date: Mon, 4 Dec 2023 12:31:02 +0100 Subject: [PATCH 109/199] 24 bit support (#406) --- canopen/objectdictionary/__init__.py | 3 ++ canopen/objectdictionary/datatypes.py | 6 ++-- canopen/objectdictionary/datatypes_24bit.py | 33 +++++++++++++++++++++ test/test_eds.py | 7 +++++ test/test_od.py | 14 +++++++++ 5 files changed, 61 insertions(+), 2 deletions(-) create mode 100644 canopen/objectdictionary/datatypes_24bit.py diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 066a069c..6cc762b6 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -10,6 +10,7 @@ import logging from canopen.objectdictionary.datatypes import * +from canopen.objectdictionary.datatypes_24bit import Integer24, Unsigned24 logger = logging.getLogger(__name__) @@ -277,10 +278,12 @@ class ODVariable: BOOLEAN: struct.Struct("?"), INTEGER8: struct.Struct("b"), INTEGER16: struct.Struct(" 0 + return self.__st.unpack(__buffer + (b'\xff' if neg else b'\x00')) + + def pack(self, *v): + return self.__st.pack(*v)[:3] + + @property + def size(self): + return 3 diff --git a/test/test_eds.py b/test/test_eds.py index a3923709..a35cbb99 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -23,6 +23,13 @@ class TestEDS(unittest.TestCase): {"hex_str": "0000", "bit_length": 16, "expected": 0}, {"hex_str": "0001", "bit_length": 16, "expected": 1} ], + "int24": [ + {"hex_str": "7FFFFF", "bit_length": 24, "expected": 8388607}, + {"hex_str": "800000", "bit_length": 24, "expected": -8388608}, + {"hex_str": "FFFFFF", "bit_length": 24, "expected": -1}, + {"hex_str": "000000", "bit_length": 24, "expected": 0}, + {"hex_str": "000001", "bit_length": 24, "expected": 1} + ], "int32": [ {"hex_str": "7FFFFFFF", "bit_length": 32, "expected": 2147483647}, {"hex_str": "80000000", "bit_length": 32, "expected": -2147483648}, diff --git a/test/test_od.py b/test/test_od.py index fe90dc13..a5f00985 100644 --- a/test/test_od.py +++ b/test/test_od.py @@ -24,6 +24,12 @@ def test_unsigned16(self): self.assertEqual(var.decode_raw(b"\xfe\xff"), 65534) self.assertEqual(var.encode_raw(65534), b"\xfe\xff") + def test_unsigned24(self): + var = od.ODVariable("Test UNSIGNED24", 0x1000) + var.data_type = od.UNSIGNED24 + self.assertEqual(var.decode_raw(b"\xfd\xfe\xff"), 16776957) + self.assertEqual(var.encode_raw(16776957), b"\xfd\xfe\xff") + def test_unsigned32(self): var = od.ODVariable("Test UNSIGNED32", 0x1000) var.data_type = od.UNSIGNED32 @@ -46,6 +52,14 @@ def test_integer16(self): self.assertEqual(var.encode_raw(-2), b"\xfe\xff") self.assertEqual(var.encode_raw(1), b"\x01\x00") + def test_integer24(self): + var = od.ODVariable("Test INTEGER24", 0x1000) + var.data_type = od.INTEGER24 + self.assertEqual(var.decode_raw(b"\xfe\xff\xff"), -2) + self.assertEqual(var.decode_raw(b"\x01\x00\x00"), 1) + self.assertEqual(var.encode_raw(-2), b"\xfe\xff\xff") + self.assertEqual(var.encode_raw(1), b"\x01\x00\x00") + def test_integer32(self): var = od.ODVariable("Test INTEGER32", 0x1000) var.data_type = od.INTEGER32 From e3d2155c7f97c7be6f176e29c306e0112ed5ab9f Mon Sep 17 00:00:00 2001 From: meifonglow Date: Wed, 17 Apr 2024 20:58:11 +1000 Subject: [PATCH 110/199] objectdictionary: Fix incorrect ParameterValue when export_dcf (#417) --- canopen/objectdictionary/eds.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 73a7eaeb..f4d9f238 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -383,7 +383,7 @@ def export_variable(var, eds): eds.set(section, "ParameterValue", var.value_raw) elif getattr(var, 'value', None) is not None: eds.set(section, "ParameterValue", - _revert_variable(var.data_type, var.default)) + _revert_variable(var.data_type, var.value)) eds.set(section, "DataType", "0x%04X" % var.data_type) eds.set(section, "PDOMapping", hex(var.pdo_mappable)) From 0e6e510fbe1e3ecac95d761b9abbbe2a29b0ab41 Mon Sep 17 00:00:00 2001 From: Samuel Lee <54152208+samsamfire@users.noreply.github.com> Date: Thu, 18 Apr 2024 08:37:39 +0200 Subject: [PATCH 111/199] SDO client fixes (#408) --- canopen/sdo/client.py | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 370aab72..d64a1c14 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -470,6 +470,7 @@ def __init__(self, sdo_client, index, subindex=0, request_crc_support=True): self._crc = sdo_client.crc_cls() self._server_crc = None self._ackseq = 0 + self._error = False logger.debug("Reading 0x%X:%d from node %d", index, subindex, sdo_client.rx_cobid - 0x600) @@ -483,9 +484,12 @@ def __init__(self, sdo_client, index, subindex=0, request_crc_support=True): response = sdo_client.request_response(request) res_command, res_index, res_subindex = SDO_STRUCT.unpack_from(response) if res_command & 0xE0 != RESPONSE_BLOCK_UPLOAD: + self._error = True + self.sdo_client.abort(0x05040001) raise SdoCommunicationError("Unexpected response 0x%02X" % res_command) # Check that the message is for us if res_index != index or res_subindex != subindex: + self._error = True raise SdoCommunicationError(( "Node returned a value for 0x{:X}:{:d} instead, " "maybe there is another SDO client communicating " @@ -537,6 +541,7 @@ def read(self, size=-1): self._crc.process(data) if self._done: if self._server_crc != self._crc.final(): + self._error = True self.sdo_client.abort(0x05040004) raise SdoCommunicationError("CRC is not OK") logger.info("CRC is OK") @@ -556,6 +561,8 @@ def _retransmit(self): # We should be back in sync self._ackseq = seqno return response + self._error = True + self.sdo_client.abort(0x05040000) raise SdoCommunicationError("Some data were lost and could not be retransmitted") def _ack_block(self): @@ -571,9 +578,11 @@ def _end_upload(self): response = self.sdo_client.read_response() res_command, self._server_crc = struct.unpack_from(" Date: Sun, 21 Apr 2024 16:54:12 +0200 Subject: [PATCH 112/199] Ignore the most significant bit in PDO mapping lengths. (#421) --- canopen/pdo/base.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index ffe6dc32..52a0aa04 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -358,11 +358,12 @@ def _raw_from(param): value = _raw_from(self.map_array[subindex]) index = value >> 16 subindex = (value >> 8) & 0xFF - size = value & 0xFF + # Ignore the highest bit, it is never valid for <= 64 PDO length + size = value & 0x7F if hasattr(self.pdo_node.node, "curtis_hack") and self.pdo_node.node.curtis_hack: # Curtis HACK: mixed up field order index = value & 0xFFFF subindex = (value >> 16) & 0xFF - size = (value >> 24) & 0xFF + size = (value >> 24) & 0x7F if index and size: self.add_variable(index, subindex, size) From a973919d0c32510b2fcadaea1fd0943377756271 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 25 Apr 2024 18:00:06 +0200 Subject: [PATCH 113/199] Implement abstract method can.Listener.stop() in MessageListener. (#422) --- canopen/network.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/canopen/network.py b/canopen/network.py index 0f9c9327..4fcb13ec 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -363,6 +363,9 @@ def on_message_received(self, msg): # Exceptions in any callbaks should not affect CAN processing logger.error(str(e)) + def stop(self) -> None: + """Override abstract base method to release any resources.""" + class NodeScanner: """Observes which nodes are present on the bus. From dc8a4ca79a45db4c5f56fe0db8f3634202b63ada Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 25 Apr 2024 21:56:52 +0200 Subject: [PATCH 114/199] Mirror some OD access API to the SdoBase / SdoVariable classes. (#423) --- canopen/sdo/base.py | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 85cfe4e9..dcd35eb3 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -1,5 +1,5 @@ import binascii -from typing import Iterable, Union +from typing import Iterable, Optional, Union try: from collections.abc import Mapping except ImportError: @@ -67,6 +67,19 @@ def __len__(self) -> int: def __contains__(self, key: Union[int, str]) -> bool: return key in self.od + def get_variable( + self, index: Union[int, str], subindex: int = 0 + ) -> Optional["SdoVariable"]: + """Get the variable object at specified index (and subindex if applicable). + + :return: SdoVariable if found, else `None` + """ + obj = self.get(index) + if isinstance(obj, SdoVariable): + return obj + elif isinstance(obj, (SdoRecord, SdoArray)): + return obj.get(subindex) + def upload(self, index: int, subindex: int) -> bytes: raise NotImplementedError() @@ -132,6 +145,14 @@ def set_data(self, data: bytes): force_segment = self.od.data_type == objectdictionary.DOMAIN self.sdo_node.download(self.od.index, self.od.subindex, data, force_segment) + @property + def writable(self) -> bool: + return self.od.writable + + @property + def readable(self) -> bool: + return self.od.readable + def open(self, mode="rb", encoding="ascii", buffering=1024, size=None, block_transfer=False, request_crc_support=True): """Open the data stream as a file like object. From 32911106425168dbc582cbfc81934a510675a59a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Sun, 28 Apr 2024 20:37:00 +0200 Subject: [PATCH 115/199] Implement equality operator for SdoAbortedError. (#424) --- canopen/sdo/exceptions.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/canopen/sdo/exceptions.py b/canopen/sdo/exceptions.py index 515b4086..db54597c 100644 --- a/canopen/sdo/exceptions.py +++ b/canopen/sdo/exceptions.py @@ -54,6 +54,10 @@ def __str__(self): text = text + ", " + self.CODES[self.code] return text + def __eq__(self, other): + """Compare two exception objects based on SDO abort code.""" + return self.code == other.code + class SdoCommunicationError(SdoError): """No or unexpected response from slave.""" From b55ce5cac8d645ecb14b622323ae6136e561966c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Fri, 26 Apr 2024 09:55:04 +0200 Subject: [PATCH 116/199] Use older type annotation syntax. Python 3.10 added the | operator for typing hint alternatives. Since this is the only place where that new syntax is used, revert it to use the Optional type and restore compatibility with Python < 3.10. --- canopen/network.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen/network.py b/canopen/network.py index 4fcb13ec..a1993b17 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -33,7 +33,7 @@ class Listener: class Network(MutableMapping): """Representation of one CAN bus containing one or more nodes.""" - def __init__(self, bus: can.BusABC | None = None): + def __init__(self, bus: Optional[can.BusABC] = None): """ :param can.BusABC bus: A python-can bus instance to re-use. From 26a68b50840e39fa3dd909506cf4a90d8cc6da66 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Wed, 15 May 2024 22:41:10 +0200 Subject: [PATCH 117/199] Clean up imports of old modules (#433) Remove compatibility leftovers from earlier versions of Python. Minimum version as of now is Python 3.6. * import Queue dates to Python 2 * import collections.*Mapping was changed to collections.abc.*Mapping in Python 3.3 * import ConfigParser dates to Python 2 * import xml.etree.cElementTree is deprecated since Python 3.3. It will pick the fastest option when using xml.etree.ElementTree. Fix some package relative imports to be consistent with surrounding code. --- canopen/lss.py | 5 +---- canopen/network.py | 5 +---- canopen/objectdictionary/__init__.py | 5 +---- canopen/objectdictionary/eds.py | 6 +----- canopen/objectdictionary/epf.py | 5 +---- canopen/pdo/__init__.py | 2 +- canopen/pdo/base.py | 5 +---- canopen/sdo/__init__.py | 2 +- canopen/sdo/base.py | 5 +---- canopen/sdo/client.py | 5 +---- canopen/variable.py | 5 +---- 11 files changed, 11 insertions(+), 39 deletions(-) diff --git a/canopen/lss.py b/canopen/lss.py index 9dee3147..d197a5a7 100644 --- a/canopen/lss.py +++ b/canopen/lss.py @@ -1,10 +1,7 @@ import logging import time import struct -try: - import queue -except ImportError: - import Queue as queue +import queue logger = logging.getLogger(__name__) diff --git a/canopen/network.py b/canopen/network.py index a1993b17..4a5a23e0 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -1,7 +1,4 @@ -try: - from collections.abc import MutableMapping -except ImportError: - from collections import MutableMapping +from collections.abc import MutableMapping import logging import threading from typing import Callable, Dict, Iterable, List, Optional, Union diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 6cc762b6..a7c79c53 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -3,10 +3,7 @@ """ import struct from typing import Dict, Iterable, List, Optional, TextIO, Union -try: - from collections.abc import MutableMapping, Mapping -except ImportError: - from collections import MutableMapping, Mapping +from collections.abc import MutableMapping, Mapping import logging from canopen.objectdictionary.datatypes import * diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index f4d9f238..a952c8a5 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -1,11 +1,7 @@ import copy import logging import re - -try: - from configparser import RawConfigParser, NoOptionError, NoSectionError -except ImportError: - from ConfigParser import RawConfigParser, NoOptionError, NoSectionError +from configparser import RawConfigParser, NoOptionError, NoSectionError from canopen import objectdictionary from canopen.objectdictionary import ObjectDictionary, datatypes diff --git a/canopen/objectdictionary/epf.py b/canopen/objectdictionary/epf.py index f884b659..46ffe59e 100644 --- a/canopen/objectdictionary/epf.py +++ b/canopen/objectdictionary/epf.py @@ -1,7 +1,4 @@ -try: - import xml.etree.cElementTree as etree -except ImportError: - import xml.etree.ElementTree as etree +import xml.etree.ElementTree as etree import logging from canopen import objectdictionary diff --git a/canopen/pdo/__init__.py b/canopen/pdo/__init__.py index 46396e30..98edab6f 100644 --- a/canopen/pdo/__init__.py +++ b/canopen/pdo/__init__.py @@ -4,7 +4,7 @@ from canopen.pdo.base import PdoBase, Maps # Compatibility -from .base import Variable +from canopen.pdo.base import Variable logger = logging.getLogger(__name__) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 52a0aa04..25c10ae2 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -1,10 +1,7 @@ import threading import math from typing import Callable, Dict, Iterable, List, Optional, Union -try: - from collections.abc import Mapping -except ImportError: - from collections import Mapping +from collections.abc import Mapping import logging import binascii diff --git a/canopen/sdo/__init__.py b/canopen/sdo/__init__.py index 775a8c4e..39b8478c 100644 --- a/canopen/sdo/__init__.py +++ b/canopen/sdo/__init__.py @@ -4,4 +4,4 @@ from canopen.sdo.exceptions import SdoAbortedError, SdoCommunicationError # Compatibility -from .base import Variable, Record, Array +from canopen.sdo.base import Variable, Record, Array diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index dcd35eb3..1a2ff566 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -1,9 +1,6 @@ import binascii from typing import Iterable, Optional, Union -try: - from collections.abc import Mapping -except ImportError: - from collections import Mapping +from collections.abc import Mapping from canopen import objectdictionary from canopen.objectdictionary import ObjectDictionary diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index d64a1c14..888d3af7 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -2,10 +2,7 @@ import logging import io import time -try: - import queue -except ImportError: - import Queue as queue +import queue from canopen.network import CanError from canopen import objectdictionary diff --git a/canopen/variable.py b/canopen/variable.py index e8687660..5ca09a24 100644 --- a/canopen/variable.py +++ b/canopen/variable.py @@ -1,9 +1,6 @@ import logging from typing import Union -try: - from collections.abc import Mapping -except ImportError: - from collections import Mapping +from collections.abc import Mapping from canopen import objectdictionary From d38045f664a4dedeee7202cf4b2cee3291c99bb4 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Wed, 15 May 2024 23:15:18 +0200 Subject: [PATCH 118/199] Rename Maps to PdoMaps and Map to PdoMap (#431) --- canopen/pdo/__init__.py | 6 +++--- canopen/pdo/base.py | 18 ++++++++++-------- canopen/profiles/p402.py | 6 +++--- doc/pdo.rst | 4 ++-- 4 files changed, 18 insertions(+), 16 deletions(-) diff --git a/canopen/pdo/__init__.py b/canopen/pdo/__init__.py index 98edab6f..8002945a 100644 --- a/canopen/pdo/__init__.py +++ b/canopen/pdo/__init__.py @@ -1,7 +1,7 @@ import logging from canopen import node -from canopen.pdo.base import PdoBase, Maps +from canopen.pdo.base import PdoBase, PdoMaps # Compatibility from canopen.pdo.base import Variable @@ -38,7 +38,7 @@ class RPDO(PdoBase): def __init__(self, node): super(RPDO, self).__init__(node) - self.map = Maps(0x1400, 0x1600, self, 0x200) + self.map = PdoMaps(0x1400, 0x1600, self, 0x200) logger.debug('RPDO Map as {0}'.format(len(self.map))) def stop(self): @@ -63,7 +63,7 @@ class TPDO(PdoBase): def __init__(self, node): super(TPDO, self).__init__(node) - self.map = Maps(0x1800, 0x1A00, self, 0x180) + self.map = PdoMaps(0x1800, 0x1A00, self, 0x180) logger.debug('TPDO Map as {0}'.format(len(self.map))) def stop(self): diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 25c10ae2..d563ef82 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -24,7 +24,7 @@ class PdoBase(Mapping): def __init__(self, node): self.network = None - self.map = None # instance of Maps + self.map = None # instance of PdoMaps self.node = node def __iter__(self): @@ -121,7 +121,7 @@ def stop(self): pdo_map.stop() -class Maps(Mapping): +class PdoMaps(Mapping): """A collection of transmit or receive maps.""" def __init__(self, com_offset, map_offset, pdo_node: PdoBase, cob_base=None): @@ -131,10 +131,10 @@ def __init__(self, com_offset, map_offset, pdo_node: PdoBase, cob_base=None): :param pdo_node: :param cob_base: """ - self.maps: Dict[int, "Map"] = {} + self.maps: Dict[int, "PdoMap"] = {} for map_no in range(512): if com_offset + map_no in pdo_node.node.object_dictionary: - new_map = Map( + new_map = PdoMap( pdo_node, pdo_node.node.sdo[com_offset + map_no], pdo_node.node.sdo[map_offset + map_no]) @@ -143,7 +143,7 @@ def __init__(self, com_offset, map_offset, pdo_node: PdoBase, cob_base=None): new_map.predefined_cob_id = cob_base + map_no * 0x100 + pdo_node.node.id self.maps[map_no + 1] = new_map - def __getitem__(self, key: int) -> "Map": + def __getitem__(self, key: int) -> "PdoMap": return self.maps[key] def __iter__(self) -> Iterable[int]: @@ -153,7 +153,7 @@ def __len__(self) -> int: return len(self.maps) -class Map: +class PdoMap: """One message which can have up to 8 bytes of variables mapped.""" def __init__(self, pdo_node, com_record, map_array): @@ -301,12 +301,12 @@ def on_message(self, can_id, data, timestamp): for callback in self.callbacks: callback(self) - def add_callback(self, callback: Callable[["Map"], None]) -> None: + def add_callback(self, callback: Callable[["PdoMap"], None]) -> None: """Add a callback which will be called on receive. :param callback: The function to call which must take one argument of a - :class:`~canopen.pdo.Map`. + :class:`~canopen.pdo.PdoMap`. """ self.callbacks.append(callback) @@ -606,3 +606,5 @@ def set_data(self, data: bytes): # For compatibility Variable = PdoVariable +Maps = PdoMaps +Map = PdoMap diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 2e5fb133..d5b4ce5e 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -212,8 +212,8 @@ class BaseNode402(RemoteNode): def __init__(self, node_id, object_dictionary): super(BaseNode402, self).__init__(node_id, object_dictionary) self.tpdo_values = {} # { index: value from last received TPDO } - self.tpdo_pointers = {} # { index: pdo.Map instance } - self.rpdo_pointers = {} # { index: pdo.Map instance } + self.tpdo_pointers = {} # { index: pdo.PdoMap instance } + self.rpdo_pointers = {} # { index: pdo.PdoMap instance } def setup_402_state_machine(self, read_pdos=True): """Configure the state machine by searching for a TPDO that has the StatusWord mapped. @@ -459,7 +459,7 @@ def on_TPDOs_update_callback(self, mapobject): """Cache updated values from a TPDO received from this node. :param mapobject: The received PDO message. - :type mapobject: canopen.pdo.Map + :type mapobject: canopen.pdo.PdoMap """ for obj in mapobject: self.tpdo_values[obj.index] = obj.raw diff --git a/doc/pdo.rst b/doc/pdo.rst index 05e1e94d..bcef197b 100644 --- a/doc/pdo.rst +++ b/doc/pdo.rst @@ -89,7 +89,7 @@ API .. describe:: pdo[no] - Return the :class:`canopen.pdo.Map` for the specified map number. + Return the :class:`canopen.pdo.PdoMap` for the specified map number. First map starts at 1. .. describe:: iter(pdo) @@ -101,7 +101,7 @@ API Return the number of supported maps. -.. autoclass:: canopen.pdo.Map +.. autoclass:: canopen.pdo.PdoMap :members: .. describe:: map[name] From 681706657f02fc3b41285678209f786562bc49be Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Thu, 16 May 2024 13:54:40 +0200 Subject: [PATCH 119/199] Make pause after sending SDO request configurable (#429) --- canopen/sdo/client.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 888d3af7..77b7ac9f 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -25,6 +25,9 @@ class SdoClient(SdoBase): #: Seconds to wait before sending a request, for rate limiting PAUSE_BEFORE_SEND = 0.0 + #: Seconds to wait after sending a request + PAUSE_AFTER_SEND = 0.1 + def __init__(self, rx_cobid, tx_cobid, od): """ :param int rx_cobid: @@ -53,7 +56,8 @@ def send_request(self, request): if not retries_left: raise logger.info(str(e)) - time.sleep(0.1) + if self.PAUSE_AFTER_SEND: + time.sleep(self.PAUSE_AFTER_SEND) else: break From 3c1d86c1d621f3406cb83007641a6775e568c24c Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Thu, 16 May 2024 17:15:04 +0200 Subject: [PATCH 120/199] Add meaningful "representation" formatter to object classes (#432) Add __repr__() method for the object classes *Variable(), *Array() and *Record(). Extend ODVariable with a ".qualname" attribute which prepends the parent's name with a dot. --- canopen/objectdictionary/__init__.py | 17 +++++++++++++++++ canopen/pdo/base.py | 3 +++ canopen/sdo/base.py | 6 ++++++ canopen/variable.py | 6 ++++++ 4 files changed, 32 insertions(+) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index a7c79c53..a3bcc527 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -176,6 +176,9 @@ def __init__(self, name: str, index: int): self.subindices = {} self.names = {} + def __repr__(self) -> str: + return f"<{type(self).__qualname__} {self.name!r} at 0x{self.index:04X}>" + def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": item = self.names.get(subindex) or self.subindices.get(subindex) if item is None: @@ -232,6 +235,9 @@ def __init__(self, name: str, index: int): self.subindices = {} self.names = {} + def __repr__(self) -> str: + return f"<{type(self).__qualname__} {self.name!r} at 0x{self.index:04X}>" + def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": var = self.names.get(subindex) or self.subindices.get(subindex) if var is not None: @@ -327,6 +333,17 @@ def __init__(self, name: str, index: int, subindex: int = 0): #: Can this variable be mapped to a PDO self.pdo_mappable = False + def __repr__(self) -> str: + suffix = f":{self.subindex:02X}" if isinstance(self.parent, (ODRecord, ODArray)) else "" + return f"<{type(self).__qualname__} {self.qualname!r} at 0x{self.index:04X}{suffix}>" + + @property + def qualname(self) -> str: + """Fully qualified name of the variable. If the variable is a subindex + of a record or array, the name will be prefixed with the parent's name.""" + if isinstance(self.parent, (ODRecord, ODArray)): + return f"{self.parent.name}.{self.name}" + return self.name def __eq__(self, other: "ODVariable") -> bool: return (self.index == other.index and diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index d563ef82..7312f660 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -191,6 +191,9 @@ def __init__(self, pdo_node, com_record, map_array): self.is_received: bool = False self._task = None + def __repr__(self) -> str: + return f"<{type(self).__qualname__} {self.name!r} at COB-ID 0x{self.cob_id:X}>" + def __getitem_by_index(self, value): valid_values = [] for var in self.map: diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 1a2ff566..f9daebf5 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -96,6 +96,9 @@ def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.sdo_node = sdo_node self.od = od + def __repr__(self) -> str: + return f"<{type(self).__qualname__} {self.od.name!r} at 0x{self.od.index:04X}>" + def __getitem__(self, subindex: Union[int, str]) -> "SdoVariable": return SdoVariable(self.sdo_node, self.od[subindex]) @@ -115,6 +118,9 @@ def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.sdo_node = sdo_node self.od = od + def __repr__(self) -> str: + return f"<{type(self).__qualname__} {self.od.name!r} at 0x{self.od.index:04X}>" + def __getitem__(self, subindex: Union[int, str]) -> "SdoVariable": return SdoVariable(self.sdo_node, self.od[subindex]) diff --git a/canopen/variable.py b/canopen/variable.py index 5ca09a24..a75b68c0 100644 --- a/canopen/variable.py +++ b/canopen/variable.py @@ -22,6 +22,12 @@ def __init__(self, od: objectdictionary.ODVariable): #: Holds a local, overridable copy of the Object Subindex self.subindex = od.subindex + def __repr__(self) -> str: + suffix = f":{self.subindex:02X}" if isinstance(self.od.parent, + (objectdictionary.ODRecord, objectdictionary.ODArray) + ) else "" + return f"<{type(self).__qualname__} {self.name!r} at 0x{self.index:04X}{suffix}>" + def get_data(self) -> bytes: raise NotImplementedError("Variable is not readable") From 54ebbd45a8084f664c21be270fae0f7a1a658355 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Thu, 16 May 2024 17:52:28 +0200 Subject: [PATCH 121/199] Add support for using dot (.) to get subobjects from the OD (#426) --- canopen/objectdictionary/__init__.py | 3 +++ doc/od.rst | 3 ++- doc/sdo.rst | 5 ++++- test/test_od.py | 14 ++++++++++++++ 4 files changed, 23 insertions(+), 2 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index a3bcc527..19196951 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -105,6 +105,9 @@ def __getitem__( """Get object from object dictionary by name or index.""" item = self.names.get(index) or self.indices.get(index) if item is None: + if isinstance(index, str) and '.' in index: + idx, sub = index.split('.', maxsplit=1) + return self[idx][sub] name = "0x%X" % index if isinstance(index, int) else index raise KeyError("%s was not found in Object Dictionary" % name) return item diff --git a/doc/od.rst b/doc/od.rst index 6e7eb3b5..f31c7813 100644 --- a/doc/od.rst +++ b/doc/od.rst @@ -48,7 +48,8 @@ You can access the objects using either index/subindex or names:: device_name_obj = node.object_dictionary['ManufacturerDeviceName'] vendor_id_obj = node.object_dictionary[0x1018][1] - + actual_speed = node.object_dictionary['ApplicationStatus.ActualSpeed'] + command_all = node.object_dictionary['ApplicationCommands.CommandAll'] API --- diff --git a/doc/sdo.rst b/doc/sdo.rst index 7b06118e..8634d28c 100644 --- a/doc/sdo.rst +++ b/doc/sdo.rst @@ -30,11 +30,14 @@ Examples -------- SDO objects can be accessed using the ``.sdo`` member which works like a Python -dictionary. Indexes and subindexes can be identified by either name or number. +dictionary. Indexes can be identified by either name or number. +There are two ways to idenity subindexes, either by using the index and subindex +as separate arguments or by using a combined syntax using a dot. The code below only creates objects, no messages are sent or received yet:: # Complex records command_all = node.sdo['ApplicationCommands']['CommandAll'] + command_all = node.sdo['ApplicationCommands.CommandAll'] actual_speed = node.sdo['ApplicationStatus']['ActualSpeed'] control_mode = node.sdo['ApplicationSetupParameters']['RequestedControlMode'] diff --git a/test/test_od.py b/test/test_od.py index a5f00985..9c25bfcb 100644 --- a/test/test_od.py +++ b/test/test_od.py @@ -136,6 +136,20 @@ def test_add_array(self): self.assertEqual(test_od["Test Array"], array) self.assertEqual(test_od[0x1002], array) + def test_get_item_dot(self): + test_od = od.ObjectDictionary() + array = od.ODArray("Test Array", 0x1000) + last_subindex = od.ODVariable("Last subindex", 0x1000, 0) + last_subindex.data_type = od.UNSIGNED8 + member1 = od.ODVariable("Test Variable", 0x1000, 1) + member2 = od.ODVariable("Test Variable 2", 0x1000, 2) + array.add_member(last_subindex) + array.add_member(member1) + array.add_member(member2) + test_od.add_object(array) + self.assertEqual(test_od["Test Array.Last subindex"], last_subindex) + self.assertEqual(test_od["Test Array.Test Variable"], member1) + self.assertEqual(test_od["Test Array.Test Variable 2"], member2) class TestArray(unittest.TestCase): From 24df6e846a4e71508fd82c378d1385d65f000c94 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Sat, 18 May 2024 15:59:22 +0200 Subject: [PATCH 122/199] Fixup RETRY_DELAY on SDO send (#435) --- canopen/sdo/client.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 77b7ac9f..519bbd5f 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -25,8 +25,8 @@ class SdoClient(SdoBase): #: Seconds to wait before sending a request, for rate limiting PAUSE_BEFORE_SEND = 0.0 - #: Seconds to wait after sending a request - PAUSE_AFTER_SEND = 0.1 + #: Seconds to wait before retrying a request after a send error + RETRY_DELAY = 0.1 def __init__(self, rx_cobid, tx_cobid, od): """ @@ -45,10 +45,10 @@ def on_response(self, can_id, data, timestamp): def send_request(self, request): retries_left = self.MAX_RETRIES + if self.PAUSE_BEFORE_SEND: + time.sleep(self.PAUSE_BEFORE_SEND) while True: try: - if self.PAUSE_BEFORE_SEND: - time.sleep(self.PAUSE_BEFORE_SEND) self.network.send_message(self.rx_cobid, request) except CanError as e: # Could be a buffer overflow. Wait some time before trying again @@ -56,8 +56,8 @@ def send_request(self, request): if not retries_left: raise logger.info(str(e)) - if self.PAUSE_AFTER_SEND: - time.sleep(self.PAUSE_AFTER_SEND) + if self.RETRY_DELAY: + time.sleep(self.RETRY_DELAY) else: break From 94f337d779c9294db99083821a6a834fe58b167a Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Sun, 26 May 2024 13:19:35 +0200 Subject: [PATCH 123/199] Minor linting nitpicks and Python 2 removal (#441) * Removed py2 handling in import_eds * Made file open more robust in import_eds * Additional whitespace removals --- canopen/lss.py | 4 ++-- canopen/network.py | 2 +- canopen/objectdictionary/eds.py | 18 ++++++++---------- canopen/sdo/client.py | 8 ++++---- canopen/sdo/server.py | 2 +- canopen/variable.py | 6 ++---- examples/eds/e35.eds | 10 +++++----- test/test_eds.py | 4 ++-- 8 files changed, 25 insertions(+), 29 deletions(-) diff --git a/canopen/lss.py b/canopen/lss.py index d197a5a7..83d225c5 100644 --- a/canopen/lss.py +++ b/canopen/lss.py @@ -239,12 +239,12 @@ def send_identify_non_configured_remote_slave(self): self.__send_command(message) def fast_scan(self): - """This command sends a series of fastscan message + """This command sends a series of fastscan message to find unconfigured slave with lowest number of LSS idenities :return: True if a slave is found. - False if there is no candidate. + False if there is no candidate. list is the LSS identities [vendor_id, product_code, revision_number, serial_number] :rtype: bool, list """ diff --git a/canopen/network.py b/canopen/network.py index 4a5a23e0..9e9a252e 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -298,7 +298,7 @@ def __init__( bus, remote: bool = False, ): - """ + """ :param can_id: CAN-ID of the message :param data: diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index a952c8a5..b718c945 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -19,19 +19,17 @@ def import_eds(source, node_id): eds = RawConfigParser(inline_comment_prefixes=(';',)) eds.optionxform = str - if hasattr(source, "read"): - fp = source - else: - fp = open(source) + opened_here = False try: - # Python 3 + if hasattr(source, "read"): + fp = source + else: + fp = open(source) + opened_here = True eds.read_file(fp) - except AttributeError: - # Python 2 - eds.readfp(fp) finally: # Only close object if opened in this fn - if not hasattr(source, "read"): + if opened_here: fp.close() od = ObjectDictionary() @@ -208,7 +206,7 @@ def _calc_bit_length(data_type): def _signed_int_from_hex(hex_str, bit_length): number = int(hex_str, 0) max_value = (1 << (bit_length - 1)) - 1 - + if number > max_value: return number - (1 << bit_length) else: diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 519bbd5f..e1a57acd 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -86,7 +86,7 @@ def request_response(self, sdo_request): except SdoCommunicationError as e: retries_left -= 1 if not retries_left: - self.abort(0x5040000) + self.abort(0x5040000) raise logger.warning(str(e)) @@ -463,7 +463,7 @@ def __init__(self, sdo_client, index, subindex=0, request_crc_support=True): :param int subindex: Object dictionary sub-index to read from. :param bool request_crc_support: - If crc calculation should be requested when using block transfer + If crc calculation should be requested when using block transfer """ self._done = False self.sdo_client = sdo_client @@ -628,7 +628,7 @@ def __init__(self, sdo_client, index, subindex=0, size=None, request_crc_support :param int size: Size of data in number of bytes if known in advance. :param bool request_crc_support: - If crc calculation should be requested when using block transfer + If crc calculation should be requested when using block transfer """ self.sdo_client = sdo_client self.size = size @@ -755,7 +755,7 @@ def _block_ack(self): logger.debug("Server requested a block size of %d", blksize) self._blksize = blksize self._seqno = 0 - + def _retransmit(self, ackseq, blksize): """Retransmit the failed block""" logger.info(("%d of %d sequences were received. " diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index e9574feb..3707d92c 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -203,7 +203,7 @@ def download( data: bytes, force_segment: bool = False, ): - """May be called to make a write operation without an Object Dictionary. + """May be called to make a write operation without an Object Dictionary. :param index: Index of object to write. diff --git a/canopen/variable.py b/canopen/variable.py index a75b68c0..892818ad 100644 --- a/canopen/variable.py +++ b/canopen/variable.py @@ -61,11 +61,9 @@ def raw(self) -> Union[int, bool, float, str, bytes]: +---------------------------+----------------------------+ | REALxx | :class:`float` | +---------------------------+----------------------------+ - | VISIBLE_STRING | :class:`str` / | - | | ``unicode`` (Python 2) | + | VISIBLE_STRING | :class:`str` | +---------------------------+----------------------------+ - | UNICODE_STRING | :class:`str` / | - | | ``unicode`` (Python 2) | + | UNICODE_STRING | :class:`str` | +---------------------------+----------------------------+ | OCTET_STRING | :class:`bytes` | +---------------------------+----------------------------+ diff --git a/examples/eds/e35.eds b/examples/eds/e35.eds index 17b24879..c8a02f9a 100644 --- a/examples/eds/e35.eds +++ b/examples/eds/e35.eds @@ -5083,7 +5083,7 @@ DefaultValue=0 PDOMapping=0x0 [2C01subB] -ParameterName=Accumulator divide register +ParameterName=Accumulator divide register ObjectType=0x7 DataType=0x0004 AccessType=wo @@ -5099,7 +5099,7 @@ DefaultValue=0 PDOMapping=0x0 [2C01subD] -ParameterName=Accumulator multiply register +ParameterName=Accumulator multiply register ObjectType=0x7 DataType=0x0004 AccessType=wo @@ -5131,7 +5131,7 @@ DefaultValue=0 PDOMapping=0x0 [2C01sub11] -ParameterName=Shift left accumulator by register +ParameterName=Shift left accumulator by register ObjectType=0x7 DataType=0x0004 AccessType=wo @@ -5139,7 +5139,7 @@ DefaultValue=0 PDOMapping=0x0 [2C01sub12] -ParameterName=Shift right accumulator by register +ParameterName=Shift right accumulator by register ObjectType=0x7 DataType=0x0004 AccessType=wo @@ -7835,7 +7835,7 @@ PDOMapping=0x0 ParameterValue=0x2 [1A02sub1] -ParameterName=Position Actual Value +ParameterName=Position Actual Value ObjectType=0x7 DataType=0x0007 AccessType=rw diff --git a/test/test_eds.py b/test/test_eds.py index a35cbb99..d86a6ae3 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -157,7 +157,7 @@ def test_dummy_variable(self): def test_dummy_variable_undefined(self): with self.assertRaises(KeyError): var_undef = self.od['Dummy0001'] - + def test_reading_factor(self): var = self.od['EDS file extensions']['FactorAndDescription'] self.assertEqual(var.factor, 0.1) @@ -167,7 +167,7 @@ def test_reading_factor(self): self.assertEqual(var2.description, '') self.assertEqual(var2.factor, 1) self.assertEqual(var2.unit, '') - + def test_comments(self): From b7b124264bdf867e4753b7a0bbd47da9afdb12b6 Mon Sep 17 00:00:00 2001 From: hepr-skylotec <89248334+hepr-skylotec@users.noreply.github.com> Date: Tue, 4 Jun 2024 14:46:49 +0200 Subject: [PATCH 124/199] Revert "change missing Baudrate to BaudRate" (#452) The CiA 306 CANopen electronic data sheet (EDS) standard is quite clear that in the DeviceCommisioning block, baudrate is spelled 'Baudrate' and not 'BaudRate'. This commit is to be reverted, as it prevents loading of standards compliant DCF files. Chapter 5.3.3.3 is clear in the casing of Baudrate for DeviceCommisioning and BaudRate for DeviceInfo. This seems to be an inconcistency in the standard, and we should probably accept both as a long term solution. This reverts commit 074cbbc4d4c2c7803dc1e0151f6f534dbe44efc8. --- canopen/objectdictionary/eds.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index b718c945..4481eaae 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -85,7 +85,7 @@ def import_eds(source, node_id): pass if eds.has_section("DeviceComissioning"): - od.bitrate = int(eds.get("DeviceComissioning", "BaudRate")) * 1000 + od.bitrate = int(eds.get("DeviceComissioning", "Baudrate")) * 1000 od.node_id = int(eds.get("DeviceComissioning", "NodeID"), 0) for section in eds.sections(): @@ -467,7 +467,7 @@ def export_record(var, eds): if device_commisioning and (od.bitrate or od.node_id): eds.add_section("DeviceComissioning") if od.bitrate: - eds.set("DeviceComissioning", "BaudRate", int(od.bitrate / 1000)) + eds.set("DeviceComissioning", "Baudrate", int(od.bitrate / 1000)) if od.node_id: eds.set("DeviceComissioning", "NodeID", int(od.node_id)) From 4d10c84ac57efb48b4a8460eca8e2821569d15be Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 4 Jun 2024 14:53:29 +0200 Subject: [PATCH 125/199] Fix capitalization of Baudrate in [DeviceComissioning] section. As pointed out in #452, there is an inconsistency in the CiA 306 spec regarding the exact spelling. Under DeviceComissioning (sic!), it is spelled with a lowercase "r", while under DeviceInfo it is BaudRate_* with an uppercase "R". That change however broke the tests, because the library currently handles keys in a case-sensitive way (which is wrong in itself). --- test/sample.eds | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/sample.eds b/test/sample.eds index b88ff75b..16d0c31a 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -32,7 +32,7 @@ LSS_Supported=0 [DeviceComissioning] NodeID=2 NodeName=Some name -BaudRate=500 +Baudrate=500 NetNumber=0 LSS_SerialNumber=0 From 6b0c7cf591f8e7a46c0d752be7fb249fb56aac73 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 4 Jun 2024 15:07:26 +0200 Subject: [PATCH 126/199] Fix "hearbeat" typos (fixes #389) (#453) Rename the misspelled NmtMaster.add_hearbeat_callback() function to add_heartbeat_callback, with an assignment for the legacy name to not break compatibility in an unexpected manner. Adjust parameter / function documentation and local variables with the same typo consistently. --- canopen/nmt.py | 19 +++++++++++-------- test/test_local.py | 2 +- 2 files changed, 12 insertions(+), 9 deletions(-) diff --git a/canopen/nmt.py b/canopen/nmt.py index 98d8ea25..401ad15e 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -163,7 +163,7 @@ def wait_for_bootup(self, timeout: float = 10) -> None: if self._state_received == 0: break - def add_hearbeat_callback(self, callback: Callable[[int], None]): + def add_heartbeat_callback(self, callback: Callable[[int], None]): """Add function to be called on heartbeat reception. :param callback: @@ -171,6 +171,9 @@ def add_hearbeat_callback(self, callback: Callable[[int], None]): """ self._callbacks.append(callback) + # Compatibility with previous typo + add_hearbeat_callback = add_heartbeat_callback + def start_node_guarding(self, period: float): """Starts the node guarding mechanism. @@ -225,16 +228,16 @@ def send_command(self, code: int) -> None: def on_write(self, index, data, **kwargs): if index == 0x1017: - hearbeat_time, = struct.unpack_from(" 0: - logger.info("Start the hearbeat timer, interval is %d ms", self._heartbeat_time_ms) + logger.info("Start the heartbeat timer, interval is %d ms", self._heartbeat_time_ms) self._send_task = self.network.send_periodic( 0x700 + self.id, [self._state], heartbeat_time_ms / 1000.0) def stop_heartbeat(self): - """Stop the hearbeat service.""" + """Stop the heartbeat service.""" if self._send_task is not None: logger.info("Stop the heartbeat timer") self._send_task.stop() diff --git a/test/test_local.py b/test/test_local.py index 493cef1b..dd6efe1a 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -89,7 +89,7 @@ def test_segmented_download(self): self.assertEqual(value, b"Another cool device") def test_slave_send_heartbeat(self): - # Setting the heartbeat time should trigger hearbeating + # Setting the heartbeat time should trigger heartbeating # to start self.remote_node.sdo["Producer heartbeat time"].raw = 1000 state = self.remote_node.nmt.wait_for_heartbeat() From 98283a2405cbea752b721b3870d4de906afbecaa Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Tue, 4 Jun 2024 21:33:26 +0200 Subject: [PATCH 127/199] Cleanup f-strings, logging and formats (#443) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Change old-style % formatting to f-strings * Change str.format() to f-strings * Harmonize logging function to use % formatting and arguments. * Consistently print OD index and subindex in 0x01AB:0C notation. * Introduce helper function pretty_index() for the latter usage. Co-authored-by: Erlend E. Aasland Co-authored-by: André Colomb --- canopen/emcy.py | 2 +- canopen/lss.py | 6 +-- canopen/node/local.py | 2 +- canopen/node/remote.py | 16 +++---- canopen/objectdictionary/__init__.py | 30 ++++++------- canopen/objectdictionary/eds.py | 36 +++++++-------- canopen/pdo/__init__.py | 4 +- canopen/pdo/base.py | 16 +++---- canopen/profiles/p402.py | 44 +++++++++---------- canopen/profiles/tools/test_p402_states.py | 8 ++-- canopen/sdo/base.py | 5 ++- canopen/sdo/client.py | 51 +++++++++++----------- canopen/sdo/exceptions.py | 2 +- canopen/sdo/server.py | 12 ++--- canopen/utils.py | 22 ++++++++++ canopen/variable.py | 15 +++---- doc/network.rst | 2 +- doc/od.rst | 4 +- doc/pdo.rst | 6 +-- doc/sdo.rst | 6 +-- examples/simple_ds402_node.py | 16 +++---- test/test_eds.py | 13 +++--- test/test_network.py | 2 +- test/test_sdo.py | 4 +- test/test_utils.py | 20 +++++++++ 25 files changed, 189 insertions(+), 155 deletions(-) create mode 100644 canopen/utils.py create mode 100644 test/test_utils.py diff --git a/canopen/emcy.py b/canopen/emcy.py index 118ede4f..1bbdeb75 100644 --- a/canopen/emcy.py +++ b/canopen/emcy.py @@ -130,7 +130,7 @@ def get_desc(self) -> str: return "" def __str__(self): - text = "Code 0x{:04X}".format(self.code) + text = f"Code 0x{self.code:04X}" description = self.get_desc() if description: text = text + ", " + description diff --git a/canopen/lss.py b/canopen/lss.py index 83d225c5..93b7d4ec 100644 --- a/canopen/lss.py +++ b/canopen/lss.py @@ -353,7 +353,7 @@ def __send_configure(self, req_cs, value1=0, value2=0): raise LssError("Response message is not for the request") if error_code != ERROR_NONE: - error_msg = "LSS Error: %d" % error_code + error_msg = f"LSS Error: {error_code}" raise LssError(error_msg) def __send_command(self, message): @@ -368,9 +368,7 @@ def __send_command(self, message): :rtype: bytes """ - message_str = " ".join(["{:02x}".format(x) for x in message]) - logger.info( - "Sending LSS message {}".format(message_str)) + logger.info("Sending LSS message %s", message.hex(" ").upper()) response = None if not self.responses.empty(): diff --git a/canopen/node/local.py b/canopen/node/local.py index de3e23b9..eb74b98d 100644 --- a/canopen/node/local.py +++ b/canopen/node/local.py @@ -86,7 +86,7 @@ def get_data( return obj.encode_raw(obj.default) # Resource not available - logger.info("Resource unavailable for 0x%X:%d", index, subindex) + logger.info("Resource unavailable for 0x%04X:%02X", index, subindex) raise SdoAbortedError(0x060A0023) def set_data( diff --git a/canopen/node/remote.py b/canopen/node/remote.py index 07462422..37eb2ab2 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -122,18 +122,13 @@ def __load_configuration_helper(self, index, subindex, name, value): """ try: if subindex is not None: - logger.info(str('SDO [{index:#06x}][{subindex:#06x}]: {name}: {value:#06x}'.format( - index=index, - subindex=subindex, - name=name, - value=value))) + logger.info('SDO [0x%04X][0x%02X]: %s: %#06x', + index, subindex, name, value) self.sdo[index][subindex].raw = value else: self.sdo[index].raw = value - logger.info(str('SDO [{index:#06x}]: {name}: {value:#06x}'.format( - index=index, - name=name, - value=value))) + logger.info('SDO [0x%04X]: %s: %#06x', + index, name, value) except SdoCommunicationError as e: logger.warning(str(e)) except SdoAbortedError as e: @@ -142,7 +137,8 @@ def __load_configuration_helper(self, index, subindex, name, value): if e.code != 0x06010002: # Abort codes other than "Attempt to write a read-only object" # should still be reported. - logger.warning('[ERROR SETTING object {0:#06x}:{1:#06x}] {2}'.format(index, subindex, str(e))) + logger.warning('[ERROR SETTING object 0x%04X:%02X] %s', + index, subindex, e) raise def load_configuration(self): diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 19196951..103ebf19 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -8,6 +8,7 @@ from canopen.objectdictionary.datatypes import * from canopen.objectdictionary.datatypes_24bit import Integer24, Unsigned24 +from canopen.utils import pretty_index logger = logging.getLogger(__name__) @@ -108,8 +109,7 @@ def __getitem__( if isinstance(index, str) and '.' in index: idx, sub = index.split('.', maxsplit=1) return self[idx][sub] - name = "0x%X" % index if isinstance(index, int) else index - raise KeyError("%s was not found in Object Dictionary" % name) + raise KeyError(f"{pretty_index(index)} was not found in Object Dictionary") return item def __setitem__( @@ -180,12 +180,12 @@ def __init__(self, name: str, index: int): self.names = {} def __repr__(self) -> str: - return f"<{type(self).__qualname__} {self.name!r} at 0x{self.index:04X}>" + return f"<{type(self).__qualname__} {self.name!r} at {pretty_index(self.index)}>" def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": item = self.names.get(subindex) or self.subindices.get(subindex) if item is None: - raise KeyError("Subindex %s was not found" % subindex) + raise KeyError(f"Subindex {pretty_index(None, subindex)} was not found") return item def __setitem__(self, subindex: Union[int, str], var: "ODVariable"): @@ -239,7 +239,7 @@ def __init__(self, name: str, index: int): self.names = {} def __repr__(self) -> str: - return f"<{type(self).__qualname__} {self.name!r} at 0x{self.index:04X}>" + return f"<{type(self).__qualname__} {self.name!r} at {pretty_index(self.index)}>" def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": var = self.names.get(subindex) or self.subindices.get(subindex) @@ -249,7 +249,7 @@ def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": elif isinstance(subindex, int) and 0 < subindex < 256: # Create a new variable based on first array item template = self.subindices[1] - name = "%s_%x" % (template.name, subindex) + name = f"{template.name}_{subindex:x}" var = ODVariable(name, self.index, subindex) var.parent = self for attr in ("data_type", "unit", "factor", "min", "max", "default", @@ -258,7 +258,7 @@ def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": if attr in template.__dict__: var.__dict__[attr] = template.__dict__[attr] else: - raise KeyError("Could not find subindex %r" % subindex) + raise KeyError(f"Could not find subindex {pretty_index(None, subindex)}") return var def __len__(self) -> int: @@ -337,8 +337,8 @@ def __init__(self, name: str, index: int, subindex: int = 0): self.pdo_mappable = False def __repr__(self) -> str: - suffix = f":{self.subindex:02X}" if isinstance(self.parent, (ODRecord, ODArray)) else "" - return f"<{type(self).__qualname__} {self.qualname!r} at 0x{self.index:04X}{suffix}>" + subindex = self.subindex if isinstance(self.parent, (ODRecord, ODArray)) else None + return f"<{type(self).__qualname__} {self.qualname!r} at {pretty_index(self.index, subindex)}>" @property def qualname(self) -> str: @@ -417,8 +417,7 @@ def encode_raw(self, value: Union[int, float, str, bytes, bytearray]) -> bytes: if self.max is not None and value > self.max: logger.warning( "Value %d is greater than max value %d", - value, - self.max) + value, self.max) try: return self.STRUCT_TYPES[self.data_type].pack(value) except struct.error: @@ -427,8 +426,7 @@ def encode_raw(self, value: Union[int, float, str, bytes, bytearray]) -> bytes: raise ObjectDictionaryError("Data type has not been specified") else: raise TypeError( - "Do not know how to encode %r to data type %Xh" % ( - value, self.data_type)) + f"Do not know how to encode {value!r} to data type 0x{self.data_type:X}") def decode_phys(self, value: int) -> Union[int, bool, float, str, bytes]: if self.data_type in INTEGER_TYPES: @@ -446,7 +444,7 @@ def decode_desc(self, value: int) -> str: raise ObjectDictionaryError("No value descriptions exist") elif value not in self.value_descriptions: raise ObjectDictionaryError( - "No value description exists for %d" % value) + f"No value description exists for {value}") else: return self.value_descriptions[value] @@ -458,8 +456,8 @@ def encode_desc(self, desc: str) -> int: if description == desc: return value valid_values = ", ".join(self.value_descriptions.values()) - error_text = "No value corresponds to '%s'. Valid values are: %s" - raise ValueError(error_text % (desc, valid_values)) + raise ValueError( + f"No value corresponds to '{desc}'. Valid values are: {valid_values}") def decode_bits(self, value: int, bits: List[int]) -> int: try: diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 4481eaae..5c2a72d5 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -43,7 +43,7 @@ def import_eds(source, node_id): if eds.has_section("Comments"): linecount = int(eds.get("Comments", "Lines"), 0) od.comments = '\n'.join([ - eds.get("Comments", "Line%i" % line) + eds.get("Comments", f"Line{line}") for line in range(1, linecount+1) ]) @@ -52,7 +52,7 @@ def import_eds(source, node_id): else: for rate in [10, 20, 50, 125, 250, 500, 800, 1000]: baudPossible = int( - eds.get("DeviceInfo", "BaudRate_%i" % rate, fallback='0'), 0) + eds.get("DeviceInfo", f"BaudRate_{rate}", fallback='0'), 0) if baudPossible != 0: od.device_information.allowed_baudrates.add(rate*1000) @@ -93,7 +93,7 @@ def import_eds(source, node_id): match = re.match(r"^[Dd]ummy[Uu]sage$", section) if match is not None: for i in range(1, 8): - key = "Dummy%04d" % i + key = f"Dummy{i:04d}" if eds.getint(section, key) == 1: var = objectdictionary.ODVariable(key, i, 0) var.data_type = i @@ -239,7 +239,7 @@ def _revert_variable(var_type, value): elif var_type in datatypes.FLOAT_TYPES: return value else: - return "0x%02X" % value + return f"0x{value:02X}" def build_variable(eds, section, node_id, index, subindex=0): @@ -264,9 +264,9 @@ def build_variable(eds, section, node_id, index, subindex=0): # The eds.get function gives us 0x00A0 now convert to String without hex representation and upper case # The sub2 part is then the section where the type parameter stands try: - var.data_type = int(eds.get("%Xsub1" % var.data_type, "DefaultValue"), 0) + var.data_type = int(eds.get(f"{var.data_type:X}sub1", "DefaultValue"), 0) except NoSectionError: - logger.warning("%s has an unknown or unsupported data type (%X)", name, var.data_type) + logger.warning("%s has an unknown or unsupported data type (0x%X)", name, var.data_type) # Assume DOMAIN to force application to interpret the byte data var.data_type = datatypes.DOMAIN @@ -354,15 +354,15 @@ def export_common(var, eds, section): def export_variable(var, eds): if isinstance(var.parent, ObjectDictionary): # top level variable - section = "%04X" % var.index + section = f"{var.index:04X}" else: # nested variable - section = "%04Xsub%X" % (var.index, var.subindex) + section = f"{var.index:04X}sub{var.subindex:X}" export_common(var, eds, section) - eds.set(section, "ObjectType", "0x%X" % VAR) + eds.set(section, "ObjectType", f"0x{VAR:X}") if var.data_type: - eds.set(section, "DataType", "0x%04X" % var.data_type) + eds.set(section, "DataType", f"0x{var.data_type:04X}") if var.access_type: eds.set(section, "AccessType", var.access_type) @@ -379,7 +379,7 @@ def export_variable(var, eds): eds.set(section, "ParameterValue", _revert_variable(var.data_type, var.value)) - eds.set(section, "DataType", "0x%04X" % var.data_type) + eds.set(section, "DataType", f"0x{var.data_type:04X}") eds.set(section, "PDOMapping", hex(var.pdo_mappable)) if getattr(var, 'min', None) is not None: @@ -395,11 +395,11 @@ def export_variable(var, eds): eds.set(section, "Unit", var.unit) def export_record(var, eds): - section = "%04X" % var.index + section = f"{var.index:04X}" export_common(var, eds, section) - eds.set(section, "SubNumber", "0x%X" % len(var.subindices)) + eds.set(section, "SubNumber", f"0x{len(var.subindices):X}") ot = RECORD if isinstance(var, objectdictionary.ODRecord) else ARR - eds.set(section, "ObjectType", "0x%X" % ot) + eds.set(section, "ObjectType", f"0x{ot:X}") for i in var: export_variable(var[i], eds) @@ -461,7 +461,7 @@ def export_record(var, eds): for rate in od.device_information.allowed_baudrates.union( {10e3, 20e3, 50e3, 125e3, 250e3, 500e3, 800e3, 1000e3}): eds.set( - "DeviceInfo", "BaudRate_%i" % (rate/1000), + "DeviceInfo", f"BaudRate_{rate//1000}", int(rate in od.device_information.allowed_baudrates)) if device_commisioning and (od.bitrate or od.node_id): @@ -475,12 +475,12 @@ def export_record(var, eds): i = 0 for line in od.comments.splitlines(): i += 1 - eds.set("Comments", "Line%i" % i, line) + eds.set("Comments", f"Line{i}", line) eds.set("Comments", "Lines", i) eds.add_section("DummyUsage") for i in range(1, 8): - key = "Dummy%04d" % i + key = f"Dummy{i:04d}" eds.set("DummyUsage", key, 1 if (key in od) else 0) def mandatory_indices(x): @@ -504,7 +504,7 @@ def add_list(section, list): eds.add_section(section) eds.set(section, "SupportedObjects", len(list)) for i in range(0, len(list)): - eds.set(section, (i + 1), "0x%04X" % list[i]) + eds.set(section, (i + 1), f"0x{list[i]:04X}") for index in list: export_object(od[index], eds) diff --git a/canopen/pdo/__init__.py b/canopen/pdo/__init__.py index 8002945a..1c951cf5 100644 --- a/canopen/pdo/__init__.py +++ b/canopen/pdo/__init__.py @@ -39,7 +39,7 @@ class RPDO(PdoBase): def __init__(self, node): super(RPDO, self).__init__(node) self.map = PdoMaps(0x1400, 0x1600, self, 0x200) - logger.debug('RPDO Map as {0}'.format(len(self.map))) + logger.debug('RPDO Map as %d', len(self.map)) def stop(self): """Stop transmission of all RPDOs. @@ -64,7 +64,7 @@ class TPDO(PdoBase): def __init__(self, node): super(TPDO, self).__init__(node) self.map = PdoMaps(0x1800, 0x1A00, self, 0x180) - logger.debug('TPDO Map as {0}'.format(len(self.map))) + logger.debug('TPDO Map as %d', len(self.map)) def stop(self): """Stop transmission of all TPDOs. diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 7312f660..1f4bf3e4 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -42,7 +42,7 @@ def __getitem__(self, key): except KeyError: # ignore if one specific PDO does not have the key and try the next one continue - raise KeyError("PDO: {0} was not found in any map".format(key)) + raise KeyError(f"PDO: {key} was not found in any map") def __len__(self): return len(self.map) @@ -201,8 +201,8 @@ def __getitem_by_index(self, value): valid_values.append(var.index) if var.index == value: return var - raise KeyError('{0} not found in map. Valid entries are {1}'.format( - value, ', '.join(str(v) for v in valid_values))) + raise KeyError(f"{value} not found in map. Valid entries are " + f"{', '.join(str(v) for v in valid_values)}") def __getitem_by_name(self, value): valid_values = [] @@ -211,8 +211,8 @@ def __getitem_by_name(self, value): valid_values.append(var.name) if var.name == value: return var - raise KeyError('{0} not found in map. Valid entries are {1}'.format( - value, ', '.join(valid_values))) + raise KeyError(f"{value} not found in map. Valid entries are " + f"{', '.join(valid_values)}") def __getitem__(self, key: Union[int, str]) -> "PdoVariable": var = None @@ -272,7 +272,7 @@ def name(self) -> str: if direction == "Rx": map_id -= 1 node_id = self.cob_id & 0x7F - return "%sPDO%d_node%d" % (direction, map_id, node_id) + return f"{direction}PDO{map_id}_node{node_id}" @property def is_periodic(self) -> bool: @@ -398,7 +398,7 @@ def save(self) -> None: self._fill_map(self.map_array[0].raw) subindex = 1 for var in self.map: - logger.info("Writing %s (0x%X:%d, %d bits) to PDO map", + logger.info("Writing %s (0x%04X:%02X, %d bits) to PDO map", var.name, var.index, var.subindex, var.length) if hasattr(self.pdo_node.node, "curtis_hack") and self.pdo_node.node.curtis_hack: # Curtis HACK: mixed up field order self.map_array[subindex].raw = (var.index | @@ -467,7 +467,7 @@ def add_variable( # We want to see the bit fields within the PDO start_bit = var.offset end_bit = start_bit + var.length - 1 - logger.info("Adding %s (0x%X:%d) at bits %d - %d to PDO map", + logger.info("Adding %s (0x%04X:%02X) at bits %d - %d to PDO map", var.name, var.index, var.subindex, start_bit, end_bit) self.map.append(var) self.length += var.length diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index d5b4ce5e..c94e5356 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -249,7 +249,7 @@ def _init_tpdo_values(self): if tpdo.enabled: tpdo.add_callback(self.on_TPDOs_update_callback) for obj in tpdo: - logger.debug('Configured TPDO: {0}'.format(obj.index)) + logger.debug('Configured TPDO: 0x%04X', obj.index) if obj.index not in self.tpdo_values: self.tpdo_values[obj.index] = 0 self.tpdo_pointers[obj.index] = obj @@ -260,31 +260,31 @@ def _init_rpdo_pointers(self): for rpdo in self.rpdo.values(): if rpdo.enabled: for obj in rpdo: - logger.debug('Configured RPDO: {0}'.format(obj.index)) + logger.debug('Configured RPDO: 0x%04X', obj.index) if obj.index not in self.rpdo_pointers: self.rpdo_pointers[obj.index] = obj def _check_controlword_configured(self): if 0x6040 not in self.rpdo_pointers: # Controlword logger.warning( - "Controlword not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( - self.id)) + "Controlword not configured in node %s's PDOs. Using SDOs can cause slow performance.", + self.id) def _check_statusword_configured(self): if 0x6041 not in self.tpdo_values: # Statusword logger.warning( - "Statusword not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( - self.id)) + "Statusword not configured in node %s's PDOs. Using SDOs can cause slow performance.", + self.id) def _check_op_mode_configured(self): if 0x6060 not in self.rpdo_pointers: # Operation Mode logger.warning( - "Operation Mode not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( - self.id)) + "Operation Mode not configured in node %s's PDOs. Using SDOs can cause slow performance.", + self.id) if 0x6061 not in self.tpdo_values: # Operation Mode Display logger.warning( - "Operation Mode Display not configured in node {0}'s PDOs. Using SDOs can cause slow performance.".format( - self.id)) + "Operation Mode Display not configured in node %s's PDOs. Using SDOs can cause slow performance.", + self.id) def reset_from_fault(self): """Reset node from fault and set it to Operation Enable state.""" @@ -357,7 +357,7 @@ def homing(self, timeout=None, restore_op_mode=False): homingstatus = self._homing_status() if homingstatus in ('INTERRUPTED', 'ERROR VELOCITY IS NOT ZERO', 'ERROR VELOCITY IS ZERO'): - raise RuntimeError('Unable to home. Reason: {0}'.format(homingstatus)) + raise RuntimeError(f'Unable to home. Reason: {homingstatus}') if timeout and time.monotonic() > t: raise RuntimeError('Unable to home, timeout reached') logger.info('Homing mode carried out successfully.') @@ -397,8 +397,7 @@ def op_mode(self): if pdo.is_periodic: timestamp = pdo.wait_for_reception(timeout=self.TIMEOUT_CHECK_TPDO) if timestamp is None: - raise RuntimeError("Timeout getting node {0}'s mode of operation.".format( - self.id)) + raise RuntimeError(f"Timeout getting node {self.id}'s mode of operation.") code = self.tpdo_values[0x6061] except KeyError: logger.warning('The object 0x6061 is not a configured TPDO, fallback to SDO') @@ -410,7 +409,7 @@ def op_mode(self, mode): try: if not self.is_op_mode_supported(mode): raise TypeError( - 'Operation mode {m} not suppported on node {n}.'.format(n=self.id, m=mode)) + f'Operation mode {mode} not suppported on node {self.id}.') # Update operation mode in RPDO if possible, fall back to SDO if 0x6060 in self.rpdo_pointers: self.rpdo_pointers[0x6060].raw = OperationMode.NAME2CODE[mode] @@ -423,13 +422,12 @@ def op_mode(self, mode): while self.op_mode != mode: if time.monotonic() > timeout: raise RuntimeError( - "Timeout setting node {0}'s new mode of operation to {1}.".format( - self.id, mode)) - logger.info('Set node {n} operation mode to {m}.'.format(n=self.id, m=mode)) + f"Timeout setting node {self.id}'s new mode of operation to {mode}.") + logger.info('Set node %s operation mode to %s.', self.id, mode) except SdoCommunicationError as e: - logger.warning('[SDO communication error] Cause: {0}'.format(str(e))) + logger.warning('[SDO communication error] Cause: %s', e) except (RuntimeError, ValueError) as e: - logger.warning('{0}'.format(str(e))) + logger.warning(str(e)) def _clear_target_values(self): # [target velocity, target position, target torque] @@ -450,8 +448,8 @@ def is_op_mode_supported(self, mode): if not hasattr(self, '_op_mode_support'): # Cache value only on first lookup, this object should never change. self._op_mode_support = self.sdo[0x6502].raw - logger.info('Caching node {n} supported operation modes 0x{m:04X}'.format( - n=self.id, m=self._op_mode_support)) + logger.info('Caching node %s supported operation modes 0x%04X', + self.id, self._op_mode_support) bits = OperationMode.SUPPORTED[mode] return self._op_mode_support & bits == bits @@ -561,7 +559,7 @@ def _next_state(self, target_state): 'FAULT REACTION ACTIVE', 'FAULT'): raise ValueError( - 'Target state {} cannot be entered programmatically'.format(target_state)) + f'Target state {target_state} cannot be entered programmatically') from_state = self.state if (from_state, target_state) in State402.TRANSITIONTABLE: return target_state @@ -573,7 +571,7 @@ def _change_state(self, target_state): self.controlword = State402.TRANSITIONTABLE[(self.state, target_state)] except KeyError: raise ValueError( - 'Illegal state transition from {f} to {t}'.format(f=self.state, t=target_state)) + f'Illegal state transition from {self.state} to {target_state}') timeout = time.monotonic() + self.TIMEOUT_SWITCH_STATE_SINGLE while self.state != target_state: if time.monotonic() > timeout: diff --git a/canopen/profiles/tools/test_p402_states.py b/canopen/profiles/tools/test_p402_states.py index 39f085f5..721865db 100644 --- a/canopen/profiles/tools/test_p402_states.py +++ b/canopen/profiles/tools/test_p402_states.py @@ -19,19 +19,19 @@ if target_state == from_state: continue if (from_state, target_state) in State402.TRANSITIONTABLE: - print('direct:\t{} -> {}'.format(from_state, target_state)) + print(f'direct:\t{from_state} -> {target_state}') else: next_state = State402.next_state_indirect(from_state) if not next_state: - print('FAIL:\t{} -> {}'.format(from_state, next_state)) + print(f'FAIL:\t{from_state} -> {next_state}') else: - print('\t{} -> {} ...'.format(from_state, next_state)) + print(f'\t{from_state} -> {next_state} ...') try: while from_state != target_state: n.tpdo_values[0x6041] = State402.SW_MASK[from_state][1] next_state = n._next_state(target_state) - print('\t\t-> {}'.format(next_state)) + print(f'\t\t-> {next_state}') from_state = next_state except ValueError: print('\t\t-> disallowed!') diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index f9daebf5..1099a144 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -5,6 +5,7 @@ from canopen import objectdictionary from canopen.objectdictionary import ObjectDictionary from canopen import variable +from canopen.utils import pretty_index class CrcXmodem: @@ -97,7 +98,7 @@ def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.od = od def __repr__(self) -> str: - return f"<{type(self).__qualname__} {self.od.name!r} at 0x{self.od.index:04X}>" + return f"<{type(self).__qualname__} {self.od.name!r} at {pretty_index(self.od.index)}>" def __getitem__(self, subindex: Union[int, str]) -> "SdoVariable": return SdoVariable(self.sdo_node, self.od[subindex]) @@ -119,7 +120,7 @@ def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): self.od = od def __repr__(self) -> str: - return f"<{type(self).__qualname__} {self.od.name!r} at 0x{self.od.index:04X}>" + return f"<{type(self).__qualname__} {self.od.name!r} at {pretty_index(self.od.index)}>" def __getitem__(self, subindex: Union[int, str]) -> "SdoVariable": return SdoVariable(self.sdo_node, self.od[subindex]) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index e1a57acd..e4c50aa8 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -7,6 +7,7 @@ from canopen.network import CanError from canopen import objectdictionary from canopen.sdo.base import SdoBase +from canopen.utils import pretty_index from canopen.sdo.constants import * from canopen.sdo.exceptions import * @@ -97,7 +98,7 @@ def abort(self, abort_code=0x08000000): # TODO: Is it necessary to include index and subindex? struct.pack_into(" bytes: """May be called to make a read operation without an Object Dictionary. @@ -244,7 +245,7 @@ def __init__(self, sdo_client, index, subindex=0): self._toggle = 0 self.pos = 0 - logger.debug("Reading 0x%X:%d from node %d", index, subindex, + logger.debug("Reading 0x%04X:%02X from node %d", index, subindex, sdo_client.rx_cobid - 0x600) request = bytearray(8) SDO_STRUCT.pack_into(request, 0, REQUEST_UPLOAD, index, subindex) @@ -253,14 +254,14 @@ def __init__(self, sdo_client, index, subindex=0): res_data = response[4:8] if res_command & 0xE0 != RESPONSE_UPLOAD: - raise SdoCommunicationError("Unexpected response 0x%02X" % res_command) + raise SdoCommunicationError(f"Unexpected response 0x{res_command:02X}") # Check that the message is for us if res_index != index or res_subindex != subindex: - raise SdoCommunicationError(( - "Node returned a value for 0x{:X}:{:d} instead, " + raise SdoCommunicationError( + f"Node returned a value for {pretty_index(res_index, res_subindex)} instead, " "maybe there is another SDO client communicating " - "on the same SDO channel?").format(res_index, res_subindex)) + "on the same SDO channel?") self.exp_data = None if res_command & EXPEDITED: @@ -301,7 +302,7 @@ def read(self, size=-1): response = self.sdo_client.request_response(request) res_command, = struct.unpack_from("B", response) if res_command & 0xE0 != RESPONSE_SEGMENT_UPLOAD: - raise SdoCommunicationError("Unexpected response 0x%02X" % res_command) + raise SdoCommunicationError(f"Unexpected response 0x{res_command:02X}") if res_command & TOGGLE_BIT != self._toggle: raise SdoCommunicationError("Toggle bit mismatch") length = 7 - ((res_command >> 1) & 0x7) @@ -362,7 +363,7 @@ def __init__(self, sdo_client, index, subindex=0, size=None, force_segment=False res_command, = struct.unpack_from("B", response) if res_command != RESPONSE_DOWNLOAD: raise SdoCommunicationError( - "Unexpected response 0x%02X" % res_command) + f"Unexpected response 0x{res_command:02X}") else: # Expedited download # Prepare header (first 4 bytes in CAN message) @@ -390,7 +391,7 @@ def write(self, b): res_command, = struct.unpack_from("B", response) if res_command & 0xE0 != RESPONSE_DOWNLOAD: raise SdoCommunicationError( - "Unexpected response 0x%02X" % res_command) + f"Unexpected response 0x{res_command:02X}") bytes_sent = len(b) self._done = True else: @@ -414,8 +415,8 @@ def write(self, b): res_command, = struct.unpack("B", response[0:1]) if res_command & 0xE0 != RESPONSE_SEGMENT_DOWNLOAD: raise SdoCommunicationError( - "Unexpected response 0x%02X (expected 0x%02X)" % - (res_command, RESPONSE_SEGMENT_DOWNLOAD)) + f"Unexpected response 0x{res_command:02X} " + f"(expected 0x{RESPONSE_SEGMENT_DOWNLOAD:02X})") # Advance position self.pos += bytes_sent return bytes_sent @@ -473,7 +474,7 @@ def __init__(self, sdo_client, index, subindex=0, request_crc_support=True): self._ackseq = 0 self._error = False - logger.debug("Reading 0x%X:%d from node %d", index, subindex, + logger.debug("Reading 0x%04X:%02X from node %d", index, subindex, sdo_client.rx_cobid - 0x600) # Initiate Block Upload request = bytearray(8) @@ -487,14 +488,14 @@ def __init__(self, sdo_client, index, subindex=0, request_crc_support=True): if res_command & 0xE0 != RESPONSE_BLOCK_UPLOAD: self._error = True self.sdo_client.abort(0x05040001) - raise SdoCommunicationError("Unexpected response 0x%02X" % res_command) + raise SdoCommunicationError(f"Unexpected response 0x{res_command:02X}") # Check that the message is for us if res_index != index or res_subindex != subindex: self._error = True - raise SdoCommunicationError(( - "Node returned a value for 0x{:X}:{:d} instead, " + raise SdoCommunicationError( + f"Node returned a value for {pretty_index(res_index, res_subindex)} instead, " "maybe there is another SDO client communicating " - "on the same SDO channel?").format(res_index, res_subindex)) + "on the same SDO channel?") if res_command & BLOCK_SIZE_SPECIFIED: self.size, = struct.unpack_from("> 2) & 0x3) else: size = 4 self._node.set_data(index, subindex, request[4:4 + size], check_writable=True) else: - logger.info("Initiating segmented download for 0x%X:%d", index, subindex) + logger.info("Initiating segmented download for 0x%04X:%02X", index, subindex) if command & SIZE_SPECIFIED: size, = struct.unpack_from(" bytes: """May be called to make a read operation without an Object Dictionary. diff --git a/canopen/utils.py b/canopen/utils.py new file mode 100644 index 00000000..37feda93 --- /dev/null +++ b/canopen/utils.py @@ -0,0 +1,22 @@ +"""Additional utility functions for canopen.""" +from typing import Optional, Union + + +def pretty_index(index: Optional[Union[int, str]], + sub: Optional[Union[int, str]] = None): + """Format an index and subindex as a string.""" + + index_str = "" + if isinstance(index, int): + index_str = f"0x{index:04X}" + elif index: + index_str = f"{index!r}" + + sub_str = "" + if isinstance(sub, int): + # Need 0x prefix if index is not present + sub_str = f"{'0x' if not index_str else ''}{sub:02X}" + elif sub: + sub_str = f"{sub!r}" + + return ":".join(s for s in (index_str, sub_str) if s) diff --git a/canopen/variable.py b/canopen/variable.py index 892818ad..3ec67c79 100644 --- a/canopen/variable.py +++ b/canopen/variable.py @@ -3,6 +3,7 @@ from collections.abc import Mapping from canopen import objectdictionary +from canopen.utils import pretty_index logger = logging.getLogger(__name__) @@ -23,10 +24,10 @@ def __init__(self, od: objectdictionary.ODVariable): self.subindex = od.subindex def __repr__(self) -> str: - suffix = f":{self.subindex:02X}" if isinstance(self.od.parent, + subindex = self.subindex if isinstance(self.od.parent, (objectdictionary.ODRecord, objectdictionary.ODArray) - ) else "" - return f"<{type(self).__qualname__} {self.name!r} at 0x{self.index:04X}{suffix}>" + ) else None + return f"<{type(self).__qualname__} {self.name!r} at {pretty_index(self.index, subindex)}>" def get_data(self) -> bytes: raise NotImplementedError("Variable is not readable") @@ -74,17 +75,15 @@ def raw(self) -> Union[int, bool, float, str, bytes]: written as :class:`bytes`. """ value = self.od.decode_raw(self.data) - text = "Value of %s (0x%X:%d) is %r" % ( - self.name, self.index, - self.subindex, value) + text = f"Value of {self.name!r} ({pretty_index(self.index, self.subindex)}) is {value!r}" if value in self.od.value_descriptions: - text += " (%s)" % self.od.value_descriptions[value] + text += f" ({self.od.value_descriptions[value]})" logger.debug(text) return value @raw.setter def raw(self, value: Union[int, bool, float, str, bytes]): - logger.debug("Writing %s (0x%X:%d) = %r", + logger.debug("Writing %r (0x%04X:%02X) = %r", self.name, self.index, self.subindex, value) self.data = self.od.encode_raw(value) diff --git a/doc/network.rst b/doc/network.rst index 4fad9cd4..7efab634 100644 --- a/doc/network.rst +++ b/doc/network.rst @@ -51,7 +51,7 @@ To automatically detect which nodes are present on the network, there is the # We may need to wait a short while here to allow all nodes to respond time.sleep(0.05) for node_id in network.scanner.nodes: - print("Found node %d!" % node_id) + print(f"Found node {node_id}!") Finally, make sure to disconnect after you are done:: diff --git a/doc/od.rst b/doc/od.rst index f31c7813..6040bb5e 100644 --- a/doc/od.rst +++ b/doc/od.rst @@ -39,10 +39,10 @@ Here is an example where the entire object dictionary gets printed out:: node = network.add_node(6, 'od.eds') for obj in node.object_dictionary.values(): - print('0x%X: %s' % (obj.index, obj.name)) + print(f'0x{obj.index:X}: {obj.name}') if isinstance(obj, canopen.objectdictionary.ODRecord): for subobj in obj.values(): - print(' %d: %s' % (subobj.subindex, subobj.name)) + print(f' {subobj.subindex}: {subobj.name}') You can access the objects using either index/subindex or names:: diff --git a/doc/pdo.rst b/doc/pdo.rst index bcef197b..d718ea5f 100644 --- a/doc/pdo.rst +++ b/doc/pdo.rst @@ -65,14 +65,14 @@ starts at 1, not 0):: for i in range(50): node.tpdo[4].wait_for_reception() speed = node.tpdo['Application Status.Actual Speed'].phys - f.write('%s\n' % speed) + f.write(f'{speed}\n') # Using a callback to asynchronously receive values # Do not do any blocking operations here! def print_speed(message): - print('%s received' % message.name) + print(f'{message.name} received') for var in message: - print('%s = %d' % (var.name, var.raw)) + print(f'{var.name} = {var.raw}') node.tpdo[4].add_callback(print_speed) time.sleep(5) diff --git a/doc/sdo.rst b/doc/sdo.rst index 8634d28c..a1436572 100644 --- a/doc/sdo.rst +++ b/doc/sdo.rst @@ -50,7 +50,7 @@ The code below only creates objects, no messages are sent or received yet:: To actually read or write the variables, use the ``.raw``, ``.phys``, ``.desc``, or ``.bits`` attributes:: - print("The device type is 0x%X" % device_type.raw) + print(f"The device type is 0x{device_type.raw:X}") # Using value descriptions instead of integers (if supported by OD) control_mode.desc = 'Speed Mode' @@ -59,11 +59,11 @@ or ``.bits`` attributes:: command_all.bits[3] = 1 # Read and write physical values scaled by a factor (if supported by OD) - print("The actual speed is %f rpm" % actual_speed.phys) + print(f"The actual speed is {actual_speed.phys} rpm") # Iterate over arrays or records for error in error_log.values(): - print("Error 0x%X was found in the log" % error.raw) + print(f"Error 0x{error.raw:X} was found in the log") It is also possible to read and write to variables that are not in the Object Dictionary, but only using raw bytes:: diff --git a/examples/simple_ds402_node.py b/examples/simple_ds402_node.py index c99831a0..5847923d 100644 --- a/examples/simple_ds402_node.py +++ b/examples/simple_ds402_node.py @@ -26,17 +26,17 @@ #node.nmt.state = 'RESET' node.nmt.wait_for_bootup(15) - print('node state 1) = {0}'.format(node.nmt.state)) + print(f'node state 1) = {node.nmt.state}') # Iterate over arrays or records error_log = node.sdo[0x1003] for error in error_log.values(): - print("Error {0} was found in the log".format(error.raw)) + print(f"Error {error.raw} was found in the log") for node_id in network: print(network[node_id]) - print('node state 2) = {0}'.format(node.nmt.state)) + print(f'node state 2) = {node.nmt.state}') # Read a variable using SDO @@ -51,7 +51,7 @@ node.load_configuration() - print('node state 3) = {0}'.format(node.nmt.state)) + print(f'node state 3) = {node.nmt.state}') node.setup_402_state_machine() @@ -63,7 +63,7 @@ node.state = 'SWITCH ON DISABLED' - print('node state 4) = {0}'.format(node.nmt.state)) + print(f'node state 4) = {node.nmt.state}') # Read PDO configuration from node node.tpdo.read() @@ -115,7 +115,7 @@ raise Exception('Timeout when trying to change state') time.sleep(0.001) - print('Node Status {0}'.format(node.powerstate_402.state)) + print(f'Node Status {node.powerstate_402.state}') # ----------------------------------------------------------------------------------------- node.nmt.start_node_guarding(0.01) @@ -132,8 +132,8 @@ # Read the state of the Statusword statusword = node.sdo[0x6041].raw - print('statusword: {0}'.format(statusword)) - print('VEL: {0}'.format(speed)) + print(f'statusword: {statusword}') + print(f'VEL: {speed}') time.sleep(0.01) diff --git a/test/test_eds.py b/test/test_eds.py index d86a6ae3..88654a0f 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -2,6 +2,7 @@ import unittest import canopen from canopen.objectdictionary.eds import _signed_int_from_hex +from canopen.utils import pretty_index EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') @@ -185,7 +186,7 @@ def test_export_eds(self): for doctype in {"eds", "dcf"}: tempfile = str(Path(tempdir, "test." + doctype)) with open(tempfile, "w+") as tempeds: - print("exporting %s to " % doctype + tempeds.name) + print(f"exporting {doctype} to {tempeds.name}") canopen.export_od(self.od, tempeds, doc_type=doctype) exported_od = canopen.import_od(tempfile) @@ -236,15 +237,15 @@ def test_export_eds(self): for evar, avar in zip(expected_vars, actual_vars): self.assertEqual(getattr(avar, "data_type", None), getattr(evar, "data_type", None), - " mismatch on %04X:%X" % (evar.index, evar.subindex)) + f" mismatch on {pretty_index(evar.index, evar.subindex)}") self.assertEqual(getattr(avar, "default_raw", None), getattr(evar, "default_raw", None), - " mismatch on %04X:%X" % (evar.index, evar.subindex)) + f" mismatch on {pretty_index(evar.index, evar.subindex)}") self.assertEqual(getattr(avar, "min", None), getattr(evar, "min", None), - " mismatch on %04X:%X" % (evar.index, evar.subindex)) + f" mismatch on {pretty_index(evar.index, evar.subindex)}") self.assertEqual(getattr(avar, "max", None), getattr(evar, "max", None), - " mismatch on %04X:%X" % (evar.index, evar.subindex)) + f" mismatch on {pretty_index(evar.index, evar.subindex)}") if doctype == "dcf": self.assertEqual(getattr(avar, "value", None), getattr(evar, "value", None), - " mismatch on %04X:%X" % (evar.index, evar.subindex)) + f" mismatch on {pretty_index(evar.index, evar.subindex)}") self.assertEqual(self.od.comments, exported_od.comments) diff --git a/test/test_network.py b/test/test_network.py index 04129271..095648ad 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -61,7 +61,7 @@ def test_send_perodic(self): time.sleep(0.1) # FIXME: This test is a little fragile, as the number of elements # depends on the timing of the machine. - print("Queue size: %s" % (bus.queue.qsize(),)) + print(f"Queue size: {bus.queue.qsize()}") self.assertTrue(9 <= bus.queue.qsize() <= 13) msg = bus.recv(0) self.assertIsNotNone(msg) diff --git a/test/test_sdo.py b/test/test_sdo.py index c0ba086b..31759c22 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -23,11 +23,11 @@ def _send_message(self, can_id, data, remote=False): """ next_data = self.data.pop(0) self.assertEqual(next_data[0], TX, "No transmission was expected") - # print("> %s (%s)" % (binascii.hexlify(data), binascii.hexlify(next_data[1]))) + # print(f"> {binascii.hexlify(data)} ({binascii.hexlify(next_data[1])})") self.assertSequenceEqual(data, next_data[1]) self.assertEqual(can_id, 0x602) while self.data and self.data[0][0] == RX: - # print("< %s" % binascii.hexlify(self.data[0][1])) + # print(f"< {binascii.hexlify(self.data[0][1])}") self.network.notify(0x582, self.data.pop(0)[1], 0.0) def setUp(self): diff --git a/test/test_utils.py b/test/test_utils.py new file mode 100644 index 00000000..b412e365 --- /dev/null +++ b/test/test_utils.py @@ -0,0 +1,20 @@ +import unittest +from canopen.utils import pretty_index + + +class TestUtils(unittest.TestCase): + + def test_pretty_index(self): + self.assertEqual(pretty_index(0x12ab), "0x12AB") + self.assertEqual(pretty_index(0x12ab, 0xcd), "0x12AB:CD") + self.assertEqual(pretty_index(0x12ab, ""), "0x12AB") + self.assertEqual(pretty_index("test"), "'test'") + self.assertEqual(pretty_index("test", 0xcd), "'test':CD") + self.assertEqual(pretty_index(None), "") + self.assertEqual(pretty_index(""), "") + self.assertEqual(pretty_index("", ""), "") + self.assertEqual(pretty_index(None, 0xab), "0xAB") + + +if __name__ == "__main__": + unittest.main() From 5367d83ec953e2eaefcbf654ca3f6b65c8ee088c Mon Sep 17 00:00:00 2001 From: Jan Sommer Date: Tue, 4 Jun 2024 21:43:08 +0200 Subject: [PATCH 128/199] objectdictionary: Use node_id from DCF if not provided (#350) If no valid node_id (zero or None) is passed to import_eds(), try applying the one from the DeviceComissioning section if available. This mainly affects internal usage during import, namely interpolation of $NODEID references. --- canopen/objectdictionary/eds.py | 1 + 1 file changed, 1 insertion(+) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 5c2a72d5..cd64f604 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -87,6 +87,7 @@ def import_eds(source, node_id): if eds.has_section("DeviceComissioning"): od.bitrate = int(eds.get("DeviceComissioning", "Baudrate")) * 1000 od.node_id = int(eds.get("DeviceComissioning", "NodeID"), 0) + node_id = node_id or od.node_id for section in eds.sections(): # Match dummy definitions From fc577d1ec0affc7c76ba27aa4f9101e0a7453afb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Frieder=20Sch=C3=BCler?= Date: Mon, 10 Jun 2024 22:42:14 +0200 Subject: [PATCH 129/199] pdo: Skip saving if no COB-ID was set (fixes #445) (#446) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit The PdoBase.save() method would fail with a cryptic TypeError exception when the COB-ID was not previously set (still at None). Instead just skip the corresponding PDO and log an INFO level message about it. Add logging when re-enabling the PDO as well. Also fix some minor issues in surrounding code: * Added a test for PDO saving from EDS without further settings. * Skip the always true condition "self.map is not None". The attribute is initialized as an empty list. * Simplify check for curtis_hack using getattr(). * Remove unnecessary initialization in PdoMap.__getitem__(). * Removed unused variable "data" in PdoVariable.set_data() * Wrong type for empty argument to send_message(). Co-authored-by: Frieder Schüler --- canopen/pdo/base.py | 84 ++++++++++++++++++++++++--------------------- test/test_pdo.py | 5 +++ 2 files changed, 49 insertions(+), 40 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 1f4bf3e4..17847603 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -215,7 +215,6 @@ def __getitem_by_name(self, value): f"{', '.join(valid_values)}") def __getitem__(self, key: Union[int, str]) -> "PdoVariable": - var = None if isinstance(key, int): # there is a maximum available of 8 slots per PDO map if key in range(0, 8): @@ -360,7 +359,8 @@ def _raw_from(param): subindex = (value >> 8) & 0xFF # Ignore the highest bit, it is never valid for <= 64 PDO length size = value & 0x7F - if hasattr(self.pdo_node.node, "curtis_hack") and self.pdo_node.node.curtis_hack: # Curtis HACK: mixed up field order + if getattr(self.pdo_node.node, "curtis_hack", False): + # Curtis HACK: mixed up field order index = value & 0xFFFF subindex = (value >> 16) & 0xFF size = (value >> 24) & 0x7F @@ -371,8 +371,10 @@ def _raw_from(param): def save(self) -> None: """Save PDO configuration for this map using SDO.""" - logger.info("Setting COB-ID 0x%X and temporarily disabling PDO", - self.cob_id) + if self.cob_id is None: + logger.info("Skip saving %s: COB-ID was never set", self.com_record.od.name) + return + logger.info("Setting COB-ID 0x%X and temporarily disabling PDO", self.cob_id) self.com_record[1].raw = self.cob_id | PDO_NOT_VALID | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0x0) if self.trans_type is not None: logger.info("Setting transmission type to %d", self.trans_type) @@ -387,42 +389,44 @@ def save(self) -> None: logger.info("Setting SYNC start value to %d", self.sync_start_value) self.com_record[6].raw = self.sync_start_value - if self.map is not None: - try: - self.map_array[0].raw = 0 - except SdoAbortedError: - # WORKAROUND for broken implementations: If the array has a - # fixed number of entries (count not writable), generate dummy - # mappings for an invalid object 0x0000:00 to overwrite any - # excess entries with all-zeros. - self._fill_map(self.map_array[0].raw) - subindex = 1 - for var in self.map: - logger.info("Writing %s (0x%04X:%02X, %d bits) to PDO map", - var.name, var.index, var.subindex, var.length) - if hasattr(self.pdo_node.node, "curtis_hack") and self.pdo_node.node.curtis_hack: # Curtis HACK: mixed up field order - self.map_array[subindex].raw = (var.index | - var.subindex << 16 | - var.length << 24) - else: - self.map_array[subindex].raw = (var.index << 16 | - var.subindex << 8 | - var.length) - subindex += 1 - try: - self.map_array[0].raw = len(self.map) - except SdoAbortedError as e: - # WORKAROUND for broken implementations: If the array - # number-of-entries parameter is not writable, we have already - # generated the required number of mappings above. - if e.code != 0x06010002: - # Abort codes other than "Attempt to write a read-only - # object" should still be reported. - raise - self._update_data_size() + try: + self.map_array[0].raw = 0 + except SdoAbortedError: + # WORKAROUND for broken implementations: If the array has a + # fixed number of entries (count not writable), generate dummy + # mappings for an invalid object 0x0000:00 to overwrite any + # excess entries with all-zeros. + self._fill_map(self.map_array[0].raw) + subindex = 1 + for var in self.map: + logger.info("Writing %s (0x%04X:%02X, %d bits) to PDO map", + var.name, var.index, var.subindex, var.length) + if getattr(self.pdo_node.node, "curtis_hack", False): + # Curtis HACK: mixed up field order + self.map_array[subindex].raw = (var.index | + var.subindex << 16 | + var.length << 24) + else: + self.map_array[subindex].raw = (var.index << 16 | + var.subindex << 8 | + var.length) + subindex += 1 + try: + self.map_array[0].raw = len(self.map) + except SdoAbortedError as e: + # WORKAROUND for broken implementations: If the array + # number-of-entries parameter is not writable, we have already + # generated the required number of mappings above. + if e.code != 0x06010002: + # Abort codes other than "Attempt to write a read-only + # object" should still be reported. + raise + self._update_data_size() if self.enabled: - self.com_record[1].raw = self.cob_id | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0x0) + cob_id = self.cob_id | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0x0) + logger.info("Setting COB-ID 0x%X and re-enabling PDO", cob_id) + self.com_record[1].raw = cob_id self.subscribe() def subscribe(self) -> None: @@ -521,7 +525,7 @@ def remote_request(self) -> None: Silently ignore if not allowed. """ if self.enabled and self.rtr_allowed: - self.pdo_node.network.send_message(self.cob_id, None, remote=True) + self.pdo_node.network.send_message(self.cob_id, bytes(), remote=True) def wait_for_reception(self, timeout: float = 10) -> float: """Wait for the next transmit PDO. @@ -600,7 +604,7 @@ def set_data(self, data: bytes): cur_msg_data = cur_msg_data & bitwise_not # Set the new data on the correct position data = (data << bit_offset) | cur_msg_data - data = od_struct.pack_into(self.pdo_parent.data, byte_offset, data) + od_struct.pack_into(self.pdo_parent.data, byte_offset, data) else: self.pdo_parent.data[byte_offset:byte_offset + len(data)] = data diff --git a/test/test_pdo.py b/test/test_pdo.py index 6bba18fe..32963cf3 100644 --- a/test/test_pdo.py +++ b/test/test_pdo.py @@ -55,6 +55,11 @@ def test_bit_mapping(self): self.assertEqual(node.tpdo[0x2002].raw, 0xf) self.assertEqual(node.pdo[0x1600][0x2002].raw, 0xf) + def test_save_pdo(self): + node = canopen.Node(1, EDS_PATH) + node.tpdo.save() + node.rpdo.save() + if __name__ == "__main__": unittest.main() From 31de70c871f38fce6e07cf90f2d1b3ee2dca20ce Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 11 Jun 2024 08:38:41 +0200 Subject: [PATCH 130/199] Modernize type annotations and fix some discrepancies (#451) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Use postponed evaluation of type annotations (PEP-563 / PEP-649 style) instead of stringized type annotations. * Clarify that each SDO object has its corresponding OD entry linked in the .od attribute, not the whole ObjectDictionary. * __iter__() should return Iterator like in Mapping, not Iterable. * Annotate PdoVariable.pdo_parent type. * Conditionally import types from other sub-packages to avoid dependency cycles. Co-authored-by: Frieder Schüler --- canopen/network.py | 10 ++++--- canopen/objectdictionary/__init__.py | 38 ++++++++++++++------------ canopen/pdo/base.py | 41 ++++++++++++++++------------ canopen/sdo/base.py | 27 +++++++++--------- 4 files changed, 64 insertions(+), 52 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index 9e9a252e..54280909 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -1,7 +1,9 @@ +from __future__ import annotations + from collections.abc import MutableMapping import logging import threading -from typing import Callable, Dict, Iterable, List, Optional, Union +from typing import Callable, Dict, Iterator, List, Optional, Union try: import can @@ -82,7 +84,7 @@ def unsubscribe(self, can_id, callback=None) -> None: else: self.subscribers[can_id].remove(callback) - def connect(self, *args, **kwargs) -> "Network": + def connect(self, *args, **kwargs) -> Network: """Connect to CAN bus using python-can. Arguments are passed directly to :class:`can.BusABC`. Typically these @@ -214,7 +216,7 @@ def send_message(self, can_id: int, data: bytes, remote: bool = False) -> None: def send_periodic( self, can_id: int, data: bytes, period: float, remote: bool = False - ) -> "PeriodicMessageTask": + ) -> PeriodicMessageTask: """Start sending a message periodically. :param can_id: @@ -277,7 +279,7 @@ def __delitem__(self, node_id: int): self.nodes[node_id].remove_network() del self.nodes[node_id] - def __iter__(self) -> Iterable[int]: + def __iter__(self) -> Iterator[int]: return iter(self.nodes) def __len__(self) -> int: diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 103ebf19..56dbbee2 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -1,8 +1,10 @@ """ Object Dictionary module """ +from __future__ import annotations + import struct -from typing import Dict, Iterable, List, Optional, TextIO, Union +from typing import Dict, Iterator, List, Optional, TextIO, Union from collections.abc import MutableMapping, Mapping import logging @@ -13,7 +15,7 @@ logger = logging.getLogger(__name__) -def export_od(od, dest:Union[str,TextIO,None]=None, doc_type:Optional[str]=None): +def export_od(od, dest: Union[str, TextIO, None] = None, doc_type: Optional[str] = None): """ Export :class: ObjectDictionary to a file. :param od: @@ -55,7 +57,7 @@ def export_od(od, dest:Union[str,TextIO,None]=None, doc_type:Optional[str]=None) def import_od( source: Union[str, TextIO, None], node_id: Optional[int] = None, -) -> "ObjectDictionary": +) -> ObjectDictionary: """Parse an EDS, DCF, or EPF file. :param source: @@ -102,7 +104,7 @@ def __init__(self): def __getitem__( self, index: Union[int, str] - ) -> Union["ODArray", "ODRecord", "ODVariable"]: + ) -> Union[ODArray, ODRecord, ODVariable]: """Get object from object dictionary by name or index.""" item = self.names.get(index) or self.indices.get(index) if item is None: @@ -113,7 +115,7 @@ def __getitem__( return item def __setitem__( - self, index: Union[int, str], obj: Union["ODArray", "ODRecord", "ODVariable"] + self, index: Union[int, str], obj: Union[ODArray, ODRecord, ODVariable] ): assert index == obj.index or index == obj.name self.add_object(obj) @@ -123,7 +125,7 @@ def __delitem__(self, index: Union[int, str]): del self.indices[obj.index] del self.names[obj.name] - def __iter__(self) -> Iterable[int]: + def __iter__(self) -> Iterator[int]: return iter(sorted(self.indices)) def __len__(self) -> int: @@ -132,7 +134,7 @@ def __len__(self) -> int: def __contains__(self, index: Union[int, str]): return index in self.names or index in self.indices - def add_object(self, obj: Union["ODArray", "ODRecord", "ODVariable"]) -> None: + def add_object(self, obj: Union[ODArray, ODRecord, ODVariable]) -> None: """Add object to the object dictionary. :param obj: @@ -147,7 +149,7 @@ def add_object(self, obj: Union["ODArray", "ODRecord", "ODVariable"]) -> None: def get_variable( self, index: Union[int, str], subindex: int = 0 - ) -> Optional["ODVariable"]: + ) -> Optional[ODVariable]: """Get the variable object at specified index (and subindex if applicable). :return: ODVariable if found, else `None` @@ -182,13 +184,13 @@ def __init__(self, name: str, index: int): def __repr__(self) -> str: return f"<{type(self).__qualname__} {self.name!r} at {pretty_index(self.index)}>" - def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": + def __getitem__(self, subindex: Union[int, str]) -> ODVariable: item = self.names.get(subindex) or self.subindices.get(subindex) if item is None: raise KeyError(f"Subindex {pretty_index(None, subindex)} was not found") return item - def __setitem__(self, subindex: Union[int, str], var: "ODVariable"): + def __setitem__(self, subindex: Union[int, str], var: ODVariable): assert subindex == var.subindex self.add_member(var) @@ -200,16 +202,16 @@ def __delitem__(self, subindex: Union[int, str]): def __len__(self) -> int: return len(self.subindices) - def __iter__(self) -> Iterable[int]: + def __iter__(self) -> Iterator[int]: return iter(sorted(self.subindices)) def __contains__(self, subindex: Union[int, str]) -> bool: return subindex in self.names or subindex in self.subindices - def __eq__(self, other: "ODRecord") -> bool: + def __eq__(self, other: ODRecord) -> bool: return self.index == other.index - def add_member(self, variable: "ODVariable") -> None: + def add_member(self, variable: ODVariable) -> None: """Adds a :class:`~canopen.objectdictionary.ODVariable` to the record.""" variable.parent = self self.subindices[variable.subindex] = variable @@ -241,7 +243,7 @@ def __init__(self, name: str, index: int): def __repr__(self) -> str: return f"<{type(self).__qualname__} {self.name!r} at {pretty_index(self.index)}>" - def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": + def __getitem__(self, subindex: Union[int, str]) -> ODVariable: var = self.names.get(subindex) or self.subindices.get(subindex) if var is not None: # This subindex is defined @@ -264,13 +266,13 @@ def __getitem__(self, subindex: Union[int, str]) -> "ODVariable": def __len__(self) -> int: return len(self.subindices) - def __iter__(self) -> Iterable[int]: + def __iter__(self) -> Iterator[int]: return iter(sorted(self.subindices)) - def __eq__(self, other: "ODArray") -> bool: + def __eq__(self, other: ODArray) -> bool: return self.index == other.index - def add_member(self, variable: "ODVariable") -> None: + def add_member(self, variable: ODVariable) -> None: """Adds a :class:`~canopen.objectdictionary.ODVariable` to the record.""" variable.parent = self self.subindices[variable.subindex] = variable @@ -348,7 +350,7 @@ def qualname(self) -> str: return f"{self.parent.name}.{self.name}" return self.name - def __eq__(self, other: "ODVariable") -> bool: + def __eq__(self, other: ODVariable) -> bool: return (self.index == other.index and self.subindex == other.subindex) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 17847603..d467cdb3 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -1,6 +1,7 @@ +from __future__ import annotations import threading import math -from typing import Callable, Dict, Iterable, List, Optional, Union +from typing import Callable, Dict, Iterator, List, Optional, Union, TYPE_CHECKING from collections.abc import Mapping import logging import binascii @@ -9,6 +10,12 @@ from canopen import objectdictionary from canopen import variable +if TYPE_CHECKING: + from canopen.network import Network + from canopen import LocalNode, RemoteNode + from canopen.pdo import RPDO, TPDO + from canopen.sdo import SdoRecord + PDO_NOT_VALID = 1 << 31 RTR_NOT_ALLOWED = 1 << 30 @@ -22,10 +29,10 @@ class PdoBase(Mapping): Parent object associated with this PDO instance """ - def __init__(self, node): - self.network = None - self.map = None # instance of PdoMaps - self.node = node + def __init__(self, node: Union[LocalNode, RemoteNode]): + self.network: Optional[Network] = None + self.map: Optional[PdoMaps] = None + self.node: Union[LocalNode, RemoteNode] = node def __iter__(self): return iter(self.map) @@ -131,7 +138,7 @@ def __init__(self, com_offset, map_offset, pdo_node: PdoBase, cob_base=None): :param pdo_node: :param cob_base: """ - self.maps: Dict[int, "PdoMap"] = {} + self.maps: Dict[int, PdoMap] = {} for map_no in range(512): if com_offset + map_no in pdo_node.node.object_dictionary: new_map = PdoMap( @@ -143,10 +150,10 @@ def __init__(self, com_offset, map_offset, pdo_node: PdoBase, cob_base=None): new_map.predefined_cob_id = cob_base + map_no * 0x100 + pdo_node.node.id self.maps[map_no + 1] = new_map - def __getitem__(self, key: int) -> "PdoMap": + def __getitem__(self, key: int) -> PdoMap: return self.maps[key] - def __iter__(self) -> Iterable[int]: + def __iter__(self) -> Iterator[int]: return iter(self.maps) def __len__(self) -> int: @@ -157,9 +164,9 @@ class PdoMap: """One message which can have up to 8 bytes of variables mapped.""" def __init__(self, pdo_node, com_record, map_array): - self.pdo_node = pdo_node - self.com_record = com_record - self.map_array = map_array + self.pdo_node: Union[TPDO, RPDO] = pdo_node + self.com_record: SdoRecord = com_record + self.map_array: SdoRecord = map_array #: If this map is valid self.enabled: bool = False #: COB-ID for this PDO @@ -177,7 +184,7 @@ def __init__(self, pdo_node, com_record, map_array): #: Ignores SYNC objects up to this SYNC counter value (optional) self.sync_start_value: Optional[int] = None #: List of variables mapped to this PDO - self.map: List["PdoVariable"] = [] + self.map: List[PdoVariable] = [] self.length: int = 0 #: Current message data self.data = bytearray() @@ -214,7 +221,7 @@ def __getitem_by_name(self, value): raise KeyError(f"{value} not found in map. Valid entries are " f"{', '.join(valid_values)}") - def __getitem__(self, key: Union[int, str]) -> "PdoVariable": + def __getitem__(self, key: Union[int, str]) -> PdoVariable: if isinstance(key, int): # there is a maximum available of 8 slots per PDO map if key in range(0, 8): @@ -228,7 +235,7 @@ def __getitem__(self, key: Union[int, str]) -> "PdoVariable": var = self.__getitem_by_name(key) return var - def __iter__(self) -> Iterable["PdoVariable"]: + def __iter__(self) -> Iterator[PdoVariable]: return iter(self.map) def __len__(self) -> int: @@ -303,7 +310,7 @@ def on_message(self, can_id, data, timestamp): for callback in self.callbacks: callback(self) - def add_callback(self, callback: Callable[["PdoMap"], None]) -> None: + def add_callback(self, callback: Callable[[PdoMap], None]) -> None: """Add a callback which will be called on receive. :param callback: @@ -451,7 +458,7 @@ def add_variable( index: Union[str, int], subindex: Union[str, int] = 0, length: Optional[int] = None, - ) -> "PdoVariable": + ) -> PdoVariable: """Add a variable from object dictionary as the next entry. :param index: Index of variable as name or number @@ -544,7 +551,7 @@ class PdoVariable(variable.Variable): def __init__(self, od: objectdictionary.ODVariable): #: PDO object that is associated with this ODVariable Object - self.pdo_parent = None + self.pdo_parent: Optional[PdoMap] = None #: Location of variable in the message in bits self.offset = None self.length = len(od) diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 1099a144..0bb068b4 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -1,9 +1,10 @@ +from __future__ import annotations + import binascii -from typing import Iterable, Optional, Union +from typing import Iterator, Optional, Union from collections.abc import Mapping from canopen import objectdictionary -from canopen.objectdictionary import ObjectDictionary from canopen import variable from canopen.utils import pretty_index @@ -30,7 +31,7 @@ def __init__( self, rx_cobid: int, tx_cobid: int, - od: ObjectDictionary, + od: objectdictionary.ObjectDictionary, ): """ :param rx_cobid: @@ -47,7 +48,7 @@ def __init__( def __getitem__( self, index: Union[str, int] - ) -> Union["SdoVariable", "SdoArray", "SdoRecord"]: + ) -> Union[SdoVariable, SdoArray, SdoRecord]: entry = self.od[index] if isinstance(entry, objectdictionary.ODVariable): return SdoVariable(self, entry) @@ -56,7 +57,7 @@ def __getitem__( elif isinstance(entry, objectdictionary.ODRecord): return SdoRecord(self, entry) - def __iter__(self) -> Iterable[int]: + def __iter__(self) -> Iterator[int]: return iter(self.od) def __len__(self) -> int: @@ -67,7 +68,7 @@ def __contains__(self, key: Union[int, str]) -> bool: def get_variable( self, index: Union[int, str], subindex: int = 0 - ) -> Optional["SdoVariable"]: + ) -> Optional[SdoVariable]: """Get the variable object at specified index (and subindex if applicable). :return: SdoVariable if found, else `None` @@ -93,17 +94,17 @@ def download( class SdoRecord(Mapping): - def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): + def __init__(self, sdo_node: SdoBase, od: objectdictionary.ODRecord): self.sdo_node = sdo_node self.od = od def __repr__(self) -> str: return f"<{type(self).__qualname__} {self.od.name!r} at {pretty_index(self.od.index)}>" - def __getitem__(self, subindex: Union[int, str]) -> "SdoVariable": + def __getitem__(self, subindex: Union[int, str]) -> SdoVariable: return SdoVariable(self.sdo_node, self.od[subindex]) - def __iter__(self) -> Iterable[int]: + def __iter__(self) -> Iterator[int]: return iter(self.od) def __len__(self) -> int: @@ -115,17 +116,17 @@ def __contains__(self, subindex: Union[int, str]) -> bool: class SdoArray(Mapping): - def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): + def __init__(self, sdo_node: SdoBase, od: objectdictionary.ODArray): self.sdo_node = sdo_node self.od = od def __repr__(self) -> str: return f"<{type(self).__qualname__} {self.od.name!r} at {pretty_index(self.od.index)}>" - def __getitem__(self, subindex: Union[int, str]) -> "SdoVariable": + def __getitem__(self, subindex: Union[int, str]) -> SdoVariable: return SdoVariable(self.sdo_node, self.od[subindex]) - def __iter__(self) -> Iterable[int]: + def __iter__(self) -> Iterator[int]: return iter(range(1, len(self) + 1)) def __len__(self) -> int: @@ -138,7 +139,7 @@ def __contains__(self, subindex: int) -> bool: class SdoVariable(variable.Variable): """Access object dictionary variable values using SDO protocol.""" - def __init__(self, sdo_node: SdoBase, od: ObjectDictionary): + def __init__(self, sdo_node: SdoBase, od: objectdictionary.ODVariable): self.sdo_node = sdo_node variable.Variable.__init__(self, od) From 9bd503ed224bd1c2f39217cb468b8cb028f58356 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 14 May 2024 11:41:30 +0200 Subject: [PATCH 131/199] Create py.typed marker for automatic type checker discovery. This should solve the "Cannot find implementation or library stub" errors from mypy if installed properly. Since the code already has internal type hints, adding the marker is sufficient for mypy to use them. --- canopen/py.typed | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 canopen/py.typed diff --git a/canopen/py.typed b/canopen/py.typed new file mode 100644 index 00000000..e69de29b From a4ebc730fe106dd030c6db0b97b6b8ed2b9c6dc0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 14 May 2024 11:43:22 +0200 Subject: [PATCH 132/199] Migrate setup.cfg to pyproject.toml for newer setuptools compat. The setuptools>=69 dependency includes a fix to automatically include the py.typed marker in the distribution, thus making type hints usage much easier. The newer version however fails to build when the basic project metadata is missing in pyproject.toml. Thus the settings from setup.cfg are migrated entirely, upgrading to setuptools_scm >= 8 in the process. --- pyproject.toml | 38 ++++++++++++++++++++++++++++++++++++-- setup.cfg | 29 ----------------------------- 2 files changed, 36 insertions(+), 31 deletions(-) delete mode 100644 setup.cfg diff --git a/pyproject.toml b/pyproject.toml index 403805fb..b6268c0c 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,6 +1,40 @@ [build-system] -requires = ["setuptools>=45", "wheel", "setuptools_scm>=6.2"] +requires = ["setuptools>=69", "wheel", "setuptools_scm>=8"] build-backend = "setuptools.build_meta" +[project] +name = "canopen" +authors = [ + {name = "Christian Sandberg", email = "christiansandberg@me.com"}, +] +description = "CANopen stack implementation" +readme = "README.rst" +requires-python = ">=3.6" +license = {file = "LICENSE.txt"} +classifiers = [ + "Development Status :: 5 - Production/Stable", + "License :: OSI Approved :: MIT License", + "Operating System :: OS Independent", + "Programming Language :: Python :: 3 :: Only", + "Intended Audience :: Developers", + "Topic :: Scientific/Engineering", +] +dependencies = [ + "python-can >= 3.0.0", +] +dynamic = ["version"] + +[project.urls] +documentation = "https://canopen.readthedocs.io/en/stable/" +repository = "https://github.com/christiansandberg/canopen" + [tool.setuptools_scm] -write_to = "canopen/_version.py" +version_file = "canopen/_version.py" + +[tool.pytest.ini_options] +testpaths = [ + "test", +] +filterwarnings = [ + "ignore::DeprecationWarning", +] diff --git a/setup.cfg b/setup.cfg deleted file mode 100644 index 7d33e805..00000000 --- a/setup.cfg +++ /dev/null @@ -1,29 +0,0 @@ -[metadata] -name = canopen -description = CANopen stack implementation -long_description = file: README.rst -project_urls = - Documentation = http://canopen.readthedocs.io/en/stable/ - Source Code = https://github.com/christiansandberg/canopen -author = Christian Sandberg -author_email = christiansandberg@me.com -classifier = - Development Status :: 5 - Production/Stable - License :: OSI Approved :: MIT License - Operating System :: OS Independent - Programming Language :: Python :: 3 :: Only - Intended Audience :: Developers - Topic :: Scientific/Engineering - -[options] -packages = find: -python_requires = >=3.6 -install_requires = - python-can >= 3.0.0 -include_package_data = True - -[tool:pytest] -testpaths = - test -filterwarnings = - ignore::DeprecationWarning From 599f4ac0bdbfab8d3523338946e2274d9d2a9b2a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 11 Jun 2024 20:44:07 +0200 Subject: [PATCH 133/199] Include top-three contributors as authors. Based on stats from GitHub, master branch as of today. --- pyproject.toml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/pyproject.toml b/pyproject.toml index b6268c0c..bffee508 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -6,6 +6,8 @@ build-backend = "setuptools.build_meta" name = "canopen" authors = [ {name = "Christian Sandberg", email = "christiansandberg@me.com"}, + {name = "André Colomb", email = "src@andre.colomb.de"}, + {name = "André Filipe Silva", email = "afsilva.work@gmail.com"}, ] description = "CANopen stack implementation" readme = "README.rst" From 9df972c92aee2c06898d609e8da99912574e7e78 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Tue, 11 Jun 2024 21:03:31 +0200 Subject: [PATCH 134/199] Implement the remaining canopen datatypes (#440) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Implement the remaining canopen datatypes * Add datatype defs for the canopen standard types * Move datatypes_24.py classes to datatypes.py * Replace Unsigned24 and Interger24 by generic UnsignedN and IntegerN respectively * Add EDS-file containing all datatypes * Added tests for encoding and decoding all datatypes * Added tests for SDO uploads of all datatypes * Annotate type hint for STRUCT_TYPES listing. * Disable failing tests waiting on a fix for #436. Co-authored-by: André Colomb --- canopen/objectdictionary/__init__.py | 27 +- canopen/objectdictionary/datatypes.py | 105 ++++++- canopen/objectdictionary/datatypes_24bit.py | 33 -- test/datatypes.eds | 310 +++++++++++++++++++ test/test_od.py | 97 ++++++ test/test_sdo.py | 325 ++++++++++++++++++++ 6 files changed, 854 insertions(+), 43 deletions(-) delete mode 100644 canopen/objectdictionary/datatypes_24bit.py create mode 100644 test/datatypes.eds diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 56dbbee2..156972fd 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -9,7 +9,6 @@ import logging from canopen.objectdictionary.datatypes import * -from canopen.objectdictionary.datatypes_24bit import Integer24, Unsigned24 from canopen.utils import pretty_index logger = logging.getLogger(__name__) @@ -282,17 +281,25 @@ def add_member(self, variable: ODVariable) -> None: class ODVariable: """Simple variable.""" - STRUCT_TYPES = { + STRUCT_TYPES: dict[int, struct.Struct] = { + # Use struct module to pack/unpack data where possible and use the + # custom IntegerN and UnsignedN classes for the special data types. BOOLEAN: struct.Struct("?"), INTEGER8: struct.Struct("b"), INTEGER16: struct.Struct(" None: def decode_raw(self, data: bytes) -> Union[int, float, str, bytes, bytearray]: if self.data_type == VISIBLE_STRING: - return data.rstrip(b"\x00").decode("ascii", errors="ignore") + # Strip any trailing NUL characters from C-based systems + return data.decode("ascii", errors="ignore").rstrip("\x00") elif self.data_type == UNICODE_STRING: - # Is this correct? - return data.rstrip(b"\x00").decode("utf_16_le", errors="ignore") + # The CANopen standard does not specify the encoding. This + # library assumes UTF-16, being the most common two-byte encoding format. + # Strip any trailing NUL characters from C-based systems + return data.decode("utf_16_le", errors="ignore").rstrip("\x00") elif self.data_type in self.STRUCT_TYPES: try: value, = self.STRUCT_TYPES[self.data_type].unpack(data) @@ -407,8 +417,9 @@ def encode_raw(self, value: Union[int, float, str, bytes, bytearray]) -> bytes: elif self.data_type == VISIBLE_STRING: return value.encode("ascii") elif self.data_type == UNICODE_STRING: - # Is this correct? return value.encode("utf_16_le") + elif self.data_type in (DOMAIN, OCTET_STRING): + return bytes(value) elif self.data_type in self.STRUCT_TYPES: if self.data_type in INTEGER_TYPES: value = int(value) diff --git a/canopen/objectdictionary/datatypes.py b/canopen/objectdictionary/datatypes.py index fa849d5c..ad37fe6f 100644 --- a/canopen/objectdictionary/datatypes.py +++ b/canopen/objectdictionary/datatypes.py @@ -1,3 +1,4 @@ +import struct BOOLEAN = 0x1 INTEGER8 = 0x2 @@ -10,16 +11,116 @@ VISIBLE_STRING = 0x9 OCTET_STRING = 0xA UNICODE_STRING = 0xB +TIME_OF_DAY = 0xC +TIME_DIFFERENCE = 0xD DOMAIN = 0xF INTEGER24 = 0x10 REAL64 = 0x11 +INTEGER40 = 0x12 +INTEGER48 = 0x13 +INTEGER56 = 0x14 INTEGER64 = 0x15 UNSIGNED24 = 0x16 +UNSIGNED40 = 0x18 +UNSIGNED48 = 0x19 +UNSIGNED56 = 0x1A UNSIGNED64 = 0x1B +PDO_COMMUNICATION_PARAMETER = 0x20 +PDO_MAPPING = 0x21 +SDO_PARAMETER = 0x22 +IDENTITY = 0x23 -SIGNED_TYPES = (INTEGER8, INTEGER16, INTEGER24, INTEGER32, INTEGER64) -UNSIGNED_TYPES = (UNSIGNED8, UNSIGNED16, UNSIGNED24, UNSIGNED32, UNSIGNED64) +SIGNED_TYPES = ( + INTEGER8, + INTEGER16, + INTEGER24, + INTEGER32, + INTEGER40, + INTEGER48, + INTEGER56, + INTEGER64, +) +UNSIGNED_TYPES = ( + UNSIGNED8, + UNSIGNED16, + UNSIGNED24, + UNSIGNED32, + UNSIGNED40, + UNSIGNED48, + UNSIGNED56, + UNSIGNED64, +) INTEGER_TYPES = SIGNED_TYPES + UNSIGNED_TYPES FLOAT_TYPES = (REAL32, REAL64) NUMBER_TYPES = INTEGER_TYPES + FLOAT_TYPES DATA_TYPES = (VISIBLE_STRING, OCTET_STRING, UNICODE_STRING, DOMAIN) + + +class UnsignedN(struct.Struct): + """Packing and unpacking unsigned integers of arbitrary width, like struct.Struct. + + The width must be a multiple of 8 and must be between 8 and 64. + """ + + def __init__(self, width: int): + self.width = width + if width % 8 != 0: + raise ValueError("Width must be a multiple of 8") + if width <= 0 or width > 64: + raise ValueError("Invalid width for UnsignedN") + elif width <= 8: + fmt = "B" + elif width <= 16: + fmt = " int: + return self.width // 8 + + +class IntegerN(struct.Struct): + """Packing and unpacking integers of arbitrary width, like struct.Struct. + + The width must be a multiple of 8 and must be between 8 and 64. + """ + + def __init__(self, width: int): + self.width = width + if width % 8 != 0: + raise ValueError("Width must be a multiple of 8") + if width <= 0 or width > 64: + raise ValueError("Invalid width for IntegerN") + elif width <= 8: + fmt = "b" + elif width <= 16: + fmt = " 0 + return super().unpack( + buffer + (b'\xff' if neg else b'\x00') * (super().size - self.size) + ) + + def pack(self, *v): + return super().pack(*v)[:self.size] + + @property + def size(self) -> int: + return self.width // 8 diff --git a/canopen/objectdictionary/datatypes_24bit.py b/canopen/objectdictionary/datatypes_24bit.py deleted file mode 100644 index 475e7526..00000000 --- a/canopen/objectdictionary/datatypes_24bit.py +++ /dev/null @@ -1,33 +0,0 @@ -import struct - - -class Unsigned24: - def __init__(self): - self.__st = struct.Struct(" 0 - return self.__st.unpack(__buffer + (b'\xff' if neg else b'\x00')) - - def pack(self, *v): - return self.__st.pack(*v)[:3] - - @property - def size(self): - return 3 diff --git a/test/datatypes.eds b/test/datatypes.eds new file mode 100644 index 00000000..ff858cb1 --- /dev/null +++ b/test/datatypes.eds @@ -0,0 +1,310 @@ +[FileInfo] +FileName=datatypes.eds +FileVersion=1 +FileRevision=1 +EDSVersion=4.0 +Description=OD implementing the CANOpen datatype catalog +CreationTime=07:31PM +CreationDate=05-24-2024 +CreatedBy=objdictgen +ModificationTime=07:31PM +ModificationDate=05-24-2024 +ModifiedBy=objdictgen + +[DeviceInfo] +VendorName=objdictgen +VendorNumber=0x00000000 +ProductName=Alltypes +ProductNumber=0x00000000 +RevisionNumber=0x00000000 +BaudRate_10=1 +BaudRate_20=1 +BaudRate_50=1 +BaudRate_125=1 +BaudRate_250=1 +BaudRate_500=1 +BaudRate_800=1 +BaudRate_1000=1 +SimpleBootUpMaster=1 +SimpleBootUpSlave=0 +Granularity=8 +DynamicChannelsSupported=0 +CompactPDO=0 +GroupMessaging=0 +NrOfRXPDO=0 +NrOfTXPDO=0 +LSS_Supported=0 + +[DummyUsage] +Dummy0001=0 +Dummy0002=1 +Dummy0003=1 +Dummy0004=1 +Dummy0005=1 +Dummy0006=1 +Dummy0007=1 + +[Comments] +Lines=0 + +[MandatoryObjects] +SupportedObjects=1 +1=0x1018 + +[1018] +ParameterName=Identity +ObjectType=0x9 +SubNumber=5 + +[1018sub0] +ParameterName=Number of Entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=4 +PDOMapping=0 + +[1018sub1] +ParameterName=Vendor ID +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +[1018sub2] +ParameterName=Product Code +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +[1018sub3] +ParameterName=Revision Number +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +[1018sub4] +ParameterName=Serial Number +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +[OptionalObjects] +SupportedObjects=0 + +[ManufacturerObjects] +SupportedObjects=23 +1=0x2001 +2=0x2002 +3=0x2003 +4=0x2004 +5=0x2005 +6=0x2006 +7=0x2007 +8=0x2008 +9=0x2009 +10=0x200A +11=0x200B +12=0x200F +13=0x2010 +14=0x2011 +15=0x2012 +16=0x2013 +17=0x2014 +18=0x2015 +19=0x2016 +20=0x2018 +21=0x2019 +22=0x201A +23=0x201B + +[2001] +ParameterName=BOOLEAN +ObjectType=0x7 +DataType=0x0001 +AccessType=rw +DefaultValue=0 +PDOMapping=1 + +[2002] +ParameterName=INTEGER8 +ObjectType=0x7 +DataType=0x0002 +AccessType=rw +DefaultValue=12 +PDOMapping=1 + +[2003] +ParameterName=INTEGER16 +ObjectType=0x7 +DataType=0x0003 +AccessType=rw +DefaultValue=34 +PDOMapping=1 + +[2004] +ParameterName=INTEGER32 +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=45 +PDOMapping=1 + +[2005] +ParameterName=UNSIGNED8 +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=56 +PDOMapping=1 + +[2006] +ParameterName=UNSIGNED16 +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=8198 +PDOMapping=1 + +[2007] +ParameterName=UNSIGNED32 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=537337864 +PDOMapping=1 + +[2008] +ParameterName=REAL32 +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +DefaultValue=1.2 +PDOMapping=1 + +[2009] +ParameterName=VISIBLE_STRING +ObjectType=0x7 +DataType=0x0009 +AccessType=rw +DefaultValue=ABCD +PDOMapping=1 + +[200A] +ParameterName=OCTET_STRING +ObjectType=0x7 +DataType=0x000A +AccessType=rw +DefaultValue=ABCD +PDOMapping=1 + +[200B] +ParameterName=UNICODE_STRING +ObjectType=0x7 +DataType=0x000B +AccessType=rw +DefaultValue=abc✓ +PDOMapping=1 + +[200F] +ParameterName=DOMAIN +ObjectType=0x7 +DataType=0x000F +AccessType=rw +DefaultValue=@ABCD +PDOMapping=1 + +[2010] +ParameterName=INTEGER24 +ObjectType=0x7 +DataType=0x0010 +AccessType=rw +DefaultValue=-1 +PDOMapping=1 + +[2011] +ParameterName=REAL64 +ObjectType=0x7 +DataType=0x0011 +AccessType=rw +DefaultValue=1.6 +PDOMapping=1 + +[2012] +ParameterName=INTEGER40 +ObjectType=0x7 +DataType=0x0012 +AccessType=rw +DefaultValue=-40 +PDOMapping=1 + +[2013] +ParameterName=INTEGER48 +ObjectType=0x7 +DataType=0x0013 +AccessType=rw +DefaultValue=-48 +PDOMapping=1 + +[2014] +ParameterName=INTEGER56 +ObjectType=0x7 +DataType=0x0014 +AccessType=rw +DefaultValue=-56 +PDOMapping=1 + +[2015] +ParameterName=INTEGER64 +ObjectType=0x7 +DataType=0x0015 +AccessType=rw +DefaultValue=-64 +PDOMapping=1 + +[2016] +ParameterName=UNSIGNED24 +ObjectType=0x7 +DataType=0x0016 +AccessType=rw +DefaultValue=24 +PDOMapping=1 + +[2018] +ParameterName=UNSIGNED40 +ObjectType=0x7 +DataType=0x0018 +AccessType=rw +DefaultValue=40 +PDOMapping=1 + +[2019] +ParameterName=UNSIGNED48 +ObjectType=0x7 +DataType=0x0019 +AccessType=rw +DefaultValue=48 +PDOMapping=1 + +[201A] +ParameterName=UNSIGNED56 +ObjectType=0x7 +DataType=0x001A +AccessType=rw +DefaultValue=56 +PDOMapping=1 + +[201B] +ParameterName=UNSIGNED64 +ObjectType=0x7 +DataType=0x001B +AccessType=rw +DefaultValue=64 +PDOMapping=1 diff --git a/test/test_od.py b/test/test_od.py index 9c25bfcb..d3755234 100644 --- a/test/test_od.py +++ b/test/test_od.py @@ -36,6 +36,30 @@ def test_unsigned32(self): self.assertEqual(var.decode_raw(b"\xfc\xfd\xfe\xff"), 4294901244) self.assertEqual(var.encode_raw(4294901244), b"\xfc\xfd\xfe\xff") + def test_unsigned40(self): + var = od.ODVariable("Test UNSIGNED40", 0x1000) + var.data_type = od.UNSIGNED40 + self.assertEqual(var.decode_raw(b"\xfb\xfc\xfd\xfe\xff"), 0xfffefdfcfb) + self.assertEqual(var.encode_raw(0xfffefdfcfb), b"\xfb\xfc\xfd\xfe\xff") + + def test_unsigned48(self): + var = od.ODVariable("Test UNSIGNED48", 0x1000) + var.data_type = od.UNSIGNED48 + self.assertEqual(var.decode_raw(b"\xfa\xfb\xfc\xfd\xfe\xff"), 0xfffefdfcfbfa) + self.assertEqual(var.encode_raw(0xfffefdfcfbfa), b"\xfa\xfb\xfc\xfd\xfe\xff") + + def test_unsigned56(self): + var = od.ODVariable("Test UNSIGNED56", 0x1000) + var.data_type = od.UNSIGNED56 + self.assertEqual(var.decode_raw(b"\xf9\xfa\xfb\xfc\xfd\xfe\xff"), 0xfffefdfcfbfaf9) + self.assertEqual(var.encode_raw(0xfffefdfcfbfaf9), b"\xf9\xfa\xfb\xfc\xfd\xfe\xff") + + def test_unsigned64(self): + var = od.ODVariable("Test UNSIGNED64", 0x1000) + var.data_type = od.UNSIGNED64 + self.assertEqual(var.decode_raw(b"\xf8\xf9\xfa\xfb\xfc\xfd\xfe\xff"), 0xfffefdfcfbfaf9f8) + self.assertEqual(var.encode_raw(0xfffefdfcfbfaf9f8), b"\xf8\xf9\xfa\xfb\xfc\xfd\xfe\xff") + def test_integer8(self): var = od.ODVariable("Test INTEGER8", 0x1000) var.data_type = od.INTEGER8 @@ -64,8 +88,58 @@ def test_integer32(self): var = od.ODVariable("Test INTEGER32", 0x1000) var.data_type = od.INTEGER32 self.assertEqual(var.decode_raw(b"\xfe\xff\xff\xff"), -2) + self.assertEqual(var.decode_raw(b"\x01\x00\x00\x00"), 1) + self.assertEqual(var.encode_raw(1), b"\x01\x00\x00\x00") self.assertEqual(var.encode_raw(-2), b"\xfe\xff\xff\xff") + def test_integer40(self): + var = od.ODVariable("Test INTEGER40", 0x1000) + var.data_type = od.INTEGER40 + self.assertEqual(var.decode_raw(b"\xfe\xff\xff\xff\xff"), -2) + self.assertEqual(var.decode_raw(b"\x01\x00\x00\x00\x00"), 1) + self.assertEqual(var.encode_raw(-2), b"\xfe\xff\xff\xff\xff") + self.assertEqual(var.encode_raw(1), b"\x01\x00\x00\x00\x00") + + def test_integer48(self): + var = od.ODVariable("Test INTEGER48", 0x1000) + var.data_type = od.INTEGER48 + self.assertEqual(var.decode_raw(b"\xfe\xff\xff\xff\xff\xff"), -2) + self.assertEqual(var.decode_raw(b"\x01\x00\x00\x00\x00\x00"), 1) + self.assertEqual(var.encode_raw(-2), b"\xfe\xff\xff\xff\xff\xff") + self.assertEqual(var.encode_raw(1), b"\x01\x00\x00\x00\x00\x00") + + def test_integer56(self): + var = od.ODVariable("Test INTEGER56", 0x1000) + var.data_type = od.INTEGER56 + self.assertEqual(var.decode_raw(b"\xfe\xff\xff\xff\xff\xff\xff"), -2) + self.assertEqual(var.decode_raw(b"\x01\x00\x00\x00\x00\x00\x00"), 1) + self.assertEqual(var.encode_raw(-2), b"\xfe\xff\xff\xff\xff\xff\xff") + self.assertEqual(var.encode_raw(1), b"\x01\x00\x00\x00\x00\x00\x00") + + def test_integer64(self): + var = od.ODVariable("Test INTEGER64", 0x1000) + var.data_type = od.INTEGER64 + self.assertEqual(var.decode_raw(b"\xfe\xff\xff\xff\xff\xff\xff\xff"), -2) + self.assertEqual(var.decode_raw(b"\x01\x00\x00\x00\x00\x00\x00\x00"), 1) + self.assertEqual(var.encode_raw(-2), b"\xfe\xff\xff\xff\xff\xff\xff\xff") + self.assertEqual(var.encode_raw(1), b"\x01\x00\x00\x00\x00\x00\x00\x00") + + def test_real32(self): + var = od.ODVariable("Test REAL32", 0x1000) + var.data_type = od.REAL32 + # Select values that are exaclty representable in decimal notation + self.assertEqual(var.decode_raw(b"\x00\x00\x00\x00"), 0.) + self.assertEqual(var.decode_raw(b"\x00\x00\x60\x40"), 3.5) + self.assertEqual(var.decode_raw(b"\x00\x20\x7a\xc4"), -1000.5) + + def test_real64(self): + var = od.ODVariable("Test REAL64", 0x1000) + var.data_type = od.REAL64 + # Select values that are exaclty representable in decimal notation + self.assertEqual(var.decode_raw(b"\x00\x00\x00\x00\x00\x00\x00\x00"), 0.) + self.assertEqual(var.decode_raw(b"\x00\x00\x00\x00\x00\x4a\x93\x40"), 1234.5) + self.assertEqual(var.decode_raw(b"\x06\x81\x95\x43\x0b\x42\x8f\xc0"), -1000.2555) + def test_visible_string(self): var = od.ODVariable("Test VISIBLE_STRING", 0x1000) var.data_type = od.VISIBLE_STRING @@ -73,6 +147,29 @@ def test_visible_string(self): self.assertEqual(var.decode_raw(b"zero terminated\x00"), "zero terminated") self.assertEqual(var.encode_raw("testing"), b"testing") + def test_unicode_string(self): + var = od.ODVariable("Test UNICODE_STRING", 0x1000) + var.data_type = od.UNICODE_STRING + self.assertEqual(var.decode_raw(b"\x61\x00\x62\x00\x63\x00"), "abc") + self.assertEqual(var.decode_raw(b"\x61\x00\x62\x00\x63\x00\x00\x00"), "abc") # Zero terminated + self.assertEqual(var.encode_raw("abc"), b"\x61\x00\x62\x00\x63\x00") + self.assertEqual(var.decode_raw(b"\x60\x3f\x7d\x59"), "\u3f60\u597d") # Chinese "Nǐ hǎo", hello + self.assertEqual(var.encode_raw("\u3f60\u597d"), b"\x60\x3f\x7d\x59") # Chinese "Nǐ hǎo", hello + + def test_octet_string(self): + var = od.ODVariable("Test OCTET_STRING", 0x1000) + var.data_type = od.OCTET_STRING + self.assertEqual(var.decode_raw(b"abcdefg"), b"abcdefg") + self.assertEqual(var.decode_raw(b"zero terminated\x00"), b"zero terminated\x00") + self.assertEqual(var.encode_raw(b"testing"), b"testing") + + def test_domain(self): + var = od.ODVariable("Test DOMAIN", 0x1000) + var.data_type = od.DOMAIN + self.assertEqual(var.decode_raw(b"abcdefg"), b"abcdefg") + self.assertEqual(var.decode_raw(b"zero terminated\x00"), b"zero terminated\x00") + self.assertEqual(var.encode_raw(b"testing"), b"testing") + class TestAlternativeRepresentations(unittest.TestCase): diff --git a/test/test_sdo.py b/test/test_sdo.py index 31759c22..1ec35dab 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -2,8 +2,11 @@ import unittest # import binascii import canopen +from canopen.objectdictionary import ODVariable +import canopen.objectdictionary.datatypes as dt EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') +DATAEDS_PATH = os.path.join(os.path.dirname(__file__), 'datatypes.eds') TX = 1 RX = 2 @@ -164,5 +167,327 @@ def test_add_sdo_channel(self): self.assertIn(client, self.network[2].sdo_channels) +class TestSDOClientDatatypes(unittest.TestCase): + """Test the SDO client uploads with the different data types in CANopen.""" + + def _send_message(self, can_id, data, remote=False): + """Will be used instead of the usual Network.send_message method. + + Checks that the message data is according to expected and answers + with the provided data. + """ + next_data = self.data.pop(0) + self.assertEqual(next_data[0], TX, "No transmission was expected") + # print("> %s (%s)" % (binascii.hexlify(data), binascii.hexlify(next_data[1]))) + self.assertSequenceEqual(data, next_data[1]) + self.assertEqual(can_id, 0x602) + while self.data and self.data[0][0] == RX: + # print("< %s" % binascii.hexlify(self.data[0][1])) + self.network.notify(0x582, self.data.pop(0)[1], 0.0) + + def setUp(self): + network = canopen.Network() + network.send_message = self._send_message + node = network.add_node(2, DATAEDS_PATH) + node.sdo.RESPONSE_TIMEOUT = 0.01 + self.node = node + self.network = network + + def test_boolean(self): + self.data = [ + (TX, b'\x40\x01\x20\x00\x00\x00\x00\x00'), + (RX, b'\x4f\x01\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.BOOLEAN, 0) + self.assertEqual(data, b'\xfe') + + def test_unsigned8(self): + self.data = [ + (TX, b'\x40\x05\x20\x00\x00\x00\x00\x00'), + (RX, b'\x4f\x05\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNSIGNED8, 0) + self.assertEqual(data, b'\xfe') + + def test_unsigned16(self): + self.data = [ + (TX, b'\x40\x06\x20\x00\x00\x00\x00\x00'), + (RX, b'\x4b\x06\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNSIGNED16, 0) + self.assertEqual(data, b'\xfe\xfd') + + def test_unsigned24(self): + self.data = [ + (TX, b'\x40\x16\x20\x00\x00\x00\x00\x00'), + (RX, b'\x47\x16\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNSIGNED24, 0) + self.assertEqual(data, b'\xfe\xfd\xfc') + + def test_unsigned32(self): + self.data = [ + (TX, b'\x40\x07\x20\x00\x00\x00\x00\x00'), + (RX, b'\x43\x07\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNSIGNED32, 0) + self.assertEqual(data, b'\xfe\xfd\xfc\xfb') + + def test_unsigned40(self): + self.data = [ + (TX, b'\x40\x18\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x18\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x05\xb2\x01\x20\x02\x91\x12\x03'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNSIGNED40, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91') + + def test_unsigned48(self): + self.data = [ + (TX, b'\x40\x19\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x19\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x03\xb2\x01\x20\x02\x91\x12\x03'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNSIGNED48, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12') + + def test_unsigned56(self): + self.data = [ + (TX, b'\x40\x1a\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x1a\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x01\xb2\x01\x20\x02\x91\x12\x03'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNSIGNED56, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12\x03') + + def test_unsigned64(self): + self.data = [ + (TX, b'\x40\x1b\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x1b\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\xb2\x01\x20\x02\x91\x12\x03'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x1d\x19\x21\x70\xfe\xfd\xfc\xfb'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNSIGNED64, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12\x03\x19') + + def test_integer8(self): + self.data = [ + (TX, b'\x40\x02\x20\x00\x00\x00\x00\x00'), + (RX, b'\x4f\x02\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.INTEGER8, 0) + self.assertEqual(data, b'\xfe') + + def test_integer16(self): + self.data = [ + (TX, b'\x40\x03\x20\x00\x00\x00\x00\x00'), + (RX, b'\x4b\x03\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.INTEGER16, 0) + self.assertEqual(data, b'\xfe\xfd') + + def test_integer24(self): + self.data = [ + (TX, b'\x40\x10\x20\x00\x00\x00\x00\x00'), + (RX, b'\x47\x10\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.INTEGER24, 0) + self.assertEqual(data, b'\xfe\xfd\xfc') + + def test_integer32(self): + self.data = [ + (TX, b'\x40\x04\x20\x00\x00\x00\x00\x00'), + (RX, b'\x43\x04\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.INTEGER32, 0) + self.assertEqual(data, b'\xfe\xfd\xfc\xfb') + + def test_integer40(self): + self.data = [ + (TX, b'\x40\x12\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x12\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x05\xb2\x01\x20\x02\x91\x12\x03'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.INTEGER40, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91') + + def test_integer48(self): + self.data = [ + (TX, b'\x40\x13\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x13\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x03\xb2\x01\x20\x02\x91\x12\x03'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.INTEGER48, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12') + + def test_integer56(self): + self.data = [ + (TX, b'\x40\x14\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x14\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x01\xb2\x01\x20\x02\x91\x12\x03'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.INTEGER56, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12\x03') + + def test_integer64(self): + self.data = [ + (TX, b'\x40\x15\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x15\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\xb2\x01\x20\x02\x91\x12\x03'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x1d\x19\x21\x70\xfe\xfd\xfc\xfb'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.INTEGER64, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12\x03\x19') + + def test_real32(self): + self.data = [ + (TX, b'\x40\x08\x20\x00\x00\x00\x00\x00'), + (RX, b'\x43\x08\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2000 + dt.REAL32, 0) + self.assertEqual(data, b'\xfe\xfd\xfc\xfb') + + def test_real64(self): + self.data = [ + (TX, b'\x40\x11\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x11\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\xb2\x01\x20\x02\x91\x12\x03'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x1d\x19\x21\x70\xfe\xfd\xfc\xfb'), + ] + data = self.network[2].sdo.upload(0x2000 + dt.REAL64, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12\x03\x19') + + def test_visible_string(self): + self.data = [ + (TX, b'\x40\x09\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x09\x20\x00\x1A\x00\x00\x00'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\x54\x69\x6E\x79\x20\x4E\x6F'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x10\x64\x65\x20\x2D\x20\x4D\x65'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\x67\x61\x20\x44\x6F\x6D\x61'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x15\x69\x6E\x73\x20\x21\x00\x00') + ] + data = self.network[2].sdo.upload(0x2000 + dt.VISIBLE_STRING, 0) + self.assertEqual(data, b'Tiny Node - Mega Domains !') + + def test_unicode_string(self): + self.data = [ + (TX, b'\x40\x0b\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x0b\x20\x00\x1A\x00\x00\x00'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\x54\x69\x6E\x79\x20\x4E\x6F'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x10\x64\x65\x20\x2D\x20\x4D\x65'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\x67\x61\x20\x44\x6F\x6D\x61'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x15\x69\x6E\x73\x20\x21\x00\x00') + ] + data = self.network[2].sdo.upload(0x2000 + dt.UNICODE_STRING, 0) + self.assertEqual(data, b'Tiny Node - Mega Domains !') + + def test_octet_string(self): + self.data = [ + (TX, b'\x40\x0a\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x0a\x20\x00\x1A\x00\x00\x00'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\x54\x69\x6E\x79\x20\x4E\x6F'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x10\x64\x65\x20\x2D\x20\x4D\x65'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\x67\x61\x20\x44\x6F\x6D\x61'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x15\x69\x6E\x73\x20\x21\x00\x00') + ] + data = self.network[2].sdo.upload(0x2000 + dt.OCTET_STRING, 0) + self.assertEqual(data, b'Tiny Node - Mega Domains !') + + def test_domain(self): + self.data = [ + (TX, b'\x40\x0f\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\x0f\x20\x00\x1A\x00\x00\x00'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\x54\x69\x6E\x79\x20\x4E\x6F'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x10\x64\x65\x20\x2D\x20\x4D\x65'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\x67\x61\x20\x44\x6F\x6D\x61'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x15\x69\x6E\x73\x20\x21\x00\x00') + ] + data = self.network[2].sdo.upload(0x2000 + dt.DOMAIN, 0) + self.assertEqual(data, b'Tiny Node - Mega Domains !') + + def test_unknown_od_32(self): + """Test an unknown OD entry of 32 bits (4 bytes).""" + self.data = [ + (TX, b'\x40\xFF\x20\x00\x00\x00\x00\x00'), + (RX, b'\x43\xFF\x20\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x20FF, 0) + self.assertEqual(data, b'\xfe\xfd\xfc\xfb') + + def test_unknown_od_112(self): + """Test an unknown OD entry of 112 bits (14 bytes).""" + self.data = [ + (TX, b'\x40\xFF\x20\x00\x00\x00\x00\x00'), + (RX, b'\x41\xFF\x20\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\xb2\x01\x20\x02\x91\x12\x03'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x11\x19\x21\x70\xfe\xfd\xfc\xfb'), + ] + data = self.network[2].sdo.upload(0x20FF, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12\x03\x19\x21\x70\xfe\xfd\xfc\xfb') + + def test_unknown_datatype32(self): + """Test an unknown datatype, but known OD, of 32 bits (4 bytes).""" + return # FIXME: Disabled temporarily until datatype conditionals are fixed, see #436 + # Add fake entry 0x2100 to OD, using fake datatype 0xFF + if 0x2100 not in self.node.object_dictionary: + fake_var = ODVariable("Fake", 0x2100) + fake_var.data_type = 0xFF + self.node.object_dictionary.add_object(fake_var) + self.data = [ + (TX, b'\x40\x00\x21\x00\x00\x00\x00\x00'), + (RX, b'\x43\x00\x21\x00\xfe\xfd\xfc\xfb') + ] + data = self.network[2].sdo.upload(0x2100, 0) + self.assertEqual(data, b'\xfe\xfd\xfc\xfb') + + def test_unknown_datatype112(self): + """Test an unknown datatype, but known OD, of 112 bits (14 bytes).""" + return # FIXME: Disabled temporarily until datatype conditionals are fixed, see #436 + # Add fake entry 0x2100 to OD, using fake datatype 0xFF + if 0x2100 not in self.node.object_dictionary: + fake_var = ODVariable("Fake", 0x2100) + fake_var.data_type = 0xFF + self.node.object_dictionary.add_object(fake_var) + self.data = [ + (TX, b'\x40\x00\x21\x00\x00\x00\x00\x00'), + (RX, b'\x41\x00\x21\x00\xfe\xfd\xfc\xfb'), + (TX, b'\x60\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x00\xb2\x01\x20\x02\x91\x12\x03'), + (TX, b'\x70\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x11\x19\x21\x70\xfe\xfd\xfc\xfb'), + ] + data = self.network[2].sdo.upload(0x2100, 0) + self.assertEqual(data, b'\xb2\x01\x20\x02\x91\x12\x03\x19\x21\x70\xfe\xfd\xfc\xfb') + if __name__ == "__main__": unittest.main() From b93f951cc3df2107adbea32ee9af8e39d79683b9 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Wed, 12 Jun 2024 09:08:29 +0200 Subject: [PATCH 135/199] Add codecov support (fixes #366) (#367) * Integrate codecov into pythonpackage.yml --- .github/workflows/pythonpackage.yml | 8 ++++++-- codecov.yml | 7 +++++++ 2 files changed, 13 insertions(+), 2 deletions(-) create mode 100644 codecov.yml diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index fd81104e..8fbd0aca 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -27,8 +27,12 @@ jobs: - name: Install dependencies run: | python -m pip install --upgrade pip - pip install pytest + pip install pytest pytest-cov pip install -e . - name: Test with pytest run: | - pytest -v + pytest -v --cov=canopen --cov-report=xml --cov-branch + - name: Upload coverage reports to Codecov + uses: codecov/codecov-action@v4 + with: + token: ${{ secrets.CODECOV_TOKEN }} diff --git a/codecov.yml b/codecov.yml new file mode 100644 index 00000000..1c4754de --- /dev/null +++ b/codecov.yml @@ -0,0 +1,7 @@ +ignore: + - "*/test/*" + +comment: + require_changes: true + layout: "reach, diff, flags, files" + behavior: default From 6de7f1f963e7496afaa0e3ff19cdee0f9979fa2d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 13 Jun 2024 22:20:02 +0200 Subject: [PATCH 136/199] Require Python version 3.8, because of setuptools dependency. --- pyproject.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pyproject.toml b/pyproject.toml index bffee508..f2ed1b6a 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -11,7 +11,7 @@ authors = [ ] description = "CANopen stack implementation" readme = "README.rst" -requires-python = ">=3.6" +requires-python = ">=3.8" license = {file = "LICENSE.txt"} classifiers = [ "Development Status :: 5 - Production/Stable", From 11b540adc6b3848d4bd8a2bb7278a35568b8216d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 13 Jun 2024 22:37:26 +0200 Subject: [PATCH 137/199] Fixup another Python 3.6 reference. --- README.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.rst b/README.rst index bdf66701..3c469e84 100644 --- a/README.rst +++ b/README.rst @@ -6,7 +6,7 @@ The aim of the project is to support the most common parts of the CiA 301 standard in a simple Pythonic interface. It is mainly targeted for testing and automation tasks rather than a standard compliant master implementation. -The library supports Python 3.6+. +The library supports Python 3.8+. Features From 3600880f1b45d90a2cef4851fe301df8b5538f79 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Frieder=20Sch=C3=BCler?= Date: Mon, 17 Jun 2024 11:52:15 +0200 Subject: [PATCH 138/199] Add all public API parts to __all__ (#462) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Frieder Schüler --- canopen/__init__.py | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/canopen/__init__.py b/canopen/__init__.py index ee5ff7b5..9bd19b1d 100644 --- a/canopen/__init__.py +++ b/canopen/__init__.py @@ -9,6 +9,19 @@ # package is not installed __version__ = "unknown" -Node = RemoteNode - +__all__ = [ + "Network", + "NodeScanner", + "RemoteNode", + "LocalNode", + "SdoCommunicationError", + "SdoAbortedError", + "import_od", + "export_od", + "ObjectDictionary", + "ObjectDictionaryError", + "BaseNode402", +] __pypi_url__ = "https://pypi.org/project/canopen/" + +Node = RemoteNode From 8f89d4286c1ade657508b1880c56da69a6b40928 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 18 Jun 2024 10:02:25 +0200 Subject: [PATCH 139/199] doc: Clean up and modernize Sphinx configuration (fixes #463) (#465) * Switch from setuptools' pkg_resources to importlib.metadata. The remaining changes are based on a fresh invocation of sphinx-quickstart (version 7.2.6), trying to format our existing modifications in the same style. * Update string literals to assume UTF-8 default. * Remove commented Sphinx configuration options. * Remove Sphinx options which are at their default. * Reorder, project settings first. * Remove explanatory comments on configuration options. * Include section headers as generated via sphinx-quickstart. * Remove default HTML theme option. * Reorder (sort) extensions. * Fix undefined default language. * Rename modernized Sphinx options. * Clean up section headings and move autodoc option down. * Import Makefile generated by sphinx-quickstart. --- doc/Makefile | 20 +++ doc/conf.py | 341 ++++++--------------------------------------------- 2 files changed, 60 insertions(+), 301 deletions(-) create mode 100644 doc/Makefile diff --git a/doc/Makefile b/doc/Makefile new file mode 100644 index 00000000..d4bb2cbb --- /dev/null +++ b/doc/Makefile @@ -0,0 +1,20 @@ +# Minimal makefile for Sphinx documentation +# + +# You can set these variables from the command line, and also +# from the environment for the first two. +SPHINXOPTS ?= +SPHINXBUILD ?= sphinx-build +SOURCEDIR = . +BUILDDIR = _build + +# Put it first so that "make" without argument is like "make help". +help: + @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) + +.PHONY: help Makefile + +# Catch-all target: route all unknown targets to Sphinx using the new +# "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). +%: Makefile + @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) diff --git a/doc/conf.py b/doc/conf.py index 3f865400..d7a6e6b1 100644 --- a/doc/conf.py +++ b/doc/conf.py @@ -1,349 +1,88 @@ -# -*- coding: utf-8 -*- +# Configuration file for the Sphinx documentation builder. # -# canopen documentation build configuration file, created by -# sphinx-quickstart on Mon Sep 19 22:15:46 2016. -# -# This file is execfile()d with the current directory set to its -# containing dir. -# -# Note that not all possible configuration values are present in this -# autogenerated file. -# -# All configuration values have a default; values that are commented out -# serve to show the default. +# For the full list of built-in configuration values, see the documentation: +# https://www.sphinx-doc.org/en/master/usage/configuration.html # If extensions (or modules to document with autodoc) are in another directory, # add these directories to sys.path here. If the directory is relative to the # documentation root, use os.path.abspath to make it absolute, like shown here. -# import os import sys -from pkg_resources import get_distribution +from importlib import metadata + sys.path.insert(0, os.path.abspath('..')) -# -- General configuration ------------------------------------------------ -# If your documentation needs a minimal Sphinx version, state it here. -# -# needs_sphinx = '1.0' +# -- Project information ----------------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/configuration.html#project-information + +project = 'canopen' +project_copyright = '2016, Christian Sandberg' +author = 'Christian Sandberg' +# The full version, including alpha/beta/rc tags. +release = metadata.version('canopen') +# The short X.Y version. +version = '.'.join(release.split('.')[:2]) + +# -- General configuration --------------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/configuration.html#general-configuration -# Add any Sphinx extension module names here, as strings. They can be -# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom -# ones. extensions = [ 'sphinx.ext.autodoc', 'sphinx.ext.intersphinx', - 'sphinx_autodoc_typehints', 'sphinx.ext.viewcode', + 'sphinx_autodoc_typehints', ] -# Add any paths that contain templates here, relative to this directory. templates_path = ['_templates'] - -# The suffix(es) of source filenames. -# You can specify multiple suffix as a list of string: -# -# source_suffix = ['.rst', '.md'] -source_suffix = '.rst' - -# The encoding of source files. -# -# source_encoding = 'utf-8-sig' - -# The master toctree document. -master_doc = 'index' - -# General information about the project. -project = u'canopen' -copyright = u'2016, Christian Sandberg' -author = u'Christian Sandberg' - -# The version info for the project you're documenting, acts as replacement for -# |version| and |release|, also used in various other places throughout the -# built documents. -# -# The full version, including alpha/beta/rc tags. -release = get_distribution('canopen').version -# The short X.Y version. -version = '.'.join(release.split('.')[:2]) - -# The language for content autogenerated by Sphinx. Refer to documentation -# for a list of supported languages. -# -# This is also used if you do content translation via gettext catalogs. -# Usually you set "language" from the command line for these cases. -language = None - -# There are two options for replacing |today|: either, you set today to some -# non-false value, then it is used: -# -# today = '' -# -# Else, today_fmt is used as the format for a strftime call. -# -# today_fmt = '%B %d, %Y' - -# List of patterns, relative to source directory, that match files and -# directories to ignore when looking for source files. -# This patterns also effect to html_static_path and html_extra_path +root_doc = 'index' exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store'] -# The reST default role (used for this markup: `text`) to use for all -# documents. -# -# default_role = None - -# If true, '()' will be appended to :func: etc. cross-reference text. -# -# add_function_parentheses = True - -# If true, the current module name will be prepended to all description -# unit titles (such as .. function::). -# -# add_module_names = True - -# If true, sectionauthor and moduleauthor directives will be shown in the -# output. They are ignored by default. -# -# show_authors = False - -# The name of the Pygments (syntax highlighting) style to use. -pygments_style = 'sphinx' - -# Include documentation from both the class level and __init__ -autoclass_content = "both" - -# A list of ignored prefixes for module index sorting. -# modindex_common_prefix = [] - -# If true, keep warnings as "system message" paragraphs in the built documents. -# keep_warnings = False +language = 'en' -# If true, `todo` and `todoList` produce output, else they produce nothing. -todo_include_todos = False - -# -- Options for HTML output ---------------------------------------------- - -# The theme to use for HTML and HTML Help pages. See the documentation for -# a list of builtin themes. -# -html_theme = 'default' - -# Theme options are theme-specific and customize the look and feel of a theme -# further. For a list of options available for each theme, see the -# documentation. -# -# html_theme_options = {} - -# Add any paths that contain custom themes here, relative to this directory. -# html_theme_path = [] - -# The name for this set of Sphinx documents. -# " v documentation" by default. -# -# html_title = u'canopen v0.3.0' - -# A shorter title for the navigation bar. Default is the same as html_title. -# -# html_short_title = None - -# The name of an image file (relative to this directory) to place at the top -# of the sidebar. -# -# html_logo = None - -# The name of an image file (relative to this directory) to use as a favicon of -# the docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 -# pixels large. -# -# html_favicon = None +# -- Options for HTML output ------------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-output -# Add any paths that contain custom static files (such as style sheets) here, -# relative to this directory. They are copied after the builtin static files, -# so a file named "default.css" will overwrite the builtin "default.css". html_static_path = ['_static'] -# Add any extra paths that contain custom files (such as robots.txt or -# .htaccess) here, relative to this directory. These files are copied -# directly to the root of the documentation. -# -# html_extra_path = [] - -# If not None, a 'Last updated on:' timestamp is inserted at every page -# bottom, using the given strftime format. -# The empty string is equivalent to '%b %d, %Y'. -# -# html_last_updated_fmt = None - -# If true, SmartyPants will be used to convert quotes and dashes to -# typographically correct entities. -# -# html_use_smartypants = True - -# Custom sidebar templates, maps document names to template names. -# -# html_sidebars = {} - -# Additional templates that should be rendered to pages, maps page names to -# template names. -# -# html_additional_pages = {} - -# If false, no module index is generated. -# -# html_domain_indices = True - -# If false, no index is generated. -# -# html_use_index = True - -# If true, the index is split into individual pages for each letter. -# -# html_split_index = False - -# If true, links to the reST sources are added to the pages. -# -# html_show_sourcelink = True - -# If true, "Created using Sphinx" is shown in the HTML footer. Default is True. -# -# html_show_sphinx = True - -# If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. -# -# html_show_copyright = True - -# If true, an OpenSearch description file will be output, and all pages will -# contain a tag referring to it. The value of this option must be the -# base URL from which the finished HTML is served. -# -# html_use_opensearch = '' - -# This is the file name suffix for HTML files (e.g. ".xhtml"). -# html_file_suffix = None - -# Language to be used for generating the HTML full-text search index. -# Sphinx supports the following languages: -# 'da', 'de', 'en', 'es', 'fi', 'fr', 'hu', 'it', 'ja' -# 'nl', 'no', 'pt', 'ro', 'ru', 'sv', 'tr', 'zh' -# -# html_search_language = 'en' - -# A dictionary with options for the search language support, empty by default. -# 'ja' uses this config value. -# 'zh' user can custom change `jieba` dictionary path. -# -# html_search_options = {'type': 'default'} +# -- Options for HTML help output -------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-help-output -# The name of a javascript file (relative to the configuration directory) that -# implements a search results scorer. If empty, the default will be used. -# -# html_search_scorer = 'scorer.js' - -# Output file base name for HTML help builder. htmlhelp_basename = 'canopendoc' -# -- Options for LaTeX output --------------------------------------------- - -latex_elements = { - # The paper size ('letterpaper' or 'a4paper'). - # - # 'papersize': 'letterpaper', - - # The font size ('10pt', '11pt' or '12pt'). - # - # 'pointsize': '10pt', - - # Additional stuff for the LaTeX preamble. - # - # 'preamble': '', - - # Latex figure (float) alignment - # - # 'figure_align': 'htbp', -} +# -- Options for LaTeX output ------------------------------------------------ +# https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-latex-output -# Grouping the document tree into LaTeX files. List of tuples -# (source start file, target name, title, -# author, documentclass [howto, manual, or own class]). latex_documents = [ - (master_doc, 'canopen.tex', u'canopen Documentation', - u'Christian Sandberg', 'manual'), + (root_doc, 'canopen.tex', 'canopen Documentation', + 'Christian Sandberg', 'manual'), ] -# The name of an image file (relative to this directory) to place at the top of -# the title page. -# -# latex_logo = None - -# For "manual" documents, if this is true, then toplevel headings are parts, -# not chapters. -# -# latex_use_parts = False - -# If true, show page references after internal links. -# -# latex_show_pagerefs = False - -# If true, show URL addresses after external links. -# -# latex_show_urls = False - -# Documents to append as an appendix to all manuals. -# -# latex_appendices = [] - -# It false, will not define \strong, \code, itleref, \crossref ... but only -# \sphinxstrong, ..., \sphinxtitleref, ... To help avoid clash with user added -# packages. -# -# latex_keep_old_macro_names = True - -# If false, no module index is generated. -# -# latex_domain_indices = True - -# -- Options for manual page output --------------------------------------- +# -- Options for manual page output ------------------------------------------ +# https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-manual-page-output -# One entry per manual page. List of tuples -# (source start file, name, description, authors, manual section). man_pages = [ - (master_doc, 'canopen', u'canopen Documentation', + (root_doc, 'canopen', 'canopen Documentation', [author], 1) ] -# If true, show URL addresses after external links. -# -# man_show_urls = False - -# -- Options for Texinfo output ------------------------------------------- +# -- Options for Texinfo output ---------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-texinfo-output -# Grouping the document tree into Texinfo files. List of tuples -# (source start file, target name, title, author, -# dir menu entry, description, category) texinfo_documents = [ - (master_doc, 'canopen', u'canopen Documentation', + (root_doc, 'canopen', 'canopen Documentation', author, 'canopen', 'One line description of project.', 'Miscellaneous'), ] -# Documents to append as an appendix to all manuals. -# -# texinfo_appendices = [] +# -- Options for autodoc extension ------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/extensions/autodoc.html#configuration -# If false, no module index is generated. -# -# texinfo_domain_indices = True +autoclass_content = 'both' -# How to display URL addresses: 'footnote', 'no', or 'inline'. -# -# texinfo_show_urls = 'footnote' - -# If true, do not generate a @detailmenu in the "Top" node's menu. -# -# texinfo_no_detailmenu = False +# -- Options for intersphinx extension --------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/extensions/intersphinx.html#configuration -# Example configuration for intersphinx: refer to the Python standard library. intersphinx_mapping = { 'python': ('https://docs.python.org/3/', None), 'can': ('https://python-can.readthedocs.io/en/stable/', None), From 509aaeab493a3ae9e1c668fc02caaaac4f73ea94 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 18 Jun 2024 10:10:05 +0200 Subject: [PATCH 140/199] Switch back to "classic" Sphinx theme. --- doc/conf.py | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/conf.py b/doc/conf.py index d7a6e6b1..c4f52eb1 100644 --- a/doc/conf.py +++ b/doc/conf.py @@ -43,6 +43,7 @@ # -- Options for HTML output ------------------------------------------------- # https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-output +html_theme = 'classic' html_static_path = ['_static'] # -- Options for HTML help output -------------------------------------------- From 11ba262335904f5ba3d51e0f9457781afc4f3018 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 18 Jun 2024 10:20:48 +0200 Subject: [PATCH 141/199] Switch to more modern "furo" Sphinx theme. --- doc/conf.py | 2 +- doc/requirements.txt | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/doc/conf.py b/doc/conf.py index c4f52eb1..ecd59f31 100644 --- a/doc/conf.py +++ b/doc/conf.py @@ -43,7 +43,7 @@ # -- Options for HTML output ------------------------------------------------- # https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-output -html_theme = 'classic' +html_theme = 'furo' html_static_path = ['_static'] # -- Options for HTML help output -------------------------------------------- diff --git a/doc/requirements.txt b/doc/requirements.txt index 2ca4275e..f4bba38a 100644 --- a/doc/requirements.txt +++ b/doc/requirements.txt @@ -1,2 +1,3 @@ sphinx sphinx-autodoc-typehints +furo From e40d8627de2b5740a3201a040085064015644e72 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 18 Jun 2024 20:42:01 +0200 Subject: [PATCH 142/199] Test explicit import of Struct-derived classes. --- canopen/objectdictionary/__init__.py | 1 + 1 file changed, 1 insertion(+) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 156972fd..f90c09f3 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -9,6 +9,7 @@ import logging from canopen.objectdictionary.datatypes import * +from canopen.objectdictionary.datatypes import IntegerN, UnsignedN from canopen.utils import pretty_index logger = logging.getLogger(__name__) From 1fc63b5f4835eba80462c7892a2cd00f786ec9ce Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Mon, 24 Jun 2024 23:52:19 +0200 Subject: [PATCH 143/199] build: Explicitly specify packages to install (fixes #467) (#468) Hint setuptools to only the canopen package. --- pyproject.toml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/pyproject.toml b/pyproject.toml index f2ed1b6a..67a435d8 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -30,6 +30,9 @@ dynamic = ["version"] documentation = "https://canopen.readthedocs.io/en/stable/" repository = "https://github.com/christiansandberg/canopen" +[tool.setuptools] +packages = ["canopen"] + [tool.setuptools_scm] version_file = "canopen/_version.py" From 5db59130423948e1e8034a67983ca00afd0269d8 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Sun, 30 Jun 2024 18:47:45 +0200 Subject: [PATCH 144/199] Ensure proper close after open in export_od (#469) Co-authored-by: Erlend E. Aasland --- canopen/objectdictionary/__init__.py | 49 ++++----- test/test_eds.py | 142 +++++++++++++++------------ 2 files changed, 107 insertions(+), 84 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index f90c09f3..d9a2a2f7 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -29,29 +29,32 @@ def export_od(od, dest: Union[str, TextIO, None] = None, doc_type: Optional[str] :rtype: str or None """ - doctypes = {"eds", "dcf"} - if isinstance(dest, str): - if doc_type is None: - for t in doctypes: - if dest.endswith(f".{t}"): - doc_type = t - break - - if doc_type is None: - doc_type = "eds" - dest = open(dest, 'w') - assert doc_type in doctypes - - if doc_type == "eds": - from canopen.objectdictionary import eds - return eds.export_eds(od, dest) - elif doc_type == "dcf": - from canopen.objectdictionary import eds - return eds.export_dcf(od, dest) - - # If dest is opened in this fn, it should be closed - if type(dest) is str: - dest.close() + opened_here = False + try: + doctypes = {"eds", "dcf"} + if isinstance(dest, str): + if doc_type is None: + for t in doctypes: + if dest.endswith(f".{t}"): + doc_type = t + break + else: + doc_type = "eds" + dest = open(dest, 'w') + opened_here = True + + if doc_type == "eds": + from canopen.objectdictionary import eds + return eds.export_eds(od, dest) + elif doc_type == "dcf": + from canopen.objectdictionary import eds + return eds.export_dcf(od, dest) + else: + raise NotImplementedError(f"No support for the {doc_type!r} format") + finally: + # If dest is opened in this fn, it should be closed + if opened_here: + dest.close() def import_od( diff --git a/test/test_eds.py b/test/test_eds.py index 88654a0f..e023b3b0 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -184,68 +184,88 @@ def test_export_eds(self): from pathlib import Path with tempfile.TemporaryDirectory() as tempdir: for doctype in {"eds", "dcf"}: + + # Test export_od with file object tempfile = str(Path(tempdir, "test." + doctype)) with open(tempfile, "w+") as tempeds: print(f"exporting {doctype} to {tempeds.name}") canopen.export_od(self.od, tempeds, doc_type=doctype) - - exported_od = canopen.import_od(tempfile) - - for index in exported_od: - self.assertIn(exported_od[index].name, self.od) - self.assertIn(index, self.od) - - for index in self.od: - if index < 0x0008: - # ignore dummies - continue - self.assertIn(self.od[index].name, exported_od) - self.assertIn(index, exported_od) - - actual_object = exported_od[index] - expected_object = self.od[index] - self.assertEqual(type(actual_object), type(expected_object)) - self.assertEqual(actual_object.name, expected_object.name) - - if isinstance(actual_object, canopen.objectdictionary.ODVariable): - expected_vars = [expected_object] - actual_vars = [actual_object] - else: - expected_vars = [expected_object[idx] for idx in expected_object] - actual_vars = [actual_object[idx] for idx in actual_object] - - for prop in [ - "allowed_baudrates", - "vendor_name", - "vendor_number", - "product_name", - "product_number", - "revision_number", - "order_code", - "simple_boot_up_master", - "simple_boot_up_slave", - "granularity", - "dynamic_channels_supported", - "group_messaging", - "nr_of_RXPDO", - "nr_of_TXPDO", - "LSS_supported", - ]: - self.assertEqual(getattr(self.od.device_information, prop), - getattr(exported_od.device_information, prop), - f"prop {prop!r} mismatch on DeviceInfo") - - for evar, avar in zip(expected_vars, actual_vars): - self.assertEqual(getattr(avar, "data_type", None), getattr(evar, "data_type", None), - f" mismatch on {pretty_index(evar.index, evar.subindex)}") - self.assertEqual(getattr(avar, "default_raw", None), getattr(evar, "default_raw", None), - f" mismatch on {pretty_index(evar.index, evar.subindex)}") - self.assertEqual(getattr(avar, "min", None), getattr(evar, "min", None), - f" mismatch on {pretty_index(evar.index, evar.subindex)}") - self.assertEqual(getattr(avar, "max", None), getattr(evar, "max", None), - f" mismatch on {pretty_index(evar.index, evar.subindex)}") - if doctype == "dcf": - self.assertEqual(getattr(avar, "value", None), getattr(evar, "value", None), - f" mismatch on {pretty_index(evar.index, evar.subindex)}") - - self.assertEqual(self.od.comments, exported_od.comments) + self.verify_od(tempfile, doctype) + + # Test export_od handling opening and closing the file + tempfile = str(Path(tempdir, "test2." + doctype)) + canopen.export_od(self.od, tempfile, doc_type=doctype) + self.verify_od(tempfile, doctype) + + # Test for unknown doctype + with self.assertRaises(NotImplementedError): + tempfile = str(Path(tempdir, "test.unknown")) + canopen.export_od(self.od, tempfile, doc_type="unknown") + + # Omit doctype + tempfile = str(Path(tempdir, "test.eds")) + canopen.export_od(self.od, tempfile) + self.verify_od(tempfile, "eds") + + + def verify_od(self, tempfile, doctype): + exported_od = canopen.import_od(tempfile) + + for index in exported_od: + self.assertIn(exported_od[index].name, self.od) + self.assertIn(index, self.od) + + for index in self.od: + if index < 0x0008: + # ignore dummies + continue + self.assertIn(self.od[index].name, exported_od) + self.assertIn(index, exported_od) + + actual_object = exported_od[index] + expected_object = self.od[index] + self.assertEqual(type(actual_object), type(expected_object)) + self.assertEqual(actual_object.name, expected_object.name) + + if isinstance(actual_object, canopen.objectdictionary.ODVariable): + expected_vars = [expected_object] + actual_vars = [actual_object] + else: + expected_vars = [expected_object[idx] for idx in expected_object] + actual_vars = [actual_object[idx] for idx in actual_object] + + for prop in [ + "allowed_baudrates", + "vendor_name", + "vendor_number", + "product_name", + "product_number", + "revision_number", + "order_code", + "simple_boot_up_master", + "simple_boot_up_slave", + "granularity", + "dynamic_channels_supported", + "group_messaging", + "nr_of_RXPDO", + "nr_of_TXPDO", + "LSS_supported", + ]: + self.assertEqual(getattr(self.od.device_information, prop), + getattr(exported_od.device_information, prop), + f"prop {prop!r} mismatch on DeviceInfo") + + for evar, avar in zip(expected_vars, actual_vars): + self.assertEqual(getattr(avar, "data_type", None), getattr(evar, "data_type", None), + f" mismatch on {pretty_index(evar.index, evar.subindex)}") + self.assertEqual(getattr(avar, "default_raw", None), getattr(evar, "default_raw", None), + f" mismatch on {pretty_index(evar.index, evar.subindex)}") + self.assertEqual(getattr(avar, "min", None), getattr(evar, "min", None), + f" mismatch on {pretty_index(evar.index, evar.subindex)}") + self.assertEqual(getattr(avar, "max", None), getattr(evar, "max", None), + f" mismatch on {pretty_index(evar.index, evar.subindex)}") + if doctype == "dcf": + self.assertEqual(getattr(avar, "value", None), getattr(evar, "value", None), + f" mismatch on {pretty_index(evar.index, evar.subindex)}") + + self.assertEqual(self.od.comments, exported_od.comments) From 5734f37ee758e1d025701b4d40e0b89a57db2317 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 2 Jul 2024 12:04:26 +0200 Subject: [PATCH 145/199] Export PdoMap and PdoVariable classes in pdo module (#464) * Reintroduce PdoMap and PdoVariable to public API of sub-package pdo. With commit 0285f582beb344de708ce8308274a99bc04988a1, the Map class was inadvertently removed from the imports directly available within the canopen.pdo package. However, it is referenced as canopen.pdo.PdoMap in the p402 module and documentation. Restore that import using the new names PdoMap and PdoVariable. Move the compatibility define to the very bottom, just like in other modules. Provide an __all__ listing to clarify what constitutes the public API. * Use type hints for PdoMap in BaseNode402. Replace the sphinx parameter type documentation with a proper type hint annotation. Same for the tpdo_pointers and rpdo_pointers attributes. --- canopen/pdo/__init__.py | 18 +++++++++++++++--- canopen/profiles/p402.py | 9 +++++---- 2 files changed, 20 insertions(+), 7 deletions(-) diff --git a/canopen/pdo/__init__.py b/canopen/pdo/__init__.py index 1c951cf5..533309f8 100644 --- a/canopen/pdo/__init__.py +++ b/canopen/pdo/__init__.py @@ -1,10 +1,18 @@ import logging from canopen import node -from canopen.pdo.base import PdoBase, PdoMaps +from canopen.pdo.base import PdoBase, PdoMap, PdoMaps, PdoVariable -# Compatibility -from canopen.pdo.base import Variable + +__all__ = [ + "PdoBase", + "PdoMap", + "PdoMaps", + "PdoVariable", + "PDO", + "RPDO", + "TPDO", +] logger = logging.getLogger(__name__) @@ -77,3 +85,7 @@ def stop(self): pdo.stop() else: raise TypeError('The node type does not support this function.') + + +# Compatibility +Variable = PdoVariable diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index c94e5356..10156d01 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -1,8 +1,10 @@ # inspired by the NmtMaster code import logging import time +from typing import Dict from canopen.node import RemoteNode +from canopen.pdo import PdoMap from canopen.sdo import SdoCommunicationError logger = logging.getLogger(__name__) @@ -212,8 +214,8 @@ class BaseNode402(RemoteNode): def __init__(self, node_id, object_dictionary): super(BaseNode402, self).__init__(node_id, object_dictionary) self.tpdo_values = {} # { index: value from last received TPDO } - self.tpdo_pointers = {} # { index: pdo.PdoMap instance } - self.rpdo_pointers = {} # { index: pdo.PdoMap instance } + self.tpdo_pointers: Dict[int, PdoMap] = {} + self.rpdo_pointers: Dict[int, PdoMap] = {} def setup_402_state_machine(self, read_pdos=True): """Configure the state machine by searching for a TPDO that has the StatusWord mapped. @@ -453,11 +455,10 @@ def is_op_mode_supported(self, mode): bits = OperationMode.SUPPORTED[mode] return self._op_mode_support & bits == bits - def on_TPDOs_update_callback(self, mapobject): + def on_TPDOs_update_callback(self, mapobject: PdoMap): """Cache updated values from a TPDO received from this node. :param mapobject: The received PDO message. - :type mapobject: canopen.pdo.PdoMap """ for obj in mapobject: self.tpdo_values[obj.index] = obj.raw From 503918c9bd9ff0499a604c7805e7627ca38fb332 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 2 Jul 2024 12:32:52 +0200 Subject: [PATCH 146/199] Raise ValueError for unknown formats in the import/export OD APIs (#476) Fixes #475 * Test the offending suffix is part of the error message * Make the exception message more helpful --- canopen/objectdictionary/__init__.py | 13 +++++++++++-- test/test_eds.py | 6 +++++- 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index d9a2a2f7..441ade99 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -50,7 +50,11 @@ def export_od(od, dest: Union[str, TextIO, None] = None, doc_type: Optional[str] from canopen.objectdictionary import eds return eds.export_dcf(od, dest) else: - raise NotImplementedError(f"No support for the {doc_type!r} format") + allowed = ", ".join(doctypes) + raise ValueError( + f"Cannot export to the {doc_type!r} format; " + f"supported formats: {allowed}" + ) finally: # If dest is opened in this fn, it should be closed if opened_here: @@ -88,7 +92,12 @@ def import_od( from canopen.objectdictionary import epf return epf.import_epf(source) else: - raise NotImplementedError("No support for this format") + doc_type = suffix[1:] + allowed = ", ".join(["eds", "dcf", "epf"]) + raise ValueError( + f"Cannot import from the {doc_type!r} format; " + f"supported formats: {allowed}" + ) class ObjectDictionary(MutableMapping): diff --git a/test/test_eds.py b/test/test_eds.py index e023b3b0..2275e485 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -54,6 +54,10 @@ def test_load_nonexisting_file(self): with self.assertRaises(IOError): canopen.import_od('/path/to/wrong_file.eds') + def test_load_unsupported_format(self): + with self.assertRaisesRegex(ValueError, "'py'"): + canopen.import_od(__file__) + def test_load_file_object(self): with open(EDS_PATH) as fp: od = canopen.import_od(fp) @@ -198,7 +202,7 @@ def test_export_eds(self): self.verify_od(tempfile, doctype) # Test for unknown doctype - with self.assertRaises(NotImplementedError): + with self.assertRaisesRegex(ValueError, "'unknown'"): tempfile = str(Path(tempdir, "test.unknown")) canopen.export_od(self.od, tempfile, doc_type="unknown") From d141e13970ce5bb5e696a97b92131356d34092bc Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 2 Jul 2024 13:19:58 +0200 Subject: [PATCH 147/199] Improve the RemoteNode.load_configuration() docs (#477) Spell out how it works and link to PdoBase.read() Moreover, add return annotation to make sure that's included in the rendered docs. --- canopen/node/remote.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/canopen/node/remote.py b/canopen/node/remote.py index 37eb2ab2..f3054391 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -141,8 +141,16 @@ def __load_configuration_helper(self, index, subindex, name, value): index, subindex, e) raise - def load_configuration(self): - ''' Load the configuration of the node from the object dictionary.''' + def load_configuration(self) -> None: + """Load the configuration of the node from the Object Dictionary. + + Iterate through all objects in the Object Dictionary and download the + values to the remote node via SDO. + Then, to avoid PDO mapping conflicts, read back (upload) the PDO + configuration via SDO. + + :see-also: :meth:`canopen.pdo.PdoBase.read` + """ for obj in self.object_dictionary.values(): if isinstance(obj, ODRecord) or isinstance(obj, ODArray): for subobj in obj.values(): From 028a57f49510803eeef4965b95f3aa76ce18e648 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 2 Jul 2024 13:21:46 +0200 Subject: [PATCH 148/199] Expose and improve the docstrings of `export_od` and `import_id` (#473) Resolves #472 * Expose and improve the docstrings of export_od and import_id * export_od(od, None, doctype) does not return a string; it writes to stdout * Clarify 'doc_type' details * Add exception info --- canopen/objectdictionary/__init__.py | 39 ++++++++++++++++++---------- doc/od.rst | 4 +++ 2 files changed, 30 insertions(+), 13 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 441ade99..1a723616 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -15,18 +15,27 @@ logger = logging.getLogger(__name__) -def export_od(od, dest: Union[str, TextIO, None] = None, doc_type: Optional[str] = None): - """ Export :class: ObjectDictionary to a file. +def export_od( + od: ObjectDictionary, + dest: Union[str, TextIO, None] = None, + doc_type: Optional[str] = None +) -> None: + """Export an object dictionary. :param od: - :class: ObjectDictionary object to be exported + The object dictionary to be exported. :param dest: - export destination. filename, or file-like object or None. - if None, the document is returned as string - :param doc_type: type of document to export. - If a filename is given for dest, this default to the file extension. - Otherwise, this defaults to "eds" - :rtype: str or None + The export destination as a filename, a file-like object, or ``None``. + If ``None``, the document is written to :data:`sys.stdout`. + :param doc_type: + The type of document to export. + If *dest* is a file-like object or ``None``, + *doc_type* must be explicitly provided. + If *dest* is a filename and its extension is ``.eds`` or ``.dcf``, + *doc_type* defaults to that extension (the preceeding dot excluded); + else, it defaults to ``eds``. + :raises ValueError: + When exporting to an unknown format. """ opened_here = False @@ -68,10 +77,14 @@ def import_od( """Parse an EDS, DCF, or EPF file. :param source: - Path to object dictionary file or a file like object or an EPF XML tree. - - :return: - An Object Dictionary instance. + The path to object dictionary file, a file like object, or an EPF XML tree. + :param node_id: + For EDS and DCF files, the node ID to use. + For other formats, this parameter is ignored. + :raises ObjectDictionaryError: + For object dictionary errors and inconsistencies. + :raises ValueError: + When passed a file of an unknown format. """ if source is None: return ObjectDictionary() diff --git a/doc/od.rst b/doc/od.rst index 6040bb5e..4b88e5f6 100644 --- a/doc/od.rst +++ b/doc/od.rst @@ -54,6 +54,10 @@ You can access the objects using either index/subindex or names:: API --- +.. autofunction:: canopen.export_od + +.. autofunction:: canopen.import_od + .. autoclass:: canopen.ObjectDictionary :members: From e3af0eb31bdfde2203d56f1dd953dbd23b4b6609 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 2 Jul 2024 13:26:36 +0200 Subject: [PATCH 149/199] Increase export_eds() test coverage (#474) * Test export_eds() to stdout * Use StringIO as a context manager iso. addCleanup * Expand the test to cover most paths * Expand test for unknown doctypes * Use subTest for better debugging --- test/test_eds.py | 103 +++++++++++++++++++++++++++++++++-------------- 1 file changed, 73 insertions(+), 30 deletions(-) diff --git a/test/test_eds.py b/test/test_eds.py index 2275e485..693fac2c 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -183,37 +183,80 @@ def test_comments(self): |-------------| """.strip()) - def test_export_eds(self): + def test_export_eds_to_file(self): import tempfile - from pathlib import Path - with tempfile.TemporaryDirectory() as tempdir: - for doctype in {"eds", "dcf"}: - - # Test export_od with file object - tempfile = str(Path(tempdir, "test." + doctype)) - with open(tempfile, "w+") as tempeds: - print(f"exporting {doctype} to {tempeds.name}") - canopen.export_od(self.od, tempeds, doc_type=doctype) - self.verify_od(tempfile, doctype) - - # Test export_od handling opening and closing the file - tempfile = str(Path(tempdir, "test2." + doctype)) - canopen.export_od(self.od, tempfile, doc_type=doctype) - self.verify_od(tempfile, doctype) - - # Test for unknown doctype - with self.assertRaisesRegex(ValueError, "'unknown'"): - tempfile = str(Path(tempdir, "test.unknown")) - canopen.export_od(self.od, tempfile, doc_type="unknown") - - # Omit doctype - tempfile = str(Path(tempdir, "test.eds")) - canopen.export_od(self.od, tempfile) - self.verify_od(tempfile, "eds") - - - def verify_od(self, tempfile, doctype): - exported_od = canopen.import_od(tempfile) + for suffix in "eds", "dcf": + for implicit in True, False: + with tempfile.NamedTemporaryFile() as fn: + dest = f"{fn.name}.{suffix}" + doctype = None if implicit else suffix + with self.subTest(dest=dest, doctype=doctype): + canopen.export_od(self.od, dest, doctype) + self.verify_od(dest, doctype) + + def test_export_eds_to_file_unknown_extension(self): + import io + import tempfile + for suffix in ".txt", "": + with tempfile.NamedTemporaryFile() as fn: + dest = f"{fn.name}{suffix}" + with self.subTest(dest=dest, doctype=None): + canopen.export_od(self.od, dest) + + # The import_od() API has some shortcomings compared to the + # export_od() API, namely that it does not take a doctype + # parameter. This means it has to be able to deduce the + # doctype from its 'source' parameter. In this case, this + # is not possible, since we're using an unknown extension, + # so we have to do a couple of tricks in order to make this + # work. + with open(dest, "r") as source: + data = source.read() + with io.StringIO() as buf: + buf.write(data) + buf.seek(io.SEEK_SET) + buf.name = "mock.eds" + self.verify_od(buf, "eds") + + def test_export_eds_unknown_doctype(self): + import io + filelike_object = io.StringIO() + self.addCleanup(filelike_object.close) + for dest in "filename", None, filelike_object: + with self.subTest(dest=dest): + with self.assertRaisesRegex(ValueError, "'unknown'"): + canopen.export_od(self.od, dest, doc_type="unknown") + + def test_export_eds_to_filelike_object(self): + import io + for doctype in "eds", "dcf": + with io.StringIO() as dest: + with self.subTest(dest=dest, doctype=doctype): + canopen.export_od(self.od, dest, doctype) + + # The import_od() API assumes the file-like object has a + # well-behaved 'name' member. + dest.name = f"mock.{doctype}" + dest.seek(io.SEEK_SET) + self.verify_od(dest, doctype) + + def test_export_eds_to_stdout(self): + import contextlib + import io + with contextlib.redirect_stdout(io.StringIO()) as f: + ret = canopen.export_od(self.od, None, "eds") + self.assertIsNone(ret) + + dump = f.getvalue() + with io.StringIO(dump) as buf: + # The import_od() API assumes the TextIO object has a well-behaved + # 'name' member. + buf.name = "mock.eds" + self.verify_od(buf, "eds") + + + def verify_od(self, source, doctype): + exported_od = canopen.import_od(source) for index in exported_od: self.assertIn(exported_od[index].name, self.od) From 71da1bc38f56e602d95686adec22abd3ee0d3939 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 2 Jul 2024 13:54:49 +0200 Subject: [PATCH 150/199] Remove temporary files created in EDS tests Clean-up post #474 --- test/test_eds.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/test/test_eds.py b/test/test_eds.py index 693fac2c..23e18c10 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -185,11 +185,11 @@ def test_comments(self): def test_export_eds_to_file(self): import tempfile - for suffix in "eds", "dcf": + for suffix in ".eds", ".dcf": for implicit in True, False: - with tempfile.NamedTemporaryFile() as fn: - dest = f"{fn.name}.{suffix}" - doctype = None if implicit else suffix + with tempfile.NamedTemporaryFile(suffix=suffix) as tmp: + doctype = None if implicit else suffix[1:] + dest = tmp.name with self.subTest(dest=dest, doctype=doctype): canopen.export_od(self.od, dest, doctype) self.verify_od(dest, doctype) @@ -198,8 +198,8 @@ def test_export_eds_to_file_unknown_extension(self): import io import tempfile for suffix in ".txt", "": - with tempfile.NamedTemporaryFile() as fn: - dest = f"{fn.name}{suffix}" + with tempfile.NamedTemporaryFile(suffix=suffix) as tmp: + dest = tmp.name with self.subTest(dest=dest, doctype=None): canopen.export_od(self.od, dest) @@ -222,6 +222,7 @@ def test_export_eds_unknown_doctype(self): import io filelike_object = io.StringIO() self.addCleanup(filelike_object.close) + self.addCleanup(os.unlink, "filename") for dest in "filename", None, filelike_object: with self.subTest(dest=dest): with self.assertRaisesRegex(ValueError, "'unknown'"): From 65bfaab0fd4d826be125dc0045834b179e47fb22 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 2 Jul 2024 13:56:05 +0200 Subject: [PATCH 151/199] Reduce diff --- test/test_eds.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/test_eds.py b/test/test_eds.py index 23e18c10..4cbe9148 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -188,8 +188,8 @@ def test_export_eds_to_file(self): for suffix in ".eds", ".dcf": for implicit in True, False: with tempfile.NamedTemporaryFile(suffix=suffix) as tmp: - doctype = None if implicit else suffix[1:] dest = tmp.name + doctype = None if implicit else suffix[1:] with self.subTest(dest=dest, doctype=doctype): canopen.export_od(self.od, dest, doctype) self.verify_od(dest, doctype) From cc37aee4e172a5a83f9f9dc956cc66d82bd1a8b7 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Wed, 3 Jul 2024 11:40:54 +0200 Subject: [PATCH 152/199] Bail early if an unsupported doctype is passed to export_od() (#486) Fixes #485 --- canopen/objectdictionary/__init__.py | 16 ++++++++-------- test/test_eds.py | 5 ++++- 2 files changed, 12 insertions(+), 9 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 1a723616..1e80283b 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -37,13 +37,19 @@ def export_od( :raises ValueError: When exporting to an unknown format. """ + supported_doctypes = {"eds", "dcf"} + if doc_type and doc_type not in supported_doctypes: + supported = ", ".join(supported_doctypes) + raise ValueError( + f"Cannot export to the {doc_type!r} format; " + f"supported formats: {supported}" + ) opened_here = False try: - doctypes = {"eds", "dcf"} if isinstance(dest, str): if doc_type is None: - for t in doctypes: + for t in supported_doctypes: if dest.endswith(f".{t}"): doc_type = t break @@ -58,12 +64,6 @@ def export_od( elif doc_type == "dcf": from canopen.objectdictionary import eds return eds.export_dcf(od, dest) - else: - allowed = ", ".join(doctypes) - raise ValueError( - f"Cannot export to the {doc_type!r} format; " - f"supported formats: {allowed}" - ) finally: # If dest is opened in this fn, it should be closed if opened_here: diff --git a/test/test_eds.py b/test/test_eds.py index 4cbe9148..6caf0fa7 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -222,11 +222,14 @@ def test_export_eds_unknown_doctype(self): import io filelike_object = io.StringIO() self.addCleanup(filelike_object.close) - self.addCleanup(os.unlink, "filename") for dest in "filename", None, filelike_object: with self.subTest(dest=dest): with self.assertRaisesRegex(ValueError, "'unknown'"): canopen.export_od(self.od, dest, doc_type="unknown") + # Make sure no files are created is a filename is supplied. + if isinstance(dest, str): + with self.assertRaises(FileNotFoundError): + os.stat(dest) def test_export_eds_to_filelike_object(self): import io From 2938a908fb3cb93a65db5d30a7d889a08f66c956 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Wed, 3 Jul 2024 23:20:47 +0200 Subject: [PATCH 153/199] Adapt to renamed "bustype" parameter on can.Bus (#489) The bustype keyword has long been replaced by "interface" and the former is deprecated in python-can. The Network class passes it through without caring for the name, but documentation and tests referred to the older name regularly. --- README.rst | 12 ++++++------ canopen/network.py | 2 +- doc/network.rst | 10 +++++----- examples/simple_ds402_node.py | 2 +- test/test_local.py | 12 ++++++------ test/test_network.py | 8 ++++---- test/test_sync.py | 4 ++-- test/test_time.py | 2 +- 8 files changed, 26 insertions(+), 26 deletions(-) diff --git a/README.rst b/README.rst index 3c469e84..34246093 100644 --- a/README.rst +++ b/README.rst @@ -107,12 +107,12 @@ The :code:`n` is the PDO index (normally 1 to 4). The second form of access is f # Arguments are passed to python-can's can.Bus() constructor # (see https://python-can.readthedocs.io/en/latest/bus.html). network.connect() - # network.connect(bustype='socketcan', channel='can0') - # network.connect(bustype='kvaser', channel=0, bitrate=250000) - # network.connect(bustype='pcan', channel='PCAN_USBBUS1', bitrate=250000) - # network.connect(bustype='ixxat', channel=0, bitrate=250000) - # network.connect(bustype='vector', app_name='CANalyzer', channel=0, bitrate=250000) - # network.connect(bustype='nican', channel='CAN0', bitrate=250000) + # network.connect(interface='socketcan', channel='can0') + # network.connect(interface='kvaser', channel=0, bitrate=250000) + # network.connect(interface='pcan', channel='PCAN_USBBUS1', bitrate=250000) + # network.connect(interface='ixxat', channel=0, bitrate=250000) + # network.connect(interface='vector', app_name='CANalyzer', channel=0, bitrate=250000) + # network.connect(interface='nican', channel='CAN0', bitrate=250000) # Read a variable using SDO device_name = node.sdo['Manufacturer device name'].raw diff --git a/canopen/network.py b/canopen/network.py index 54280909..f6446208 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -92,7 +92,7 @@ def connect(self, *args, **kwargs) -> Network: :param channel: Backend specific channel for the CAN interface. - :param str bustype: + :param str interface: Name of the interface. See `python-can manual `__ for full list of supported interfaces. diff --git a/doc/network.rst b/doc/network.rst index 7efab634..42b6618a 100644 --- a/doc/network.rst +++ b/doc/network.rst @@ -25,11 +25,11 @@ See its documentation for specifics on how to configure your specific interface. Call the :meth:`~canopen.Network.connect` method to start the communication, optionally providing arguments passed to a the :class:`can.BusABC` constructor:: - network.connect(channel='can0', bustype='socketcan') - # network.connect(bustype='kvaser', channel=0, bitrate=250000) - # network.connect(bustype='pcan', channel='PCAN_USBBUS1', bitrate=250000) - # network.connect(bustype='ixxat', channel=0, bitrate=250000) - # network.connect(bustype='nican', channel='CAN0', bitrate=250000) + network.connect(channel='can0', interface='socketcan') + # network.connect(interface='kvaser', channel=0, bitrate=250000) + # network.connect(interface='pcan', channel='PCAN_USBBUS1', bitrate=250000) + # network.connect(interface='ixxat', channel=0, bitrate=250000) + # network.connect(interface='nican', channel='CAN0', bitrate=250000) Add nodes to the network using the :meth:`~canopen.Network.add_node` method:: diff --git a/examples/simple_ds402_node.py b/examples/simple_ds402_node.py index 5847923d..b9b96180 100644 --- a/examples/simple_ds402_node.py +++ b/examples/simple_ds402_node.py @@ -11,7 +11,7 @@ network = canopen.Network() # Connect to the CAN bus - network.connect(bustype='kvaser', channel=0, bitrate=1000000) + network.connect(interface='kvaser', channel=0, bitrate=1000000) network.check() diff --git a/test/test_local.py b/test/test_local.py index dd6efe1a..387c9f88 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -17,11 +17,11 @@ class TestSDO(unittest.TestCase): @classmethod def setUpClass(cls): cls.network1 = canopen.Network() - cls.network1.connect("test", bustype="virtual") + cls.network1.connect("test", interface="virtual") cls.remote_node = cls.network1.add_node(2, EDS_PATH) cls.network2 = canopen.Network() - cls.network2.connect("test", bustype="virtual") + cls.network2.connect("test", interface="virtual") cls.local_node = cls.network2.create_node(2, EDS_PATH) cls.remote_node2 = cls.network1.add_node(3, EDS_PATH) @@ -180,11 +180,11 @@ class TestNMT(unittest.TestCase): @classmethod def setUpClass(cls): cls.network1 = canopen.Network() - cls.network1.connect("test", bustype="virtual") + cls.network1.connect("test", interface="virtual") cls.remote_node = cls.network1.add_node(2, EDS_PATH) cls.network2 = canopen.Network() - cls.network2.connect("test", bustype="virtual") + cls.network2.connect("test", interface="virtual") cls.local_node = cls.network2.create_node(2, EDS_PATH) cls.remote_node2 = cls.network1.add_node(3, EDS_PATH) @@ -242,11 +242,11 @@ class TestPDO(unittest.TestCase): @classmethod def setUpClass(cls): cls.network1 = canopen.Network() - cls.network1.connect("test", bustype="virtual") + cls.network1.connect("test", interface="virtual") cls.remote_node = cls.network1.add_node(2, EDS_PATH) cls.network2 = canopen.Network() - cls.network2.connect("test", bustype="virtual") + cls.network2.connect("test", interface="virtual") cls.local_node = cls.network2.create_node(2, EDS_PATH) @classmethod diff --git a/test/test_network.py b/test/test_network.py index 095648ad..03cbe61b 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -32,8 +32,8 @@ def test_notify(self): self.assertListEqual(self.network.scanner.nodes, [2]) def test_send(self): - bus = can.interface.Bus(bustype="virtual", channel=1) - self.network.connect(bustype="virtual", channel=1) + bus = can.interface.Bus(interface="virtual", channel=1) + self.network.connect(interface="virtual", channel=1) # Send standard ID self.network.send_message(0x123, [1, 2, 3, 4, 5, 6, 7, 8]) @@ -54,8 +54,8 @@ def test_send(self): self.network.disconnect() def test_send_perodic(self): - bus = can.interface.Bus(bustype="virtual", channel=1) - self.network.connect(bustype="virtual", channel=1) + bus = can.interface.Bus(interface="virtual", channel=1) + self.network.connect(interface="virtual", channel=1) task = self.network.send_periodic(0x123, [1, 2, 3], 0.01) time.sleep(0.1) diff --git a/test/test_sync.py b/test/test_sync.py index 0321ceb6..a88fd0b5 100644 --- a/test/test_sync.py +++ b/test/test_sync.py @@ -6,7 +6,7 @@ class TestSync(unittest.TestCase): def test_sync_producer(self): network = canopen.Network() - network.connect(bustype="virtual", receive_own_messages=True) + network.connect(interface="virtual", receive_own_messages=True) producer = canopen.sync.SyncProducer(network) producer.transmit() msg = network.bus.recv(1) @@ -16,7 +16,7 @@ def test_sync_producer(self): def test_sync_producer_counter(self): network = canopen.Network() - network.connect(bustype="virtual", receive_own_messages=True) + network.connect(interface="virtual", receive_own_messages=True) producer = canopen.sync.SyncProducer(network) producer.transmit(2) msg = network.bus.recv(1) diff --git a/test/test_time.py b/test/test_time.py index d8d12e53..a5922442 100644 --- a/test/test_time.py +++ b/test/test_time.py @@ -6,7 +6,7 @@ class TestTime(unittest.TestCase): def test_time_producer(self): network = canopen.Network() - network.connect(bustype="virtual", receive_own_messages=True) + network.connect(interface="virtual", receive_own_messages=True) producer = canopen.timestamp.TimeProducer(network) producer.transmit(1486236238) msg = network.bus.recv(1) From 6a4ca1184e219c64768fbb0eb8434b04320d4803 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Thu, 4 Jul 2024 00:08:24 +0200 Subject: [PATCH 154/199] Save the passed node ID to the resulting OD in import_od() (#484) Only for DCF-files (which include a DeviceComissioning section), the Node-ID from the file is stored in the ObjectDictionary instance. When given an override value via the `import_od(..., node_id=...)` argument, that was however not applied to the OD attribute, but only used for $NODEID interpolation. Make sure the interpolated values match the stored node_id in this case. Also handle a missing NodeID option within the DeviceComissioning section gracefully, instead of raising an exception. --- canopen/objectdictionary/eds.py | 7 +++++-- test/sample.eds | 2 +- test/test_eds.py | 32 +++++++++++++++++++++++++++++--- 3 files changed, 35 insertions(+), 6 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index cd64f604..40342d32 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -86,8 +86,11 @@ def import_eds(source, node_id): if eds.has_section("DeviceComissioning"): od.bitrate = int(eds.get("DeviceComissioning", "Baudrate")) * 1000 - od.node_id = int(eds.get("DeviceComissioning", "NodeID"), 0) - node_id = node_id or od.node_id + + if node_id is None: + if val := eds.get("DeviceComissioning", "NodeID", fallback=None): + node_id = int(val, base=0) + od.node_id = node_id for section in eds.sections(): # Match dummy definitions diff --git a/test/sample.eds b/test/sample.eds index 16d0c31a..3c1bbcf9 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -30,7 +30,7 @@ NrOfTXPDO=4 LSS_Supported=0 [DeviceComissioning] -NodeID=2 +NodeID=0x10 NodeName=Some name Baudrate=500 NetNumber=0 diff --git a/test/test_eds.py b/test/test_eds.py index 6caf0fa7..da59e0e6 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -4,7 +4,9 @@ from canopen.objectdictionary.eds import _signed_int_from_hex from canopen.utils import pretty_index -EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') + +SAMPLE_EDS = os.path.join(os.path.dirname(__file__), 'sample.eds') +DATATYPES_EDS = os.path.join(os.path.dirname(__file__), 'datatypes.eds') class TestEDS(unittest.TestCase): @@ -48,7 +50,7 @@ class TestEDS(unittest.TestCase): } def setUp(self): - self.od = canopen.import_od(EDS_PATH, 2) + self.od = canopen.import_od(SAMPLE_EDS, 2) def test_load_nonexisting_file(self): with self.assertRaises(IOError): @@ -59,10 +61,34 @@ def test_load_unsupported_format(self): canopen.import_od(__file__) def test_load_file_object(self): - with open(EDS_PATH) as fp: + with open(SAMPLE_EDS) as fp: od = canopen.import_od(fp) self.assertTrue(len(od) > 0) + def test_load_implicit_nodeid(self): + # sample.eds has a DeviceComissioning section with NodeID set to 0x10. + od = canopen.import_od(SAMPLE_EDS) + self.assertEqual(od.node_id, 16) + + def test_load_implicit_nodeid_fallback(self): + import io + + # First, remove the NodeID option from DeviceComissioning. + with open(SAMPLE_EDS) as f: + lines = [L for L in f.readlines() if not L.startswith("NodeID=")] + with io.StringIO("".join(lines)) as buf: + buf.name = "mock.eds" + od = canopen.import_od(buf) + self.assertIsNone(od.node_id) + + # Next, try an EDS file without a DeviceComissioning section. + od = canopen.import_od(DATATYPES_EDS) + self.assertIsNone(od.node_id) + + def test_load_explicit_nodeid(self): + od = canopen.import_od(SAMPLE_EDS, node_id=3) + self.assertEqual(od.node_id, 3) + def test_variable(self): var = self.od['Producer heartbeat time'] self.assertIsInstance(var, canopen.objectdictionary.ODVariable) From f1315d3df4354cf02ac2acc70b53b91761c2f242 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 4 Jul 2024 00:28:33 +0200 Subject: [PATCH 155/199] Gracefully handle missing Baudrate setting in DCF (#492) The CiA306 spec is not quite clear on which fields are mandatory within the DeviceComissioning section. Thus it should be assumed that the two options handled here could be missing. Instead of raising an exception, ignore the absence of the Baudrate setting. --- canopen/objectdictionary/eds.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 40342d32..8dd73762 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -85,7 +85,8 @@ def import_eds(source, node_id): pass if eds.has_section("DeviceComissioning"): - od.bitrate = int(eds.get("DeviceComissioning", "Baudrate")) * 1000 + if val := eds.get("DeviceComissioning", "Baudrate", fallback=None): + od.bitrate = int(val) * 1000 if node_id is None: if val := eds.get("DeviceComissioning", "NodeID", fallback=None): From 02ebc0c44fac791ca44f232c6d6ac1950617bfab Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Thu, 4 Jul 2024 12:40:47 +0200 Subject: [PATCH 156/199] Add tests for bitrate parsing in import_eds() (#495) --- canopen/objectdictionary/eds.py | 4 ++-- test/test_eds.py | 15 +++++++++++++++ 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 8dd73762..3884d809 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -85,8 +85,8 @@ def import_eds(source, node_id): pass if eds.has_section("DeviceComissioning"): - if val := eds.get("DeviceComissioning", "Baudrate", fallback=None): - od.bitrate = int(val) * 1000 + if val := eds.getint("DeviceComissioning", "Baudrate", fallback=None): + od.bitrate = val * 1000 if node_id is None: if val := eds.get("DeviceComissioning", "NodeID", fallback=None): diff --git a/test/test_eds.py b/test/test_eds.py index da59e0e6..49d09ab7 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -89,6 +89,21 @@ def test_load_explicit_nodeid(self): od = canopen.import_od(SAMPLE_EDS, node_id=3) self.assertEqual(od.node_id, 3) + def test_load_baudrate(self): + od = canopen.import_od(SAMPLE_EDS) + self.assertEqual(od.bitrate, 500_000) + + def test_load_baudrate_fallback(self): + import io + + # Remove the Baudrate option. + with open(SAMPLE_EDS) as f: + lines = [L for L in f.readlines() if not L.startswith("Baudrate=")] + with io.StringIO("".join(lines)) as buf: + buf.name = "mock.eds" + od = canopen.import_od(buf) + self.assertIsNone(od.bitrate) + def test_variable(self): var = self.od['Producer heartbeat time'] self.assertIsInstance(var, canopen.objectdictionary.ODVariable) From 36c8488febc20e1d351135c90dd8966ab1d07dfb Mon Sep 17 00:00:00 2001 From: meifonglow Date: Fri, 5 Jul 2024 06:45:12 +1000 Subject: [PATCH 157/199] Add support for loading DCF configuration to remote node (#427) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Handle PDO-related objects through the associated methods in the PdoBase class when initializing a RemoteNode from an ObjectDictionary with provided values (DCF file usually). This avoids the locally cached mapping information to get out of sync with the PDO configuration parameters, and thus eliminates the need to read back those same objects. The PdoBase.read() method must honor DCF-provided values for this purpose. It previously only respected the OD default values when called with from_od=True. Co-authored-by: André Colomb --- canopen/node/remote.py | 15 +++++++++++---- canopen/pdo/base.py | 13 +++++++++++-- 2 files changed, 22 insertions(+), 6 deletions(-) diff --git a/canopen/node/remote.py b/canopen/node/remote.py index f3054391..4f3281db 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -146,16 +146,23 @@ def load_configuration(self) -> None: Iterate through all objects in the Object Dictionary and download the values to the remote node via SDO. - Then, to avoid PDO mapping conflicts, read back (upload) the PDO - configuration via SDO. + To avoid PDO mapping conflicts, PDO-related objects are handled through + the methods :meth:`canopen.pdo.PdoBase.read` and + :meth:`canopen.pdo.PdoBase.save`. - :see-also: :meth:`canopen.pdo.PdoBase.read` """ + # First apply PDO configuration from object dictionary + self.pdo.read(from_od=True) + self.pdo.save() + + # Now apply all other records in object dictionary for obj in self.object_dictionary.values(): + if 0x1400 <= obj.index < 0x1c00: + # Ignore PDO related objects + continue if isinstance(obj, ODRecord) or isinstance(obj, ODArray): for subobj in obj.values(): if isinstance(subobj, ODVariable) and subobj.writable and (subobj.value is not None): self.__load_configuration_helper(subobj.index, subobj.subindex, subobj.name, subobj.value) elif isinstance(obj, ODVariable) and obj.writable and (obj.value is not None): self.__load_configuration_helper(obj.index, None, obj.name, obj.value) - self.pdo.read() # reads the new configuration from the driver diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index d467cdb3..def74ff0 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -320,11 +320,20 @@ def add_callback(self, callback: Callable[[PdoMap], None]) -> None: self.callbacks.append(callback) def read(self, from_od=False) -> None: - """Read PDO configuration for this map using SDO.""" + """Read PDO configuration for this map. + + :param from_od: + Read using SDO if False, read from object dictionary if True. + When reading from object dictionary, if DCF populated a value, the + DCF value will be used, otherwise the EDS default will be used instead. + """ def _raw_from(param): if from_od: - return param.od.default + if param.od.value is not None: + return param.od.value + else: + return param.od.default return param.raw cob_id = _raw_from(self.com_record[1]) From 62e9c1f851cb8721355d22c8571f2b41599c1b36 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Sat, 6 Jul 2024 19:44:05 +0200 Subject: [PATCH 158/199] README: Add formatting and amend doc build instructions (#494) - add formatting to Git branch names - add formatting to Python module names - spell out Python version support --- README.rst | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/README.rst b/README.rst index 34246093..daf9fda2 100644 --- a/README.rst +++ b/README.rst @@ -6,7 +6,7 @@ The aim of the project is to support the most common parts of the CiA 301 standard in a simple Pythonic interface. It is mainly targeted for testing and automation tasks rather than a standard compliant master implementation. -The library supports Python 3.8+. +The library supports Python 3.8 or newer. Features @@ -36,11 +36,11 @@ Incomplete support for creating slave nodes also exists. Installation ------------ -Install from PyPI_ using pip:: +Install from PyPI_ using :program:`pip`:: $ pip install canopen -Install from latest master on GitHub:: +Install from latest ``master`` on GitHub:: $ pip install https://github.com/christiansandberg/canopen/archive/master.zip @@ -56,6 +56,10 @@ Unit tests can be run using the pytest_ framework:: $ pip install pytest $ pytest -v +You can also use :mod:`unittest` standard library module:: + + $ python3 -m unittest discover test -v + Documentation ------------- @@ -65,7 +69,8 @@ http://canopen.readthedocs.io/en/latest/ It can also be generated from a local clone using Sphinx_:: - $ python setup.py build_sphinx + $ pip install -r doc/requirements.txt + $ make -C doc html Hardware support From c413eaffd0e13389512cfdf43dd51694842a427b Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Mon, 8 Jul 2024 12:41:48 +0200 Subject: [PATCH 159/199] Git: correctly ignore docs build directory (#499) --- .gitignore | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index e8507cc0..d9a523a6 100644 --- a/.gitignore +++ b/.gitignore @@ -57,7 +57,7 @@ coverage.xml *.log # Sphinx documentation -docs/_build/ +doc/_build/ # PyBuilder target/ From 08eba81f519e637e0c20d58560ca9d6637e0adfe Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Mon, 8 Jul 2024 15:42:45 +0200 Subject: [PATCH 160/199] Tests: establish test/util.py and test/test_nmt.py (#503) Give NMT tests their own file, and establish a util.py for the test suite for common stuff like the location of sample EDS files. Consistently use SAMPLE_EDS instead of EDS_PATH. --- test/__init__.py | 0 test/test_eds.py | 6 ++-- test/test_local.py | 84 +++++--------------------------------------- test/test_network.py | 8 ++--- test/test_nmt.py | 64 +++++++++++++++++++++++++++++++++ test/test_pdo.py | 9 +++-- test/test_sdo.py | 16 +++------ test/util.py | 5 +++ 8 files changed, 92 insertions(+), 100 deletions(-) create mode 100644 test/__init__.py create mode 100644 test/test_nmt.py create mode 100644 test/util.py diff --git a/test/__init__.py b/test/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/test/test_eds.py b/test/test_eds.py index 49d09ab7..d953b994 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -1,12 +1,10 @@ import os import unittest + import canopen from canopen.objectdictionary.eds import _signed_int_from_hex from canopen.utils import pretty_index - - -SAMPLE_EDS = os.path.join(os.path.dirname(__file__), 'sample.eds') -DATATYPES_EDS = os.path.join(os.path.dirname(__file__), 'datatypes.eds') +from .util import SAMPLE_EDS, DATATYPES_EDS class TestEDS(unittest.TestCase): diff --git a/test/test_local.py b/test/test_local.py index 387c9f88..9c5fc0c1 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -1,12 +1,8 @@ -import os -import unittest -import canopen -import logging import time +import unittest -# logging.basicConfig(level=logging.DEBUG) - -EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') +import canopen +from .util import SAMPLE_EDS class TestSDO(unittest.TestCase): @@ -18,15 +14,15 @@ class TestSDO(unittest.TestCase): def setUpClass(cls): cls.network1 = canopen.Network() cls.network1.connect("test", interface="virtual") - cls.remote_node = cls.network1.add_node(2, EDS_PATH) + cls.remote_node = cls.network1.add_node(2, SAMPLE_EDS) cls.network2 = canopen.Network() cls.network2.connect("test", interface="virtual") - cls.local_node = cls.network2.create_node(2, EDS_PATH) + cls.local_node = cls.network2.create_node(2, SAMPLE_EDS) - cls.remote_node2 = cls.network1.add_node(3, EDS_PATH) + cls.remote_node2 = cls.network1.add_node(3, SAMPLE_EDS) - cls.local_node2 = cls.network2.create_node(3, EDS_PATH) + cls.local_node2 = cls.network2.create_node(3, SAMPLE_EDS) @classmethod def tearDownClass(cls): @@ -172,68 +168,6 @@ def test_callbacks(self): self.assertEqual(self._kwargs["data"], b"\x03\x04") -class TestNMT(unittest.TestCase): - """ - Test NMT slave. - """ - - @classmethod - def setUpClass(cls): - cls.network1 = canopen.Network() - cls.network1.connect("test", interface="virtual") - cls.remote_node = cls.network1.add_node(2, EDS_PATH) - - cls.network2 = canopen.Network() - cls.network2.connect("test", interface="virtual") - cls.local_node = cls.network2.create_node(2, EDS_PATH) - - cls.remote_node2 = cls.network1.add_node(3, EDS_PATH) - - cls.local_node2 = cls.network2.create_node(3, EDS_PATH) - - @classmethod - def tearDownClass(cls): - cls.network1.disconnect() - cls.network2.disconnect() - - def test_start_two_remote_nodes(self): - self.remote_node.nmt.state = 'OPERATIONAL' - # Line below is just so that we are sure the client have received the command - # before we do the check - time.sleep(0.1) - slave_state = self.local_node.nmt.state - self.assertEqual(slave_state, 'OPERATIONAL') - - self.remote_node2.nmt.state = 'OPERATIONAL' - # Line below is just so that we are sure the client have received the command - # before we do the check - time.sleep(0.1) - slave_state = self.local_node2.nmt.state - self.assertEqual(slave_state, 'OPERATIONAL') - - def test_stop_two_remote_nodes_using_broadcast(self): - # This is a NMT broadcast "Stop remote node" - # ie. set the node in STOPPED state - self.network1.send_message(0, [2, 0]) - - # Line below is just so that we are sure the slaves have received the command - # before we do the check - time.sleep(0.1) - slave_state = self.local_node.nmt.state - self.assertEqual(slave_state, 'STOPPED') - slave_state = self.local_node2.nmt.state - self.assertEqual(slave_state, 'STOPPED') - - def test_heartbeat(self): - # self.assertEqual(self.remote_node.nmt.state, 'INITIALISING') - # self.assertEqual(self.local_node.nmt.state, 'INITIALISING') - self.local_node.nmt.state = 'OPERATIONAL' - self.local_node.sdo[0x1017].raw = 100 - time.sleep(0.2) - self.assertEqual(self.remote_node.nmt.state, 'OPERATIONAL') - - self.local_node.nmt.stop_heartbeat() - class TestPDO(unittest.TestCase): """ Test PDO slave. @@ -243,11 +177,11 @@ class TestPDO(unittest.TestCase): def setUpClass(cls): cls.network1 = canopen.Network() cls.network1.connect("test", interface="virtual") - cls.remote_node = cls.network1.add_node(2, EDS_PATH) + cls.remote_node = cls.network1.add_node(2, SAMPLE_EDS) cls.network2 = canopen.Network() cls.network2.connect("test", interface="virtual") - cls.local_node = cls.network2.create_node(2, EDS_PATH) + cls.local_node = cls.network2.create_node(2, SAMPLE_EDS) @classmethod def tearDownClass(cls): diff --git a/test/test_network.py b/test/test_network.py index 03cbe61b..ed440326 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -1,18 +1,16 @@ import time -import os import unittest -import canopen +import canopen import can - -EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') +from .util import SAMPLE_EDS class TestNetwork(unittest.TestCase): def setUp(self): network = canopen.Network() - network.add_node(2, EDS_PATH) + network.add_node(2, SAMPLE_EDS) network.add_node(3, network[2].object_dictionary) self.network = network diff --git a/test/test_nmt.py b/test/test_nmt.py new file mode 100644 index 00000000..50db1187 --- /dev/null +++ b/test/test_nmt.py @@ -0,0 +1,64 @@ +import time +import unittest + +import canopen +from .util import SAMPLE_EDS + + +class TestNmtSlave(unittest.TestCase): + def setUp(self): + self.network1 = canopen.Network() + self.network1.connect("test", interface="virtual") + self.remote_node = self.network1.add_node(2, SAMPLE_EDS) + + self.network2 = canopen.Network() + self.network2.connect("test", interface="virtual") + self.local_node = self.network2.create_node(2, SAMPLE_EDS) + self.remote_node2 = self.network1.add_node(3, SAMPLE_EDS) + self.local_node2 = self.network2.create_node(3, SAMPLE_EDS) + + def tearDown(self): + self.network1.disconnect() + self.network2.disconnect() + + def test_start_two_remote_nodes(self): + self.remote_node.nmt.state = "OPERATIONAL" + # Line below is just so that we are sure the client have received the command + # before we do the check + time.sleep(0.1) + slave_state = self.local_node.nmt.state + self.assertEqual(slave_state, "OPERATIONAL") + + self.remote_node2.nmt.state = "OPERATIONAL" + # Line below is just so that we are sure the client have received the command + # before we do the check + time.sleep(0.1) + slave_state = self.local_node2.nmt.state + self.assertEqual(slave_state, "OPERATIONAL") + + def test_stop_two_remote_nodes_using_broadcast(self): + # This is a NMT broadcast "Stop remote node" + # ie. set the node in STOPPED state + self.network1.send_message(0, [2, 0]) + + # Line below is just so that we are sure the slaves have received the command + # before we do the check + time.sleep(0.1) + slave_state = self.local_node.nmt.state + self.assertEqual(slave_state, "STOPPED") + slave_state = self.local_node2.nmt.state + self.assertEqual(slave_state, "STOPPED") + + def test_heartbeat(self): + self.assertEqual(self.remote_node.nmt.state, "INITIALISING") + self.assertEqual(self.local_node.nmt.state, "INITIALISING") + self.local_node.nmt.state = "OPERATIONAL" + self.local_node.sdo[0x1017].raw = 100 + time.sleep(0.2) + self.assertEqual(self.remote_node.nmt.state, "OPERATIONAL") + + self.local_node.nmt.stop_heartbeat() + + +if __name__ == "__main__": + unittest.main() diff --git a/test/test_pdo.py b/test/test_pdo.py index 32963cf3..7e9947f1 100644 --- a/test/test_pdo.py +++ b/test/test_pdo.py @@ -1,14 +1,13 @@ -import os.path import unittest -import canopen -EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') +import canopen +from .util import SAMPLE_EDS class TestPDO(unittest.TestCase): def test_bit_mapping(self): - node = canopen.Node(1, EDS_PATH) + node = canopen.Node(1, SAMPLE_EDS) map = node.pdo.tx[1] map.add_variable('INTEGER16 value') # 0x2001 map.add_variable('UNSIGNED8 value', length=4) # 0x2002 @@ -56,7 +55,7 @@ def test_bit_mapping(self): self.assertEqual(node.pdo[0x1600][0x2002].raw, 0xf) def test_save_pdo(self): - node = canopen.Node(1, EDS_PATH) + node = canopen.Node(1, SAMPLE_EDS) node.tpdo.save() node.rpdo.save() diff --git a/test/test_sdo.py b/test/test_sdo.py index 1ec35dab..f399a33f 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -1,12 +1,10 @@ -import os import unittest -# import binascii + import canopen -from canopen.objectdictionary import ODVariable import canopen.objectdictionary.datatypes as dt +from canopen.objectdictionary import ODVariable +from .util import SAMPLE_EDS, DATATYPES_EDS -EDS_PATH = os.path.join(os.path.dirname(__file__), 'sample.eds') -DATAEDS_PATH = os.path.join(os.path.dirname(__file__), 'datatypes.eds') TX = 1 RX = 2 @@ -26,17 +24,15 @@ def _send_message(self, can_id, data, remote=False): """ next_data = self.data.pop(0) self.assertEqual(next_data[0], TX, "No transmission was expected") - # print(f"> {binascii.hexlify(data)} ({binascii.hexlify(next_data[1])})") self.assertSequenceEqual(data, next_data[1]) self.assertEqual(can_id, 0x602) while self.data and self.data[0][0] == RX: - # print(f"< {binascii.hexlify(self.data[0][1])}") self.network.notify(0x582, self.data.pop(0)[1], 0.0) def setUp(self): network = canopen.Network() network.send_message = self._send_message - node = network.add_node(2, EDS_PATH) + node = network.add_node(2, SAMPLE_EDS) node.sdo.RESPONSE_TIMEOUT = 0.01 self.network = network @@ -178,17 +174,15 @@ def _send_message(self, can_id, data, remote=False): """ next_data = self.data.pop(0) self.assertEqual(next_data[0], TX, "No transmission was expected") - # print("> %s (%s)" % (binascii.hexlify(data), binascii.hexlify(next_data[1]))) self.assertSequenceEqual(data, next_data[1]) self.assertEqual(can_id, 0x602) while self.data and self.data[0][0] == RX: - # print("< %s" % binascii.hexlify(self.data[0][1])) self.network.notify(0x582, self.data.pop(0)[1], 0.0) def setUp(self): network = canopen.Network() network.send_message = self._send_message - node = network.add_node(2, DATAEDS_PATH) + node = network.add_node(2, DATATYPES_EDS) node.sdo.RESPONSE_TIMEOUT = 0.01 self.node = node self.network = network diff --git a/test/util.py b/test/util.py new file mode 100644 index 00000000..a4395921 --- /dev/null +++ b/test/util.py @@ -0,0 +1,5 @@ +import os + + +DATATYPES_EDS = os.path.join(os.path.dirname(__file__), "datatypes.eds") +SAMPLE_EDS = os.path.join(os.path.dirname(__file__), "sample.eds") From 6bd39ba8f1fef7e32732fcc61ae548aa2392b7e0 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 9 Jul 2024 08:51:33 +0200 Subject: [PATCH 161/199] Add back PdoBase.export() dependency (canmatrix) (#493) The canmatrix optional dependency was removed on Oct 10, 2021 with commit c46228f. It is now added back as an optional dependency, using the same name as previously: db_export. To install the dependency: $ python3 -m pip install 'canopen[db_export]' Resolves #488 --- .github/workflows/pythonpackage.yml | 3 +- canopen/pdo/base.py | 14 +++++- pyproject.toml | 5 ++ test/test_pdo.py | 77 ++++++++++++++++++----------- 4 files changed, 68 insertions(+), 31 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 8fbd0aca..03a8c826 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -17,6 +17,7 @@ jobs: fail-fast: false matrix: python-version: ['3.x'] + features: ['', '[db_export]'] steps: - uses: actions/checkout@v3 @@ -28,7 +29,7 @@ jobs: run: | python -m pip install --upgrade pip pip install pytest pytest-cov - pip install -e . + pip install -e '.${{ matrix.features }}' - name: Test with pytest run: | pytest -v --cov=canopen --cov-report=xml --cov-branch diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index def74ff0..f2a7d205 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -78,14 +78,24 @@ def subscribe(self): def export(self, filename): """Export current configuration to a database file. + .. note:: + This API requires the ``db_export`` feature to be installed:: + + python3 -m pip install 'canopen[db_export]' + :param str filename: Filename to save to (e.g. DBC, DBF, ARXML, KCD etc) + :raises NotImplementedError: + When the ``canopen[db_export]`` feature is not installed. :return: The CanMatrix object created :rtype: canmatrix.canmatrix.CanMatrix """ - from canmatrix import canmatrix - from canmatrix import formats + try: + from canmatrix import canmatrix + from canmatrix import formats + except ImportError: + raise NotImplementedError("This feature requires the 'canopen[db_export]' feature") db = canmatrix.CanMatrix() for pdo_map in self.map.values(): diff --git a/pyproject.toml b/pyproject.toml index 67a435d8..a87ba589 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -26,6 +26,11 @@ dependencies = [ ] dynamic = ["version"] +[project.optional-dependencies] +db_export = [ + "canmatrix ~= 1.0", +] + [project.urls] documentation = "https://canopen.readthedocs.io/en/stable/" repository = "https://github.com/christiansandberg/canopen" diff --git a/test/test_pdo.py b/test/test_pdo.py index 7e9947f1..32c0f174 100644 --- a/test/test_pdo.py +++ b/test/test_pdo.py @@ -5,36 +5,41 @@ class TestPDO(unittest.TestCase): - - def test_bit_mapping(self): + def setUp(self): node = canopen.Node(1, SAMPLE_EDS) - map = node.pdo.tx[1] - map.add_variable('INTEGER16 value') # 0x2001 - map.add_variable('UNSIGNED8 value', length=4) # 0x2002 - map.add_variable('INTEGER8 value', length=4) # 0x2003 - map.add_variable('INTEGER32 value') # 0x2004 - map.add_variable('BOOLEAN value', length=1) # 0x2005 - map.add_variable('BOOLEAN value 2', length=1) # 0x2006 + pdo = node.pdo.tx[1] + pdo.add_variable('INTEGER16 value') # 0x2001 + pdo.add_variable('UNSIGNED8 value', length=4) # 0x2002 + pdo.add_variable('INTEGER8 value', length=4) # 0x2003 + pdo.add_variable('INTEGER32 value') # 0x2004 + pdo.add_variable('BOOLEAN value', length=1) # 0x2005 + pdo.add_variable('BOOLEAN value 2', length=1) # 0x2006 # Write some values - map['INTEGER16 value'].raw = -3 - map['UNSIGNED8 value'].raw = 0xf - map['INTEGER8 value'].raw = -2 - map['INTEGER32 value'].raw = 0x01020304 - map['BOOLEAN value'].raw = False - map['BOOLEAN value 2'].raw = True + pdo['INTEGER16 value'].raw = -3 + pdo['UNSIGNED8 value'].raw = 0xf + pdo['INTEGER8 value'].raw = -2 + pdo['INTEGER32 value'].raw = 0x01020304 + pdo['BOOLEAN value'].raw = False + pdo['BOOLEAN value 2'].raw = True + + self.pdo = pdo + self.node = node - # Check expected data - self.assertEqual(map.data, b'\xfd\xff\xef\x04\x03\x02\x01\x02') + def test_pdo_map_bit_mapping(self): + self.assertEqual(self.pdo.data, b'\xfd\xff\xef\x04\x03\x02\x01\x02') - # Read values from data - self.assertEqual(map['INTEGER16 value'].raw, -3) - self.assertEqual(map['UNSIGNED8 value'].raw, 0xf) - self.assertEqual(map['INTEGER8 value'].raw, -2) - self.assertEqual(map['INTEGER32 value'].raw, 0x01020304) - self.assertEqual(map['BOOLEAN value'].raw, False) - self.assertEqual(map['BOOLEAN value 2'].raw, True) + def test_pdo_map_getitem(self): + pdo = self.pdo + self.assertEqual(pdo['INTEGER16 value'].raw, -3) + self.assertEqual(pdo['UNSIGNED8 value'].raw, 0xf) + self.assertEqual(pdo['INTEGER8 value'].raw, -2) + self.assertEqual(pdo['INTEGER32 value'].raw, 0x01020304) + self.assertEqual(pdo['BOOLEAN value'].raw, False) + self.assertEqual(pdo['BOOLEAN value 2'].raw, True) + def test_pdo_getitem(self): + node = self.node self.assertEqual(node.tpdo[1]['INTEGER16 value'].raw, -3) self.assertEqual(node.tpdo[1]['UNSIGNED8 value'].raw, 0xf) self.assertEqual(node.tpdo[1]['INTEGER8 value'].raw, -2) @@ -54,10 +59,26 @@ def test_bit_mapping(self): self.assertEqual(node.tpdo[0x2002].raw, 0xf) self.assertEqual(node.pdo[0x1600][0x2002].raw, 0xf) - def test_save_pdo(self): - node = canopen.Node(1, SAMPLE_EDS) - node.tpdo.save() - node.rpdo.save() + def test_pdo_save(self): + self.node.tpdo.save() + self.node.rpdo.save() + + def test_pdo_export(self): + import tempfile + try: + import canmatrix + except ImportError: + raise unittest.SkipTest("The PDO export API requires canmatrix") + + for pdo in "tpdo", "rpdo": + with tempfile.NamedTemporaryFile(suffix=".csv") as tmp: + fn = tmp.name + with self.subTest(filename=fn, pdo=pdo): + getattr(self.node, pdo).export(fn) + with open(fn) as csv: + header = csv.readline() + self.assertIn("ID", header) + self.assertIn("Frame Name", header) if __name__ == "__main__": From c4560daa37bec67a663046834a42b8058b5ceedc Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 9 Jul 2024 08:54:25 +0200 Subject: [PATCH 162/199] Build docs in CI (fixes #497) (#498) --- .github/workflows/pythonpackage.yml | 16 ++++++++++++++++ doc/requirements.txt | 6 +++--- 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 03a8c826..427ad9c7 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -37,3 +37,19 @@ jobs: uses: codecov/codecov-action@v4 with: token: ${{ secrets.CODECOV_TOKEN }} + + docs: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v4 + - uses: actions/setup-python@v5 + with: + python-version: 3.12 + cache: 'pip' + cache-dependency-path: | + 'pyproject.toml' + 'doc/requirements.txt' + - name: Install dependencies + run: python3 -m pip install -r doc/requirements.txt -e . + - name: Build docs + run: make -C doc html diff --git a/doc/requirements.txt b/doc/requirements.txt index f4bba38a..ce269bc3 100644 --- a/doc/requirements.txt +++ b/doc/requirements.txt @@ -1,3 +1,3 @@ -sphinx -sphinx-autodoc-typehints -furo +sphinx~=7.3 +sphinx-autodoc-typehints~=2.2 +furo~=2024.5 From fa74236b3f3312c03d09e72de3fa6d3cf077fbec Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 9 Jul 2024 12:15:33 +0200 Subject: [PATCH 163/199] Add tests for NMT base and NMT master (#504) --- test/test_nmt.py | 126 +++++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 122 insertions(+), 4 deletions(-) diff --git a/test/test_nmt.py b/test/test_nmt.py index 50db1187..c24e8d96 100644 --- a/test/test_nmt.py +++ b/test/test_nmt.py @@ -1,21 +1,139 @@ import time import unittest +import can import canopen +from canopen.nmt import COMMAND_TO_STATE, NMT_STATES, NMT_COMMANDS, NmtError from .util import SAMPLE_EDS +class TestNmtBase(unittest.TestCase): + def setUp(self): + node_id = 2 + self.node_id = node_id + self.nmt = canopen.nmt.NmtBase(node_id) + + def test_send_command(self): + dataset = ( + "OPERATIONAL", + "PRE-OPERATIONAL", + "SLEEP", + "STANDBY", + "STOPPED", + ) + for cmd in dataset: + with self.subTest(cmd=cmd): + code = NMT_COMMANDS[cmd] + self.nmt.send_command(code) + expected = NMT_STATES[COMMAND_TO_STATE[code]] + self.assertEqual(self.nmt.state, expected) + + def test_state_getset(self): + for state in NMT_STATES.values(): + with self.subTest(state=state): + self.nmt.state = state + self.assertEqual(self.nmt.state, state) + + def test_state_set_invalid(self): + with self.assertRaisesRegex(ValueError, "INVALID"): + self.nmt.state = "INVALID" + + +class TestNmtMaster(unittest.TestCase): + NODE_ID = 2 + COB_ID = 0x700 + NODE_ID + PERIOD = 0.01 + TIMEOUT = PERIOD * 2 + + def setUp(self): + bus = can.ThreadSafeBus( + interface="virtual", + channel="test", + receive_own_messages=True, + ) + net = canopen.Network(bus) + net.connect() + with self.assertLogs(): + node = net.add_node(self.NODE_ID, SAMPLE_EDS) + + self.bus = bus + self.net = net + self.node = node + + def tearDown(self): + self.net.disconnect() + + def test_nmt_master_no_heartbeat(self): + with self.assertRaisesRegex(NmtError, "heartbeat"): + self.node.nmt.wait_for_heartbeat(self.TIMEOUT) + with self.assertRaisesRegex(NmtError, "boot-up"): + self.node.nmt.wait_for_bootup(self.TIMEOUT) + + def test_nmt_master_on_heartbeat(self): + # Skip the special INITIALISING case. + for code in [st for st in NMT_STATES if st != 0]: + with self.subTest(code=code): + task = self.net.send_periodic(self.COB_ID, [code], self.PERIOD) + try: + actual = self.node.nmt.wait_for_heartbeat(self.TIMEOUT) + finally: + task.stop() + expected = NMT_STATES[code] + self.assertEqual(actual, expected) + + def test_nmt_master_on_heartbeat_initialising(self): + task = self.net.send_periodic(self.COB_ID, [0], self.PERIOD) + self.addCleanup(task.stop) + self.node.nmt.wait_for_bootup(self.TIMEOUT) + state = self.node.nmt.wait_for_heartbeat(self.TIMEOUT) + self.assertEqual(state, "PRE-OPERATIONAL") + + @unittest.expectedFailure + def test_nmt_master_on_heartbeat_unknown_state(self): + task = self.net.send_periodic(self.COB_ID, [0xcb], self.PERIOD) + self.addCleanup(task.stop) + state = self.node.nmt.wait_for_heartbeat(self.TIMEOUT) + # Expect the high bit to be masked out, and and unknown state string to + # be returned. + self.assertEqual(state, "UNKNOWN STATE '75'") + + def test_nmt_master_add_heartbeat_callback(self): + from threading import Event + event = Event() + state = None + def hook(st): + nonlocal state + state = st + event.set() + self.node.nmt.add_heartbeat_callback(hook) + self.net.send_message(self.COB_ID, bytes([127])) + self.assertTrue(event.wait(self.TIMEOUT)) + self.assertEqual(state, 127) + + def test_nmt_master_node_guarding(self): + self.node.nmt.start_node_guarding(self.PERIOD) + msg = self.bus.recv(self.TIMEOUT) + self.assertIsNotNone(msg) + self.assertEqual(msg.arbitration_id, self.COB_ID) + self.assertEqual(msg.dlc, 0) + + self.node.nmt.stop_node_guarding() + self.assertIsNone(self.bus.recv(self.TIMEOUT)) + + class TestNmtSlave(unittest.TestCase): def setUp(self): self.network1 = canopen.Network() self.network1.connect("test", interface="virtual") - self.remote_node = self.network1.add_node(2, SAMPLE_EDS) + with self.assertLogs(): + self.remote_node = self.network1.add_node(2, SAMPLE_EDS) self.network2 = canopen.Network() self.network2.connect("test", interface="virtual") - self.local_node = self.network2.create_node(2, SAMPLE_EDS) - self.remote_node2 = self.network1.add_node(3, SAMPLE_EDS) - self.local_node2 = self.network2.create_node(3, SAMPLE_EDS) + with self.assertLogs(): + self.local_node = self.network2.create_node(2, SAMPLE_EDS) + self.remote_node2 = self.network1.add_node(3, SAMPLE_EDS) + self.local_node2 = self.network2.create_node(3, SAMPLE_EDS) def tearDown(self): self.network1.disconnect() From 5207b322907b9d3fa2a4343ed17dc4d89fe26109 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 9 Jul 2024 12:58:36 +0200 Subject: [PATCH 164/199] Ensure NmtBase.state always returns a string (#506) Fixes #500 --- canopen/nmt.py | 6 +++--- test/test_nmt.py | 3 +-- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/canopen/nmt.py b/canopen/nmt.py index 401ad15e..8ce737ea 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -86,10 +86,10 @@ def state(self) -> str: - 'RESET' - 'RESET COMMUNICATION' """ - if self._state in NMT_STATES: + try: return NMT_STATES[self._state] - else: - return self._state + except KeyError: + return f"UNKNOWN STATE '{self._state}'" @state.setter def state(self, new_state: str): diff --git a/test/test_nmt.py b/test/test_nmt.py index c24e8d96..b6892cff 100644 --- a/test/test_nmt.py +++ b/test/test_nmt.py @@ -88,12 +88,11 @@ def test_nmt_master_on_heartbeat_initialising(self): state = self.node.nmt.wait_for_heartbeat(self.TIMEOUT) self.assertEqual(state, "PRE-OPERATIONAL") - @unittest.expectedFailure def test_nmt_master_on_heartbeat_unknown_state(self): task = self.net.send_periodic(self.COB_ID, [0xcb], self.PERIOD) self.addCleanup(task.stop) state = self.node.nmt.wait_for_heartbeat(self.TIMEOUT) - # Expect the high bit to be masked out, and and unknown state string to + # Expect the high bit to be masked out, and a formatted string to # be returned. self.assertEqual(state, "UNKNOWN STATE '75'") From 3aa509db9fea8094516e5eb717be3df182f0751a Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 9 Jul 2024 13:06:57 +0200 Subject: [PATCH 165/199] Tests: harden TestNetwork (#505) - make tests deterministic - use cleanup hooks - check the periodicity of heartbeats, by number of triggers - roughly check the interval --- test/test_network.py | 68 ++++++++++++++++++++++++++------------------ 1 file changed, 41 insertions(+), 27 deletions(-) diff --git a/test/test_network.py b/test/test_network.py index ed440326..d488a2bc 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -1,5 +1,5 @@ -import time import unittest +from threading import Event import canopen import can @@ -10,7 +10,8 @@ class TestNetwork(unittest.TestCase): def setUp(self): network = canopen.Network() - network.add_node(2, SAMPLE_EDS) + with self.assertLogs(): + network.add_node(2, SAMPLE_EDS) network.add_node(3, network[2].object_dictionary) self.network = network @@ -31,7 +32,10 @@ def test_notify(self): def test_send(self): bus = can.interface.Bus(interface="virtual", channel=1) + self.addCleanup(bus.shutdown) + self.network.connect(interface="virtual", channel=1) + self.addCleanup(self.network.disconnect) # Send standard ID self.network.send_message(0x123, [1, 2, 3, 4, 5, 6, 7, 8]) @@ -48,33 +52,43 @@ def test_send(self): self.assertEqual(msg.arbitration_id, 0x12345) self.assertTrue(msg.is_extended_id) - bus.shutdown() - self.network.disconnect() - - def test_send_perodic(self): - bus = can.interface.Bus(interface="virtual", channel=1) - self.network.connect(interface="virtual", channel=1) - - task = self.network.send_periodic(0x123, [1, 2, 3], 0.01) - time.sleep(0.1) - # FIXME: This test is a little fragile, as the number of elements - # depends on the timing of the machine. - print(f"Queue size: {bus.queue.qsize()}") - self.assertTrue(9 <= bus.queue.qsize() <= 13) - msg = bus.recv(0) - self.assertIsNotNone(msg) - self.assertSequenceEqual(msg.data, [1, 2, 3]) - # Update data - task.update([4, 5, 6]) - time.sleep(0.02) - while msg is not None and msg.data == b'\x01\x02\x03': - msg = bus.recv(0) - self.assertIsNotNone(msg) - self.assertSequenceEqual(msg.data, [4, 5, 6]) + def test_send_periodic(self): + DATA1 = bytes([1, 2, 3]) + DATA2 = bytes([4, 5, 6]) + COB_ID = 0x123 + PERIOD = 0.1 + self.network.connect( + interface="virtual", + channel=1, + receive_own_messages=True + ) + self.addCleanup(self.network.disconnect) + + acc = [] + event = Event() + + def hook(_, data, ts): + acc.append((data, ts)) + event.set() + + self.network.subscribe(COB_ID, hook) + self.addCleanup(self.network.unsubscribe, COB_ID) + + task = self.network.send_periodic(COB_ID, DATA1, PERIOD) + self.addCleanup(task.stop) + + event.wait(PERIOD*2) + + # Update task data. + task.update(DATA2) + event.clear() + event.wait(PERIOD*2) task.stop() - bus.shutdown() - self.network.disconnect() + data = [v[0] for v in acc] + self.assertEqual(data, [DATA1, DATA2]) + ts = [v[1] for v in acc] + self.assertAlmostEqual(ts[1]-ts[0], PERIOD, places=1) class TestScanner(unittest.TestCase): From 55d870e2d4fd1f36141712ebad318e6b611ea50c Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Wed, 10 Jul 2024 16:44:01 +0200 Subject: [PATCH 166/199] Tests: make sure temporary files are pre-closed (#507) Windows fails with a permission error if the temporary file is already opened. Fixes #501 --- test/test_eds.py | 8 +++----- test/test_pdo.py | 5 ++--- test/util.py | 9 +++++++++ 3 files changed, 14 insertions(+), 8 deletions(-) diff --git a/test/test_eds.py b/test/test_eds.py index d953b994..775b7a41 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -4,7 +4,7 @@ import canopen from canopen.objectdictionary.eds import _signed_int_from_hex from canopen.utils import pretty_index -from .util import SAMPLE_EDS, DATATYPES_EDS +from .util import SAMPLE_EDS, DATATYPES_EDS, tmp_file class TestEDS(unittest.TestCase): @@ -223,10 +223,9 @@ def test_comments(self): """.strip()) def test_export_eds_to_file(self): - import tempfile for suffix in ".eds", ".dcf": for implicit in True, False: - with tempfile.NamedTemporaryFile(suffix=suffix) as tmp: + with tmp_file(suffix=suffix) as tmp: dest = tmp.name doctype = None if implicit else suffix[1:] with self.subTest(dest=dest, doctype=doctype): @@ -235,9 +234,8 @@ def test_export_eds_to_file(self): def test_export_eds_to_file_unknown_extension(self): import io - import tempfile for suffix in ".txt", "": - with tempfile.NamedTemporaryFile(suffix=suffix) as tmp: + with tmp_file(suffix=suffix) as tmp: dest = tmp.name with self.subTest(dest=dest, doctype=None): canopen.export_od(self.od, dest) diff --git a/test/test_pdo.py b/test/test_pdo.py index 32c0f174..e3ad219f 100644 --- a/test/test_pdo.py +++ b/test/test_pdo.py @@ -1,7 +1,7 @@ import unittest import canopen -from .util import SAMPLE_EDS +from .util import SAMPLE_EDS, tmp_file class TestPDO(unittest.TestCase): @@ -64,14 +64,13 @@ def test_pdo_save(self): self.node.rpdo.save() def test_pdo_export(self): - import tempfile try: import canmatrix except ImportError: raise unittest.SkipTest("The PDO export API requires canmatrix") for pdo in "tpdo", "rpdo": - with tempfile.NamedTemporaryFile(suffix=".csv") as tmp: + with tmp_file(suffix=".csv") as tmp: fn = tmp.name with self.subTest(filename=fn, pdo=pdo): getattr(self.node, pdo).export(fn) diff --git a/test/util.py b/test/util.py index a4395921..2c8eccca 100644 --- a/test/util.py +++ b/test/util.py @@ -1,5 +1,14 @@ +import contextlib import os +import tempfile DATATYPES_EDS = os.path.join(os.path.dirname(__file__), "datatypes.eds") SAMPLE_EDS = os.path.join(os.path.dirname(__file__), "sample.eds") + + +@contextlib.contextmanager +def tmp_file(*args, **kwds): + with tempfile.NamedTemporaryFile(*args, **kwds) as tmp: + tmp.close() + yield tmp From a196e1e3b62bddcfd62cea9fc5293efe8a8cc0a4 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Wed, 10 Jul 2024 16:47:57 +0200 Subject: [PATCH 167/199] Purge import hack from network.py (#510) Always require dependencies to be installed. Resolved #509 --- canopen/network.py | 13 +++---------- 1 file changed, 3 insertions(+), 10 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index f6446208..967d804a 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -5,16 +5,9 @@ import threading from typing import Callable, Dict, Iterator, List, Optional, Union -try: - import can - from can import Listener - from can import CanError -except ImportError: - # Do not fail if python-can is not installed - can = None - CanError = Exception - class Listener: - """ Dummy listener """ +import can +from can import Listener +from can import CanError from canopen.node import RemoteNode, LocalNode from canopen.sync import SyncProducer From 7d7e2f17c6aeef6aea2e6970f3f80064a3b8b2cc Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 6 Aug 2024 21:43:06 +0200 Subject: [PATCH 168/199] Tests: improve coverage of Network (#515) --- test/test_network.py | 210 ++++++++++++++++++++++++++++++++++++++----- 1 file changed, 190 insertions(+), 20 deletions(-) diff --git a/test/test_network.py b/test/test_network.py index d488a2bc..16c7616c 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -1,3 +1,4 @@ +import logging import unittest from threading import Event @@ -9,20 +10,82 @@ class TestNetwork(unittest.TestCase): def setUp(self): - network = canopen.Network() - with self.assertLogs(): - network.add_node(2, SAMPLE_EDS) - network.add_node(3, network[2].object_dictionary) - self.network = network + self.network = canopen.Network() - def test_add_node(self): - node = self.network[2] - self.assertIsInstance(node, canopen.Node) - self.assertEqual(node.id, 2) + def test_network_add_node(self): + # Add using str. + with self.assertLogs(): + node = self.network.add_node(2, SAMPLE_EDS) self.assertEqual(self.network[2], node) - self.assertEqual(len(self.network), 2) + self.assertEqual(node.id, 2) + self.assertIsInstance(node, canopen.RemoteNode) + + # Add using OD. + node = self.network.add_node(3, self.network[2].object_dictionary) + self.assertEqual(self.network[3], node) + self.assertEqual(node.id, 3) + self.assertIsInstance(node, canopen.RemoteNode) + + # Add using RemoteNode. + with self.assertLogs(): + node = canopen.RemoteNode(4, SAMPLE_EDS) + self.network.add_node(node) + self.assertEqual(self.network[4], node) + self.assertEqual(node.id, 4) + self.assertIsInstance(node, canopen.RemoteNode) + + # Add using LocalNode. + with self.assertLogs(): + node = canopen.LocalNode(5, SAMPLE_EDS) + self.network.add_node(node) + self.assertEqual(self.network[5], node) + self.assertEqual(node.id, 5) + self.assertIsInstance(node, canopen.LocalNode) + + # Verify that we've got the correct number of nodes. + self.assertEqual(len(self.network), 4) - def test_notify(self): + def test_network_add_node_upload_eds(self): + # Will err because we're not connected to a real network. + with self.assertLogs(level=logging.ERROR): + self.network.add_node(2, SAMPLE_EDS, upload_eds=True) + + def test_network_create_node(self): + with self.assertLogs(): + self.network.create_node(2, SAMPLE_EDS) + self.network.create_node(3, SAMPLE_EDS) + node = canopen.RemoteNode(4, SAMPLE_EDS) + self.network.create_node(node) + self.assertIsInstance(self.network[2], canopen.LocalNode) + self.assertIsInstance(self.network[3], canopen.LocalNode) + self.assertIsInstance(self.network[4], canopen.RemoteNode) + + def test_network_check(self): + self.network.connect(interface="virtual") + + def cleanup(): + # We must clear the fake exception installed below, since + # .disconnect() implicitly calls .check() during test tear down. + self.network.notifier.exception = None + self.network.disconnect() + + self.addCleanup(cleanup) + self.assertIsNone(self.network.check()) + + class Custom(Exception): + pass + + self.network.notifier.exception = Custom("fake") + with self.assertRaisesRegex(Custom, "fake"): + with self.assertLogs(level=logging.ERROR): + self.network.check() + with self.assertRaisesRegex(Custom, "fake"): + with self.assertLogs(level=logging.ERROR): + self.network.disconnect() + + def test_network_notify(self): + with self.assertLogs(): + self.network.add_node(2, SAMPLE_EDS) node = self.network[2] self.network.notify(0x82, b'\x01\x20\x02\x00\x01\x02\x03\x04', 1473418396.0) self.assertEqual(len(node.emcy.active), 1) @@ -30,11 +93,11 @@ def test_notify(self): self.assertEqual(node.nmt.state, 'OPERATIONAL') self.assertListEqual(self.network.scanner.nodes, [2]) - def test_send(self): - bus = can.interface.Bus(interface="virtual", channel=1) + def test_network_send_message(self): + bus = can.interface.Bus(interface="virtual") self.addCleanup(bus.shutdown) - self.network.connect(interface="virtual", channel=1) + self.network.connect(interface="virtual") self.addCleanup(self.network.disconnect) # Send standard ID @@ -52,16 +115,123 @@ def test_send(self): self.assertEqual(msg.arbitration_id, 0x12345) self.assertTrue(msg.is_extended_id) - def test_send_periodic(self): + def test_network_subscribe_unsubscribe(self): + N_HOOKS = 3 + accumulators = [] * N_HOOKS + + self.network.connect(interface="virtual", receive_own_messages=True) + self.addCleanup(self.network.disconnect) + + for i in range(N_HOOKS): + accumulators.append([]) + def hook(*args, i=i): + accumulators[i].append(args) + self.network.subscribe(i, hook) + + self.network.notify(0, bytes([1, 2, 3]), 1000) + self.network.notify(1, bytes([2, 3, 4]), 1001) + self.network.notify(1, bytes([3, 4, 5]), 1002) + self.network.notify(2, bytes([4, 5, 6]), 1003) + + self.assertEqual(accumulators[0], [(0, bytes([1, 2, 3]), 1000)]) + self.assertEqual(accumulators[1], [ + (1, bytes([2, 3, 4]), 1001), + (1, bytes([3, 4, 5]), 1002), + ]) + self.assertEqual(accumulators[2], [(2, bytes([4, 5, 6]), 1003)]) + + self.network.unsubscribe(0) + self.network.notify(0, bytes([7, 7, 7]), 1004) + # Verify that no new data was added to the accumulator. + self.assertEqual(accumulators[0], [(0, bytes([1, 2, 3]), 1000)]) + + def test_network_subscribe_multiple(self): + N_HOOKS = 3 + self.network.connect(interface="virtual", receive_own_messages=True) + self.addCleanup(self.network.disconnect) + + accumulators = [] + hooks = [] + for i in range(N_HOOKS): + accumulators.append([]) + def hook(*args, i=i): + accumulators[i].append(args) + hooks.append(hook) + self.network.subscribe(0x20, hook) + + self.network.notify(0xaa, bytes([1, 1, 1]), 2000) + self.network.notify(0x20, bytes([2, 3, 4]), 2001) + self.network.notify(0xbb, bytes([2, 2, 2]), 2002) + self.network.notify(0x20, bytes([3, 4, 5]), 2003) + self.network.notify(0xcc, bytes([3, 3, 3]), 2004) + + BATCH1 = [ + (0x20, bytes([2, 3, 4]), 2001), + (0x20, bytes([3, 4, 5]), 2003), + ] + for n, acc in enumerate(accumulators): + with self.subTest(hook=n): + self.assertEqual(acc, BATCH1) + + # Unsubscribe the second hook; dispatch a new message. + self.network.unsubscribe(0x20, hooks[1]) + + BATCH2 = 0x20, bytes([4, 5, 6]), 2005 + self.network.notify(*BATCH2) + self.assertEqual(accumulators[0], BATCH1 + [BATCH2]) + self.assertEqual(accumulators[1], BATCH1) + self.assertEqual(accumulators[2], BATCH1 + [BATCH2]) + + # Unsubscribe the first hook; dispatch yet another message. + self.network.unsubscribe(0x20, hooks[0]) + + BATCH3 = 0x20, bytes([5, 6, 7]), 2006 + self.network.notify(*BATCH3) + self.assertEqual(accumulators[0], BATCH1 + [BATCH2]) + self.assertEqual(accumulators[1], BATCH1) + self.assertEqual(accumulators[2], BATCH1 + [BATCH2] + [BATCH3]) + + # Unsubscribe the rest (only one remaining); dispatch a new message. + self.network.unsubscribe(0x20) + self.network.notify(0x20, bytes([7, 7, 7]), 2007) + self.assertEqual(accumulators[0], BATCH1 + [BATCH2]) + self.assertEqual(accumulators[1], BATCH1) + self.assertEqual(accumulators[2], BATCH1 + [BATCH2] + [BATCH3]) + + def test_network_context_manager(self): + with self.network.connect(interface="virtual"): + pass + with self.assertRaisesRegex(RuntimeError, "Not connected"): + self.network.send_message(0, []) + + def test_network_item_access(self): + with self.assertLogs(): + self.network.add_node(2, SAMPLE_EDS) + self.network.add_node(3, SAMPLE_EDS) + self.assertEqual([2, 3], [node for node in self.network]) + + # Check __delitem__. + del self.network[2] + self.assertEqual([3], [node for node in self.network]) + with self.assertRaises(KeyError): + del self.network[2] + + # Check __setitem__. + old = self.network[3] + with self.assertLogs(): + new = canopen.Node(3, SAMPLE_EDS) + self.network[3] = new + + # Check __getitem__. + self.assertNotEqual(self.network[3], old) + self.assertEqual([3], [node for node in self.network]) + + def test_network_send_periodic(self): DATA1 = bytes([1, 2, 3]) DATA2 = bytes([4, 5, 6]) COB_ID = 0x123 PERIOD = 0.1 - self.network.connect( - interface="virtual", - channel=1, - receive_own_messages=True - ) + self.network.connect(interface="virtual", receive_own_messages=True) self.addCleanup(self.network.disconnect) acc = [] From ecf216a760c8f0016826bb0c4f8e1f7944951d21 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 6 Aug 2024 22:03:04 +0200 Subject: [PATCH 169/199] Tests: harden TestNetwork and TestNmt even more (#508) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - take into account that payloads with DATA1 may be in flight when we update the task - test task.stop() - use more lenient timeout - use threading.Condition for improved readability - wait for periodicity to be established before validation; some platforms are a little bit flaky Co-authored-by: André Colomb --- test/test_network.py | 52 ++++++++++++++++++++++++++++++++------------ test/test_nmt.py | 6 ++++- 2 files changed, 43 insertions(+), 15 deletions(-) diff --git a/test/test_network.py b/test/test_network.py index 16c7616c..f43bce0c 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -1,6 +1,6 @@ import logging import unittest -from threading import Event +import threading import canopen import can @@ -231,15 +231,18 @@ def test_network_send_periodic(self): DATA2 = bytes([4, 5, 6]) COB_ID = 0x123 PERIOD = 0.1 + TIMEOUT = PERIOD * 10 self.network.connect(interface="virtual", receive_own_messages=True) self.addCleanup(self.network.disconnect) acc = [] - event = Event() + condition = threading.Condition() def hook(_, data, ts): - acc.append((data, ts)) - event.set() + with condition: + item = data, ts + acc.append(item) + condition.notify_all() self.network.subscribe(COB_ID, hook) self.addCleanup(self.network.unsubscribe, COB_ID) @@ -247,18 +250,39 @@ def hook(_, data, ts): task = self.network.send_periodic(COB_ID, DATA1, PERIOD) self.addCleanup(task.stop) - event.wait(PERIOD*2) - - # Update task data. + def periodicity(): + # Check if periodicity is established; flakiness has been observed + # on macOS. + if len(acc) >= 2: + delta = acc[-1][1] - acc[-2][1] + return round(delta, ndigits=1) == PERIOD + return False + + # Wait for frames to arrive; then check the result. + with condition: + condition.wait_for(periodicity, TIMEOUT) + self.assertTrue(all(v[0] == DATA1 for v in acc)) + + # Update task data, which may implicitly restart the timer. + # Wait for frames to arrive; then check the result. task.update(DATA2) - event.clear() - event.wait(PERIOD*2) - task.stop() - + with condition: + acc.clear() + condition.wait_for(periodicity, TIMEOUT) + # Find the first message with new data, and verify that all subsequent + # messages also carry the new payload. data = [v[0] for v in acc] - self.assertEqual(data, [DATA1, DATA2]) - ts = [v[1] for v in acc] - self.assertAlmostEqual(ts[1]-ts[0], PERIOD, places=1) + idx = data.index(DATA2) + self.assertTrue(all(v[0] == DATA2 for v in acc[idx:])) + + # Stop the task. + task.stop() + # A message may have been in flight when we stopped the timer, + # so allow a single failure. + bus = self.network.bus + msg = bus.recv(TIMEOUT) + if msg is not None: + self.assertIsNone(bus.recv(TIMEOUT)) class TestScanner(unittest.TestCase): diff --git a/test/test_nmt.py b/test/test_nmt.py index b6892cff..059e1982 100644 --- a/test/test_nmt.py +++ b/test/test_nmt.py @@ -117,7 +117,11 @@ def test_nmt_master_node_guarding(self): self.assertEqual(msg.dlc, 0) self.node.nmt.stop_node_guarding() - self.assertIsNone(self.bus.recv(self.TIMEOUT)) + # A message may have been in flight when we stopped the timer, + # so allow a single failure. + msg = self.bus.recv(self.TIMEOUT) + if msg is not None: + self.assertIsNone(self.bus.recv(self.TIMEOUT)) class TestNmtSlave(unittest.TestCase): From d1c28e51b93c7d45fce40187672e7ab7a0616cac Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Tue, 6 Aug 2024 22:08:49 +0200 Subject: [PATCH 170/199] Tests: improve coverage of NodeScanner (#517) --- test/test_network.py | 72 ++++++++++++++++++++++++++++++++++++++++---- 1 file changed, 66 insertions(+), 6 deletions(-) diff --git a/test/test_network.py b/test/test_network.py index f43bce0c..f407adc7 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -286,13 +286,73 @@ def periodicity(): class TestScanner(unittest.TestCase): + TIMEOUT = 0.1 - def test_passive_scanning(self): - scanner = canopen.network.NodeScanner() - scanner.on_message_received(0x586) - scanner.on_message_received(0x587) - scanner.on_message_received(0x586) - self.assertListEqual(scanner.nodes, [6, 7]) + def setUp(self): + self.scanner = canopen.network.NodeScanner() + + def test_scanner_on_message_received(self): + # Emergency frames should be recognized. + self.scanner.on_message_received(0x081) + # Heartbeats should be recognized. + self.scanner.on_message_received(0x703) + # Tx PDOs should be recognized, but not Rx PDOs. + self.scanner.on_message_received(0x185) + self.scanner.on_message_received(0x206) + self.scanner.on_message_received(0x287) + self.scanner.on_message_received(0x308) + self.scanner.on_message_received(0x389) + self.scanner.on_message_received(0x40a) + self.scanner.on_message_received(0x48b) + self.scanner.on_message_received(0x50c) + # SDO responses from .search() should be recognized, + # but not SDO requests. + self.scanner.on_message_received(0x58d) + self.scanner.on_message_received(0x50e) + self.assertListEqual(self.scanner.nodes, [1, 3, 5, 7, 9, 11, 13]) + + def test_scanner_reset(self): + self.scanner.nodes = [1, 2, 3] # Mock scan. + self.scanner.reset() + self.assertListEqual(self.scanner.nodes, []) + + def test_scanner_search_no_network(self): + with self.assertRaisesRegex(RuntimeError, "Network is required"): + self.scanner.search() + + def test_scanner_search(self): + bus = can.Bus(interface="virtual", receive_own_messages=True) + net = canopen.Network(bus) + net.connect() + self.addCleanup(net.disconnect) + + self.scanner.network = net + self.scanner.search() + + payload = bytes([64, 0, 16, 0, 0, 0, 0, 0]) + acc = [bus.recv(self.TIMEOUT) for _ in range(127)] + for node_id, msg in enumerate(acc, start=1): + with self.subTest(node_id=node_id): + self.assertIsNotNone(msg) + self.assertEqual(msg.arbitration_id, 0x600 + node_id) + self.assertEqual(msg.data, payload) + # Check that no spurious packets were sent. + self.assertIsNone(bus.recv(self.TIMEOUT)) + + def test_scanner_search_limit(self): + bus = can.Bus(interface="virtual", receive_own_messages=True) + net = canopen.Network(bus) + net.connect() + self.addCleanup(net.disconnect) + + self.scanner.network = net + self.scanner.search(limit=1) + + msg = bus.recv(self.TIMEOUT) + self.assertIsNotNone(msg) + self.assertEqual(msg.arbitration_id, 0x601) + # Check that no spurious packets were sent. + self.assertIsNone(bus.recv(self.TIMEOUT)) if __name__ == "__main__": From d75c5f09b11b1ffee200bd8813efac5c8f0127e8 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Sun, 11 Aug 2024 22:40:47 +0200 Subject: [PATCH 171/199] Make node scanner tests more deterministic (#526) This fixes up the tests added with #517 (commit d1c28e51b93c7d45fce40187672e7ab7a0616cac). --- test/test_network.py | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/test/test_network.py b/test/test_network.py index f407adc7..a87954d3 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -321,8 +321,13 @@ def test_scanner_search_no_network(self): self.scanner.search() def test_scanner_search(self): - bus = can.Bus(interface="virtual", receive_own_messages=True) - net = canopen.Network(bus) + rxbus = can.Bus(interface="virtual") + self.addCleanup(rxbus.shutdown) + + txbus = can.Bus(interface="virtual") + self.addCleanup(txbus.shutdown) + + net = canopen.Network(txbus) net.connect() self.addCleanup(net.disconnect) @@ -330,14 +335,14 @@ def test_scanner_search(self): self.scanner.search() payload = bytes([64, 0, 16, 0, 0, 0, 0, 0]) - acc = [bus.recv(self.TIMEOUT) for _ in range(127)] + acc = [rxbus.recv(self.TIMEOUT) for _ in range(127)] for node_id, msg in enumerate(acc, start=1): with self.subTest(node_id=node_id): self.assertIsNotNone(msg) self.assertEqual(msg.arbitration_id, 0x600 + node_id) self.assertEqual(msg.data, payload) # Check that no spurious packets were sent. - self.assertIsNone(bus.recv(self.TIMEOUT)) + self.assertIsNone(rxbus.recv(self.TIMEOUT)) def test_scanner_search_limit(self): bus = can.Bus(interface="virtual", receive_own_messages=True) From 28ee18c14a628671ebeb6105f3cd1ed02af02cc4 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Sun, 11 Aug 2024 22:50:49 +0200 Subject: [PATCH 172/199] Remove unused NodeScanner.active member (#527) The .active functionality was purged on June 9, 2017 with commit a28ef2762. --- canopen/network.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index 967d804a..e886b655 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -372,9 +372,6 @@ class NodeScanner: The network to use when doing active searching. """ - #: Activate or deactivate scanning - active = True - SERVICES = (0x700, 0x580, 0x180, 0x280, 0x380, 0x480, 0x80) def __init__(self, network: Optional[Network] = None): From 5004363e011b5f22b5e16825328189c81889a205 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Mon, 12 Aug 2024 09:27:54 +0200 Subject: [PATCH 173/199] Tests: improve EMCY coverage (#529) --- test/test_emcy.py | 257 ++++++++++++++++++++++++++++++++++++---------- 1 file changed, 203 insertions(+), 54 deletions(-) diff --git a/test/test_emcy.py b/test/test_emcy.py index 34c3ca29..a48f24fc 100644 --- a/test/test_emcy.py +++ b/test/test_emcy.py @@ -1,61 +1,210 @@ +import logging +import threading import unittest -from canopen import emcy - -class TestEmcyConsumer(unittest.TestCase): - - def test_emcy_list(self): - emcy_node = emcy.EmcyConsumer() - emcy_node.on_emcy(0x81, b'\x01\x20\x02\x00\x01\x02\x03\x04', 1473418396.0) - emcy_node.on_emcy(0x81, b'\x10\x90\x01\x00\x01\x02\x03\x04', 1473418397.0) - - self.assertEqual(len(emcy_node.log), 2) - self.assertEqual(len(emcy_node.active), 2) - - error = emcy_node.log[0] - self.assertIsInstance(error, emcy.EmcyError) - self.assertIsInstance(error, Exception) +import can +import canopen +from canopen.emcy import EmcyError + + +TIMEOUT = 0.1 + + +class TestEmcy(unittest.TestCase): + def setUp(self): + self.emcy = canopen.emcy.EmcyConsumer() + + def check_error(self, err, code, reg, data, ts): + self.assertIsInstance(err, EmcyError) + self.assertIsInstance(err, Exception) + self.assertEqual(err.code, code) + self.assertEqual(err.register, reg) + self.assertEqual(err.data, data) + self.assertAlmostEqual(err.timestamp, ts) + + def test_emcy_consumer_on_emcy(self): + # Make sure multiple callbacks receive the same information. + acc1 = [] + acc2 = [] + self.emcy.add_callback(lambda err: acc1.append(err)) + self.emcy.add_callback(lambda err: acc2.append(err)) + + # Dispatch an EMCY datagram. + self.emcy.on_emcy(0x81, b'\x01\x20\x02\x00\x01\x02\x03\x04', 1000) + + self.assertEqual(len(self.emcy.log), 1) + self.assertEqual(len(self.emcy.active), 1) + + error = self.emcy.log[0] + self.assertEqual(self.emcy.active[0], error) + for err in error, acc1[0], acc2[0]: + self.check_error( + error, code=0x2001, reg=0x02, + data=bytes([0, 1, 2, 3, 4]), ts=1000, + ) + + # Dispatch a new EMCY datagram. + self.emcy.on_emcy(0x81, b'\x10\x90\x01\x04\x03\x02\x01\x00', 2000) + self.assertEqual(len(self.emcy.log), 2) + self.assertEqual(len(self.emcy.active), 2) + + error = self.emcy.log[1] + self.assertEqual(self.emcy.active[1], error) + for err in error, acc1[1], acc2[1]: + self.check_error( + error, code=0x9010, reg=0x01, + data=bytes([4, 3, 2, 1, 0]), ts=2000, + ) + + # Dispatch an EMCY reset. + self.emcy.on_emcy(0x81, b'\x00\x00\x00\x00\x00\x00\x00\x00', 2000) + self.assertEqual(len(self.emcy.log), 3) + self.assertEqual(len(self.emcy.active), 0) + + def test_emcy_consumer_reset(self): + self.emcy.on_emcy(0x81, b'\x01\x20\x02\x00\x01\x02\x03\x04', 1000) + self.emcy.on_emcy(0x81, b'\x10\x90\x01\x04\x03\x02\x01\x00', 2000) + self.assertEqual(len(self.emcy.log), 2) + self.assertEqual(len(self.emcy.active), 2) + + self.emcy.reset() + self.assertEqual(len(self.emcy.log), 0) + self.assertEqual(len(self.emcy.active), 0) + + def test_emcy_consumer_wait(self): + PAUSE = TIMEOUT / 4 + + def push_err(): + self.emcy.on_emcy(0x81, b'\x01\x20\x01\x01\x02\x03\x04\x05', 100) + + def check_err(err): + self.assertIsNotNone(err) + self.check_error( + err, code=0x2001, reg=1, + data=bytes([1, 2, 3, 4, 5]), ts=100, + ) + + # Check unfiltered wait, on timeout. + self.assertIsNone(self.emcy.wait(timeout=TIMEOUT)) + + # Check unfiltered wait, on success. + timer = threading.Timer(PAUSE, push_err) + timer.start() + with self.assertLogs(level=logging.INFO): + err = self.emcy.wait(timeout=TIMEOUT) + check_err(err) + + # Check filtered wait, on success. + timer = threading.Timer(PAUSE, push_err) + timer.start() + with self.assertLogs(level=logging.INFO): + err = self.emcy.wait(0x2001, TIMEOUT) + check_err(err) + + # Check filtered wait, on timeout. + timer = threading.Timer(PAUSE, push_err) + timer.start() + self.assertIsNone(self.emcy.wait(0x9000, TIMEOUT)) + + def push_reset(): + self.emcy.on_emcy(0x81, b'\x00\x00\x00\x00\x00\x00\x00\x00', 100) + + timer = threading.Timer(PAUSE, push_reset) + timer.start() + self.assertIsNone(self.emcy.wait(0x9000, TIMEOUT)) + + +class TestEmcyError(unittest.TestCase): + def test_emcy_error(self): + error = EmcyError(0x2001, 0x02, b'\x00\x01\x02\x03\x04', 1000) self.assertEqual(error.code, 0x2001) - self.assertEqual(error.register, 0x02) self.assertEqual(error.data, b'\x00\x01\x02\x03\x04') - self.assertAlmostEqual(error.timestamp, 1473418396.0) - self.assertEqual(emcy_node.active[0], error) - - error = emcy_node.log[1] - self.assertEqual(error.code, 0x9010) - self.assertEqual(error.register, 0x01) - self.assertEqual(error.data, b'\x00\x01\x02\x03\x04') - self.assertAlmostEqual(error.timestamp, 1473418397.0) - self.assertEqual(emcy_node.active[1], error) - - emcy_node.on_emcy(0x81, b'\x00\x00\x00\x00\x00\x00\x00\x00', 1473418397.0) - self.assertEqual(len(emcy_node.log), 3) - self.assertEqual(len(emcy_node.active), 0) - - def test_str(self): - error = emcy.EmcyError(0x2001, 0x02, b'\x00\x01\x02\x03\x04', 1473418396.0) - self.assertEqual(str(error), "Code 0x2001, Current") - - error = emcy.EmcyError(0x50FF, 0x01, b'\x00\x01\x02\x03\x04', 1473418396.0) - self.assertEqual(str(error), "Code 0x50FF, Device Hardware") - - error = emcy.EmcyError(0x7100, 0x01, b'\x00\x01\x02\x03\x04', 1473418396.0) - self.assertEqual(str(error), "Code 0x7100") - - -class MockNetwork(object): - - data = None - - def send_message(self, can_id, data): - self.data = data + self.assertEqual(error.register, 2) + self.assertEqual(error.timestamp, 1000) + + def test_emcy_str(self): + def check(code, expected): + err = EmcyError(code, 1, b'', 1000) + actual = str(err) + self.assertEqual(actual, expected) + + check(0x2001, "Code 0x2001, Current") + check(0x3abc, "Code 0x3ABC, Voltage") + check(0x0234, "Code 0x0234") + check(0xbeef, "Code 0xBEEF") + + def test_emcy_get_desc(self): + def check(code, expected): + err = EmcyError(code, 1, b'', 1000) + actual = err.get_desc() + self.assertEqual(actual, expected) + + check(0x0000, "Error Reset / No Error") + check(0x00ff, "Error Reset / No Error") + check(0x0100, "") + check(0x1000, "Generic Error") + check(0x10ff, "Generic Error") + check(0x1100, "") + check(0x2000, "Current") + check(0x2fff, "Current") + check(0x3000, "Voltage") + check(0x3fff, "Voltage") + check(0x4000, "Temperature") + check(0x4fff, "Temperature") + check(0x5000, "Device Hardware") + check(0x50ff, "Device Hardware") + check(0x5100, "") + check(0x6000, "Device Software") + check(0x6fff, "Device Software") + check(0x7000, "Additional Modules") + check(0x70ff, "Additional Modules") + check(0x7100, "") + check(0x8000, "Monitoring") + check(0x8fff, "Monitoring") + check(0x9000, "External Error") + check(0x90ff, "External Error") + check(0x9100, "") + check(0xf000, "Additional Functions") + check(0xf0ff, "Additional Functions") + check(0xf100, "") + check(0xff00, "Device Specific") + check(0xffff, "Device Specific") class TestEmcyProducer(unittest.TestCase): - - def test_send(self): - network = MockNetwork() - emcy_node = emcy.EmcyProducer(0x80 + 1) - emcy_node.network = network - emcy_node.send(0x2001, 0x2, b'\x00\x01\x02\x03\x04') - self.assertEqual(network.data, b'\x01\x20\x02\x00\x01\x02\x03\x04') + def setUp(self): + self.txbus = can.Bus(interface="virtual") + self.rxbus = can.Bus(interface="virtual") + self.net = canopen.Network(self.txbus) + self.net.connect() + self.emcy = canopen.emcy.EmcyProducer(0x80 + 1) + self.emcy.network = self.net + + def tearDown(self): + self.net.disconnect() + self.txbus.shutdown() + self.rxbus.shutdown() + + def check_response(self, expected): + msg = self.rxbus.recv(TIMEOUT) + self.assertIsNotNone(msg) + actual = msg.data + self.assertEqual(actual, expected) + + def test_emcy_producer_send(self): + def check(*args, res): + self.emcy.send(*args) + self.check_response(res) + + check(0x2001, res=b'\x01\x20\x00\x00\x00\x00\x00\x00') + check(0x2001, 0x2, res=b'\x01\x20\x02\x00\x00\x00\x00\x00') + check(0x2001, 0x2, b'\x2a', res=b'\x01\x20\x02\x2a\x00\x00\x00\x00') + + def test_emcy_producer_reset(self): + def check(*args, res): + self.emcy.reset(*args) + self.check_response(res) + + check(res=b'\x00\x00\x00\x00\x00\x00\x00\x00') + check(3, res=b'\x00\x00\x03\x00\x00\x00\x00\x00') + check(3, b"\xaa\xbb", res=b'\x00\x00\x03\xaa\xbb\x00\x00\x00') From 78f6dded0b714e542dd0c5bac7af73b8012b499c Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Mon, 12 Aug 2024 09:45:51 +0200 Subject: [PATCH 174/199] Docs: remove unused Sphinx config 'html_static_path' (#521) --- doc/conf.py | 1 - 1 file changed, 1 deletion(-) diff --git a/doc/conf.py b/doc/conf.py index ecd59f31..97012efc 100644 --- a/doc/conf.py +++ b/doc/conf.py @@ -44,7 +44,6 @@ # https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-output html_theme = 'furo' -html_static_path = ['_static'] # -- Options for HTML help output -------------------------------------------- # https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-help-output From 83594ac89ee8f07d3bf346f3ceeab3b52d954625 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Mon, 12 Aug 2024 10:22:00 +0200 Subject: [PATCH 175/199] Tests: improve SYNC coverage (#531) --- test/test_sync.py | 76 ++++++++++++++++++++++++++++++++++++++--------- 1 file changed, 62 insertions(+), 14 deletions(-) diff --git a/test/test_sync.py b/test/test_sync.py index a88fd0b5..2ff3e9d3 100644 --- a/test/test_sync.py +++ b/test/test_sync.py @@ -1,29 +1,77 @@ +import threading import unittest + +import can import canopen +PERIOD = 0.01 +TIMEOUT = PERIOD * 10 + + class TestSync(unittest.TestCase): + def setUp(self): + self.net = canopen.Network() + self.net.connect(interface="virtual") + self.sync = canopen.sync.SyncProducer(self.net) + self.rxbus = can.Bus(interface="virtual") - def test_sync_producer(self): - network = canopen.Network() - network.connect(interface="virtual", receive_own_messages=True) - producer = canopen.sync.SyncProducer(network) - producer.transmit() - msg = network.bus.recv(1) - network.disconnect() + def tearDown(self): + self.net.disconnect() + self.rxbus.shutdown() + + def test_sync_producer_transmit(self): + self.sync.transmit() + msg = self.rxbus.recv(TIMEOUT) + self.assertIsNotNone(msg) self.assertEqual(msg.arbitration_id, 0x80) self.assertEqual(msg.dlc, 0) - def test_sync_producer_counter(self): - network = canopen.Network() - network.connect(interface="virtual", receive_own_messages=True) - producer = canopen.sync.SyncProducer(network) - producer.transmit(2) - msg = network.bus.recv(1) - network.disconnect() + def test_sync_producer_transmit_count(self): + self.sync.transmit(2) + msg = self.rxbus.recv(TIMEOUT) + self.assertIsNotNone(msg) self.assertEqual(msg.arbitration_id, 0x80) self.assertEqual(msg.dlc, 1) self.assertEqual(msg.data, b"\x02") + def test_sync_producer_start_invalid_period(self): + with self.assertRaises(ValueError): + self.sync.start(0) + + def test_sync_producer_start(self): + self.sync.start(PERIOD) + self.addCleanup(self.sync.stop) + + acc = [] + condition = threading.Condition() + + def hook(id_, data, ts): + item = id_, data, ts + acc.append(item) + condition.notify() + + def periodicity(): + # Check if periodicity has been established. + if len(acc) > 2: + delta = acc[-1][2] - acc[-2][2] + return round(delta, ndigits=1) == PERIOD + + # Sample messages. + with condition: + condition.wait_for(periodicity, TIMEOUT) + for msg in acc: + self.assertIsNotNone(msg) + self.assertEqual(msg[0], 0x80) + self.assertEqual(msg[1], b"") + + self.sync.stop() + # A message may have been in flight when we stopped the timer, + # so allow a single failure. + msg = self.rxbus.recv(TIMEOUT) + if msg is not None: + self.assertIsNone(self.net.bus.recv(TIMEOUT)) + + if __name__ == "__main__": unittest.main() From 4301c4bfed020565bfdb939deaf30b8d49de5727 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Mon, 12 Aug 2024 12:01:01 +0200 Subject: [PATCH 176/199] Tests: harden test_emcy_consumer_wait (#532) * Tests: harden test_emcy_consumer_wait Wait a little bit longer before dispatching the EMCY packet, and start the one-shot timer just before invoking the wait() call. * Better resource management --- test/test_emcy.py | 39 ++++++++++++++++++++++++--------------- 1 file changed, 24 insertions(+), 15 deletions(-) diff --git a/test/test_emcy.py b/test/test_emcy.py index a48f24fc..a09b8eb9 100644 --- a/test/test_emcy.py +++ b/test/test_emcy.py @@ -1,6 +1,7 @@ import logging import threading import unittest +from contextlib import contextmanager import can import canopen @@ -72,7 +73,7 @@ def test_emcy_consumer_reset(self): self.assertEqual(len(self.emcy.active), 0) def test_emcy_consumer_wait(self): - PAUSE = TIMEOUT / 4 + PAUSE = TIMEOUT / 2 def push_err(): self.emcy.on_emcy(0x81, b'\x01\x20\x01\x01\x02\x03\x04\x05', 100) @@ -84,34 +85,42 @@ def check_err(err): data=bytes([1, 2, 3, 4, 5]), ts=100, ) + @contextmanager + def timer(func): + t = threading.Timer(PAUSE, func) + try: + yield t + finally: + t.join(TIMEOUT) + # Check unfiltered wait, on timeout. self.assertIsNone(self.emcy.wait(timeout=TIMEOUT)) # Check unfiltered wait, on success. - timer = threading.Timer(PAUSE, push_err) - timer.start() - with self.assertLogs(level=logging.INFO): - err = self.emcy.wait(timeout=TIMEOUT) + with timer(push_err) as t: + with self.assertLogs(level=logging.INFO): + t.start() + err = self.emcy.wait(timeout=TIMEOUT) check_err(err) # Check filtered wait, on success. - timer = threading.Timer(PAUSE, push_err) - timer.start() - with self.assertLogs(level=logging.INFO): - err = self.emcy.wait(0x2001, TIMEOUT) + with timer(push_err) as t: + with self.assertLogs(level=logging.INFO): + t.start() + err = self.emcy.wait(0x2001, TIMEOUT) check_err(err) # Check filtered wait, on timeout. - timer = threading.Timer(PAUSE, push_err) - timer.start() - self.assertIsNone(self.emcy.wait(0x9000, TIMEOUT)) + with timer(push_err) as t: + t.start() + self.assertIsNone(self.emcy.wait(0x9000, TIMEOUT)) def push_reset(): self.emcy.on_emcy(0x81, b'\x00\x00\x00\x00\x00\x00\x00\x00', 100) - timer = threading.Timer(PAUSE, push_reset) - timer.start() - self.assertIsNone(self.emcy.wait(0x9000, TIMEOUT)) + with timer(push_reset) as t: + t.start() + self.assertIsNone(self.emcy.wait(0x9000, TIMEOUT)) class TestEmcyError(unittest.TestCase): From 932c6212bf077596dbfec91fd6ca66308142b972 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Mon, 12 Aug 2024 12:59:10 +0200 Subject: [PATCH 177/199] CI: Add requirements-dev.txt and add pip cache (#533) Also: - bump GitHub checkout action to v4 - bump GitHub setup-python action to v5 - ignore README and LICENSE files - invoke pip according to best practise Follow-up of #498 --- .github/workflows/pythonpackage.yml | 28 ++++++++++++++++++---------- README.rst | 2 +- requirements-dev.txt | 2 ++ 3 files changed, 21 insertions(+), 11 deletions(-) create mode 100644 requirements-dev.txt diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 427ad9c7..71c11242 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -5,9 +5,17 @@ name: Python package on: push: - branches: [ "master" ] + branches: + - 'master' + paths-ignore: + - 'README.rst' + - 'LICENSE.txt' pull_request: - branches: [ "master" ] + branches: + - 'master' + paths-ignore: + - 'README.rst' + - 'LICENSE.txt' jobs: build: @@ -20,19 +28,19 @@ jobs: features: ['', '[db_export]'] steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Set up Python ${{ matrix.python-version }} - uses: actions/setup-python@v3 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python-version }} + cache: 'pip' + cache-dependency-path: | + 'pyproject.toml' + 'requirements-dev.txt' - name: Install dependencies - run: | - python -m pip install --upgrade pip - pip install pytest pytest-cov - pip install -e '.${{ matrix.features }}' + run: python3 -m pip install -e '.${{ matrix.features }}' -r requirements-dev.txt - name: Test with pytest - run: | - pytest -v --cov=canopen --cov-report=xml --cov-branch + run: pytest -v --cov=canopen --cov-report=xml --cov-branch - name: Upload coverage reports to Codecov uses: codecov/codecov-action@v4 with: diff --git a/README.rst b/README.rst index daf9fda2..90359b0d 100644 --- a/README.rst +++ b/README.rst @@ -53,7 +53,7 @@ it in `develop mode`_:: Unit tests can be run using the pytest_ framework:: - $ pip install pytest + $ pip install -r requirements-dev.txt $ pytest -v You can also use :mod:`unittest` standard library module:: diff --git a/requirements-dev.txt b/requirements-dev.txt new file mode 100644 index 00000000..1a1c1f37 --- /dev/null +++ b/requirements-dev.txt @@ -0,0 +1,2 @@ +pytest~=8.3 +pytest-cov~=5.0 From 6ef4f5e35d84a7d776d1758842bc8138215e9715 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Wed, 14 Aug 2024 12:47:13 +0200 Subject: [PATCH 178/199] Make Network.notifier timeouts customizable (fixes #530) (#536) * Add configurable timeouts for Network.notifier. Move the hard-coded 1 second maximum cycle duration passed during can.Notifier construction to a class variable NOTIFIER_CYCLE. Explicitly specify the timeout to stop the notifier in another class variable NOTIFIER_SHUTDOWN_TIMEOUT, matching the default used in python-can. These can be overridden per instance if needed. * Do not wait for notifier thread shutdown during tests. Explicitly set the NOTIFIER_SHUTDOWN_TIMEOUT to zero in all Network instances created for unit tests. This reduces total test running time from ~30 to ~9 seconds when run locally. --- canopen/network.py | 7 +++++-- test/test_emcy.py | 1 + test/test_local.py | 4 ++++ test/test_network.py | 3 +++ test/test_nmt.py | 3 +++ test/test_sdo.py | 2 ++ test/test_sync.py | 1 + test/test_time.py | 1 + 8 files changed, 20 insertions(+), 2 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index e886b655..31584085 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -25,6 +25,9 @@ class Network(MutableMapping): """Representation of one CAN bus containing one or more nodes.""" + NOTIFIER_CYCLE: float = 1.0 #: Maximum waiting time for one notifier iteration. + NOTIFIER_SHUTDOWN_TIMEOUT: float = 5.0 #: Maximum waiting time to stop notifiers. + def __init__(self, bus: Optional[can.BusABC] = None): """ :param can.BusABC bus: @@ -105,7 +108,7 @@ def connect(self, *args, **kwargs) -> Network: if self.bus is None: self.bus = can.Bus(*args, **kwargs) logger.info("Connected to '%s'", self.bus.channel_info) - self.notifier = can.Notifier(self.bus, self.listeners, 1) + self.notifier = can.Notifier(self.bus, self.listeners, self.NOTIFIER_CYCLE) return self def disconnect(self) -> None: @@ -117,7 +120,7 @@ def disconnect(self) -> None: if hasattr(node, "pdo"): node.pdo.stop() if self.notifier is not None: - self.notifier.stop() + self.notifier.stop(self.NOTIFIER_SHUTDOWN_TIMEOUT) if self.bus is not None: self.bus.shutdown() self.bus = None diff --git a/test/test_emcy.py b/test/test_emcy.py index a09b8eb9..b8d7b4e1 100644 --- a/test/test_emcy.py +++ b/test/test_emcy.py @@ -185,6 +185,7 @@ def setUp(self): self.txbus = can.Bus(interface="virtual") self.rxbus = can.Bus(interface="virtual") self.net = canopen.Network(self.txbus) + self.net.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 self.net.connect() self.emcy = canopen.emcy.EmcyProducer(0x80 + 1) self.emcy.network = self.net diff --git a/test/test_local.py b/test/test_local.py index 9c5fc0c1..5f7929c9 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -13,10 +13,12 @@ class TestSDO(unittest.TestCase): @classmethod def setUpClass(cls): cls.network1 = canopen.Network() + cls.network1.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 cls.network1.connect("test", interface="virtual") cls.remote_node = cls.network1.add_node(2, SAMPLE_EDS) cls.network2 = canopen.Network() + cls.network2.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 cls.network2.connect("test", interface="virtual") cls.local_node = cls.network2.create_node(2, SAMPLE_EDS) @@ -176,10 +178,12 @@ class TestPDO(unittest.TestCase): @classmethod def setUpClass(cls): cls.network1 = canopen.Network() + cls.network1.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 cls.network1.connect("test", interface="virtual") cls.remote_node = cls.network1.add_node(2, SAMPLE_EDS) cls.network2 = canopen.Network() + cls.network2.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 cls.network2.connect("test", interface="virtual") cls.local_node = cls.network2.create_node(2, SAMPLE_EDS) diff --git a/test/test_network.py b/test/test_network.py index a87954d3..3a59a597 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -11,6 +11,7 @@ class TestNetwork(unittest.TestCase): def setUp(self): self.network = canopen.Network() + self.network.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 def test_network_add_node(self): # Add using str. @@ -328,6 +329,7 @@ def test_scanner_search(self): self.addCleanup(txbus.shutdown) net = canopen.Network(txbus) + net.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 net.connect() self.addCleanup(net.disconnect) @@ -347,6 +349,7 @@ def test_scanner_search(self): def test_scanner_search_limit(self): bus = can.Bus(interface="virtual", receive_own_messages=True) net = canopen.Network(bus) + net.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 net.connect() self.addCleanup(net.disconnect) diff --git a/test/test_nmt.py b/test/test_nmt.py index 059e1982..ae295435 100644 --- a/test/test_nmt.py +++ b/test/test_nmt.py @@ -52,6 +52,7 @@ def setUp(self): receive_own_messages=True, ) net = canopen.Network(bus) + net.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 net.connect() with self.assertLogs(): node = net.add_node(self.NODE_ID, SAMPLE_EDS) @@ -127,11 +128,13 @@ def test_nmt_master_node_guarding(self): class TestNmtSlave(unittest.TestCase): def setUp(self): self.network1 = canopen.Network() + self.network1.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 self.network1.connect("test", interface="virtual") with self.assertLogs(): self.remote_node = self.network1.add_node(2, SAMPLE_EDS) self.network2 = canopen.Network() + self.network2.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 self.network2.connect("test", interface="virtual") with self.assertLogs(): self.local_node = self.network2.create_node(2, SAMPLE_EDS) diff --git a/test/test_sdo.py b/test/test_sdo.py index f399a33f..d3d0dfb6 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -31,6 +31,7 @@ def _send_message(self, can_id, data, remote=False): def setUp(self): network = canopen.Network() + network.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 network.send_message = self._send_message node = network.add_node(2, SAMPLE_EDS) node.sdo.RESPONSE_TIMEOUT = 0.01 @@ -181,6 +182,7 @@ def _send_message(self, can_id, data, remote=False): def setUp(self): network = canopen.Network() + network.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 network.send_message = self._send_message node = network.add_node(2, DATATYPES_EDS) node.sdo.RESPONSE_TIMEOUT = 0.01 diff --git a/test/test_sync.py b/test/test_sync.py index 2ff3e9d3..f376d2a1 100644 --- a/test/test_sync.py +++ b/test/test_sync.py @@ -12,6 +12,7 @@ class TestSync(unittest.TestCase): def setUp(self): self.net = canopen.Network() + self.net.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 self.net.connect(interface="virtual") self.sync = canopen.sync.SyncProducer(self.net) self.rxbus = can.Bus(interface="virtual") diff --git a/test/test_time.py b/test/test_time.py index a5922442..71a84622 100644 --- a/test/test_time.py +++ b/test/test_time.py @@ -6,6 +6,7 @@ class TestTime(unittest.TestCase): def test_time_producer(self): network = canopen.Network() + network.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 network.connect(interface="virtual", receive_own_messages=True) producer = canopen.timestamp.TimeProducer(network) producer.transmit(1486236238) From 1b7c06f57ba8a46afbddfa2b4ca29196e63a465d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Wed, 14 Aug 2024 23:17:36 +0200 Subject: [PATCH 179/199] Fix some type checker errors in network module (#534) * Annotate PeriodicMessageTask in NmtMaster and NmtSlave. * Type annotate Network.notifier. * Remove duplicate initialization of PeriodicMessageTask._task. The attribute is set within the method directly following. So there is no need to initialize it to None before, only to confuse type checkers. --- canopen/network.py | 3 +-- canopen/nmt.py | 10 +++++++--- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index 31584085..cd754c8c 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -41,7 +41,7 @@ def __init__(self, bus: Optional[can.BusABC] = None): #: List of :class:`can.Listener` objects. #: Includes at least MessageListener. self.listeners = [MessageListener(self)] - self.notifier = None + self.notifier: Optional[can.Notifier] = None self.nodes: Dict[int, Union[RemoteNode, LocalNode]] = {} self.subscribers: Dict[int, List[Callback]] = {} self.send_lock = threading.Lock() @@ -311,7 +311,6 @@ def __init__( self.msg = can.Message(is_extended_id=can_id > 0x7FF, arbitration_id=can_id, data=data, is_remote_frame=remote) - self._task = None self._start() def _start(self): diff --git a/canopen/nmt.py b/canopen/nmt.py index 8ce737ea..125042d3 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -2,7 +2,11 @@ import logging import struct import time -from typing import Callable, Optional +from typing import Callable, Optional, TYPE_CHECKING + +if TYPE_CHECKING: + from canopen.network import PeriodicMessageTask + logger = logging.getLogger(__name__) @@ -107,7 +111,7 @@ class NmtMaster(NmtBase): def __init__(self, node_id: int): super(NmtMaster, self).__init__(node_id) self._state_received = None - self._node_guarding_producer = None + self._node_guarding_producer: Optional[PeriodicMessageTask] = None #: Timestamp of last heartbeat message self.timestamp: Optional[float] = None self.state_update = threading.Condition() @@ -197,7 +201,7 @@ class NmtSlave(NmtBase): def __init__(self, node_id: int, local_node): super(NmtSlave, self).__init__(node_id) - self._send_task = None + self._send_task: Optional[PeriodicMessageTask] = None self._heartbeat_time_ms = 0 self._local_node = local_node From 210374a857b8afbb9fb2bf2a93d374f4e0f70563 Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Thu, 15 Aug 2024 08:46:09 +0200 Subject: [PATCH 180/199] Tests: speed up test suite (#537) * Speed up NMT tests * Make test_emcy, test_eds, and test_od executable scripts * Harden and speed up test_network_send_periodic() * Shorten heartbeat period in test_local * Join as cleanup action * Fix test_network_send_periodic() periodicity test --- test/test_eds.py | 4 ++++ test/test_emcy.py | 4 ++++ test/test_local.py | 4 ++-- test/test_network.py | 55 +++++++++++++++++++++---------------------- test/test_nmt.py | 56 +++++++++++++++++++++++++------------------- test/test_od.py | 4 ++++ 6 files changed, 73 insertions(+), 54 deletions(-) diff --git a/test/test_eds.py b/test/test_eds.py index 775b7a41..986010f4 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -357,3 +357,7 @@ def verify_od(self, source, doctype): f" mismatch on {pretty_index(evar.index, evar.subindex)}") self.assertEqual(self.od.comments, exported_od.comments) + + +if __name__ == "__main__": + unittest.main() diff --git a/test/test_emcy.py b/test/test_emcy.py index b8d7b4e1..f9ad87e4 100644 --- a/test/test_emcy.py +++ b/test/test_emcy.py @@ -218,3 +218,7 @@ def check(*args, res): check(res=b'\x00\x00\x00\x00\x00\x00\x00\x00') check(3, res=b'\x00\x00\x03\x00\x00\x00\x00\x00') check(3, b"\xaa\xbb", res=b'\x00\x00\x03\xaa\xbb\x00\x00\x00') + + +if __name__ == "__main__": + unittest.main() diff --git a/test/test_local.py b/test/test_local.py index 5f7929c9..5f6d477b 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -89,7 +89,7 @@ def test_segmented_download(self): def test_slave_send_heartbeat(self): # Setting the heartbeat time should trigger heartbeating # to start - self.remote_node.sdo["Producer heartbeat time"].raw = 1000 + self.remote_node.sdo["Producer heartbeat time"].raw = 100 state = self.remote_node.nmt.wait_for_heartbeat() self.local_node.nmt.stop_heartbeat() # The NMT master will change the state INITIALISING (0) @@ -98,7 +98,7 @@ def test_slave_send_heartbeat(self): def test_nmt_state_initializing_to_preoper(self): # Initialize the heartbeat timer - self.local_node.sdo["Producer heartbeat time"].raw = 1000 + self.local_node.sdo["Producer heartbeat time"].raw = 100 self.local_node.nmt.stop_heartbeat() # This transition shall start the heartbeating self.local_node.nmt.state = 'INITIALISING' diff --git a/test/test_network.py b/test/test_network.py index 3a59a597..c08baaca 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -1,6 +1,7 @@ import logging -import unittest import threading +import time +import unittest import canopen import can @@ -231,59 +232,57 @@ def test_network_send_periodic(self): DATA1 = bytes([1, 2, 3]) DATA2 = bytes([4, 5, 6]) COB_ID = 0x123 - PERIOD = 0.1 + PERIOD = 0.01 TIMEOUT = PERIOD * 10 - self.network.connect(interface="virtual", receive_own_messages=True) + self.network.connect(interface="virtual") self.addCleanup(self.network.disconnect) - acc = [] - condition = threading.Condition() - - def hook(_, data, ts): - with condition: - item = data, ts - acc.append(item) - condition.notify_all() + bus = can.Bus(interface="virtual") + self.addCleanup(bus.shutdown) - self.network.subscribe(COB_ID, hook) - self.addCleanup(self.network.unsubscribe, COB_ID) + acc = [] task = self.network.send_periodic(COB_ID, DATA1, PERIOD) self.addCleanup(task.stop) - def periodicity(): + def wait_for_periodicity(): # Check if periodicity is established; flakiness has been observed # on macOS. - if len(acc) >= 2: - delta = acc[-1][1] - acc[-2][1] - return round(delta, ndigits=1) == PERIOD - return False + end_time = time.time() + TIMEOUT + while time.time() < end_time: + if msg := bus.recv(PERIOD): + acc.append(msg) + if len(acc) >= 2: + first, last = acc[-2:] + delta = last.timestamp - first.timestamp + if round(delta, ndigits=2) == PERIOD: + return + self.fail("Timed out") # Wait for frames to arrive; then check the result. - with condition: - condition.wait_for(periodicity, TIMEOUT) - self.assertTrue(all(v[0] == DATA1 for v in acc)) + wait_for_periodicity() + self.assertTrue(all([v.data == DATA1 for v in acc])) # Update task data, which may implicitly restart the timer. # Wait for frames to arrive; then check the result. task.update(DATA2) - with condition: - acc.clear() - condition.wait_for(periodicity, TIMEOUT) + acc.clear() + wait_for_periodicity() # Find the first message with new data, and verify that all subsequent # messages also carry the new payload. - data = [v[0] for v in acc] + data = [v.data for v in acc] + self.assertIn(DATA2, data) idx = data.index(DATA2) - self.assertTrue(all(v[0] == DATA2 for v in acc[idx:])) + self.assertTrue(all([v.data == DATA2 for v in acc[idx:]])) # Stop the task. task.stop() # A message may have been in flight when we stopped the timer, # so allow a single failure. bus = self.network.bus - msg = bus.recv(TIMEOUT) + msg = bus.recv(PERIOD) if msg is not None: - self.assertIsNone(bus.recv(TIMEOUT)) + self.assertIsNone(bus.recv(PERIOD)) class TestScanner(unittest.TestCase): diff --git a/test/test_nmt.py b/test/test_nmt.py index ae295435..85efb11d 100644 --- a/test/test_nmt.py +++ b/test/test_nmt.py @@ -1,3 +1,4 @@ +import threading import time import unittest @@ -41,28 +42,28 @@ def test_state_set_invalid(self): class TestNmtMaster(unittest.TestCase): NODE_ID = 2 - COB_ID = 0x700 + NODE_ID PERIOD = 0.01 - TIMEOUT = PERIOD * 2 + TIMEOUT = PERIOD * 10 def setUp(self): - bus = can.ThreadSafeBus( - interface="virtual", - channel="test", - receive_own_messages=True, - ) - net = canopen.Network(bus) + net = canopen.Network() net.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 - net.connect() + net.connect(interface="virtual") with self.assertLogs(): node = net.add_node(self.NODE_ID, SAMPLE_EDS) - self.bus = bus + self.bus = can.Bus(interface="virtual") self.net = net self.node = node def tearDown(self): self.net.disconnect() + self.bus.shutdown() + + def dispatch_heartbeat(self, code): + cob_id = 0x700 + self.NODE_ID + hb = can.Message(arbitration_id=cob_id, data=[code]) + self.bus.send(hb) def test_nmt_master_no_heartbeat(self): with self.assertRaisesRegex(NmtError, "heartbeat"): @@ -74,39 +75,46 @@ def test_nmt_master_on_heartbeat(self): # Skip the special INITIALISING case. for code in [st for st in NMT_STATES if st != 0]: with self.subTest(code=code): - task = self.net.send_periodic(self.COB_ID, [code], self.PERIOD) - try: - actual = self.node.nmt.wait_for_heartbeat(self.TIMEOUT) - finally: - task.stop() + t = threading.Timer(0.01, self.dispatch_heartbeat, args=(code,)) + t.start() + self.addCleanup(t.join) + actual = self.node.nmt.wait_for_heartbeat(0.1) expected = NMT_STATES[code] self.assertEqual(actual, expected) - def test_nmt_master_on_heartbeat_initialising(self): - task = self.net.send_periodic(self.COB_ID, [0], self.PERIOD) - self.addCleanup(task.stop) + def test_nmt_master_wait_for_bootup(self): + t = threading.Timer(0.01, self.dispatch_heartbeat, args=(0x00,)) + t.start() + self.addCleanup(t.join) self.node.nmt.wait_for_bootup(self.TIMEOUT) + self.assertEqual(self.node.nmt.state, "PRE-OPERATIONAL") + + def test_nmt_master_on_heartbeat_initialising(self): + t = threading.Timer(0.01, self.dispatch_heartbeat, args=(0x00,)) + t.start() + self.addCleanup(t.join) state = self.node.nmt.wait_for_heartbeat(self.TIMEOUT) self.assertEqual(state, "PRE-OPERATIONAL") def test_nmt_master_on_heartbeat_unknown_state(self): - task = self.net.send_periodic(self.COB_ID, [0xcb], self.PERIOD) - self.addCleanup(task.stop) + t = threading.Timer(0.01, self.dispatch_heartbeat, args=(0xcb,)) + t.start() + self.addCleanup(t.join) state = self.node.nmt.wait_for_heartbeat(self.TIMEOUT) # Expect the high bit to be masked out, and a formatted string to # be returned. self.assertEqual(state, "UNKNOWN STATE '75'") def test_nmt_master_add_heartbeat_callback(self): - from threading import Event - event = Event() + event = threading.Event() state = None def hook(st): nonlocal state state = st event.set() self.node.nmt.add_heartbeat_callback(hook) - self.net.send_message(self.COB_ID, bytes([127])) + + self.dispatch_heartbeat(0x7f) self.assertTrue(event.wait(self.TIMEOUT)) self.assertEqual(state, 127) @@ -114,7 +122,7 @@ def test_nmt_master_node_guarding(self): self.node.nmt.start_node_guarding(self.PERIOD) msg = self.bus.recv(self.TIMEOUT) self.assertIsNotNone(msg) - self.assertEqual(msg.arbitration_id, self.COB_ID) + self.assertEqual(msg.arbitration_id, 0x700 + self.NODE_ID) self.assertEqual(msg.dlc, 0) self.node.nmt.stop_node_guarding() diff --git a/test/test_od.py b/test/test_od.py index d3755234..2c2b9591 100644 --- a/test/test_od.py +++ b/test/test_od.py @@ -261,3 +261,7 @@ def test_subindexes(self): self.assertEqual(array[1].name, "Test Variable") self.assertEqual(array[2].name, "Test Variable 2") self.assertEqual(array[3].name, "Test Variable_3") + + +if __name__ == "__main__": + unittest.main() From 273bab17400f0eb14c5e9e7714fa88de3fce2e7f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Sat, 17 Aug 2024 22:59:54 +0200 Subject: [PATCH 181/199] Tests: Verify some basic SDO record and array assumptions (#539) * Remove one of the sub-objects in a record for testing. Adjust the EDS test accordingly, since the record length only counts sub-objects that have an actual description. * Flesh out the Pre-defined error field object in sample.eds. Switch from CompactSubObj to actual sub-entries. Leave out some of the sub-entries, targeting specific SDO tests. * Add test for SdoArray dynamically generated member variables. * Add test for SdoArray length and iteration count. * Add test for SdoRecord length and iteration count. * Expect failure on last added test. --- test/sample.eds | 60 ++++++++++++++++++++++++++++++++++++++++++------ test/test_eds.py | 2 +- test/test_sdo.py | 39 +++++++++++++++++++++++++++++++ 3 files changed, 93 insertions(+), 8 deletions(-) diff --git a/test/sample.eds b/test/sample.eds index 3c1bbcf9..1afe9965 100644 --- a/test/sample.eds +++ b/test/sample.eds @@ -100,12 +100,7 @@ DataType=0x0007 AccessType=ro PDOMapping=0 -[1018sub3] -ParameterName=Revision number -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -PDOMapping=0 +; [1018sub3] left out for testing [1018sub4] ParameterName=Serial number @@ -123,11 +118,62 @@ SupportedObjects=3 [1003] ParameterName=Pre-defined error field ObjectType=0x8 -CompactSubObj=255 +SubNumber=9 + +[1003sub0] +ParameterName=Number of errors +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=3 +PDOMapping=0 + +[1003sub1] +ParameterName=Pre-defined error field_1 +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +; [1003sub2] left out for testing + +[1003sub3] +ParameterName=Pre-defined error field_3 +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +[1003sub4] +ParameterName=Pre-defined error field_4 +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +[1003sub5] +ParameterName=Pre-defined error field_5 +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +; [1003sub6] left out for testing + +[1003sub7] +ParameterName=Pre-defined error field_7 +ObjectType=0x7 DataType=0x0007 AccessType=ro +DefaultValue=0 PDOMapping=0 +; [1003sub8] left out for testing + [1008] ParameterName=Manufacturer device name ObjectType=0x7 diff --git a/test/test_eds.py b/test/test_eds.py index 986010f4..12c3c2fa 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -121,7 +121,7 @@ def test_relative_variable(self): def test_record(self): record = self.od['Identity object'] self.assertIsInstance(record, canopen.objectdictionary.ODRecord) - self.assertEqual(len(record), 5) + self.assertEqual(len(record), 4) self.assertEqual(record.index, 0x1018) self.assertEqual(record.name, 'Identity object') var = record['Vendor-ID'] diff --git a/test/test_sdo.py b/test/test_sdo.py index d3d0dfb6..212fc7f5 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -10,6 +10,45 @@ RX = 2 +class TestSDOVariables(unittest.TestCase): + """Some basic assumptions on the behavior of SDO variable objects. + + Mostly what is stated in the API docs. + """ + + def setUp(self): + node = canopen.LocalNode(1, SAMPLE_EDS) + self.sdo_node = node.sdo + + @unittest.expectedFailure + def test_record_iter_length(self): + """Assume the "highest subindex supported" entry is not counted. + + Sub-objects without an OD entry should be skipped as well. + """ + record = self.sdo_node[0x1018] + subs = sum(1 for _ in iter(record)) + self.assertEqual(len(record), 3) + self.assertEqual(subs, 3) + + def test_array_iter_length(self): + """Assume the "highest subindex supported" entry is not counted.""" + array = self.sdo_node[0x1003] + subs = sum(1 for _ in iter(array)) + self.assertEqual(len(array), 3) + self.assertEqual(subs, 3) + # Simulate more entries getting added dynamically + array[0].set_data(b'\x08') + subs = sum(1 for _ in iter(array)) + self.assertEqual(subs, 8) + + def test_array_members_dynamic(self): + """Check if sub-objects missing from OD entry are generated dynamically.""" + array = self.sdo_node[0x1003] + for var in array.values(): + self.assertIsInstance(var, canopen.sdo.SdoVariable) + + class TestSDO(unittest.TestCase): """ Test SDO traffic by example. Most are taken from From 6bc90a817f049b52fbeb1201c699e90ca36a6136 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Sat, 17 Aug 2024 23:05:14 +0200 Subject: [PATCH 182/199] Skip the "highest subindex" entry when iterating over SdoRecord (#538) The count entry itself is not part of the data (according to CiA 301), thus should not be yielded from an iterator. That matches the behavior of SdoArray, which also yields only the array contents. Note that the basis of returned record sub-objects is still the subset described by the OD, which might be smaller than the actual entries accessible on the node, and less than indicated by the record's subindex 0. Thus the count (and iteration set) is reduced by one element only if the subindex 0 was actually part of this subset. * No need to expect test failure anymore. --- canopen/sdo/base.py | 7 +++++-- doc/sdo.rst | 23 +++++++++++++++-------- test/test_sdo.py | 1 - 3 files changed, 20 insertions(+), 11 deletions(-) diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 0bb068b4..81d5e710 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -105,10 +105,12 @@ def __getitem__(self, subindex: Union[int, str]) -> SdoVariable: return SdoVariable(self.sdo_node, self.od[subindex]) def __iter__(self) -> Iterator[int]: - return iter(self.od) + # Skip the "highest subindex" entry, which is not part of the data + return filter(None, iter(self.od)) def __len__(self) -> int: - return len(self.od) + # Skip the "highest subindex" entry, which is not part of the data + return len(self.od) - int(0 in self.od) def __contains__(self, subindex: Union[int, str]) -> bool: return subindex in self.od @@ -127,6 +129,7 @@ def __getitem__(self, subindex: Union[int, str]) -> SdoVariable: return SdoVariable(self.sdo_node, self.od[subindex]) def __iter__(self) -> Iterator[int]: + # Skip the "highest subindex" entry, which is not part of the data return iter(range(1, len(self) + 1)) def __len__(self) -> int: diff --git a/doc/sdo.rst b/doc/sdo.rst index a1436572..29314028 100644 --- a/doc/sdo.rst +++ b/doc/sdo.rst @@ -189,7 +189,10 @@ API .. describe:: iter(record) - Return an iterator over the subindexes from the record. + Return an iterator over the subindexes from the record. Only those with + a matching object dictionary entry are considered. The "highest + subindex" entry is officially not part of the data and thus skipped in + the yielded values. .. describe:: subindex in record @@ -198,7 +201,9 @@ API .. describe:: len(record) - Return the number of subindexes in the record. + Return the number of subindexes in the record, not counting the "highest + subindex" entry itself. Only those with a matching object dictionary + entry are considered. .. method:: values() @@ -220,25 +225,27 @@ API .. describe:: iter(array) Return an iterator over the subindexes from the array. - This will make a SDO read operation on subindex 0 in order to get the - actual length of the array. + This will make an SDO read operation on subindex 0 in order to get the + actual length of the array. This "highest subindex" entry is officially + not part of the data and thus skipped in the yielded values. .. describe:: subindex in array Return ``True`` if the subindex (as int) or name (as string) exists in the array. - This will make a SDO read operation on subindex 0 in order to get the + This will make an SDO read operation on subindex 0 in order to get the actual length of the array. .. describe:: len(array) - Return the length of the array. - This will make a SDO read operation on subindex 0. + Return the length of the array, not counting the "highest subindex" entry + itself. + This will make an SDO read operation on subindex 0. .. method:: values() Return a list of :class:`canopen.sdo.SdoVariable` in the array. - This will make a SDO read operation on subindex 0 in order to get the + This will make an SDO read operation on subindex 0 in order to get the actual length of the array. diff --git a/test/test_sdo.py b/test/test_sdo.py index 212fc7f5..993d4acc 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -20,7 +20,6 @@ def setUp(self): node = canopen.LocalNode(1, SAMPLE_EDS) self.sdo_node = node.sdo - @unittest.expectedFailure def test_record_iter_length(self): """Assume the "highest subindex supported" entry is not counted. From c781a225f60b1b5d39cfdad713d3d5bb4799c844 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Thu, 17 Oct 2024 21:36:11 +0200 Subject: [PATCH 183/199] Add a dummy object to designate "uninitialized" networks (fixes #511) (#525) Add an _UnitializedNetwork class and a singleton _UNINITIALIZED_NETWORK instance. It can replace the dummy "None" value for attribute initializations, which can then be properly typed as Network to avoid static type checking errors. This has the benefit of not needing `self.network is not None` checks at run-time wherever a method or attribute access is used, but still satisfies static type checking. When hitting such a code path at run-time, of course it will lead to an exception because the attributes required in the Network methods are not set. But that is a case of wrong API usage (accessing a network without associating it first), which a static checker cannot detect reliably. The dummy class provides a descriptive exception message when any attribute is accessed on it. --- canopen/emcy.py | 5 ++++- canopen/lss.py | 7 +++++-- canopen/network.py | 17 ++++++++++++++++- canopen/nmt.py | 4 +++- canopen/node/base.py | 8 +++++++- canopen/node/local.py | 19 +++++++++++-------- canopen/node/remote.py | 21 ++++++++++++--------- canopen/pdo/base.py | 4 ++-- canopen/sdo/base.py | 3 ++- 9 files changed, 62 insertions(+), 26 deletions(-) diff --git a/canopen/emcy.py b/canopen/emcy.py index 1bbdeb75..520cfdc0 100644 --- a/canopen/emcy.py +++ b/canopen/emcy.py @@ -4,6 +4,9 @@ import time from typing import Callable, List, Optional +import canopen.network + + # Error code, error register, vendor specific data EMCY_STRUCT = struct.Struct(" None: + self.network: canopen.network.Network = canopen.network._UNINITIALIZED_NETWORK self._node_id = 0 self._data = None self.responses = queue.Queue() diff --git a/canopen/network.py b/canopen/network.py index cd754c8c..9d6e66c6 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -3,7 +3,7 @@ from collections.abc import MutableMapping import logging import threading -from typing import Callable, Dict, Iterator, List, Optional, Union +from typing import Callable, Dict, Final, Iterator, List, Optional, Union import can from can import Listener @@ -282,6 +282,21 @@ def __len__(self) -> int: return len(self.nodes) +class _UninitializedNetwork(Network): + """Empty network implementation as a placeholder before actual initialization.""" + + def __init__(self, bus: Optional[can.BusABC] = None): + """Do not initialize attributes, by skipping the parent constructor.""" + + def __getattribute__(self, name): + raise RuntimeError("No actual Network object was assigned, " + "try associating to a real network first.") + + +#: Singleton instance +_UNINITIALIZED_NETWORK: Final[Network] = _UninitializedNetwork() + + class PeriodicMessageTask: """ Task object to transmit a message periodically using python-can's diff --git a/canopen/nmt.py b/canopen/nmt.py index 125042d3..6f29e917 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -4,6 +4,8 @@ import time from typing import Callable, Optional, TYPE_CHECKING +import canopen.network + if TYPE_CHECKING: from canopen.network import PeriodicMessageTask @@ -49,7 +51,7 @@ class NmtBase: def __init__(self, node_id: int): self.id = node_id - self.network = None + self.network: canopen.network.Network = canopen.network._UNINITIALIZED_NETWORK self._state = 0 def on_command(self, can_id, data, timestamp): diff --git a/canopen/node/base.py b/canopen/node/base.py index bf72d959..45ad35b4 100644 --- a/canopen/node/base.py +++ b/canopen/node/base.py @@ -1,4 +1,6 @@ from typing import TextIO, Union + +import canopen.network from canopen.objectdictionary import ObjectDictionary, import_od @@ -17,10 +19,14 @@ def __init__( node_id: int, object_dictionary: Union[ObjectDictionary, str, TextIO], ): - self.network = None + self.network: canopen.network.Network = canopen.network._UNINITIALIZED_NETWORK if not isinstance(object_dictionary, ObjectDictionary): object_dictionary = import_od(object_dictionary, node_id) self.object_dictionary = object_dictionary self.id = node_id or self.object_dictionary.node_id + + def has_network(self) -> bool: + """Check whether the node has been associated to a network.""" + return not isinstance(self.network, canopen.network._UninitializedNetwork) diff --git a/canopen/node/local.py b/canopen/node/local.py index eb74b98d..eb614601 100644 --- a/canopen/node/local.py +++ b/canopen/node/local.py @@ -1,6 +1,9 @@ +from __future__ import annotations + import logging from typing import Dict, Union +import canopen.network from canopen.node.base import BaseNode from canopen.sdo import SdoServer, SdoAbortedError from canopen.pdo import PDO, TPDO, RPDO @@ -34,7 +37,7 @@ def __init__( self.add_write_callback(self.nmt.on_write) self.emcy = EmcyProducer(0x80 + self.id) - def associate_network(self, network): + def associate_network(self, network: canopen.network.Network): self.network = network self.sdo.network = network self.tpdo.network = network @@ -44,15 +47,15 @@ def associate_network(self, network): network.subscribe(self.sdo.rx_cobid, self.sdo.on_request) network.subscribe(0, self.nmt.on_command) - def remove_network(self): + def remove_network(self) -> None: self.network.unsubscribe(self.sdo.rx_cobid, self.sdo.on_request) self.network.unsubscribe(0, self.nmt.on_command) - self.network = None - self.sdo.network = None - self.tpdo.network = None - self.rpdo.network = None - self.nmt.network = None - self.emcy.network = None + self.network = canopen.network._UNINITIALIZED_NETWORK + self.sdo.network = canopen.network._UNINITIALIZED_NETWORK + self.tpdo.network = canopen.network._UNINITIALIZED_NETWORK + self.rpdo.network = canopen.network._UNINITIALIZED_NETWORK + self.nmt.network = canopen.network._UNINITIALIZED_NETWORK + self.emcy.network = canopen.network._UNINITIALIZED_NETWORK def add_read_callback(self, callback): self._read_callbacks.append(callback) diff --git a/canopen/node/remote.py b/canopen/node/remote.py index 4f3281db..b354b8f9 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -1,6 +1,9 @@ +from __future__ import annotations + import logging from typing import Union, TextIO +import canopen.network from canopen.sdo import SdoClient, SdoCommunicationError, SdoAbortedError from canopen.nmt import NmtMaster from canopen.emcy import EmcyConsumer @@ -46,7 +49,7 @@ def __init__( if load_od: self.load_configuration() - def associate_network(self, network): + def associate_network(self, network: canopen.network.Network): self.network = network self.sdo.network = network self.pdo.network = network @@ -59,18 +62,18 @@ def associate_network(self, network): network.subscribe(0x80 + self.id, self.emcy.on_emcy) network.subscribe(0, self.nmt.on_command) - def remove_network(self): + def remove_network(self) -> None: for sdo in self.sdo_channels: self.network.unsubscribe(sdo.tx_cobid, sdo.on_response) self.network.unsubscribe(0x700 + self.id, self.nmt.on_heartbeat) self.network.unsubscribe(0x80 + self.id, self.emcy.on_emcy) self.network.unsubscribe(0, self.nmt.on_command) - self.network = None - self.sdo.network = None - self.pdo.network = None - self.tpdo.network = None - self.rpdo.network = None - self.nmt.network = None + self.network = canopen.network._UNINITIALIZED_NETWORK + self.sdo.network = canopen.network._UNINITIALIZED_NETWORK + self.pdo.network = canopen.network._UNINITIALIZED_NETWORK + self.tpdo.network = canopen.network._UNINITIALIZED_NETWORK + self.rpdo.network = canopen.network._UNINITIALIZED_NETWORK + self.nmt.network = canopen.network._UNINITIALIZED_NETWORK def add_sdo(self, rx_cobid, tx_cobid): """Add an additional SDO channel. @@ -87,7 +90,7 @@ def add_sdo(self, rx_cobid, tx_cobid): """ client = SdoClient(rx_cobid, tx_cobid, self.object_dictionary) self.sdo_channels.append(client) - if self.network is not None: + if self.has_network(): self.network.subscribe(client.tx_cobid, client.on_response) return client diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index f2a7d205..dc81aa60 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -6,12 +6,12 @@ import logging import binascii +import canopen.network from canopen.sdo import SdoAbortedError from canopen import objectdictionary from canopen import variable if TYPE_CHECKING: - from canopen.network import Network from canopen import LocalNode, RemoteNode from canopen.pdo import RPDO, TPDO from canopen.sdo import SdoRecord @@ -30,7 +30,7 @@ class PdoBase(Mapping): """ def __init__(self, node: Union[LocalNode, RemoteNode]): - self.network: Optional[Network] = None + self.network: canopen.network.Network = canopen.network._UNINITIALIZED_NETWORK self.map: Optional[PdoMaps] = None self.node: Union[LocalNode, RemoteNode] = node diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 81d5e710..39b10634 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -4,6 +4,7 @@ from typing import Iterator, Optional, Union from collections.abc import Mapping +import canopen.network from canopen import objectdictionary from canopen import variable from canopen.utils import pretty_index @@ -43,7 +44,7 @@ def __init__( """ self.rx_cobid = rx_cobid self.tx_cobid = tx_cobid - self.network = None + self.network: canopen.network.Network = canopen.network._UNINITIALIZED_NETWORK self.od = od def __getitem__( From ffbd10f44da89e407622c82b8587fcc64e3f2f49 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Fri, 18 Oct 2024 09:20:29 +0200 Subject: [PATCH 184/199] Clean up imports ordering. Follow recommendations from flake8 regarding import order and grouping. Put two blank lines after the top import block in each file. Import CanError directly from can package in canopen.sdo.client instead of from canopen.network, where it was not even used. --- canopen/__init__.py | 12 +++++++++--- canopen/emcy.py | 2 +- canopen/lss.py | 4 ++-- canopen/network.py | 14 +++++++------- canopen/nmt.py | 2 +- canopen/node/__init__.py | 2 +- canopen/node/local.py | 11 ++++++----- canopen/node/remote.py | 11 ++++++----- canopen/objectdictionary/__init__.py | 6 ++++-- canopen/objectdictionary/datatypes.py | 1 + canopen/objectdictionary/eds.py | 3 ++- canopen/objectdictionary/epf.py | 3 ++- canopen/pdo/base.py | 12 +++++++----- canopen/profiles/p402.py | 1 + canopen/profiles/tools/test_p402_states.py | 2 +- canopen/sdo/__init__.py | 6 +++--- canopen/sdo/base.py | 2 +- canopen/sdo/client.py | 12 +++++++----- canopen/sdo/server.py | 1 + canopen/timestamp.py | 3 ++- canopen/utils.py | 1 + canopen/variable.py | 3 ++- examples/simple_ds402_node.py | 7 ++++--- test/test_eds.py | 3 ++- test/test_emcy.py | 1 + test/test_local.py | 1 + test/test_network.py | 5 +++-- test/test_nmt.py | 4 +++- test/test_od.py | 1 + test/test_pdo.py | 1 + test/test_sdo.py | 3 ++- test/test_sync.py | 1 + test/test_time.py | 1 + test/test_utils.py | 1 + 34 files changed, 89 insertions(+), 54 deletions(-) diff --git a/canopen/__init__.py b/canopen/__init__.py index 9bd19b1d..ab1ccf37 100644 --- a/canopen/__init__.py +++ b/canopen/__init__.py @@ -1,8 +1,14 @@ from canopen.network import Network, NodeScanner -from canopen.node import RemoteNode, LocalNode -from canopen.sdo import SdoCommunicationError, SdoAbortedError -from canopen.objectdictionary import import_od, export_od, ObjectDictionary, ObjectDictionaryError +from canopen.node import LocalNode, RemoteNode +from canopen.objectdictionary import ( + ObjectDictionary, + ObjectDictionaryError, + export_od, + import_od, +) from canopen.profiles.p402 import BaseNode402 +from canopen.sdo import SdoAbortedError, SdoCommunicationError + try: from canopen._version import version as __version__ except ImportError: diff --git a/canopen/emcy.py b/canopen/emcy.py index 520cfdc0..ec2c489f 100644 --- a/canopen/emcy.py +++ b/canopen/emcy.py @@ -1,5 +1,5 @@ -import struct import logging +import struct import threading import time from typing import Callable, List, Optional diff --git a/canopen/lss.py b/canopen/lss.py index 5ffcc11b..7c0b92a6 100644 --- a/canopen/lss.py +++ b/canopen/lss.py @@ -1,7 +1,7 @@ import logging -import time -import struct import queue +import struct +import time import canopen.network diff --git a/canopen/network.py b/canopen/network.py index 9d6e66c6..02bec899 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -1,21 +1,21 @@ from __future__ import annotations -from collections.abc import MutableMapping import logging import threading +from collections.abc import MutableMapping from typing import Callable, Dict, Final, Iterator, List, Optional, Union import can from can import Listener -from can import CanError -from canopen.node import RemoteNode, LocalNode -from canopen.sync import SyncProducer -from canopen.timestamp import TimeProducer -from canopen.nmt import NmtMaster from canopen.lss import LssMaster -from canopen.objectdictionary.eds import import_from_node +from canopen.nmt import NmtMaster +from canopen.node import LocalNode, RemoteNode from canopen.objectdictionary import ObjectDictionary +from canopen.objectdictionary.eds import import_from_node +from canopen.sync import SyncProducer +from canopen.timestamp import TimeProducer + logger = logging.getLogger(__name__) diff --git a/canopen/nmt.py b/canopen/nmt.py index 6f29e917..622e0a33 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -1,6 +1,6 @@ -import threading import logging import struct +import threading import time from typing import Callable, Optional, TYPE_CHECKING diff --git a/canopen/node/__init__.py b/canopen/node/__init__.py index 31fed19e..704c8564 100644 --- a/canopen/node/__init__.py +++ b/canopen/node/__init__.py @@ -1,2 +1,2 @@ -from canopen.node.remote import RemoteNode from canopen.node.local import LocalNode +from canopen.node.remote import RemoteNode diff --git a/canopen/node/local.py b/canopen/node/local.py index eb614601..8f2493d9 100644 --- a/canopen/node/local.py +++ b/canopen/node/local.py @@ -4,13 +4,14 @@ from typing import Dict, Union import canopen.network -from canopen.node.base import BaseNode -from canopen.sdo import SdoServer, SdoAbortedError -from canopen.pdo import PDO, TPDO, RPDO -from canopen.nmt import NmtSlave +from canopen import objectdictionary from canopen.emcy import EmcyProducer +from canopen.nmt import NmtSlave +from canopen.node.base import BaseNode from canopen.objectdictionary import ObjectDictionary -from canopen import objectdictionary +from canopen.pdo import PDO, RPDO, TPDO +from canopen.sdo import SdoAbortedError, SdoServer + logger = logging.getLogger(__name__) diff --git a/canopen/node/remote.py b/canopen/node/remote.py index b354b8f9..226c0c0f 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -1,15 +1,16 @@ from __future__ import annotations import logging -from typing import Union, TextIO +from typing import TextIO, Union import canopen.network -from canopen.sdo import SdoClient, SdoCommunicationError, SdoAbortedError -from canopen.nmt import NmtMaster from canopen.emcy import EmcyConsumer -from canopen.pdo import TPDO, RPDO, PDO -from canopen.objectdictionary import ODRecord, ODArray, ODVariable, ObjectDictionary +from canopen.nmt import NmtMaster from canopen.node.base import BaseNode +from canopen.objectdictionary import ODArray, ODRecord, ODVariable, ObjectDictionary +from canopen.pdo import PDO, RPDO, TPDO +from canopen.sdo import SdoAbortedError, SdoClient, SdoCommunicationError + logger = logging.getLogger(__name__) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 1e80283b..09fe6e03 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -1,17 +1,19 @@ """ Object Dictionary module """ + from __future__ import annotations +import logging import struct +from collections.abc import Mapping, MutableMapping from typing import Dict, Iterator, List, Optional, TextIO, Union -from collections.abc import MutableMapping, Mapping -import logging from canopen.objectdictionary.datatypes import * from canopen.objectdictionary.datatypes import IntegerN, UnsignedN from canopen.utils import pretty_index + logger = logging.getLogger(__name__) diff --git a/canopen/objectdictionary/datatypes.py b/canopen/objectdictionary/datatypes.py index ad37fe6f..e4afd673 100644 --- a/canopen/objectdictionary/datatypes.py +++ b/canopen/objectdictionary/datatypes.py @@ -1,5 +1,6 @@ import struct + BOOLEAN = 0x1 INTEGER8 = 0x2 INTEGER16 = 0x3 diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index 3884d809..b77f9782 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -1,12 +1,13 @@ import copy import logging import re -from configparser import RawConfigParser, NoOptionError, NoSectionError +from configparser import NoOptionError, NoSectionError, RawConfigParser from canopen import objectdictionary from canopen.objectdictionary import ObjectDictionary, datatypes from canopen.sdo import SdoClient + logger = logging.getLogger(__name__) # Object type. Don't confuse with Data type diff --git a/canopen/objectdictionary/epf.py b/canopen/objectdictionary/epf.py index 46ffe59e..02d62033 100644 --- a/canopen/objectdictionary/epf.py +++ b/canopen/objectdictionary/epf.py @@ -1,9 +1,10 @@ -import xml.etree.ElementTree as etree import logging +import xml.etree.ElementTree as etree from canopen import objectdictionary from canopen.objectdictionary import ObjectDictionary + logger = logging.getLogger(__name__) DATA_TYPES = { diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index dc81aa60..0ba65199 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -1,21 +1,23 @@ from __future__ import annotations -import threading + +import binascii +import logging import math -from typing import Callable, Dict, Iterator, List, Optional, Union, TYPE_CHECKING +import threading from collections.abc import Mapping -import logging -import binascii +from typing import Callable, Dict, Iterator, List, Optional, TYPE_CHECKING, Union import canopen.network -from canopen.sdo import SdoAbortedError from canopen import objectdictionary from canopen import variable +from canopen.sdo import SdoAbortedError if TYPE_CHECKING: from canopen import LocalNode, RemoteNode from canopen.pdo import RPDO, TPDO from canopen.sdo import SdoRecord + PDO_NOT_VALID = 1 << 31 RTR_NOT_ALLOWED = 1 << 30 diff --git a/canopen/profiles/p402.py b/canopen/profiles/p402.py index 10156d01..88d86aad 100644 --- a/canopen/profiles/p402.py +++ b/canopen/profiles/p402.py @@ -7,6 +7,7 @@ from canopen.pdo import PdoMap from canopen.sdo import SdoCommunicationError + logger = logging.getLogger(__name__) diff --git a/canopen/profiles/tools/test_p402_states.py b/canopen/profiles/tools/test_p402_states.py index 721865db..6bb147ad 100644 --- a/canopen/profiles/tools/test_p402_states.py +++ b/canopen/profiles/tools/test_p402_states.py @@ -7,7 +7,7 @@ """ from canopen.objectdictionary import ObjectDictionary -from canopen.profiles.p402 import State402, BaseNode402 +from canopen.profiles.p402 import BaseNode402, State402 if __name__ == '__main__': diff --git a/canopen/sdo/__init__.py b/canopen/sdo/__init__.py index 39b8478c..25128605 100644 --- a/canopen/sdo/__init__.py +++ b/canopen/sdo/__init__.py @@ -1,7 +1,7 @@ -from canopen.sdo.base import SdoVariable, SdoRecord, SdoArray +from canopen.sdo.base import SdoArray, SdoRecord, SdoVariable from canopen.sdo.client import SdoClient -from canopen.sdo.server import SdoServer from canopen.sdo.exceptions import SdoAbortedError, SdoCommunicationError +from canopen.sdo.server import SdoServer # Compatibility -from canopen.sdo.base import Variable, Record, Array +from canopen.sdo.base import Array, Record, Variable diff --git a/canopen/sdo/base.py b/canopen/sdo/base.py index 39b10634..ddc75ed9 100644 --- a/canopen/sdo/base.py +++ b/canopen/sdo/base.py @@ -1,8 +1,8 @@ from __future__ import annotations import binascii -from typing import Iterator, Optional, Union from collections.abc import Mapping +from typing import Iterator, Optional, Union import canopen.network from canopen import objectdictionary diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index e4c50aa8..421fc3d4 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -1,15 +1,17 @@ -import struct -import logging import io -import time +import logging import queue +import struct +import time + +from can import CanError -from canopen.network import CanError from canopen import objectdictionary from canopen.sdo.base import SdoBase -from canopen.utils import pretty_index from canopen.sdo.constants import * from canopen.sdo.exceptions import * +from canopen.utils import pretty_index + logger = logging.getLogger(__name__) diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index e2a16e61..c6a4c27c 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -4,6 +4,7 @@ from canopen.sdo.constants import * from canopen.sdo.exceptions import * + logger = logging.getLogger(__name__) diff --git a/canopen/timestamp.py b/canopen/timestamp.py index f3004da2..21dcc636 100644 --- a/canopen/timestamp.py +++ b/canopen/timestamp.py @@ -1,7 +1,8 @@ -import time import struct +import time from typing import Optional + # 1 Jan 1984 OFFSET = 441763200 diff --git a/canopen/utils.py b/canopen/utils.py index 37feda93..7ddffda3 100644 --- a/canopen/utils.py +++ b/canopen/utils.py @@ -1,4 +1,5 @@ """Additional utility functions for canopen.""" + from typing import Optional, Union diff --git a/canopen/variable.py b/canopen/variable.py index 3ec67c79..d2538c3f 100644 --- a/canopen/variable.py +++ b/canopen/variable.py @@ -1,10 +1,11 @@ import logging -from typing import Union from collections.abc import Mapping +from typing import Union from canopen import objectdictionary from canopen.utils import pretty_index + logger = logging.getLogger(__name__) diff --git a/examples/simple_ds402_node.py b/examples/simple_ds402_node.py index b9b96180..7b24b9b5 100644 --- a/examples/simple_ds402_node.py +++ b/examples/simple_ds402_node.py @@ -1,9 +1,10 @@ -import canopen -import sys import os +import sys +import time import traceback -import time +import canopen + try: diff --git a/test/test_eds.py b/test/test_eds.py index 12c3c2fa..68f5ad3c 100644 --- a/test/test_eds.py +++ b/test/test_eds.py @@ -4,7 +4,8 @@ import canopen from canopen.objectdictionary.eds import _signed_int_from_hex from canopen.utils import pretty_index -from .util import SAMPLE_EDS, DATATYPES_EDS, tmp_file + +from .util import DATATYPES_EDS, SAMPLE_EDS, tmp_file class TestEDS(unittest.TestCase): diff --git a/test/test_emcy.py b/test/test_emcy.py index f9ad87e4..d883e9c8 100644 --- a/test/test_emcy.py +++ b/test/test_emcy.py @@ -4,6 +4,7 @@ from contextlib import contextmanager import can + import canopen from canopen.emcy import EmcyError diff --git a/test/test_local.py b/test/test_local.py index 5f6d477b..e184c040 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -2,6 +2,7 @@ import unittest import canopen + from .util import SAMPLE_EDS diff --git a/test/test_network.py b/test/test_network.py index c08baaca..1d45a1c2 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -1,10 +1,11 @@ import logging -import threading import time import unittest -import canopen import can + +import canopen + from .util import SAMPLE_EDS diff --git a/test/test_nmt.py b/test/test_nmt.py index 85efb11d..636126dc 100644 --- a/test/test_nmt.py +++ b/test/test_nmt.py @@ -3,8 +3,10 @@ import unittest import can + import canopen -from canopen.nmt import COMMAND_TO_STATE, NMT_STATES, NMT_COMMANDS, NmtError +from canopen.nmt import COMMAND_TO_STATE, NMT_COMMANDS, NMT_STATES, NmtError + from .util import SAMPLE_EDS diff --git a/test/test_od.py b/test/test_od.py index 2c2b9591..52de86f8 100644 --- a/test/test_od.py +++ b/test/test_od.py @@ -1,4 +1,5 @@ import unittest + from canopen import objectdictionary as od diff --git a/test/test_pdo.py b/test/test_pdo.py index e3ad219f..1badc89d 100644 --- a/test/test_pdo.py +++ b/test/test_pdo.py @@ -1,6 +1,7 @@ import unittest import canopen + from .util import SAMPLE_EDS, tmp_file diff --git a/test/test_sdo.py b/test/test_sdo.py index 993d4acc..6fe8544c 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -3,7 +3,8 @@ import canopen import canopen.objectdictionary.datatypes as dt from canopen.objectdictionary import ODVariable -from .util import SAMPLE_EDS, DATATYPES_EDS + +from .util import DATATYPES_EDS, SAMPLE_EDS TX = 1 diff --git a/test/test_sync.py b/test/test_sync.py index f376d2a1..93633538 100644 --- a/test/test_sync.py +++ b/test/test_sync.py @@ -2,6 +2,7 @@ import unittest import can + import canopen diff --git a/test/test_time.py b/test/test_time.py index 71a84622..acd2b490 100644 --- a/test/test_time.py +++ b/test/test_time.py @@ -1,4 +1,5 @@ import unittest + import canopen diff --git a/test/test_utils.py b/test/test_utils.py index b412e365..a17cce92 100644 --- a/test/test_utils.py +++ b/test/test_utils.py @@ -1,4 +1,5 @@ import unittest + from canopen.utils import pretty_index From ae71853be7fb42870bb5763066b0c3c50d015669 Mon Sep 17 00:00:00 2001 From: Thomas Willson Date: Sun, 5 Jan 2025 14:01:16 -0800 Subject: [PATCH 185/199] Fix SDO writes of empty strings (#551) Previously, when attempting a write of "" to a VISIBLE_STRING, the expedited SDO request would not be sent and the transaction would timeout. To resolve this, if the transaction size is known to be 0, a segmented transfer is used. --- canopen/sdo/client.py | 2 +- test/test_sdo.py | 17 +++++++++++++++++ 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 421fc3d4..c08d92be 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -353,7 +353,7 @@ def __init__(self, sdo_client, index, subindex=0, size=None, force_segment=False self._exp_header = None self._done = False - if size is None or size > 4 or force_segment: + if size is None or size < 1 or size > 4 or force_segment: # Initiate segmented download request = bytearray(8) command = REQUEST_DOWNLOAD diff --git a/test/test_sdo.py b/test/test_sdo.py index 6fe8544c..e4036efe 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -68,6 +68,8 @@ def _send_message(self, can_id, data, remote=False): while self.data and self.data[0][0] == RX: self.network.notify(0x582, self.data.pop(0)[1], 0.0) + self.message_sent = True + def setUp(self): network = canopen.Network() network.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 @@ -76,6 +78,8 @@ def setUp(self): node.sdo.RESPONSE_TIMEOUT = 0.01 self.network = network + self.message_sent = False + def test_expedited_upload(self): self.data = [ (TX, b'\x40\x18\x10\x01\x00\x00\x00\x00'), @@ -91,6 +95,7 @@ def test_expedited_upload(self): ] trans_type = self.network[2].sdo[0x1400]['Transmission type RPDO 1'].raw self.assertEqual(trans_type, 254) + self.assertTrue(self.message_sent) def test_size_not_specified(self): self.data = [ @@ -100,6 +105,7 @@ def test_size_not_specified(self): # Make sure the size of the data is 1 byte data = self.network[2].sdo.upload(0x1400, 2) self.assertEqual(data, b'\xfe') + self.assertTrue(self.message_sent) def test_expedited_download(self): self.data = [ @@ -107,6 +113,7 @@ def test_expedited_download(self): (RX, b'\x60\x17\x10\x00\x00\x00\x00\x00') ] self.network[2].sdo[0x1017].raw = 4000 + self.assertTrue(self.message_sent) def test_segmented_upload(self): self.data = [ @@ -153,6 +160,16 @@ def test_block_download(self): 'wb', size=len(data), block_transfer=True) as fp: fp.write(data) + def test_segmented_download_zero_length(self): + self.data = [ + (TX, b'\x21\x00\x20\x00\x00\x00\x00\x00'), + (RX, b'\x60\x00\x20\x00\x00\x00\x00\x00'), + (TX, b'\x0F\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x20\x00\x00\x00\x00\x00\x00\x00'), + ] + self.network[2].sdo[0x2000].raw = "" + self.assertTrue(self.message_sent) + def test_block_upload(self): self.data = [ (TX, b'\xa4\x08\x10\x00\x7f\x00\x00\x00'), From 5382f245d8ede61b113c6a648cb99b199667f0cd Mon Sep 17 00:00:00 2001 From: Tony Baltovski Date: Thu, 20 Feb 2025 15:20:22 -0500 Subject: [PATCH 186/199] Updated debian packaging for reprepro (#557) --- makedeb | 2 ++ 1 file changed, 2 insertions(+) diff --git a/makedeb b/makedeb index 591ffc11..28e7bca4 100755 --- a/makedeb +++ b/makedeb @@ -31,6 +31,8 @@ mkdir $package_dir/DEBIAN cat > $package_dir/DEBIAN/control < Date: Sun, 6 Apr 2025 12:25:00 +0200 Subject: [PATCH 187/199] Update GitHub URLs to new organization --- README.rst | 4 ++-- pyproject.toml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/README.rst b/README.rst index 90359b0d..0014cd67 100644 --- a/README.rst +++ b/README.rst @@ -42,12 +42,12 @@ Install from PyPI_ using :program:`pip`:: Install from latest ``master`` on GitHub:: - $ pip install https://github.com/christiansandberg/canopen/archive/master.zip + $ pip install https://github.com/canopen-python/canopen/archive/master.zip If you want to be able to change the code while using it, clone it then install it in `develop mode`_:: - $ git clone https://github.com/christiansandberg/canopen.git + $ git clone https://github.com/canopen-python/canopen.git $ cd canopen $ pip install -e . diff --git a/pyproject.toml b/pyproject.toml index a87ba589..a494188e 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -33,7 +33,7 @@ db_export = [ [project.urls] documentation = "https://canopen.readthedocs.io/en/stable/" -repository = "https://github.com/christiansandberg/canopen" +repository = "https://github.com/canopen-python/canopen" [tool.setuptools] packages = ["canopen"] From f1a71da20b918760ace20c62297f41132cd6618c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Sun, 27 Apr 2025 20:37:45 +0200 Subject: [PATCH 188/199] Bump Codecov action to version 5. --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 71c11242..18d45e49 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -42,7 +42,7 @@ jobs: - name: Test with pytest run: pytest -v --cov=canopen --cov-report=xml --cov-branch - name: Upload coverage reports to Codecov - uses: codecov/codecov-action@v4 + uses: codecov/codecov-action@v5 with: token: ${{ secrets.CODECOV_TOKEN }} From e840449fbf9ddf810d14899279cb72e61a2447f0 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Mon, 28 Apr 2025 22:36:54 +0200 Subject: [PATCH 189/199] Fix multiple associations and removals of networks (#573) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Fix multiple assosciations and removals of networks * Simplify cleanup logic in Network.unsubscribe(). Co-authored-by: André Colomb --- canopen/network.py | 6 +-- canopen/node/local.py | 4 ++ canopen/node/remote.py | 4 ++ test/test_node.py | 104 +++++++++++++++++++++++++++++++++++++++++ 4 files changed, 115 insertions(+), 3 deletions(-) create mode 100644 test/test_node.py diff --git a/canopen/network.py b/canopen/network.py index 02bec899..6f2777c8 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -75,10 +75,10 @@ def unsubscribe(self, can_id, callback=None) -> None: If given, remove only this callback. Otherwise all callbacks for the CAN ID. """ - if callback is None: - del self.subscribers[can_id] - else: + if callback is not None: self.subscribers[can_id].remove(callback) + if not self.subscribers[can_id] or callback is None: + del self.subscribers[can_id] def connect(self, *args, **kwargs) -> Network: """Connect to CAN bus using python-can. diff --git a/canopen/node/local.py b/canopen/node/local.py index 8f2493d9..34bba899 100644 --- a/canopen/node/local.py +++ b/canopen/node/local.py @@ -39,6 +39,8 @@ def __init__( self.emcy = EmcyProducer(0x80 + self.id) def associate_network(self, network: canopen.network.Network): + if self.has_network(): + raise RuntimeError("Node is already associated with a network") self.network = network self.sdo.network = network self.tpdo.network = network @@ -49,6 +51,8 @@ def associate_network(self, network: canopen.network.Network): network.subscribe(0, self.nmt.on_command) def remove_network(self) -> None: + if not self.has_network(): + return self.network.unsubscribe(self.sdo.rx_cobid, self.sdo.on_request) self.network.unsubscribe(0, self.nmt.on_command) self.network = canopen.network._UNINITIALIZED_NETWORK diff --git a/canopen/node/remote.py b/canopen/node/remote.py index 226c0c0f..371f784c 100644 --- a/canopen/node/remote.py +++ b/canopen/node/remote.py @@ -51,6 +51,8 @@ def __init__( self.load_configuration() def associate_network(self, network: canopen.network.Network): + if self.has_network(): + raise RuntimeError("Node is already associated with a network") self.network = network self.sdo.network = network self.pdo.network = network @@ -64,6 +66,8 @@ def associate_network(self, network: canopen.network.Network): network.subscribe(0, self.nmt.on_command) def remove_network(self) -> None: + if not self.has_network(): + return for sdo in self.sdo_channels: self.network.unsubscribe(sdo.tx_cobid, sdo.on_response) self.network.unsubscribe(0x700 + self.id, self.nmt.on_heartbeat) diff --git a/test/test_node.py b/test/test_node.py new file mode 100644 index 00000000..43373a2a --- /dev/null +++ b/test/test_node.py @@ -0,0 +1,104 @@ +import unittest + +import canopen + + +def count_subscribers(network: canopen.Network) -> int: + """Count the number of subscribers in the network.""" + return sum(len(n) for n in network.subscribers.values()) + + +class TestLocalNode(unittest.TestCase): + + @classmethod + def setUpClass(cls): + cls.network = canopen.Network() + cls.network.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 + cls.network.connect(interface="virtual") + + cls.node = canopen.LocalNode(2, canopen.objectdictionary.ObjectDictionary()) + + @classmethod + def tearDownClass(cls): + cls.network.disconnect() + + def test_associate_network(self): + # Need to store the number of subscribers before associating because the + # network implementation automatically adds subscribers to the list + n_subscribers = count_subscribers(self.network) + + # Associating the network with the local node + self.node.associate_network(self.network) + self.assertIs(self.node.network, self.network) + self.assertIs(self.node.sdo.network, self.network) + self.assertIs(self.node.tpdo.network, self.network) + self.assertIs(self.node.rpdo.network, self.network) + self.assertIs(self.node.nmt.network, self.network) + self.assertIs(self.node.emcy.network, self.network) + + # Test that its not possible to associate the network multiple times + with self.assertRaises(RuntimeError) as cm: + self.node.associate_network(self.network) + self.assertIn("already associated with a network", str(cm.exception)) + + # Test removal of the network. The count of subscribers should + # be the same as before the association + self.node.remove_network() + uninitalized = canopen.network._UNINITIALIZED_NETWORK + self.assertIs(self.node.network, uninitalized) + self.assertIs(self.node.sdo.network, uninitalized) + self.assertIs(self.node.tpdo.network, uninitalized) + self.assertIs(self.node.rpdo.network, uninitalized) + self.assertIs(self.node.nmt.network, uninitalized) + self.assertIs(self.node.emcy.network, uninitalized) + self.assertEqual(count_subscribers(self.network), n_subscribers) + + # Test that its possible to deassociate the network multiple times + self.node.remove_network() + + +class TestRemoteNode(unittest.TestCase): + + @classmethod + def setUpClass(cls): + cls.network = canopen.Network() + cls.network.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 + cls.network.connect(interface="virtual") + + cls.node = canopen.RemoteNode(2, canopen.objectdictionary.ObjectDictionary()) + + @classmethod + def tearDownClass(cls): + cls.network.disconnect() + + def test_associate_network(self): + # Need to store the number of subscribers before associating because the + # network implementation automatically adds subscribers to the list + n_subscribers = count_subscribers(self.network) + + # Associating the network with the local node + self.node.associate_network(self.network) + self.assertIs(self.node.network, self.network) + self.assertIs(self.node.sdo.network, self.network) + self.assertIs(self.node.tpdo.network, self.network) + self.assertIs(self.node.rpdo.network, self.network) + self.assertIs(self.node.nmt.network, self.network) + + # Test that its not possible to associate the network multiple times + with self.assertRaises(RuntimeError) as cm: + self.node.associate_network(self.network) + self.assertIn("already associated with a network", str(cm.exception)) + + # Test removal of the network. The count of subscribers should + # be the same as before the association + self.node.remove_network() + uninitalized = canopen.network._UNINITIALIZED_NETWORK + self.assertIs(self.node.network, uninitalized) + self.assertIs(self.node.sdo.network, uninitalized) + self.assertIs(self.node.tpdo.network, uninitalized) + self.assertIs(self.node.rpdo.network, uninitalized) + self.assertIs(self.node.nmt.network, uninitalized) + self.assertEqual(count_subscribers(self.network), n_subscribers) + + # Test that its possible to deassociate the network multiple times + self.node.remove_network() From cf9f33ea88cbade2ee08037926c5a653396e6fab Mon Sep 17 00:00:00 2001 From: "Erlend E. Aasland" Date: Mon, 9 Jun 2025 13:50:47 +0200 Subject: [PATCH 190/199] Add mypy CI and config (ref #358) (#518) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Estalish a minimal mypy config that ensures annotations are compatible with Python 3.8 (the oldest supported Python version). Add a forgiving CI job that does not affect the status of the GitHub workflow run. Co-authored-by: André Colomb --- .github/workflows/pr-linters.yaml | 28 ++++++++++++++++++++++++++++ pyproject.toml | 8 ++++++++ requirements-dev.txt | 1 + 3 files changed, 37 insertions(+) create mode 100644 .github/workflows/pr-linters.yaml diff --git a/.github/workflows/pr-linters.yaml b/.github/workflows/pr-linters.yaml new file mode 100644 index 00000000..62abef4f --- /dev/null +++ b/.github/workflows/pr-linters.yaml @@ -0,0 +1,28 @@ +name: Run PR linters + +on: + pull_request: + workflow_dispatch: + +permissions: + contents: read + pull-requests: read + +jobs: + + mypy: + name: Run mypy static type checker (optional) + runs-on: ubuntu-latest + continue-on-error: true + steps: + - uses: actions/checkout@v4 + - uses: actions/setup-python@v5 + with: + python-version: 3.12 + cache: pip + cache-dependency-path: | + 'pyproject.toml' + 'requirements-dev.txt' + - run: pip install -r requirements-dev.txt -e . + - name: Run mypy and report + run: mypy --config-file pyproject.toml . diff --git a/pyproject.toml b/pyproject.toml index a494188e..e9f3b871 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -48,3 +48,11 @@ testpaths = [ filterwarnings = [ "ignore::DeprecationWarning", ] + +[tool.mypy] +python_version = "3.8" +exclude = [ + "^examples*", + "^test*", + "^setup.py*", +] diff --git a/requirements-dev.txt b/requirements-dev.txt index 1a1c1f37..23f3a7aa 100644 --- a/requirements-dev.txt +++ b/requirements-dev.txt @@ -1,2 +1,3 @@ +mypy~=1.10 pytest~=8.3 pytest-cov~=5.0 From bc917f057500cfa66cbe9b24fa80e268a40f7907 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Mon, 9 Jun 2025 14:01:06 +0200 Subject: [PATCH 191/199] Type annotate everywhere Network is used (#575) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: André Colomb --- canopen/network.py | 6 +++--- canopen/objectdictionary/eds.py | 8 +++++++- canopen/sync.py | 9 +++++++-- canopen/timestamp.py | 9 +++++++-- test/test_network.py | 2 +- 5 files changed, 25 insertions(+), 9 deletions(-) diff --git a/canopen/network.py b/canopen/network.py index 6f2777c8..4e85e5b5 100644 --- a/canopen/network.py +++ b/canopen/network.py @@ -392,7 +392,9 @@ class NodeScanner: SERVICES = (0x700, 0x580, 0x180, 0x280, 0x380, 0x480, 0x80) def __init__(self, network: Optional[Network] = None): - self.network = network + if network is None: + network = _UNINITIALIZED_NETWORK + self.network: Network = network #: A :class:`list` of nodes discovered self.nodes: List[int] = [] @@ -408,8 +410,6 @@ def reset(self): def search(self, limit: int = 127) -> None: """Search for nodes by sending SDO requests to all node IDs.""" - if self.network is None: - raise RuntimeError("A Network is required to do active scanning") sdo_req = b"\x40\x00\x10\x00\x00\x00\x00\x00" for node_id in range(1, limit + 1): self.network.send_message(0x600 + node_id, sdo_req) diff --git a/canopen/objectdictionary/eds.py b/canopen/objectdictionary/eds.py index b77f9782..986d2a37 100644 --- a/canopen/objectdictionary/eds.py +++ b/canopen/objectdictionary/eds.py @@ -1,12 +1,18 @@ +from __future__ import annotations + import copy import logging import re from configparser import NoOptionError, NoSectionError, RawConfigParser +from typing import TYPE_CHECKING from canopen import objectdictionary from canopen.objectdictionary import ObjectDictionary, datatypes from canopen.sdo import SdoClient +if TYPE_CHECKING: + import canopen.network + logger = logging.getLogger(__name__) @@ -173,7 +179,7 @@ def import_eds(source, node_id): return od -def import_from_node(node_id, network): +def import_from_node(node_id: int, network: canopen.network.Network): """ Download the configuration from the remote node :param int node_id: Identifier of the node :param network: network object diff --git a/canopen/sync.py b/canopen/sync.py index d3734512..44ea56c3 100644 --- a/canopen/sync.py +++ b/canopen/sync.py @@ -1,4 +1,9 @@ -from typing import Optional +from __future__ import annotations + +from typing import Optional, TYPE_CHECKING + +if TYPE_CHECKING: + import canopen.network class SyncProducer: @@ -7,7 +12,7 @@ class SyncProducer: #: COB-ID of the SYNC message cob_id = 0x80 - def __init__(self, network): + def __init__(self, network: canopen.network.Network): self.network = network self.period: Optional[float] = None self._task = None diff --git a/canopen/timestamp.py b/canopen/timestamp.py index 21dcc636..7ff4e486 100644 --- a/canopen/timestamp.py +++ b/canopen/timestamp.py @@ -1,6 +1,11 @@ +from __future__ import annotations + import struct import time -from typing import Optional +from typing import Optional, TYPE_CHECKING + +if TYPE_CHECKING: + import canopen.network # 1 Jan 1984 @@ -17,7 +22,7 @@ class TimeProducer: #: COB-ID of the SYNC message cob_id = 0x100 - def __init__(self, network): + def __init__(self, network: canopen.network.Network): self.network = network def transmit(self, timestamp: Optional[float] = None): diff --git a/test/test_network.py b/test/test_network.py index 1d45a1c2..cd65ea71 100644 --- a/test/test_network.py +++ b/test/test_network.py @@ -318,7 +318,7 @@ def test_scanner_reset(self): self.assertListEqual(self.scanner.nodes, []) def test_scanner_search_no_network(self): - with self.assertRaisesRegex(RuntimeError, "Network is required"): + with self.assertRaisesRegex(RuntimeError, "No actual Network object was assigned"): self.scanner.search() def test_scanner_search(self): From 09c1ddd4094358081dd4a79803dacf744ab72ecf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Mon, 9 Jun 2025 22:09:10 +0200 Subject: [PATCH 192/199] Add some type annotations for the nmt module (#586) Co-authored-by: Erlend E. Aasland --- canopen/nmt.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/canopen/nmt.py b/canopen/nmt.py index 622e0a33..c13d0779 100644 --- a/canopen/nmt.py +++ b/canopen/nmt.py @@ -2,7 +2,7 @@ import struct import threading import time -from typing import Callable, Optional, TYPE_CHECKING +from typing import Callable, Dict, Final, List, Optional, TYPE_CHECKING import canopen.network @@ -12,7 +12,7 @@ logger = logging.getLogger(__name__) -NMT_STATES = { +NMT_STATES: Final[Dict[int, str]] = { 0: 'INITIALISING', 4: 'STOPPED', 5: 'OPERATIONAL', @@ -21,7 +21,7 @@ 127: 'PRE-OPERATIONAL' } -NMT_COMMANDS = { +NMT_COMMANDS: Final[Dict[str, int]] = { 'OPERATIONAL': 1, 'STOPPED': 2, 'SLEEP': 80, @@ -32,7 +32,7 @@ 'RESET COMMUNICATION': 130 } -COMMAND_TO_STATE = { +COMMAND_TO_STATE: Final[Dict[int, int]] = { 1: 5, 2: 4, 80: 80, @@ -117,7 +117,7 @@ def __init__(self, node_id: int): #: Timestamp of last heartbeat message self.timestamp: Optional[float] = None self.state_update = threading.Condition() - self._callbacks = [] + self._callbacks: List[Callable[[int], None]] = [] def on_heartbeat(self, can_id, data, timestamp): with self.state_update: @@ -186,7 +186,8 @@ def start_node_guarding(self, period: float): :param period: Period (in seconds) at which the node guarding should be advertised to the slave node. """ - if self._node_guarding_producer : self.stop_node_guarding() + if self._node_guarding_producer: + self.stop_node_guarding() self._node_guarding_producer = self.network.send_periodic(0x700 + self.id, None, period, True) def stop_node_guarding(self): From c0a4ae50b0487d5d683e6eeff1fd3c3069747a02 Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Wed, 11 Jun 2025 09:20:46 +0200 Subject: [PATCH 193/199] Correctly apply offset to custom timestamp value (fixes #563) (#576) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: André Colomb --- canopen/timestamp.py | 2 +- test/test_time.py | 31 +++++++++++++++++++++++++++++-- 2 files changed, 30 insertions(+), 3 deletions(-) diff --git a/canopen/timestamp.py b/canopen/timestamp.py index 7ff4e486..e6c572c7 100644 --- a/canopen/timestamp.py +++ b/canopen/timestamp.py @@ -31,7 +31,7 @@ def transmit(self, timestamp: Optional[float] = None): :param float timestamp: Optional Unix timestamp to use, otherwise the current time is used. """ - delta = timestamp or time.time() - OFFSET + delta = (timestamp or time.time()) - OFFSET days, seconds = divmod(delta, ONE_DAY) data = TIME_OF_DAY_STRUCT.pack(int(seconds * 1000), int(days)) self.network.send_message(self.cob_id, data) diff --git a/test/test_time.py b/test/test_time.py index acd2b490..fa45a444 100644 --- a/test/test_time.py +++ b/test/test_time.py @@ -1,22 +1,49 @@ +import struct +import time import unittest +from datetime import datetime +from unittest.mock import patch import canopen +import canopen.timestamp class TestTime(unittest.TestCase): + def test_epoch(self): + """Verify that the epoch matches the standard definition.""" + epoch = datetime.strptime( + "1984-01-01 00:00:00 +0000", "%Y-%m-%d %H:%M:%S %z" + ).timestamp() + self.assertEqual(int(epoch), canopen.timestamp.OFFSET) + def test_time_producer(self): network = canopen.Network() network.NOTIFIER_SHUTDOWN_TIMEOUT = 0.0 network.connect(interface="virtual", receive_own_messages=True) producer = canopen.timestamp.TimeProducer(network) - producer.transmit(1486236238) + + # Provide a specific time to verify the proper encoding + producer.transmit(1_927_999_438) # 2031-02-04T19:23:58+00:00 msg = network.bus.recv(1) - network.disconnect() self.assertEqual(msg.arbitration_id, 0x100) self.assertEqual(msg.dlc, 6) self.assertEqual(msg.data, b"\xb0\xa4\x29\x04\x31\x43") + # Test again with the current time as implicit timestamp + current = time.time() + with patch("canopen.timestamp.time.time", return_value=current): + current_from_epoch = current - canopen.timestamp.OFFSET + producer.transmit() + msg = network.bus.recv(1) + self.assertEqual(msg.arbitration_id, 0x100) + self.assertEqual(msg.dlc, 6) + ms, days = struct.unpack(" Date: Wed, 11 Jun 2025 09:55:03 +0200 Subject: [PATCH 194/199] Fix check for retransmission of discarded block segments (#546) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit We are waiting for the sequence number to be the same as the last good known sequence number, to start considering the messages. However, this is wrong because the SDO server will start sending the discarded segments at the start of a new block, which means the sequence number restarts from 1. Reset the internal _ackseq counter to zero after each acknowledgement, which results in the correct value being compared after retransmission. Add a block retransmit test. This test passes with this implementation but will fail with an invalid CRC without fix for discarded segments. Co-authored-by: André Colomb --- canopen/sdo/client.py | 3 +- test/test_sdo.py | 305 ++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 306 insertions(+), 2 deletions(-) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index c08d92be..6d92588e 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -575,8 +575,7 @@ def _ack_block(self): request[1] = self._ackseq request[2] = self.blksize self.sdo_client.send_request(request) - if self._ackseq == self.blksize: - self._ackseq = 0 + self._ackseq = 0 def _end_upload(self): response = self.sdo_client.read_response() diff --git a/test/test_sdo.py b/test/test_sdo.py index e4036efe..fea52b6a 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -187,6 +187,311 @@ def test_block_upload(self): data = fp.read() self.assertEqual(data, 'Tiny Node - Mega Domains !') + def test_sdo_block_upload_retransmit(self): + """Trigger a retransmit by only validating a block partially.""" + self.data = [ + (TX, b'\xa4\x08\x10\x00\x7f\x00\x00\x00'), + (RX, b'\xc4\x08\x10\x00\x00\x00\x00\x00'), + (TX, b'\xa3\x00\x00\x00\x00\x00\x00\x00'), + (RX, b'\x01\x74\x68\x65\x20\x63\x72\x61'), + (RX, b'\x02\x7a\x79\x20\x66\x6f\x78\x20'), + (RX, b'\x03\x6a\x75\x6d\x70\x73\x20\x6f'), + (RX, b'\x04\x76\x65\x72\x20\x74\x68\x65'), + (RX, b'\x05\x20\x6c\x61\x7a\x79\x20\x64'), + (RX, b'\x06\x6f\x67\x0a\x74\x68\x65\x20'), + (RX, b'\x07\x63\x72\x61\x7a\x79\x20\x66'), + (RX, b'\x08\x6f\x78\x20\x6a\x75\x6d\x70'), + (RX, b'\x09\x73\x20\x6f\x76\x65\x72\x20'), + (RX, b'\x0a\x74\x68\x65\x20\x6c\x61\x7a'), + (RX, b'\x0b\x79\x20\x64\x6f\x67\x0a\x74'), + (RX, b'\x0c\x68\x65\x20\x63\x72\x61\x7a'), + (RX, b'\x0d\x79\x20\x66\x6f\x78\x20\x6a'), + (RX, b'\x0e\x75\x6d\x70\x73\x20\x6f\x76'), + (RX, b'\x0f\x65\x72\x20\x74\x68\x65\x20'), + (RX, b'\x10\x6c\x61\x7a\x79\x20\x64\x6f'), + (RX, b'\x11\x67\x0a\x74\x68\x65\x20\x63'), + (RX, b'\x12\x72\x61\x7a\x79\x20\x66\x6f'), + (RX, b'\x13\x78\x20\x6a\x75\x6d\x70\x73'), + (RX, b'\x14\x20\x6f\x76\x65\x72\x20\x74'), + (RX, b'\x15\x68\x65\x20\x6c\x61\x7a\x79'), + (RX, b'\x16\x20\x64\x6f\x67\x0a\x74\x68'), + (RX, b'\x17\x65\x20\x63\x72\x61\x7a\x79'), + (RX, b'\x18\x20\x66\x6f\x78\x20\x6a\x75'), + (RX, b'\x19\x6d\x70\x73\x20\x6f\x76\x65'), + (RX, b'\x1a\x72\x20\x74\x68\x65\x20\x6c'), + (RX, b'\x1b\x61\x7a\x79\x20\x64\x6f\x67'), + (RX, b'\x1c\x0a\x74\x68\x65\x20\x63\x72'), + (RX, b'\x1d\x61\x7a\x79\x20\x66\x6f\x78'), + (RX, b'\x1e\x20\x6a\x75\x6d\x70\x73\x20'), + (RX, b'\x1f\x6f\x76\x65\x72\x20\x74\x68'), + (RX, b'\x20\x65\x20\x6c\x61\x7a\x79\x20'), + (RX, b'\x21\x64\x6f\x67\x0a\x74\x68\x65'), + (RX, b'\x22\x20\x63\x72\x61\x7a\x79\x20'), + (RX, b'\x23\x66\x6f\x78\x20\x6a\x75\x6d'), + (RX, b'\x24\x70\x73\x20\x6f\x76\x65\x72'), + (RX, b'\x25\x20\x74\x68\x65\x20\x6c\x61'), + (RX, b'\x26\x7a\x79\x20\x64\x6f\x67\x0a'), + (RX, b'\x27\x74\x68\x65\x20\x63\x72\x61'), + (RX, b'\x28\x7a\x79\x20\x66\x6f\x78\x20'), + (RX, b'\x29\x6a\x75\x6d\x70\x73\x20\x6f'), + (RX, b'\x2a\x76\x65\x72\x20\x74\x68\x65'), + (RX, b'\x2b\x20\x6c\x61\x7a\x79\x20\x64'), + (RX, b'\x2c\x6f\x67\x0a\x74\x68\x65\x20'), + (RX, b'\x2d\x63\x72\x61\x7a\x79\x20\x66'), + (RX, b'\x2e\x6f\x78\x20\x6a\x75\x6d\x70'), + (RX, b'\x2f\x73\x20\x6f\x76\x65\x72\x20'), + (RX, b'\x30\x74\x68\x65\x20\x6c\x61\x7a'), + (RX, b'\x31\x79\x20\x64\x6f\x67\x0a\x74'), + (RX, b'\x32\x68\x65\x20\x63\x72\x61\x7a'), + (RX, b'\x34\x79\x20\x66\x6f\x78\x20\x6a'), # --> Wrong seqno (x34 instead of x33) + (RX, b'\x33\x75\x6d\x70\x73\x20\x6f\x76'), # All the following frames until end of block + (RX, b'\x35\x65\x72\x20\x74\x68\x65\x20'), # will be ignored by the client and should be + (RX, b'\x36\x6c\x61\x7a\x79\x20\x64\x6f'), # resent by server. + (RX, b'\x37\x67\x0a\x74\x68\x65\x20\x63'), + (RX, b'\x38\x72\x61\x7a\x79\x20\x66\x6f'), + (RX, b'\x39\x78\x20\x6a\x75\x6d\x70\x73'), + (RX, b'\x3a\x20\x6f\x76\x65\x72\x20\x74'), + (RX, b'\x3b\x68\x65\x20\x6c\x61\x7a\x79'), + (RX, b'\x3c\x20\x64\x6f\x67\x0a\x74\x68'), + (RX, b'\x3d\x65\x20\x63\x72\x61\x7a\x79'), + (RX, b'\x3e\x20\x66\x6f\x78\x20\x6a\x75'), + (RX, b'\x3f\x6d\x70\x73\x20\x6f\x76\x65'), + (RX, b'\x40\x72\x20\x74\x68\x65\x20\x6c'), + (RX, b'\x41\x61\x7a\x79\x20\x64\x6f\x67'), + (RX, b'\x42\x0a\x74\x68\x65\x20\x63\x72'), + (RX, b'\x43\x61\x7a\x79\x20\x66\x6f\x78'), + (RX, b'\x44\x20\x6a\x75\x6d\x70\x73\x20'), + (RX, b'\x45\x6f\x76\x65\x72\x20\x74\x68'), + (RX, b'\x46\x65\x20\x6c\x61\x7a\x79\x20'), + (RX, b'\x47\x64\x6f\x67\x0a\x74\x68\x65'), + (RX, b'\x48\x20\x63\x72\x61\x7a\x79\x20'), + (RX, b'\x49\x66\x6f\x78\x20\x6a\x75\x6d'), + (RX, b'\x4a\x70\x73\x20\x6f\x76\x65\x72'), + (RX, b'\x4b\x20\x74\x68\x65\x20\x6c\x61'), + (RX, b'\x4c\x7a\x79\x20\x64\x6f\x67\x0a'), + (RX, b'\x4d\x74\x68\x65\x20\x63\x72\x61'), + (RX, b'\x4e\x7a\x79\x20\x66\x6f\x78\x20'), + (RX, b'\x4f\x6a\x75\x6d\x70\x73\x20\x6f'), + (RX, b'\x50\x76\x65\x72\x20\x74\x68\x65'), + (RX, b'\x51\x20\x6c\x61\x7a\x79\x20\x64'), + (RX, b'\x52\x6f\x67\x0a\x74\x68\x65\x20'), + (RX, b'\x53\x63\x72\x61\x7a\x79\x20\x66'), + (RX, b'\x54\x6f\x78\x20\x6a\x75\x6d\x70'), + (RX, b'\x55\x73\x20\x6f\x76\x65\x72\x20'), + (RX, b'\x56\x74\x68\x65\x20\x6c\x61\x7a'), + (RX, b'\x57\x79\x20\x64\x6f\x67\x0a\x74'), + (RX, b'\x58\x68\x65\x20\x63\x72\x61\x7a'), + (RX, b'\x59\x79\x20\x66\x6f\x78\x20\x6a'), + (RX, b'\x5a\x75\x6d\x70\x73\x20\x6f\x76'), + (RX, b'\x5b\x65\x72\x20\x74\x68\x65\x20'), + (RX, b'\x5c\x6c\x61\x7a\x79\x20\x64\x6f'), + (RX, b'\x5d\x67\x0a\x74\x68\x65\x20\x63'), + (RX, b'\x5e\x72\x61\x7a\x79\x20\x66\x6f'), + (RX, b'\x5f\x78\x20\x6a\x75\x6d\x70\x73'), + (RX, b'\x60\x20\x6f\x76\x65\x72\x20\x74'), + (RX, b'\x61\x68\x65\x20\x6c\x61\x7a\x79'), + (RX, b'\x62\x20\x64\x6f\x67\x0a\x74\x68'), + (RX, b'\x63\x65\x20\x63\x72\x61\x7a\x79'), + (RX, b'\x64\x20\x66\x6f\x78\x20\x6a\x75'), + (RX, b'\x65\x6d\x70\x73\x20\x6f\x76\x65'), + (RX, b'\x66\x72\x20\x74\x68\x65\x20\x6c'), + (RX, b'\x67\x61\x7a\x79\x20\x64\x6f\x67'), + (RX, b'\x68\x0a\x74\x68\x65\x20\x63\x72'), + (RX, b'\x69\x61\x7a\x79\x20\x66\x6f\x78'), + (RX, b'\x6a\x20\x6a\x75\x6d\x70\x73\x20'), + (RX, b'\x6b\x6f\x76\x65\x72\x20\x74\x68'), + (RX, b'\x6c\x65\x20\x6c\x61\x7a\x79\x20'), + (RX, b'\x6d\x64\x6f\x67\x0a\x74\x68\x65'), + (RX, b'\x6e\x20\x63\x72\x61\x7a\x79\x20'), + (RX, b'\x6f\x66\x6f\x78\x20\x6a\x75\x6d'), + (RX, b'\x70\x70\x73\x20\x6f\x76\x65\x72'), + (RX, b'\x71\x20\x74\x68\x65\x20\x6c\x61'), + (RX, b'\x72\x7a\x79\x20\x64\x6f\x67\x0a'), + (RX, b'\x73\x74\x68\x65\x20\x63\x72\x61'), + (RX, b'\x74\x7a\x79\x20\x66\x6f\x78\x20'), + (RX, b'\x75\x6a\x75\x6d\x70\x73\x20\x6f'), + (RX, b'\x76\x76\x65\x72\x20\x74\x68\x65'), + (RX, b'\x77\x20\x6c\x61\x7a\x79\x20\x64'), + (RX, b'\x78\x6f\x67\x0a\x74\x68\x65\x20'), + (RX, b'\x79\x63\x72\x61\x7a\x79\x20\x66'), + (RX, b'\x7a\x6f\x78\x20\x6a\x75\x6d\x70'), + (RX, b'\x7b\x73\x20\x6f\x76\x65\x72\x20'), + (RX, b'\x7c\x74\x68\x65\x20\x6c\x61\x7a'), + (RX, b'\x7d\x79\x20\x64\x6f\x67\x0a\x74'), + (RX, b'\x7e\x68\x65\x20\x63\x72\x61\x7a'), + (RX, b'\x7f\x79\x20\x66\x6f\x78\x20\x6a'), # --> Last element of block + (TX, b'\xa2\x32\x7f\x00\x00\x00\x00\x00'), # --> Last good seqno (x32) + (RX, b'\x01\x79\x20\x66\x6f\x78\x20\x6a'), # --> Server starts resending from last acknowledged block + (RX, b'\x02\x75\x6d\x70\x73\x20\x6f\x76'), + (RX, b'\x03\x65\x72\x20\x74\x68\x65\x20'), + (RX, b'\x04\x6c\x61\x7a\x79\x20\x64\x6f'), + (RX, b'\x05\x67\x0a\x74\x68\x65\x20\x63'), + (RX, b'\x06\x72\x61\x7a\x79\x20\x66\x6f'), + (RX, b'\x07\x78\x20\x6a\x75\x6d\x70\x73'), + (RX, b'\x08\x20\x6f\x76\x65\x72\x20\x74'), + (RX, b'\x09\x68\x65\x20\x6c\x61\x7a\x79'), + (RX, b'\x0a\x20\x64\x6f\x67\x0a\x74\x68'), + (RX, b'\x0b\x65\x20\x63\x72\x61\x7a\x79'), + (RX, b'\x0c\x20\x66\x6f\x78\x20\x6a\x75'), + (RX, b'\x0d\x6d\x70\x73\x20\x6f\x76\x65'), + (RX, b'\x0e\x72\x20\x74\x68\x65\x20\x6c'), + (RX, b'\x0f\x61\x7a\x79\x20\x64\x6f\x67'), + (RX, b'\x10\x0a\x74\x68\x65\x20\x63\x72'), + (RX, b'\x11\x61\x7a\x79\x20\x66\x6f\x78'), + (RX, b'\x12\x20\x6a\x75\x6d\x70\x73\x20'), + (RX, b'\x13\x6f\x76\x65\x72\x20\x74\x68'), + (RX, b'\x14\x65\x20\x6c\x61\x7a\x79\x20'), + (RX, b'\x15\x64\x6f\x67\x0a\x74\x68\x65'), + (RX, b'\x16\x20\x63\x72\x61\x7a\x79\x20'), + (RX, b'\x17\x66\x6f\x78\x20\x6a\x75\x6d'), + (RX, b'\x18\x70\x73\x20\x6f\x76\x65\x72'), + (RX, b'\x19\x20\x74\x68\x65\x20\x6c\x61'), + (RX, b'\x1a\x7a\x79\x20\x64\x6f\x67\x0a'), + (RX, b'\x1b\x74\x68\x65\x20\x63\x72\x61'), + (RX, b'\x1c\x7a\x79\x20\x66\x6f\x78\x20'), + (RX, b'\x1d\x6a\x75\x6d\x70\x73\x20\x6f'), + (RX, b'\x1e\x76\x65\x72\x20\x74\x68\x65'), + (RX, b'\x1f\x20\x6c\x61\x7a\x79\x20\x64'), + (RX, b'\x20\x6f\x67\x0a\x74\x68\x65\x20'), + (RX, b'\x21\x63\x72\x61\x7a\x79\x20\x66'), + (RX, b'\x22\x6f\x78\x20\x6a\x75\x6d\x70'), + (RX, b'\x23\x73\x20\x6f\x76\x65\x72\x20'), + (RX, b'\x24\x74\x68\x65\x20\x6c\x61\x7a'), + (RX, b'\x25\x79\x20\x64\x6f\x67\x0a\x74'), + (RX, b'\x26\x68\x65\x20\x63\x72\x61\x7a'), + (RX, b'\x27\x79\x20\x66\x6f\x78\x20\x6a'), + (RX, b'\x28\x75\x6d\x70\x73\x20\x6f\x76'), + (RX, b'\x29\x65\x72\x20\x74\x68\x65\x20'), + (RX, b'\x2a\x6c\x61\x7a\x79\x20\x64\x6f'), + (RX, b'\x2b\x67\x0a\x74\x68\x65\x20\x63'), + (RX, b'\x2c\x72\x61\x7a\x79\x20\x66\x6f'), + (RX, b'\x2d\x78\x20\x6a\x75\x6d\x70\x73'), + (RX, b'\x2e\x20\x6f\x76\x65\x72\x20\x74'), + (RX, b'\x2f\x68\x65\x20\x6c\x61\x7a\x79'), + (RX, b'\x30\x20\x64\x6f\x67\x0a\x74\x68'), + (RX, b'\x31\x65\x20\x63\x72\x61\x7a\x79'), + (RX, b'\x32\x20\x66\x6f\x78\x20\x6a\x75'), + (RX, b'\x33\x6d\x70\x73\x20\x6f\x76\x65'), + (RX, b'\x34\x72\x20\x74\x68\x65\x20\x6c'), + (RX, b'\x35\x61\x7a\x79\x20\x64\x6f\x67'), + (RX, b'\x36\x0a\x74\x68\x65\x20\x63\x72'), + (RX, b'\x37\x61\x7a\x79\x20\x66\x6f\x78'), + (RX, b'\x38\x20\x6a\x75\x6d\x70\x73\x20'), + (RX, b'\x39\x6f\x76\x65\x72\x20\x74\x68'), + (RX, b'\x3a\x65\x20\x6c\x61\x7a\x79\x20'), + (RX, b'\x3b\x64\x6f\x67\x0a\x74\x68\x65'), + (RX, b'\x3c\x20\x63\x72\x61\x7a\x79\x20'), + (RX, b'\x3d\x66\x6f\x78\x20\x6a\x75\x6d'), + (RX, b'\x3e\x70\x73\x20\x6f\x76\x65\x72'), + (RX, b'\x3f\x20\x74\x68\x65\x20\x6c\x61'), + (RX, b'\x40\x7a\x79\x20\x64\x6f\x67\x0a'), + (RX, b'\x41\x74\x68\x65\x20\x63\x72\x61'), + (RX, b'\x42\x7a\x79\x20\x66\x6f\x78\x20'), + (RX, b'\x43\x6a\x75\x6d\x70\x73\x20\x6f'), + (RX, b'\x44\x76\x65\x72\x20\x74\x68\x65'), + (RX, b'\x45\x20\x6c\x61\x7a\x79\x20\x64'), + (RX, b'\x46\x6f\x67\x0a\x74\x68\x65\x20'), + (RX, b'\x47\x63\x72\x61\x7a\x79\x20\x66'), + (RX, b'\x48\x6f\x78\x20\x6a\x75\x6d\x70'), + (RX, b'\x49\x73\x20\x6f\x76\x65\x72\x20'), + (RX, b'\x4a\x74\x68\x65\x20\x6c\x61\x7a'), + (RX, b'\x4b\x79\x20\x64\x6f\x67\x0a\x74'), + (RX, b'\x4c\x68\x65\x20\x63\x72\x61\x7a'), + (RX, b'\x4d\x79\x20\x66\x6f\x78\x20\x6a'), + (RX, b'\x4e\x75\x6d\x70\x73\x20\x6f\x76'), + (RX, b'\x4f\x65\x72\x20\x74\x68\x65\x20'), + (RX, b'\x50\x6c\x61\x7a\x79\x20\x64\x6f'), + (RX, b'\x51\x67\x0a\x74\x68\x65\x20\x63'), + (RX, b'\x52\x72\x61\x7a\x79\x20\x66\x6f'), + (RX, b'\x53\x78\x20\x6a\x75\x6d\x70\x73'), + (RX, b'\x54\x20\x6f\x76\x65\x72\x20\x74'), + (RX, b'\x55\x68\x65\x20\x6c\x61\x7a\x79'), + (RX, b'\x56\x20\x64\x6f\x67\x0a\x74\x68'), + (RX, b'\x57\x65\x20\x63\x72\x61\x7a\x79'), + (RX, b'\x58\x20\x66\x6f\x78\x20\x6a\x75'), + (RX, b'\x59\x6d\x70\x73\x20\x6f\x76\x65'), + (RX, b'\x5a\x72\x20\x74\x68\x65\x20\x6c'), + (RX, b'\x5b\x61\x7a\x79\x20\x64\x6f\x67'), + (RX, b'\x5c\x0a\x74\x68\x65\x20\x63\x72'), + (RX, b'\x5d\x61\x7a\x79\x20\x66\x6f\x78'), + (RX, b'\x5e\x20\x6a\x75\x6d\x70\x73\x20'), + (RX, b'\x5f\x6f\x76\x65\x72\x20\x74\x68'), + (RX, b'\x60\x65\x20\x6c\x61\x7a\x79\x20'), + (RX, b'\x61\x64\x6f\x67\x0a\x74\x68\x65'), + (RX, b'\x62\x20\x63\x72\x61\x7a\x79\x20'), + (RX, b'\x63\x66\x6f\x78\x20\x6a\x75\x6d'), + (RX, b'\x64\x70\x73\x20\x6f\x76\x65\x72'), + (RX, b'\x65\x20\x74\x68\x65\x20\x6c\x61'), + (RX, b'\x66\x7a\x79\x20\x64\x6f\x67\x0a'), + (RX, b'\x67\x74\x68\x65\x20\x63\x72\x61'), + (RX, b'\x68\x7a\x79\x20\x66\x6f\x78\x20'), + (RX, b'\x69\x6a\x75\x6d\x70\x73\x20\x6f'), + (RX, b'\x6a\x76\x65\x72\x20\x74\x68\x65'), + (RX, b'\x6b\x20\x6c\x61\x7a\x79\x20\x64'), + (RX, b'\x6c\x6f\x67\x0a\x74\x68\x65\x20'), + (RX, b'\x6d\x63\x72\x61\x7a\x79\x20\x66'), + (RX, b'\x6e\x6f\x78\x20\x6a\x75\x6d\x70'), + (RX, b'\x6f\x73\x20\x6f\x76\x65\x72\x20'), + (RX, b'\x70\x74\x68\x65\x20\x6c\x61\x7a'), + (RX, b'\x71\x79\x20\x64\x6f\x67\x0a\x74'), + (RX, b'\x72\x68\x65\x20\x63\x72\x61\x7a'), + (RX, b'\x73\x79\x20\x66\x6f\x78\x20\x6a'), + (RX, b'\x74\x75\x6d\x70\x73\x20\x6f\x76'), + (RX, b'\x75\x65\x72\x20\x74\x68\x65\x20'), + (RX, b'\x76\x6c\x61\x7a\x79\x20\x64\x6f'), + (RX, b'\x77\x67\x0a\x74\x68\x65\x20\x63'), + (RX, b'\x78\x72\x61\x7a\x79\x20\x66\x6f'), + (RX, b'\x79\x78\x20\x6a\x75\x6d\x70\x73'), + (RX, b'\x7a\x20\x6f\x76\x65\x72\x20\x74'), + (RX, b'\x7b\x68\x65\x20\x6c\x61\x7a\x79'), + (RX, b'\x7c\x20\x64\x6f\x67\x0a\x74\x68'), + (RX, b'\x7d\x65\x20\x63\x72\x61\x7a\x79'), + (RX, b'\x7e\x20\x66\x6f\x78\x20\x6a\x75'), + (RX, b'\x7f\x6d\x70\x73\x20\x6f\x76\x65'), + (TX, b'\xa2\x7f\x7f\x00\x00\x00\x00\x00'), # --> This block is acknowledged without issues + (RX, b'\x01\x72\x20\x74\x68\x65\x20\x6c'), + (RX, b'\x02\x61\x7a\x79\x20\x64\x6f\x67'), + (RX, b'\x03\x0a\x74\x68\x65\x20\x63\x72'), + (RX, b'\x04\x61\x7a\x79\x20\x66\x6f\x78'), + (RX, b'\x05\x20\x6a\x75\x6d\x70\x73\x20'), + (RX, b'\x06\x6f\x76\x65\x72\x20\x74\x68'), + (RX, b'\x07\x65\x20\x6c\x61\x7a\x79\x20'), + (RX, b'\x08\x64\x6f\x67\x0a\x74\x68\x65'), + (RX, b'\x09\x20\x63\x72\x61\x7a\x79\x20'), + (RX, b'\x0a\x66\x6f\x78\x20\x6a\x75\x6d'), + (RX, b'\x0b\x70\x73\x20\x6f\x76\x65\x72'), + (RX, b'\x0c\x20\x74\x68\x65\x20\x6c\x61'), + (RX, b'\x0d\x7a\x79\x20\x64\x6f\x67\x0a'), + (RX, b'\x0e\x74\x68\x65\x20\x63\x72\x61'), + (RX, b'\x0f\x7a\x79\x20\x66\x6f\x78\x20'), + (RX, b'\x10\x6a\x75\x6d\x70\x73\x20\x6f'), + (RX, b'\x11\x76\x65\x72\x20\x74\x68\x65'), + (RX, b'\x12\x20\x6c\x61\x7a\x79\x20\x64'), + (RX, b'\x13\x6f\x67\x0a\x74\x68\x65\x20'), + (RX, b'\x14\x63\x72\x61\x7a\x79\x20\x66'), + (RX, b'\x15\x6f\x78\x20\x6a\x75\x6d\x70'), + (RX, b'\x16\x73\x20\x6f\x76\x65\x72\x20'), + (RX, b'\x17\x74\x68\x65\x20\x6c\x61\x7a'), + (RX, b'\x18\x79\x20\x64\x6f\x67\x0a\x74'), + (RX, b'\x19\x68\x65\x20\x63\x72\x61\x7a'), + (RX, b'\x1a\x79\x20\x66\x6f\x78\x20\x6a'), + (RX, b'\x1b\x75\x6d\x70\x73\x20\x6f\x76'), + (RX, b'\x1c\x65\x72\x20\x74\x68\x65\x20'), + (RX, b'\x1d\x6c\x61\x7a\x79\x20\x64\x6f'), + (RX, b'\x1e\x67\x0a\x74\x68\x65\x20\x63'), + (RX, b'\x1f\x72\x61\x7a\x79\x20\x66\x6f'), + (RX, b'\x20\x78\x20\x6a\x75\x6d\x70\x73'), + (RX, b'\x21\x20\x6f\x76\x65\x72\x20\x74'), + (RX, b'\x22\x68\x65\x20\x6c\x61\x7a\x79'), + (RX, b'\xa3\x20\x64\x6f\x67\x0a\x00\x00'), + (TX, b'\xa2\x23\x7f\x00\x00\x00\x00\x00'), + (RX, b'\xc9\x3b\x49\x00\x00\x00\x00\x00'), + (TX, b'\xa1\x00\x00\x00\x00\x00\x00\x00'), # --> Transfer ends without issues + ] + with self.network[2].sdo[0x1008].open('r', block_transfer=True) as fp: + data = fp.read() + self.assertEqual(data, 39 * 'the crazy fox jumps over the lazy dog\n') + def test_writable_file(self): self.data = [ (TX, b'\x20\x00\x20\x00\x00\x00\x00\x00'), From 7fb914a12e239afbb8acc4134e9eb5a6afdbcb9d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Sun, 15 Jun 2025 20:20:23 +0200 Subject: [PATCH 195/199] Avoid truncating unknown types in SDO upload (fixes #436) (#591) When an OD entry is found in SdoClient.upload(), the truncation is currently skipped only for those types explicitly listed as variable length data (domain, strings). That causes unknown types to be truncated to whatever their length indicates, which is usually one byte. Invert the condition to check all types with an explicitly known size, a.k.a. those listed in STRUCT_TYPES where the required length can be deduced from the structure format. Re-enable the unit tests which were skipped based on the previously buggy behavior. --- canopen/objectdictionary/__init__.py | 6 ++++++ canopen/sdo/client.py | 4 +--- test/test_sdo.py | 2 -- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index 09fe6e03..c67b3b4a 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -419,6 +419,12 @@ def add_bit_definition(self, name: str, bits: List[int]) -> None: """ self.bit_definitions[name] = bits + @property + def fixed_size(self) -> bool: + """Indicate whether the amount of needed data is known in advance.""" + # Only for types which we parse using a structure. + return self.data_type in self.STRUCT_TYPES + def decode_raw(self, data: bytes) -> Union[int, float, str, bytes, bytearray]: if self.data_type == VISIBLE_STRING: # Strip any trailing NUL characters from C-based systems diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index 6d92588e..fd5fd99b 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -126,9 +126,7 @@ def upload(self, index: int, subindex: int) -> bytes: var = self.od.get_variable(index, subindex) if var is not None: # Found a matching variable in OD - # If this is a data type (string, domain etc) the size is - # unknown anyway so keep the data as is - if var.data_type not in objectdictionary.DATA_TYPES: + if var.fixed_size: # Get the size in bytes for this variable var_size = len(var) // 8 if response_size is None or var_size < response_size: diff --git a/test/test_sdo.py b/test/test_sdo.py index fea52b6a..78012a30 100644 --- a/test/test_sdo.py +++ b/test/test_sdo.py @@ -814,7 +814,6 @@ def test_unknown_od_112(self): def test_unknown_datatype32(self): """Test an unknown datatype, but known OD, of 32 bits (4 bytes).""" - return # FIXME: Disabled temporarily until datatype conditionals are fixed, see #436 # Add fake entry 0x2100 to OD, using fake datatype 0xFF if 0x2100 not in self.node.object_dictionary: fake_var = ODVariable("Fake", 0x2100) @@ -829,7 +828,6 @@ def test_unknown_datatype32(self): def test_unknown_datatype112(self): """Test an unknown datatype, but known OD, of 112 bits (14 bytes).""" - return # FIXME: Disabled temporarily until datatype conditionals are fixed, see #436 # Add fake entry 0x2100 to OD, using fake datatype 0xFF if 0x2100 not in self.node.object_dictionary: fake_var = ODVariable("Fake", 0x2100) From de0e644b7d2c6ce11294be40c1da4ab33a15206b Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Sun, 15 Jun 2025 20:53:02 +0200 Subject: [PATCH 196/199] Fix OD item lookup evaluating subobject's length (fixes #588) (#589) If the lookup by name returns an object (not None), the boolean expression still checks whether that object is equivalent to boolean True. This needlessly calls the object's __len__() method, while what we're interested in is just whether an object was found. --- canopen/objectdictionary/__init__.py | 4 +++- test/test_od.py | 12 ++++++++++++ 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/canopen/objectdictionary/__init__.py b/canopen/objectdictionary/__init__.py index c67b3b4a..f394da23 100644 --- a/canopen/objectdictionary/__init__.py +++ b/canopen/objectdictionary/__init__.py @@ -133,7 +133,9 @@ def __getitem__( self, index: Union[int, str] ) -> Union[ODArray, ODRecord, ODVariable]: """Get object from object dictionary by name or index.""" - item = self.names.get(index) or self.indices.get(index) + item = self.names.get(index) + if item is None: + item = self.indices.get(index) if item is None: if isinstance(index, str) and '.' in index: idx, sub = index.split('.', maxsplit=1) diff --git a/test/test_od.py b/test/test_od.py index 52de86f8..9ab0e187 100644 --- a/test/test_od.py +++ b/test/test_od.py @@ -249,6 +249,18 @@ def test_get_item_dot(self): self.assertEqual(test_od["Test Array.Test Variable"], member1) self.assertEqual(test_od["Test Array.Test Variable 2"], member2) + def test_get_item_index(self): + test_od = od.ObjectDictionary() + array = od.ODArray("Test Array", 0x1000) + test_od.add_object(array) + item = test_od[0x1000] + self.assertIsInstance(item, od.ODArray) + self.assertIs(item, array) + item = test_od["Test Array"] + self.assertIsInstance(item, od.ODArray) + self.assertIs(item, array) + + class TestArray(unittest.TestCase): def test_subindexes(self): From 80349e1326787fe4793858e0477c798489352029 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Tue, 17 Jun 2025 18:37:27 +0200 Subject: [PATCH 197/199] Abort SDO server upload when the object has zero length (#587) A data size of zero bytes cannot be encoded in the "number of bytes that do not contain data" semantics, as that would require n=4, which is however limited to two bits (maximum value 3). So the SDO expedited upload protocol simply cannot convey that condition. The current implementation however still tries and thereby corrupts the the reserved, always-zero field value. Avoid that protocol violation by responding with an SDO abort code of 0800 0024h, No data available. Add a test case for this condition, verifying that the client raises the appropriate SdoAbortedError exception. --- canopen/sdo/server.py | 6 +++++- test/test_local.py | 7 +++++++ 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index c6a4c27c..a34b3e68 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -66,7 +66,11 @@ def init_upload(self, request): data = self._node.get_data(index, subindex, check_readable=True) size = len(data) - if size <= 4: + if size == 0: + logger.info("No content to upload for 0x%04X:%02X", index, subindex) + self.abort(0x0800_0024) + return + elif size <= 4: logger.info("Expedited upload for 0x%04X:%02X", index, subindex) res_command |= EXPEDITED res_command |= (4 - size) << 2 diff --git a/test/test_local.py b/test/test_local.py index e184c040..31404bd6 100644 --- a/test/test_local.py +++ b/test/test_local.py @@ -62,6 +62,13 @@ def test_expedited_upload_default_value_real(self): sampling_rate = self.remote_node.sdo["Sensor Sampling Rate (Hz)"].raw self.assertAlmostEqual(sampling_rate, 5.2, places=2) + def test_upload_zero_length(self): + self.local_node.sdo["Manufacturer device name"].raw = b"" + with self.assertRaises(canopen.SdoAbortedError) as error: + self.remote_node.sdo["Manufacturer device name"].data + # Should be No data available + self.assertEqual(error.exception.code, 0x0800_0024) + def test_segmented_upload(self): self.local_node.sdo["Manufacturer device name"].raw = "Some cool device" device_name = self.remote_node.sdo["Manufacturer device name"].data From 8d9aa6c67c07bfe39baae1d02b058e644de23bdc Mon Sep 17 00:00:00 2001 From: Svein Seldal Date: Wed, 18 Jun 2025 17:14:36 +0200 Subject: [PATCH 198/199] Prevent warnings if SDO setup fails (#590) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: André Colomb --- canopen/sdo/client.py | 5 +++++ canopen/sdo/server.py | 4 ++++ 2 files changed, 9 insertions(+) diff --git a/canopen/sdo/client.py b/canopen/sdo/client.py index fd5fd99b..76fa6fbc 100644 --- a/canopen/sdo/client.py +++ b/canopen/sdo/client.py @@ -667,6 +667,8 @@ def __init__(self, sdo_client, index, subindex=0, size=None, request_crc_support self._blksize, = struct.unpack_from("B", response, 4) logger.debug("Server requested a block size of %d", self._blksize) self.crc_supported = bool(res_command & CRC_SUPPORTED) + # Run this last, used later to determine if initialization was successful + self._initialized = True def write(self, b): """ @@ -782,6 +784,9 @@ def close(self): if self.closed: return super(BlockDownloadStream, self).close() + if not getattr(self, "_initialized", False): + # Don't do finalization if initialization was not successful + return if not self._done: logger.error("Block transfer was not finished") command = REQUEST_BLOCK_DOWNLOAD | END_BLOCK_TRANSFER diff --git a/canopen/sdo/server.py b/canopen/sdo/server.py index a34b3e68..8d693633 100644 --- a/canopen/sdo/server.py +++ b/canopen/sdo/server.py @@ -124,6 +124,10 @@ def request_aborted(self, data): def block_download(self, data): # We currently don't support BLOCK DOWNLOAD + # Unpack the index and subindex in order to send appropriate abort + command, index, subindex = SDO_STRUCT.unpack_from(data) + self._index = index + self._subindex = subindex logger.error("Block download is not supported") self.abort(0x05040001) From 09f6e9e8e9497108790328aed9839f2552acdbae Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Andr=C3=A9=20Colomb?= Date: Sun, 22 Jun 2025 22:17:37 +0200 Subject: [PATCH 199/199] Gracefully handle readonly entries in PdoMap.save() (fixes #541) (#593) * Skip saving and log read-only PDO parameters. For PDO communication or mapping parameters which are read-only on a node, the PdoMap.save() method currently aborts with an SDO exception. However, individual parameters may simply not support configuration changes. Rely on the Object Dictionary to tell which ones are expected to fail and skip them. For communication record entries, log what is not being saved. * Switch to a LocalNode in TestPDO to not require a network. * Test PdoMap.save() skipping readonly entries. Co-authored-by: Erlend E. Aasland --- canopen/pdo/base.py | 57 ++++++++++++++++++++++++++------------------- test/test_pdo.py | 15 +++++++++++- 2 files changed, 47 insertions(+), 25 deletions(-) diff --git a/canopen/pdo/base.py b/canopen/pdo/base.py index 0ba65199..7bef6e62 100644 --- a/canopen/pdo/base.py +++ b/canopen/pdo/base.py @@ -403,19 +403,27 @@ def save(self) -> None: logger.info("Skip saving %s: COB-ID was never set", self.com_record.od.name) return logger.info("Setting COB-ID 0x%X and temporarily disabling PDO", self.cob_id) - self.com_record[1].raw = self.cob_id | PDO_NOT_VALID | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0x0) - if self.trans_type is not None: - logger.info("Setting transmission type to %d", self.trans_type) - self.com_record[2].raw = self.trans_type - if self.inhibit_time is not None: - logger.info("Setting inhibit time to %d us", (self.inhibit_time * 100)) - self.com_record[3].raw = self.inhibit_time - if self.event_timer is not None: - logger.info("Setting event timer to %d ms", self.event_timer) - self.com_record[5].raw = self.event_timer - if self.sync_start_value is not None: - logger.info("Setting SYNC start value to %d", self.sync_start_value) - self.com_record[6].raw = self.sync_start_value + self.com_record[1].raw = ( + self.cob_id + | PDO_NOT_VALID + | (RTR_NOT_ALLOWED if not self.rtr_allowed else 0) + ) + + def _set_com_record( + subindex: int, value: Optional[int], log_fmt: str, log_factor: int = 1 + ): + if value is None: + return + if self.com_record[subindex].writable: + logger.info(f"Setting {log_fmt}", value * log_factor) + self.com_record[subindex].raw = value + else: + logger.info(f"Cannot set {log_fmt}, not writable", value * log_factor) + + _set_com_record(2, self.trans_type, "transmission type to %d") + _set_com_record(3, self.inhibit_time, "inhibit time to %d us", 100) + _set_com_record(5, self.event_timer, "event timer to %d ms") + _set_com_record(6, self.sync_start_value, "SYNC start value to %d") try: self.map_array[0].raw = 0 @@ -425,20 +433,21 @@ def save(self) -> None: # mappings for an invalid object 0x0000:00 to overwrite any # excess entries with all-zeros. self._fill_map(self.map_array[0].raw) - subindex = 1 - for var in self.map: - logger.info("Writing %s (0x%04X:%02X, %d bits) to PDO map", - var.name, var.index, var.subindex, var.length) + for var, entry in zip(self.map, self.map_array.values()): + if not entry.od.writable: + continue + logger.info( + "Writing %s (0x%04X:%02X, %d bits) to PDO map", + var.name, + var.index, + var.subindex, + var.length, + ) if getattr(self.pdo_node.node, "curtis_hack", False): # Curtis HACK: mixed up field order - self.map_array[subindex].raw = (var.index | - var.subindex << 16 | - var.length << 24) + entry.raw = var.index | var.subindex << 16 | var.length << 24 else: - self.map_array[subindex].raw = (var.index << 16 | - var.subindex << 8 | - var.length) - subindex += 1 + entry.raw = var.index << 16 | var.subindex << 8 | var.length try: self.map_array[0].raw = len(self.map) except SdoAbortedError as e: diff --git a/test/test_pdo.py b/test/test_pdo.py index 1badc89d..b8bb0599 100644 --- a/test/test_pdo.py +++ b/test/test_pdo.py @@ -7,7 +7,7 @@ class TestPDO(unittest.TestCase): def setUp(self): - node = canopen.Node(1, SAMPLE_EDS) + node = canopen.LocalNode(1, SAMPLE_EDS) pdo = node.pdo.tx[1] pdo.add_variable('INTEGER16 value') # 0x2001 pdo.add_variable('UNSIGNED8 value', length=4) # 0x2002 @@ -64,6 +64,19 @@ def test_pdo_save(self): self.node.tpdo.save() self.node.rpdo.save() + def test_pdo_save_skip_readonly(self): + """Expect no exception when a record entry is not writable.""" + # Saving only happens with a defined COB ID and for specified parameters + self.node.tpdo[1].cob_id = self.node.tpdo[1].predefined_cob_id + self.node.tpdo[1].trans_type = 1 + self.node.tpdo[1].map_array[1].od.access_type = "r" + self.node.tpdo[1].save() + + self.node.tpdo[2].cob_id = self.node.tpdo[2].predefined_cob_id + self.node.tpdo[2].trans_type = 1 + self.node.tpdo[2].com_record[2].od.access_type = "r" + self.node.tpdo[2].save() + def test_pdo_export(self): try: import canmatrix