CANopen - Maxon MCD Epos Error 6061sub0
Hi all, I'm trying to control the robot described in q#292882, as that question is more general about how to configure all the robot with canopen + ixxat adapter + maxon mcd. I'm openning this new question to try find solution to an specific error that more users say that they have.
At this point, I have configured the canopen node to launch the configuration for the 6 motors.
allow-hotplug can0
iface can0 can static
bitrate 1000000
up ip link set $IFACE txqueuelen 20 # uncomment if more than 4 nodes are used
In my launch file I launch the canopen_motor_node
<node ns="hexapodo" name="driver" pkg="canopen_motor_node" type="canopen_motor_node" output="screen" clear_params="true" launch-prefix="">
<rosparam command="load" file="$(find canopen_chain_node)/config/canopen.yaml" />
</node>
When I try to init the motors (rosservice call /hexapodo/drive/init) I get 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_impl<boost::exception_detail::error_info_injector<std::bad_cast>\
\ >\nstd::exception::what: std::bad_cast\n[canopen::tag_objectdict_key*] = 6061sub0\n"
The 6061 code is refer to the "Modes of Operation Display"
I try to modify the register [6502] as @Edgar Carrasco told me here and @Mathias Lüdtke adding the default value:
[6502]
ParameterName=Supported Drive Modes
DataType=0x0007
AccessType=const
DefaultValue=0x003F0025
PDOMapping=0
ObjFlags=0x1
ParameterValue=0x003F0025
But the error persist.
Many thanks, Jorge
- - - Edit: I have generate a new DCF file from EPOS_UserInterface and paste @Mathias Lüdtke code, but now, the error is also in the service call:
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_impl<boost::exception_detail::error_info_injector<std::bad_cast>\
\ >\nstd::exception::what: std::bad_cast\n[canopen::tag_objectdict_key*] = 6061sub0\n\
; Transition timeout"
And in the launch terminal:
[ERROR] [1528463248.261114363]: /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&)
Dynamic exception type: boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<std::bad_cast> >
std::exception::what: std::bad_cast
[canopen::tag_objectdict_key*] = 6061sub0
If someone wnats to see the DCF files are in this repository. This is the chronology:
- MCDEpos_node_1.dcf
- motor_1_old.dcf
- motor_1.dcf
- Node_1.dcf
- - - Edit 2:
As @Mathias Lüdtke recommended me, I check the file with CANeds.
The result is 499 Errors and 41 Warnings detected.
I have upload the errors to the git.
Now, I will try to find how to solve all this errors and warnings.
- - - Edit 3:
I have compared my DCF file with this one.
And also try to copy the 6061sub0 paremeters. But when I launch the node, I have this error:
[ERROR] [1528795391.251278454]: /home/jorge/WS/epos_ws/src/ros_canopen/canopen_master/include/canopen_master/objdict.h(224): Throw in function const EntryConstSharedPtr& canopen::ObjectDict ...
Your DCF contains a lot of objects with wrong object types, especially the PDO settings. Please fix all of them with CANeds.
Thank you for your comment @Mathias Lüdtke. Which program for CANeds do you recommend? I used Vector CANeds, because it only shows a warning for:
Thank you
I am using CANeds 3.6 (works with wine) and your Node_1.dcf results in plenty of warnings (looks like one warning for each object). I am not sure if these are responsible for the problems.
Thank you for the program @Mathias Lütke, the are a lot of errors and warnings!! I haveuploaded to git. Do you know if there is any template to try to solve the problems to the CANopen standard?
Hi jdeleon thx for your updates! I see a lot of differences between files MCDepos_node_1.dcf and Node_1.dcf, are you sure you haven't removed something that has propagated hundreds of errors ? I have a DCF file from an EPOS2 24/2 (made in EPOS Studio) and I get only 6 erros and 1 warning with CANeds
6061sub0
should not exist in the EDS at all. (it is printed in the error message, but this is just an implementation detail)Hi @Cyril_J, I have talk with Maxon and generate a EDS file for just one motor. Here is the new file.
I check it with CANeds. When it open the file I have a lot of warning, but when I check the file I only have one warning the parameter 202E.
jedeleon, when I open your original DCF file MCDepos_node_1.dcf with CANeds, the only errors that exist are that many objects from the dictionary are set to mappable where they should not. I tried to go through all of them and uncheck the box "Object is mappable", and that solves all the errors.