Show EOL distros:
Package Summary
ROS node base implementation for CANopen chains with support for management services and diagnostics
- Maintainer status: maintained
- Maintainer: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- License: LGPLv3
- Bug / feature tracker: https://github.com/ros-industrial/ros_canopen/issues
- Source: git https://github.com/ros-industrial/ros_canopen.git (branch: indigo)
Package Summary
ROS node base implementation for CANopen chains with support for management services and diagnostics
- Maintainer status: maintained
- Maintainer: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- License: LGPLv3
- Bug / feature tracker: https://github.com/ros-industrial/ros_canopen/issues
- Source: git https://github.com/ros-industrial/ros_canopen.git (branch: jade)
Package Summary
Base implementation for CANopen chains node with support for management services and diagnostics
- Maintainer status: maintained
- Maintainer: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- License: LGPLv3
- Bug / feature tracker: https://github.com/ros-industrial/ros_canopen/issues
- Source: git https://github.com/ros-industrial/ros_canopen.git (branch: kinetic)
Package Summary
Base implementation for CANopen chains node with support for management services and diagnostics
- Maintainer status: maintained
- Maintainer: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- License: LGPLv3
- Bug / feature tracker: https://github.com/ros-industrial/ros_canopen/issues
- Source: git https://github.com/ros-industrial/ros_canopen.git (branch: kinetic)
Package Summary
Base implementation for CANopen chains node with support for management services and diagnostics
- Maintainer status: maintained
- Maintainer: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- License: LGPLv3
- Bug / feature tracker: https://github.com/ros-industrial/ros_canopen/issues
- Source: git https://github.com/ros-industrial/ros_canopen.git (branch: melodic)
Package Summary
Base implementation for CANopen chains node with support for management services and diagnostics
- Maintainer status: maintained
- Maintainer: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- Author: Mathias Lüdtke <mathias.luedtke AT ipa.fraunhofer DOT de>
- License: LGPLv3
- Bug / feature tracker: https://github.com/ros-industrial/ros_canopen/issues
- Source: git https://github.com/ros-industrial/ros_canopen.git (branch: melodic)
Contents
Overview
This packages contains the ROS interface for socketcan_interface and canopen_master. It can be used as a stand-alone ROS node, but as well as a base class for profile specific ROS interfaces, e.g. canopen_motor_node.
It manages a CANopen bus with one or more nodes, which are configures with CANopen EDS/DCF files. The ROS node runs a control loop with CANopen SYNC interval (or with an alternative update interval if the SYNC protocol is not used).
Configuration
The configuration can be split into different parts. First the bus has to be set-up, these settings are shared for all node. Then all must be configured with their CANopen and ROS interfaces. All parameters must be loaded into the nodes private namespace
CANopen Bus layer
The bus settings consists of a CAN interface (socketcan_interface) and the shared bus settings for canopen_master.
1 bus:
2 device: can0 # socketcan network
3 # loopback: false # socket should loop back messages
4 # driver_plugin: can::SocketCANInterface
5 # master_allocator: canopen::SimpleMaster::Allocator
6 sync:
7 interval_ms: 10 # set to 0 to disable sync
8 # update_ms: <interval_ms> #update interval of control loop, must be set explecitly if sync is disabled
9 overflow: 0 # overflow sync counter at value or do not set it (0, default)
10 heartbeat: # simple heartbeat producer, optional!
11 rate: 20 # heartbeat rate
12 msg: "77f#05" # message to send, cansend format: heartbeat of node 127 with status 5=Started
Node layer
All nodes are listed in the nodes parameter, either as list or a struct, and require a node ID, a name and the path to the EDS/DCF file.
Additional parameters can set either for each node or in a defaults section:
1 defaults: # optional, all defaults can be overwritten per node
2 eds_pkg: my_config_package # optional package name for relative path
3 eds_file: "my_config.dcf" # path to EDS/DCF file
4 dcf_overlay: # "ObjectID": "ParameterValue" (both as strings)
5 "1016sub1" : "0x7F0064" # heartbeat timeout of 100 ms for master at 127
6 "1017": "100" # heartbeat producer
The dcf_overlay can be used to overwrite specific settings in the EDS/DCF.
ROS layer
Each node (or in the defaults) can be passed a publish parameter with a list of object names. The topic types correspond to the object types, e.g. UNSIGNED16 to std_msgs/UInt16. It is meant for debugging or for simple CANopen interfaces, since it blocks the control loop. Each entry can have an exclamation mark appended that forces the driver to reread the object form the node in each step.
For example:
will publish on three topics with the sync/update_rate:
node1_1003sub0 (std_msgs/UInt8): number of errors for node1 (not cached)
node2_1001 (std_msgs/UInt8): error register of node2 (cached)
node3_1001 (std_msgs/UInt8): error register of node3 (cached)
The diagnostic_updater can be passed the diagnostic_period parameter in fractional seconds.
ROS API
canopen_chain_node
Published Topics
/diagnostics (diagnostic_msgs/DiagnosticStatus)- diagnostic information for the chain and each individual node
Services
driver/init (std_svrs/Trigger)- initialize the driver
- halt movements
- recover from emergency stops etc.
- shutdown all driver connections
- read CANOpen object. Specify the node using the joint name. If cached=False an SDO is sent to retrieve the current value, otherwise returns the last value received.
- write CANOpen register value.
Parameters
~diagnostic_period (double, default: 1.0)- period for diagnostics updater
- bus settings
- SYNC interval settings
- heartbeat settings
- default settings for all nodes
- settings for the nodes
Further topics will be published according to the publish parameters.
C++ API
This package provides a canopen::RosChain class that implements a canopen::LayerStack interface and takes care of the parameter parsing and the life-cycle. It can be customized via its virtual interface, especially with RosChain::nodeAdded