0
$\begingroup$

Rosanswers logo


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.

RHex robot

For it locomotion I have selected 6 Maxon MCD Epos motors. That are connected via CAN with an IXXAT USB-to-CAN adapter.

Maxon MCD Epos

IXXAT adapter http://kartmasters.fr/shop/2208-large_default/ixxat-usb-to-can-compact-v2-intelligent-can-interface.jpg

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.

  1. Setup SocketCAN Can0 port

  2. Prepare URDF with sane limits The xacro file of the robot is correct. You can download it from here

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

  4. 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/MCDepos_node_5.dcf" # path to EDS/DCF file

  node6:
    id: 6
    eds_pkg: canopen_chain_node # optionals package name for relative path
    eds_file: "config/MCDepos_node_6.dcf" # path to EDS/DCF file

defaults:

motor_allocator: canopen::Motor402::Allocator # select allocator for motor layer  
#motor_layer: # settings passed to motor layer (plugin-specific)   
switching_state: 5 # (Operation_Enable), state for mode switching   
pos_to_device: "rint(rad2deg(pos)*1000)" # rad -> mdeg   
pos_from_device: "deg2rad(obj6064)/1000" # actual position [mdeg] -> rad   
vel_to_device: "rint(rad2deg(vel)*1000)" # rad/s -> mdeg/s   
vel_from_device: "deg2rad(obj606C)/1000" # actual velocity [mdeg/s] -> rad/s   
eff_to_device: "rint(eff)" # just round to integer  
#eff_from_device: "0" # unset
  1. Prepare controller config (list of controllers and add a required_drive_mode to each motion controller) I take the same controller config that I use for the Gazebo model of the robot. The required_drive_mode I have try with #3 and #-1 but without good results

    hexapodo:

    Publish all joint states -----------------------------------

     joint_state_controller:
         type: joint_state_controller/JointStateController
         publish_rate: 50
    

    Velocity Controllers ---------------------------------------

     pata1_velocity_controller:
         type: effort_controllers/JointVelocityController
         joint: pata_1_to_base_link_joint
         pid: {p: 3.0, i: 0.0, d: 0.0}
         required_drive_mode: -1
     pata2_velocity_controller:
         type: effort_controllers/JointVelocityController
         joint: pata_2_to_base_link_joint
         pid: {p: 3.0, i: 0.0, d: 0.0}
         required_drive_mode: -1
     pata3_velocity_controller:
         type: effort_controllers/JointVelocityController
         joint: pata_3_to_base_link_joint
         pid: {p: 3.0, i: 0.0, d: 0.0}
         required_drive_mode: -1
     pata4_velocity_controller:
         type: effort_controllers/JointVelocityController
         joint: pata_4_to_base_link_joint
         pid: {p: 3.0, i: 0.0, d: 0.0}
         required_drive_mode: -1
     pata5_velocity_controller:
         type: effort_controllers/JointVelocityController
         joint: pata_5_to_base_link_joint
         pid: {p: 3.0, i: 0.0, d: 0.0}
         required_drive_mode: -1
     pata6_velocity_controller:
         type: effort_controllers/JointVelocityController
         joint: pata_6_to_base_link_joint
         pid: {p: 3.0, i: 0.0, d: 0.0}
         required_drive_mode: -1
    
  2. Prepare a launchfile for canopen_motor_node This is my launch file

     <!-- Load the URDF into ROS parameter server -->
     <param name="robot_description"
          command="$(find xacro)/xacro.py '$(find hexapodo_description)/robots/hexapodo.robot.xacro' --inorder" />
    
     <node name="canopen_chain" pkg="canopen_chain_node" type="canopen_chain_node" output="screen" clear_params="true">
         <rosparam command="load" file="$(find canopen_chain_node)/config/canopen.yaml" />
     </node>
    
     <rosparam file="$(find hexapodo_control)/config/hexapodo_control.yaml" command="load"/>
    
     <!-- load the controllers -->
     <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
       output="screen" ns="/hexapodo" args="joint_state_controller
                                        pata1_velocity_controller
                                        pata2_velocity_controller
                                        pata3_velocity_controller
                                        pata4_velocity_controller
                                        pata5_velocity_controller
                                        pata6_velocity_controller"/>
    
     <!-- Combine joint values -->
     <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher"/>
    
     <!-- Show in Rviz   -->
     <node name="rviz" pkg="rviz" type="rviz"/>
    
  3. rosservice call [/namespace]/driver/init

In the terminal of the rosservice this is the error:

ros service call /driver/init
success: False
message: "could not start node 4'"

And this is the error in the terminal of the launch:

[ INFO] [1527765454.881980035]: Initializing XXX
[ INFO] [1527765454.882339672]: Current state: 1 device error: system:0 internal_error:0 (OK)
[ INFO] [1527765454.882559786]: Current state: 2 device error: system:0 internal_error:0 (OK)
[ INFO] [1527765463.106458264]: Current state:2 device error: system:125 internal_error:0 (OK)
[ INFO] [1527765463.106574774]: Current state:0 device error: system:125 internal_error:0 (OK)
[ INFO] [1527765463.106652287]: Current state: 0 device error: system:0 internal_error:0 (OK)
[ INFO] [1527765463.106747207]: Current state: 0 device error: system:0 internal_error:0 (OK)
  1. start/switch the controllers When I launch everything I have the next error:

    [INFO] []: Controller Spawner: Waiting for service controller_manager/load_controller [WARN] []: Controller Spawner couldn't find the expected controller_manager ROS interface.

And I can't start the controllers

I don't know what I'm doing wrong or missing.

Can somebody help me with this error?

Many thanks, Jorge

PD: I forgot to say that I am using Ubuntu 16.04 with Ros Kinetic in a desktop computer with a i7 6700k processor

EDIT: something is wrong with the motor4.dcf file. I have removed it from the launcher and I can init the motors correctly.

If I call the service /drive/init I get the next:

[ INFO] [1528110567.396963215]: Initializing XXX
[ INFO] [1528110567.397355739]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1528110567.397765080]: Current state: 2 device error: system:0 internal_error: 0 (OK)
EMCY: 81#0000000000000000
EMCY: 82#0000000000000000
EMCY: 83#0000000000000000
EMCY: 85#0000000000000000
EMCY: 86#0000000000000000

The next step is to try to launch correctly the canopen_motor_node. When I get it, I will post it here.


Update June 7th

As I write at the beginning and in question #293260 for ROS CANopen is only needed the URDF of the robot.

Also I have modify the launch file as @Mathias Lüdtke explain me in the github issue.

So, at this moment:

  • I have no error with node 4. I don't know why, but I generate a new DCF file with Epos Studio and there is no error.
  • I can't continue initializing the motors. When I call the service, I have the next error:

jorge@jorge-ubuntu:~$ rosservice call /hexapodo/driver/init success: False message: "/home/jorge/WS/epos_ws/src/ros_canopen/canopen_master/src/pdo.cpp(359): Throw in
\ function void canopen::PDOMapper::Buffer::read(const canopen::ObjectDict::Entry&,
\ canopen::String&)\nDynamic exception type: boost::exception_detail::clone_implboost::exception_detail::error_info_injector<std::bad_cast
\ >\nstd::exception::what: std::bad_cast\n[canopen::tag_objectdict_key*] = 6061sub0\n"

I asked @asier.fernandez in his q#292443, but his error is different.

Searching for 6061 in the Epos Firmware Specification, there isn't any reference to this number.

But if I search for 6061 in the DCF file I get: "Modes of Operation Display".

[6061]
ParameterName=Modes of Operation Display
DataType=0x0002
AccessType=ro
PDOMapping=1
ObjFlags=0x3

Then, in the Firmware Specification Document, the Modes of Operation Display are the next:

Operation Mode - Description

6 Homing Mode

3 Profile Velocity Mode

1 Profile Position Mode

-1 Position Mode

-2 Velocity Mode

-3 Current Mode

-4 Diagnostic Mode

-5 MasterEncoder Mode

-6 Step/Direction Mode

As Mathias told me in the github issue, I download CANchkEDS from vektor, when I check the DCF files, I have 1 error:

[202E]
ParameterName=Trajectory Profile Time
DataType=7
AccessType=ro
PDOMapping=1
ObjFlags=3

I have try to comment that section of the file, but the error persists.

And now, I'm stuck at this point. I have send an email to Maxon to try to identify the 6061 Error, but still waiting for they answer.



Originally posted by jdeleon on ROS Answers with karma: 133 on 2018-05-31

Post score: 3


Original comments

Comment by Cyril Jourdan on 2018-06-01:
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.

Comment by jdeleon on 2018-06-04:
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

Comment by akosodry on 2018-06-07:
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.

Comment by jdeleon on 2018-06-07:
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:
\ >\nstd::exception::what: std::bad_cast\n[canopen::tag_objectdict_key*] = 6061sub0\n

Comment by akosodry on 2018-06-07:
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.

Comment by Soeren on 2018-06-07:
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.

Comment by Cyril Jourdan on 2018-06-07:
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.

Comment by jdeleon on 2018-06-08:
Hi @akosodry, hope you be successful, which motors are you using?

Comment by jdeleon on 2018-06-08:
Hi @Soeren, have you try epos_hardware? if you are trying to control an EPOS 2, I will try that package first. I'm trying to control my motors with velocity profile, but still stuck on that.

Comment by asier.fernandez on 2018-06-08:
Hi, as it's explained in canopen_motor_node the interfaces of controller_manager are available after initialization. First I'd focus on properly initializing it

Comment by akosodry on 2018-06-08:
Hi @jdeleon. I will be using Delta Delta ASDA A2 servo drives with a 400W servo motors. Currently i am still waiting for the USB-CAN coverter module :)

Comment by Cyril Jourdan on 2018-06-11:
I have a DCF file generated from an EPOS2 24/2 and my section for the address 6061 has more information : [6061] ParameterName=Modes of Operation Display ObjectType=0x7 DataType=0x2 AccessType=ro PDOMapping=1 ObjFlags=1 ParameterValue=0x03

Comment by akosodry on 2018-06-15:
Hi @jdeleon.

I have the same problem as you had a week ago:

[ERROR] [1529052327.383534461]: RPDO timeout; ....................
.......
std::exception::what: SDO
[canopen::tag_objectdict_key*] = 6061sub0

Did you manage to solve the problem?

Comment by jdeleon on 2018-06-19:
Hi @akosodry,

No, I couldn't solved the problem yet. I will try now with kaCanopen

Comment by akosodry on 2018-06-19:
Hi @jdeleon,

i am also facing problems, i did not think that it will be that complicated to solve..... Please keep me posted on what are your results with kaCanopen

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Hi guys, I stopped working with ros_canopen_chain_node and motor_node when I saw that the messages on the CANbus sent by a device/setobject service call to change my controlword made no sense.

I'm now using the kaCanopen C++ library - Its well documented, full of examples and works like a charm! Maybe it's also worth a shot for all who are struggling with getting ros_canopen running!

Cheers, Sören


Originally posted by Soeren with karma: 46 on 2018-06-15

This answer was ACCEPTED on the original site

Post score: 3


Original comments

Comment by jdeleon on 2018-06-19:
Hi @Soeren,

thank you for your message. I will try with that package.

Do you have Maxon motors?

Comment by Soeren on 2018-06-19:
In my setup I've got an EPOS 2 70/10 motor controller.

Comment by Cyril Jourdan on 2018-06-19:
Does this package have an interface with ros_control ?

Comment by jdeleon on 2018-06-19:
@Soeren, Could you share your project in github?

I try to compile the package, but as I'm using a IXXAT adapter, it is not supported:

"At the moment, the following drivers are available: lincan, peak_linux, serial, socket, virtual, dummy."

Comment by jdeleon on 2018-06-21:
@Soeren, could you tell me which CAN adapter are you using?

Thank you!

Comment by Cyril Jourdan on 2018-06-21:
@jdeleon, Just for information, if you need a cheap USB to CAN, the CANable works fine with SocketCAN, otherwise the Jetson TX2 is a good way to have embedded CAN bus. I use the IXAAT only as a bus sniffer on Windows.

Comment by jdeleon on 2018-06-21:
thank you for the information @Cyril_J I use IXXAT because Maxon told me that was the one that really works. And it works with example cpp with linux.

The people from Maxon told me that maybe the problem could be with that the package uses the PDOs instead the SDOs

Comment by jdeleon on 2018-06-21:
Thank you for the CANable adapter, but they don't send to Spain...

Comment by Cyril Jourdan on 2018-06-21:
KaCanOpen implements both SDOs/PDOs, I don't think that's the problem, it's a driver issue. You can try the Peak PCAN which seems to be supported, or some SPI to CAN. Other option, I used to program CAN on the mbed microcontroller and linked that with RS232 to USB to the robot computer running ROS.

Comment by Soeren on 2018-06-21:
Hey @jdeleon I'm sorry I'm not allowed to share my project, but I can tell you that I'm using a PeakCan adapter. Cheers Sören

Comment by jdeleon on 2018-06-25:
Hi @Cyril_J, I'm trying now with a borrow Peak PCAN, but have some problems compiling. I first run the EPOS with a RS232 to USB adapter, but I have less than 3 Hz, so the system didn't work correctly.

Comment by jdeleon on 2018-06-26:
Hi all, I have continue working with kacanopen package.

I couldn't control the motors with the Peak CAN controller as a pcanusb device.

But then, I try again the IXXAT controller and the kacanopen with the Socket configuration, and at this moment I can control one leg in position profile.

Comment by akosodry on 2018-06-27:
Hi @jdeleon Can you share your github repo? Or can you share your kacanopen based package? Im really interested how did you manage to control the leg in position profile. Thanks in advance.

Comment by jdeleon on 2018-06-28:
Hi @akosodry, I have create this new question #q295339 to continue there talking about kacanopen, and there, is the link to the repo

Comment by Mathias Lüdtke on 2018-12-10:
Actually, if SDOs are used for setting the control words, you missed to set-up a PDO for it. ros_canopen uses PDOs if configured properly. But not all devices support PDOs.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.