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

Revision history [back]

click to hide/show revision 1
initial version

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".