How to control Maxon MCD Epos with ROS_canopen and IXXAT adapter
Important Edit: for ROS CANopen you don't need to load the controllers, only the URDF file of the motor to get the joints and specifications of it.
Hi all, I am trying to build an RHex style robot.
For it locomotion I have selected 6 Maxon MCD Epos motors. That are connected via CAN with an IXXAT USB-to-CAN adapter.
First of all, I try to manage the MCD with the package epos_hardware ( link ), I get all the motors work but with a different configuration (the first one via USB-RS232 to the computer and then it generates a CAN network with the others motors). The problem is that the frequency to control the motors is only 3 Hz and I need at least 20 Hz.
So, having try ros package epos_hardware and testing that it can't connect to Maxon motors via Canopen I am trying to use ros_canopen package ( can_open ) and following the instructions from Mathias (Instructions)
But I'm having the same errors that CJ.
[ INFO] [1527765873.067864309]: Initializing XXX
[ INFO] [1527765873.068224620]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1527765873.068457195]: Current state: 2 device error: system:0 internal_error: 0 (OK)
[ INFO] [1527765881.288870355]: Current state: 2 device error: system:125 internal_error: 0 (OK)
[ INFO] [1527765881.288943915]: Current state: 0 device error: system:125 internal_error: 0 (OK)
[ INFO] [1527765881.288998158]: Current state: 0 device error: system:0 internal_error: 0 (OK)
[ INFO] [1527765881.289078940]: Current state: 0 device error: system:0 internal_error: 0 (OK)
And also, some errors with the controllers
[INFO] [1527765775.163013]: Controller Spawner: Waiting for service controller_manager/load_controller
[WARN] [1527765805.295161]: Controller Spawner couldn't find the expected controller_manager ROS interface.
I follow all the steps that Mathias explain in the other question.
Setup SocketCAN
Prepare URDF with sane limits The xacro file of the robot is correct. You can download it from here
Prepare EDS/DCF, take special care for the PDO mapping I generated all the 6 files with Maxon Epos Studio and change PDOmapping=0 to PDOmapping=1
Prepare driver config
- prepare chain config
- configure motor-specific settings, especially unit conversions This is my yaml file with the configuration (canopen.yaml)
bus:
device: can0
loopback: false
driver_plugin: can::SocketCANInterface
master_allocator: canopen::SimpleMaster::Allocator
sync:
interval_ms: 10
update_ms: <interval_ms>
overflow: 0
#heartbeat: # simple heartbeat producer, optional!
#rate: 20 # heartbeat rate
msg: "77f#05" # message to send, cansend format: heartbeat of node 127 with status 5=Started
nodes:
node1:
id: 1
eds_pkg: canopen_chain_node # optionals package name for relative path
eds_file: "config/MCDepos_node_1.dcf" # path to EDS/DCF file
node2:
id: 2
eds_pkg: canopen_chain_node # optionals package name for relative path
eds_file: "config/MCDepos_node_2.dcf" # path to EDS/DCF file
node3:
id: 3
eds_pkg: canopen_chain_node # optionals package name for relative path
eds_file: "config/MCDepos_node_3.dcf" # path to EDS/DCF file
node4:
id: 4
eds_pkg: canopen_chain_node # optionals package name for relative path
eds_file: "config/MCDepos_node_4.dcf" # path to EDS/DCF file
node5:
id: 5
eds_pkg: canopen_chain_node # optionals package name for relative path
eds_file: "config ...
Hi jdeleon, I'm very interesting in using maxon controllers with ros_canopen as well. I have them working in ROS for many years with my own code but it's rather limited. Unfortunately the library they provide doesn't deal with CAN and PDO AFAIK. I'll try and share my results.
Hi @Cyril_J, thank you for your reply. Please, could you tell me how are you controlling Maxon Motors? I have been stuck with this problem for more than 8 months. And I need to get a solution.
Thank you!
Jorge
Did you manage to correct the issues with motor4? Could you launch correctly the canopen_motor_node? Can you update your post with the solutions? Thanks in advance. Best regards.
Hi @akosodry, I have just update the situation. - I have no error with motor4. I don't know why. - I can launch correctly canopen_motor_node, but I can't initialize correctly the motors:
Thnk you @jdeleon for the detailed update. Its nice to have these reference subresults, without these and the forum it would have been much much difficult. I am starting to work on a Delta motors-based setup from saturday. If i succeed i will also try to help here.
Hi @jdeleon, I have exactly the same error during the driver/init service call. In my setup I've got an EPOS 2 70/10 motor controller which I would like to drive in current mode.
Hi @Soeren, this might be unrelated to your error, but I think maxon current mode is not a standard mode in CANOpen CiA 402, and also not listed in canopen_402. I'm using current mode a lot with EPOS2, so I'm very interested to know how to extend this package with custom modes.
Hi @akosodry, hope you be successful, which motors are you using?