ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Why ros_canopen needs EDS/DCF file ?

asked 2021-06-11 10:59:34 -0600

Hello,

I'm using ros_canopen and was wondering how it works internally.

I can get my controller working (maxon EPOS4) but I have to do a few modifications on the DCF file, like removing some manufacturer specific device objects and potentially setting homing method to 0 (disable) which I think is not defined by standard CiA402.

On a higher level, does someone knows why ros_canopen needs the EDS/DCF file and what does it do with it ?

Thanks !

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
2

answered 2021-06-11 15:28:05 -0600

Mathias Lüdtke gravatar image

ros_canopen needs the EDS/DCF file

That's not entirely true.. The ROS nodes need an EDF/DCF file, but the stack can work without one.

Why

Why not? ;)

CANopen (CIA 301) uses an object directory to manage all data. There are some mandatory objects (AFAIK only 3!), but most are optional, defined in the CiA profiles (lika CiA 402) or manufacturer-specific. The manufacturer can even choose to make some objects read-only or write-only. Since EDS is the standardized (CiA 306) file format for describing the available objects and their (manufacturer-specific) defaults (e.g. for PDO mappings), so I thought it would be a good idea to use it.

This way the code base can be generic and the stack can work with any CANopen device, but still enforce a strict type system, which IMHO is crucial for dealing with binary data at the communication layer.

In addition this enables the use of (commercial) tools to fill and validate the EDS/DCF files.

what does it do with it ?

The EDS file is used to fill the object registry at start-up. If you set ParameterValue in the DCF file (technically ros_canopen treats EDS and DCF alike), then these values will be kept in the internal object directory and written to the device as soon as connection is established. There is some special handling in place to set-up the PDO mapping, because the PDOs have to get disabled before any update.

This object directory is the core of canopen_master as all data changes run through it. Any access to the objects will be translated into SDO or PDO commands, unless a cached access was requested. This object directory is exposed to ROS via the canopen_chain_node, which can be used with any number and any kind of CANopen device.

canopen_motor_node is specialized version, which uses canopen_402 to read/write motor-specific data and exchange it with ros_control. Under the hood canopen_402 just connects to the object directory and modifies the objects according to the profile-specific state machines and protocols.

like removing some manufacturer specific device objects

Normally, this should not be necessary for valid, standard-compliant EDS files. However, not all manufacturers ship valid EDS file and some even use vendor-specific extensions.

potentially setting homing method to 0 (disable) which I think is not defined by standard CiA402

Actually, this should be the default value (according to the standard) and means "no homing required".

edit flag offensive delete link more

Comments

Hi Mathias, thank you for your detailed reply. When you say objects which have ParameterValue defined are written to the device at start-up, do you mean only those who have a write permission in the AccessType ?

Cyril Jourdan gravatar image Cyril Jourdan  ( 2021-06-15 01:14:27 -0600 )edit

The write permission are not taken in account at this point. So, if you set a ParameterValue in the DCF for a non-writable object, you should get an exception.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2021-06-15 09:55:14 -0600 )edit

I am a bit confused by this process, as a DCF file contains for example objects which are read only and calculated during regulation tuning process of the motor (for example electrical resistance and inductance). Those objects have their calculated values put in the ParameterValue field, while having value 0 by default. Of course it would not be possible to try to write the values again from the ROS CANopen master.

However I got a setup working without exceptions (with default verbosity) and while leaving all the "ro" objects with their ParameterValue left as when the DCF was created.

Do you advise to remove the ParameterValue line from all "ro" objects, and set their values in the DefaultValue ?

Cyril Jourdan gravatar image Cyril Jourdan  ( 2021-06-21 05:32:12 -0600 )edit

I am not 100% anymore how I implemented it. What happens if you use read-only objects with ParameterValue?

If it does not work, then we might change the code to use ParameterValue as cached value, but not write it into the device.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2021-06-21 07:34:05 -0600 )edit
0

answered 2021-07-06 04:28:38 -0600

Dear Mathias and Cyril

I guess that there might be some confusion about the meaning and usage of *.eds and *.dcf files present. Please let me explain the usage of these files in practice.

  • The .eds is a so-called "Electronic Data Sheet" and holds an overview of all CANopen objects present by a CANopen slave device. This file is typically requested by CANopen master's system manager tools (or by the ROS_CANopen library tools) to get an overview of all present objects by a slave. The .eds file does not(!) hold any "ParameterValue" because it is seen as a kind of data sheet without application specific data. Based on Mathias' comments that just in case of a "ParameterValue" present it will be written, I expect that the *.eds file does not run into the problem about writing any parameters value at all. Therefore I recommend (and expect that this has actually been the intention by the ROS_CANopen library developers) to use the *.eds file instead of the *.dcf file. The *.eds file can be easily exported by the maxon's EPOS4 like described by the linked maxon Support Center document: -> "EPOS: Export of the *.eds resp. *.esi file (Electronic Data Sheet)". It is important that the *.eds file is exported by the EPOS4 actually in use because the object dictionary depends on the concrete EPOS4 product type and installed firmware version.

  • The *.dcf file is quite similar to the *.eds file but holds parameter values too. *.dcf files are typically shared for debugging purposes to get a comprehensive overview about all parameter (resp. object) configurations in case of support issues or by setting up different EPOS4 the same way.

General remark about duplicating Parameter values:

Even in case of duplicating the settings of an EPOS4 it makes no(!) sense to write down any object's content. It is a point of fact that the content of objects with the "AccessType=ro" (-> "Read Only"!!!) or "AccessType=const" (-> "Constant"!!!) cannot be written by any CANopen master. These objects are just internally updated or set by the CANopen slave itself but cannot be written by an external device or master. The term "Read Only" of "AccessType=ro" resp. "Constant" of "AccessType=const" should clearly state this. Therefore the ROS_CANopen library or tools should not(!) write "AccessType=ro" or "AccessType=const" objects' content independent if the *.dcf holds a "ParameterValue" which has been read during data export.

Recommendation:

Please fix the functionality of the "ROS_CANopen library" taking the AccessType into account before an object's content is written. Thanks.

Another topic of concern is that the order of how the "AccessType=rw" or "AccessType=rww" objects are written can also have some impact because the value range of different objects might depend on each other, e.g. in case of different velocity with depend on each other. It also makes less sense to duplicate configuration values like the CAN "Node-ID" or CANopen PDO COB-IDs for example. Therefore it is not recommended ... (more)

edit flag offensive delete link more

Comments

Thank you very much for the detailed response!

Please fix the functionality of the "ROS_CANopen library" taking the AccessType into account before an object's content is written. Thanks.

As far as I can tell ros_canopen does not try to write any data to the ro/const objects, but it might update the internal shadow-copy of the data in the master. I would consider this a feature, because it can be used to configure ros_canopen in some edge cases.

Therefore I recommend (and expect that this has actually been the intention by the ROS_CANopen library developers) to use the *.eds file instead of the *.dcf file.

If the configuration tool can export an EDS file, then this should be preferred. This simplifies the initialization a lot as well. However, not all manufacturers have such tools, so ros_canopen can use DCFs instead.

In addition there is an option to overwrite certain ...(more)

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2021-07-06 07:00:49 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2021-06-11 10:59:34 -0600

Seen: 10,962 times

Last updated: Jun 11 '21