It should be more or less straightforward:
- Setup SocketCAN (you already have this running): http://wiki.ros.org/socketcan_interface#Initialize_NIC
- 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
- Prepare EDS/DCF, take special care for the PDO mapping (http://wiki.ros.org/canopen_402), use transmission type 1 (every sync)
- Prepare driver config
- Prepare controller config
- Prepare a launchfile for canopen_motor_node
- upload driver config as private parameters
- upload controller config into namespace
- upload robot description
- rosservice call [/namespace]/driver/init (http://wiki.ros.org/canopen_chain_node#Services)
- 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 :)
Originally posted by Mathias Lüdtke with karma: 1596 on 2016-12-16
This answer was ACCEPTED on the original site
Post score: 6
Original comments
Comment by CJ.Nilson on 2016-12-19:
Thank you for the replies. I still have some questions regarding your replies.
- item 2: I have created URDF to describe elements fo my robot, but why need URDF in ros_canopen
- item 5: Why ros_canopen package need ros_control? Could you briefly introduce the main idea for using ros_control
Comment by CJ.Nilson on 2016-12-19:
I'm trying to refer "schunk_robots and canopen_test_utils" as a model for item 4, 5 and 6. Which packages do you recommend for my case? Thanks you very much.
Comment by Mathias Lüdtke on 2016-12-19:
The URDF is used for getting the joint limits and to verify the names of the joints.
More information on ros_control can be found in the wiki: http://wiki.ros.org/ros_control
And schunk_robots
contains full-fledged examples..
If in doubt have a look at both.
Comment by CJ.Nilson on 2016-12-23:
When I tried to do item 7 you listed, I met the failure during initializing the lwa4d, have you ever meet this before ? Thanks for your reply
Comment by jdeleon on 2018-06-01:
Hello CJ and Mathias, please, could you help me with a similar problem in this question: #q292882
Many thanks,
Jorge
Comment by Cyril Jourdan on 2018-12-06:
@Mathias Lüdtke , When you say use transmission type 1, that is for both RxPDO and TxPDO ?
Comment by Mathias Lüdtke on 2018-12-10:
Yes, for both. This is how we run it with Care-O-bot. It is not mandatory, but it enforces a deterministic data flow. Otherwise the timing would be arbitrary and might result in (small) jumps.
Comment by martinlucan on 2021-07-06:
hi @Mathias Lüdtke , following your steps to successfully control the motor, is user supposed to write and implement some additional hardware interface for Maxon motor, or it is yet included in ros_canopen packages?
Comment by Mathias Lüdtke on 2021-07-06:
It is possible to implement a dedicated motor implementation (example), but it should not be necessary in general. However, I have never tested the default implementation with Maxon motors.