You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I am trying to control the motor iHSV60 but I'm getting the following error when calling the /init service. The configuration I'm using is almost the same as in the Trinamic Stepper Motor control example (launch and yml file display below).
[device_container_node-1] async_sdo_read: id=1 index=0x6502 subindex=0 object does not exist
[device_container_node-1] [ERROR] [1722519461.021056659] [IHSV60]: 01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
I tried to fix it by adding one more entry in the EDS file like this:
But this only moved the error further, now the /init call doesn't fail immediately after, now it actually tries to read the dictionary through the CAN channel:
I've checked the motor's datasheet and confirmed with the manufacturer that the motor does not support the OD 6502h. So my question is: Is it still possible to use this library if the motor does not support such dictionary? If so, what is the workaround?
paltech@paltech-thinkpad:~/ros2_ws$ ros2 launch motors-config-pkg bus_config_motor_1.launch.py
[INFO] [launch]: All log files can be found below /home/paltech/.ros/log/2024-08-01-15-56-57-036917-paltech-thinkpad-46068
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [launch.user]: /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/bus.yml
[INFO] [launch.user]: /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/master.dcf
[INFO] [launch.user]: /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/master.bin
[INFO] [launch.user]: can0
[INFO] [device_container_node-1]: process started with pid [46079]
[device_container_node-1] [INFO] [1722520617.164204044] [device_container_node]: Starting Device Container with:
[device_container_node-1] [INFO] [1722520617.164336244] [device_container_node]: master_config /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/master.dcf
[device_container_node-1] [INFO] [1722520617.164343878] [device_container_node]: bus_config /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/bus.yml
[device_container_node-1] [INFO] [1722520617.164351482] [device_container_node]: can_interface_name can0
[device_container_node-1] [INFO] [1722520617.165469895] [device_container_node]: Loading Master Configuration.
[device_container_node-1] [INFO] [1722520617.166156722] [device_container_node]: Load Library: /home/paltech/ros2_ws/install/canopen_master_driver/lib/libmaster_driver.so
[device_container_node-1] [INFO] [1722520617.169161847] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1722520617.169201192] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1722520617.172757358] [master]: NodeCanopenBasicMaster
[device_container_node-1] [INFO] [1722520617.172890029] [device_container_node]: Load master component.
[device_container_node-1] [INFO] [1722520617.172963828] [device_container_node]: Added /master to executor
[device_container_node-1] [WARN] [1722520617.174726166] [master]: No timeout parameter found in config file. Using default value of 100ms.
[device_container_node-1] [INFO] [1722520617.174778165] [master]: Master boot timeout set to 2000ms.
[device_container_node-1] [INFO] [1722520617.187685642] [device_container_node]: Loading Driver Configuration.
[device_container_node-1] [INFO] [1722520617.187797504] [device_container_node]: Found device IHSV60 with driver ros2_canopen::Cia402Driver
[device_container_node-1] [INFO] [1722520617.188177561] [device_container_node]: Load Library: /home/paltech/ros2_ws/install/canopen_402_driver/lib/libcia402_driver.so
[device_container_node-1] [INFO] [1722520617.193788208] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1722520617.193844965] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1722520617.198714772] [device_container_node]: Load driver component.
[device_container_node-1] [INFO] [1722520617.198939166] [device_container_node]: Added /IHSV60 to executor
[device_container_node-1] [INFO] [1722520617.212621347] [IHSV60]: Non transmit timeout100ms
[device_container_node-1] [WARN] [1722520617.212766852] [IHSV60]: Could not readenable diagnostics from config, setting to false.
[device_container_node-1] [INFO] [1722520617.213018768] [IHSV60]: scale_pos_to_dev_ 1000.000000
[device_container_node-1] scale_pos_from_dev_ 0.001000
[device_container_node-1] scale_vel_to_dev_ 1.000000
[device_container_node-1] scale_vel_from_dev_ 1.000000
[device_container_node-1]
[device_container_node-1] [INFO] [1722520617.215243890] [IHSV60]: eds file /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/IHSS57_60-RC_V2.3.eds
[device_container_node-1] [INFO] [1722520617.215297241] [IHSV60]: bin file /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/IHSV60.bin
[device_container_node-1] Found rpdo mapped object: index=607a subindex=0
[device_container_node-1] Found rpdo mapped object: index=6081 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6084 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6040 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6099 subindex=2
[device_container_node-1] Found rpdo mapped object: index=6099 subindex=1
[device_container_node-1] Found rpdo mapped object: index=609a subindex=0
[device_container_node-1] Found rpdo mapped object: index=6085 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6060 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6098 subindex=0
[device_container_node-1] Found rpdo mapped object: index=607a subindex=0
[device_container_node-1] Found rpdo mapped object: index=6040 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6064 subindex=0
[device_container_node-1] Found tpdo mapped object: index=606c subindex=0
[device_container_node-1] Found tpdo mapped object: index=6041 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6061 subindex=0
[device_container_node-1] [WARN] [1722520617.218262181] [IHSV60]: Wait for device to boot.
[device_container_node-1] [INFO] [1722520618.027707776] [IHSV60]: Driver booted and ready.
[device_container_node-1] [INFO] [1722520618.028548404] [IHSV60]: Starting with event mode.
[device_container_node-1] [INFO] [1722520619.028042748] [IHSV60]: Slave 0x1: Switched NMT state to START
[device_container_node-1] [ERROR] [1722520645.403552898] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.406511145] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.409170487] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.411753104] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.414021258] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.416728139] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.421436551] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.424831332] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.427197851] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [INFO] [1722520645.427294734] [canopen_402_driver]: Init: Read State
[device_container_node-1] [INFO] [1722520645.427344318] [canopen_402_driver]: Init: Enable
[device_container_node-1] [ERROR] [1722520645.429970458] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [INFO] [1722520645.430070607] [canopen_402_driver]: Init: Switch to homing
[device_container_node-1] [ERROR] [1722520645.432443578] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [INFO] [1722520645.437869184] [canopen_402_driver]: Fault reset
[device_container_node-1] [INFO] [1722520645.458901153] [canopen_402_driver]: Init: Execute homing
[device_container_node-1] [INFO] [1722520645.464218174] [canopen_402_driver]: Init: Switch no mode
Describe the bug
I am trying to control the motor iHSV60 but I'm getting the following error when calling the /init service. The configuration I'm using is almost the same as in the Trinamic Stepper Motor control example (launch and yml file display below).
I tried to fix it by adding one more entry in the EDS file like this:
But this only moved the error further, now the /init call doesn't fail immediately after, now it actually tries to read the dictionary through the CAN channel:
I've checked the motor's datasheet and confirmed with the manufacturer that the motor does not support the OD 6502h. So my question is: Is it still possible to use this library if the motor does not support such dictionary? If so, what is the workaround?
Logs
Launch file
YAML file
Launch terminal
CAN channel
Setup:
The text was updated successfully, but these errors were encountered: