
Hello!
I have the following setup: Microchip CAN BUS Analyzer + Delta ASDA A2 motor driver + ECMA AC servo motor Later there will be more motors and drivers, but now the goal is to control a single motor in ROS. Of course, i both read all the information in wiki.ros and followed all the relevant questions here in the forum, but still my setup is not working, so here i am and would like to ask the parts that are fuzzy.
Quickly i summarize what i've done: (, even though these steps are listed in most of the forum questions and answers, see jdeleon's question or Mathias Lüdtke's answer)
- I set up the ASDA motor driver to CANopen mode, + Node id to 1, + Baudrate to 500 kBps + Sync (see the link: CANopen manual on page 7)
- SocketCAN is set up, running
- URDF is written containing 2 links (base_link, link_1 with visual geometry, collision and inertial tags) + a revolute joint (name:joint_1 with limits, and parent child links) + a transmission(tran1: SimpleTransmission, PositionJointInterface). The URDF was tested in rviz with the joint_state_publisher slider it worked as expected.
- EDS file: This file was given by the manufacturer (EDS file)
- I configured the CANopen bus layer, however i don't know if the heartbeat part is necessary or not (in some forum answers i saw that it was commented out)? (can.yaml)
- i configured the Motor settings and the Node layer with name:joint_1, id:1 (manipulator1d_motors.yaml) however i dont't know what should be the default switching state? (is the default 5, i.e., quick stop ok?)
- Controller config file containing the joint_state_controller and a joint_1_position_controller (type: position_controllers/JointPositionController, joint: joint_1, required_drive_mode: 1) (manipulator1d_controller.yaml)
- Launch file containing robot_description urdf, robot_state_publisher node, joint_state_publisher node, rviz node, + canopen_motor_node with loading the aforementioned can.yaml and manipulator1d_motors.yaml files + load of the controller yaml file, + controller_spawner node with the spawning of the aforementioned controllers
- rosservice call /driver/init
Of course, in the 9th step the service call crashed, with the messages:
first terminal:
[ INFO] [1529055659.976854113]: Using fixed control period: 0.010000000 [ INFO] [1529055664.213323688]: Initializing XXX [ INFO] [1529055664.213611131]: Current state: 1 device error: system:0 internal_error: 0 (OK) [ INFO] [1529055664.213834181]: Current state: 2 device error: system:0 internal_error: 0 (OK) EMCY: 81#4154201300000000 [ERROR] [1529055667.444154070]: Throw location unknown (consider using BOOST_THROW_EXCEPTION) Dynamic exception type: boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> > std::exception::what: boost: mutex lock failed in pthread_mutex_lock: Invalid argument illegal tranistion 0 -> 2 [ INFO] [1529055667.496812113]: Current state: 0 device error: system:0 internal_error: 0 (OK) [ INFO] [1529055667.496986914]: Current state: 0 device error: system:0 internal_error: 0 (OK) second terminal:
success: False message: "Throw location unknown (consider using BOOST_THROW_EXCEPTION)\nDynamic exception\ \ type: boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error>\ \ >\nstd::exception::what: boost: mutex lock failed in pthread_mutex_lock: Invalid\ \ argument\n; Could not set transition" So at this point i started to read everything and dig into the details. More or less all concerns were focused around the EDS file. On one hand i took into account the answer of Mathias Lüdtke (here):
Mapping an object to multiple PDOs is not supported
On the other hand i considered the canopen_402 description
It recommended to map the control word (object 6040, 0x60400010), the status word (object 6041, 0x60410010) and the operation mode display (object 6061, 0x60610008) to PDOs.
And also:
The following table lists all supported drive modes and their data objects. The objects used should be mapped to PDOs.
So i changed/updated the original EDS file as follows: (i omitted the objecttype, datatype, limits, accesstype values)
[1600sub0] ParameterName=number of mapped application objects in PDO DefaultValue=1 PDOMapping=0 ParameterValue=1 [1600sub1] ParameterName=PDO mapping 1 DefaultValue=0x60400010 PDOMapping=0 ParameterValue=0x60400010 [1601sub0] ParameterName=number of mapped application objects in PDO DefaultValue=1 PDOMapping=0 ParameterValue=1 [1601sub1] ParameterName=PDO mapping 1 DefaultValue=0x60410010 PDOMapping=0 [1602sub0] ParameterName=number of mapped application objects in PDO DefaultValue=1 PDOMapping=0 ParameterValue=1 [1602sub1] ParameterName=PDO mapping 1 DefaultValue=0x60610008 PDOMapping=0 [1603sub0] ParameterName=number of mapped application objects in PDO DefaultValue=1 PDOMapping=0 ParameterValue=1 [1603sub1] ParameterName=PDO mapping 1 DefaultValue=0x607a0020 PDOMapping=0 ParameterValue=0x607a0020 Did i do it correctly? Also it is not written anywhere what should be done with the TPDO mapping? (So far i left the TPDO mapping unchanged, as it is in the original EDS file) Can someone recommend a working TPDO mapping?
Next, it is also written here by Mathias Lüdtke that transmission type 1 is required to be used. Therefore i changed the DefaultValue to 1 of the following objects: 1400sub2, 1401sub2, 1402sub2, 1403sub2, 1800sub2, 1801sub2, 1802sub2, 1803sub2
Again, did i do this right?
As a result of consecutive fails, i also tried to change the DefaultValue of the object 6060 (Modes of operation) to 1, since i'd like to use Profile position mode.
Again, no idea if this was a right step?!
After these modifications, i have different crash messages: first terminal:
[ INFO] [1529064851.906620887]: Using fixed control period: 0.010000000 [ INFO] [1529064854.740534586]: Initializing XXX [ INFO] [1529064854.740841900]: Current state: 1 device error: system:0 internal_error: 0 (OK) [ INFO] [1529064854.741085497]: Current state: 2 device error: system:0 internal_error: 0 (OK) EMCY: 81#4154201300000000 EMCY: 81#0000000000000000 EMCY: 81#4154201300000000 [ WARN] [1529064856.861450863]: RPDO timeout [ INFO] [1529064866.811915681]: Current state: 2 device error: system:125 internal_error: 0 (OK) [ INFO] [1529064866.812005487]: Current state: 0 device error: system:125 internal_error: 0 (OK) [ INFO] [1529064866.812045836]: Current state: 0 device error: system:0 internal_error: 0 (OK) [ INFO] [1529064866.812114294]: Current state: 0 device error: system:0 internal_error: 0 (OK) second terminal:
success: False message: "Transition timeout; Could not enable motor; Transition timeout" Here i am stuck, and don't really know what to do. Can someone help me? What to do, what to try? What is wrong with my setup?
I can extend this post, even i can upload the content of the files (yaml, launch, etc.) if its necessary.
Thank you in advance. Best regards, Akos
Originally posted by akosodry on ROS Answers with karma: 121 on 2018-06-15
Post score: 2