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

It should be more or less straightforward:

  1. Setup SocketCAN (you already have this running): http://wiki.ros.org/socketcan_interface#Initialize_NIC
  2. Prepare URDF with sane limits (this is required for now, will be optional in the future): http://wiki.ros.org/urdf/Tutorials/Create%20your%20own%20urdf%20file
  3. Prepare EDS/DCF, take special care for the PDO mapping (http://wiki.ros.org/canopen_402), use transmission type 1 (every sync)
  4. Prepare driver config
    • prepare chain config (http://wiki.ros.org/canopen_chain_node#Configuration)
    • configure motor-specific settings, especially unit conversions (http://wiki.ros.org/canopen_motor_node)
  5. Prepare controller config
    • list of controllers (documentation varies, http://wiki.ros.org/ros_controllers)
    • add a required_drive_mode to each motion controller, it takes the number of the mode to be used (http://wiki.ros.org/canopen_402#Drive_operation_modes)
  6. Prepare a launchfile for canopen_motor_node
    • upload driver config as private parameters
    • upload controller config into namespace
    • upload robot description
  7. rosservice call [/namespace]/driver/init (http://wiki.ros.org/canopen_chain_node#Services)
  8. start/switch the controllers (rqt_controller_manager, ontroller_manager, spawner etc.)

The EDS file parser is not really bullet proof (and EDS file format is rather flexibel) and might fail with some error indication. In addition ros_canopen enforces strict typing, some EDS files list non-standard types for some objects (e.g. signed instead of unsigned). This must be fixed as well in the EDS.

A basic driver config looks like:

bus:
  device: can0
sync:
  interval_ms: 10  # 100Hz
  overflow: 0
defaults:
  eds_pkg: my_package
  eds_file: "config/MyDescription.dcf" # the parser reads EDS and DCF
nodes:
  my_joint:
    id: 1

controller config example: https://github.com/ipa320/canopen_test_utils/blob/indigo-devel/config/rig1_controller.yaml Fairly complex examples: https://github.com/ipa320/schunk_robots/

It would be great if you could turn this into a tutorial on ROS Wiki based on your experiences :)

It should be more or less straightforward:

  1. Setup SocketCAN (you already have this running): http://wiki.ros.org/socketcan_interface#Initialize_NIC
  2. Prepare URDF with sane limits (this is required for now, will be optional in the future): http://wiki.ros.org/urdf/Tutorials/Create%20your%20own%20urdf%20file
  3. Prepare EDS/DCF, take special care for the PDO mapping (http://wiki.ros.org/canopen_402), use transmission type 1 (every sync)
  4. Prepare driver config
    • prepare chain config (http://wiki.ros.org/canopen_chain_node#Configuration)
    • configure motor-specific settings, especially unit conversions (http://wiki.ros.org/canopen_motor_node)
  5. Prepare controller config
    • list of controllers (documentation varies, http://wiki.ros.org/ros_controllers)
    • add a required_drive_mode to each motion controller, it takes the number of the mode to be used (http://wiki.ros.org/canopen_402#Drive_operation_modes)
  6. Prepare a launchfile for canopen_motor_node
    • upload driver config as private parameters
    • upload controller config into namespace
    • upload robot description
  7. rosservice call [/namespace]/driver/init (http://wiki.ros.org/canopen_chain_node#Services)
  8. start/switch the controllers (rqt_controller_manager, ontroller_manager, spawner etc.)

The EDS file parser is not really bullet proof (and EDS file format is rather flexibel) and might fail with some error indication. In addition ros_canopen enforces strict typing, some EDS files list non-standard types for some objects (e.g. signed instead of unsigned). This must be fixed as well in the EDS.

A basic driver config looks like:

bus:
  device: can0
sync:
  interval_ms: 10  # 100Hz
  overflow: 0
defaults:
  eds_pkg: my_package
  eds_file: "config/MyDescription.dcf" # the parser reads EDS and DCF
nodes:
  my_joint:
    id: 1

controller config example: https://github.com/ipa320/canopen_test_utils/blob/indigo-devel/config/rig1_controller.yaml https://github.com/ipa320/canopen_test_utils/blob/indigo-devel/config/rig1_controller.yaml

Fairly complex examples: https://github.com/ipa320/schunk_robots/

It would be great if you could turn this into a tutorial on ROS Wiki based on your experiences :)