ros-industrial / ros2_canopen

CANopen driver framework for ROS2
https://ros-industrial.github.io/ros2_canopen/manual/rolling/
156 stars 68 forks source link

Could not enable motor, Transition timed out #298

Open david-paltech opened 3 months ago

david-paltech commented 3 months ago

Describe the bug I am trying to control the motor iSV2-CAN but I'm experiencing issues when calling the service /init. The configuration I'm using is almost the same as in the Trinamic Stepper Motor control example (launch and yml file display below). When I launched the file everything seems ok until I call the service /init. When I do, the library tries to read the dictionary 6502h (according to the CAN messages) many times for some reason, and while this happens, three things occur simultaneously.

  1. The library fails to switch to Operation_Enable state (number 5). it just switches between states 2,3,4,8 Switch_On_Disabled = 2, Ready_To_Switch_On = 3, Switched_On = 4, Fault = 8, I know this because I added log msgs inside the library
  2. The ALARM of the motor short blinks 20 times, which does not correspond to any error code according to datasheet.
  3. When the timeout is fulfilled and the message "Could not enable motor" appears in the terminal, the motor responds through the CAN channel with an error message: can0 081 [8] 01 52 80 00 00 00 70 08 -> Error 5201: Servo unable to enable under current mode (according to datasheet) Additionally, the ALARM displays the same error 5201 by short blinking 9 times.

Any idea what might be happening? I've checked and the motor supports the OD 6502h, and it is defined in the EDS file:

[6502]
ParameterName=support drive modes
ObjectType=7
DataType=0x0007
AccessType=rw
LowLimit=0
HighLimit=2147483647
DefaultValue=0x0000002D
PDOMapping=0

Logs Launch file

import os
import sys

sys.path.insert(0, os.path.join(os.path.dirname(__file__), ".."))  # noqa
sys.path.insert(0, os.path.join(os.path.dirname(__file__), "..", "..", "launch"))  # noqa

import launch
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python import get_package_share_directory
from launch import LaunchDescription

PACKAGE_NAME = "motors-config-pkg"  #"trinamic_pd42_can"
BUS_CONFIG_NAME = "bus_config_motor_1"  #"single-pd42"
EDS_NAME = "iSV2.eds"

def generate_launch_description():
    ld = LaunchDescription()

    device_container = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            [
                os.path.join(get_package_share_directory("canopen_core"), "launch"),
                "/canopen.launch.py",
            ]
        ),
        launch_arguments={
            "master_config": os.path.join(
                get_package_share_directory(PACKAGE_NAME),
                "config",
                BUS_CONFIG_NAME,
                "master.dcf",
            ),
            "master_bin": os.path.join(
                get_package_share_directory(PACKAGE_NAME),
                "config",
                BUS_CONFIG_NAME,
                "master.bin",
            ),
            "bus_config": os.path.join(
                get_package_share_directory(PACKAGE_NAME),
                "config",
                BUS_CONFIG_NAME,
                "bus.yml",
            ),
            "can_interface_name": "can0",
        }.items(),
    )

    ld.add_action(device_container)

    return ld

YAML file

options:
    dcf_path: "@BUS_CONFIG_PATH@"

master:
    node_id: 2
    baudrate: 125   # kbit/s (default: 1000)
    driver: "ros2_canopen::MasterDriver"
    package: "canopen_master_driver"
    sync_period: 20000

defaults:
    dcf: "iSV2.eds"
    driver: "ros2_canopen::Cia402Driver"
    package: "canopen_402_driver"
    polling: false
    heartbeat_producer: 1000 # Heartbeat every 1000 ms
    # sdo_timeout_ms: 10000
    # scale_vel_to_dev: 1      # Scaling, 25.0: target=100 -> 100 rpm (scale_vel_from_dev=default)
    # scale_vel_from_dev: 1
    sdo:
        - {index: 0x6081, sub_index: 0, value: 1000}     # Driver constant speed
        - {index: 0x6083, sub_index: 0, value: 1000}     # Maximum acceleration
        - {index: 0x6084, sub_index: 0, value: 1000}     # Maximum deceleration
        - {index: 0x6085, sub_index: 0, value: 10000}    # Quick stop deceleration
        - {index: 0x6098, sub_index: 0, value: 3}       # Homing method
        - {index: 0x6099, sub_index: 1, value: 1000}    # Homing speed during search for switch
        - {index: 0x6099, sub_index: 2, value: 100}     # Homing speed during search for zero
        - {index: 0x609A, sub_index: 0, value: 1000}    # Homing acceleration
    # tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation
    #     1:
    #         enabled: false
    #         cob_id: "auto"
    #         transmission: 0x01
    #         mapping:
    #             - {index: 0x6064, sub_index: 0} # position actual value
    #             - {index: 0x606c, sub_index: 0} # velocity actual position
    #     2:
    #         enabled: true
    #         cob_id: "auto"
    #         transmission: 0x01
    #         mapping:
    #             - {index: 0x6041, sub_index: 0} # status word
    #             - {index: 0x6061, sub_index: 0} # mode of operation display
    #     3:
    #         enabled: false

    #     4:
    #         enabled: false

    # rpdo: # RPDO needed controlword, target position, target velocity, mode of operation
    #     1:
    #         enabled: false
    #         cob_id: "auto"
    #         mapping:
    #         - {index: 0x607A, sub_index: 0} # target position
    #         - {index: 0x6081, sub_index: 0} # target velocity
    #     2:
    #         enabled: true
    #         cob_id: "auto"
    #         mapping:
    #         - {index: 0x6040, sub_index: 0} # controlword
    #         # - {index: 0x6060, sub_index: 0} # mode of operation

nodes:
    ISV2:
        node_id: 1

Launch terminal

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-13-32-12-843393-paltech-thinkpad-32995
[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 [33006]
[device_container_node-1] [INFO] [1722511932.987664338] [device_container_node]: Starting Device Container with:
[device_container_node-1] [INFO] [1722511932.987788134] [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] [1722511932.987795720] [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] [1722511932.987802744] [device_container_node]:     can_interface_name can0
[device_container_node-1] [INFO] [1722511932.988606815] [device_container_node]: Loading Master Configuration.
[device_container_node-1] [INFO] [1722511932.989919699] [device_container_node]: Load Library: /home/paltech/ros2_ws/install/canopen_master_driver/lib/libmaster_driver.so
[device_container_node-1] [INFO] [1722511932.993051174] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1722511932.993095011] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1722511932.996032029] [master]: NodeCanopenBasicMaster
[device_container_node-1] [INFO] [1722511932.996169193] [device_container_node]: Load master component.
[device_container_node-1] [INFO] [1722511932.996249833] [device_container_node]: Added /master to executor
[device_container_node-1] [WARN] [1722511932.997924027] [master]: No timeout parameter found in config file. Using default value of 100ms.
[device_container_node-1] [INFO] [1722511932.997966872] [master]: Master boot timeout set to 2000ms.
[device_container_node-1] [INFO] [1722511933.010870325] [device_container_node]: Loading Driver Configuration.
[device_container_node-1] [INFO] [1722511933.010998380] [device_container_node]: Found device ISV2 with driver ros2_canopen::Cia402Driver
[device_container_node-1] [INFO] [1722511933.011365030] [device_container_node]: Load Library: /home/paltech/ros2_ws/install/canopen_402_driver/lib/libcia402_driver.so
[device_container_node-1] [INFO] [1722511933.017139037] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1722511933.017203165] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1722511933.020702542] [device_container_node]: Load driver component.
[device_container_node-1] [INFO] [1722511933.020929344] [device_container_node]: Added /ISV2 to executor
[device_container_node-1] [INFO] [1722511933.033055329] [ISV2]: Non transmit timeout100ms
[device_container_node-1] [WARN] [1722511933.033187342] [ISV2]: Could not read enable diagnostics from config, setting to false.
[device_container_node-1] [INFO] [1722511933.033379574] [ISV2]: scale_pos_to_dev_ 1000.000000
[device_container_node-1] scale_pos_from_dev_ 0.001000
[device_container_node-1] scale_vel_to_dev_ 1000.000000
[device_container_node-1] scale_vel_from_dev_ 0.001000
[device_container_node-1] 
[device_container_node-1] [INFO] [1722511933.034995181] [ISV2]: eds file /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/iSV2.eds
[device_container_node-1] [INFO] [1722511933.035037947] [ISV2]: bin file /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/ISV2.bin
[device_container_node-1] Found rpdo mapped object: index=6040 subindex=0
[device_container_node-1] Found rpdo mapped object: index=607a subindex=0
[device_container_node-1] Found rpdo mapped object: index=6060 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6081 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6083 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6040 subindex=0
[device_container_node-1] Found rpdo mapped object: index=60ff subindex=0
[device_container_node-1] Found rpdo mapped object: index=6060 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6083 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6084 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6041 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6041 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6064 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6061 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=6064 subindex=0
[device_container_node-1] Found tpdo mapped object: index=60fd subindex=0
[device_container_node-1] [WARN] [1722511933.043242453] [ISV2]: Wait for device to boot.
[device_container_node-1] [INFO] [1722511934.045641713] [ISV2]: Driver booted and ready.
[device_container_node-1] [INFO] [1722511934.046445824] [ISV2]: Starting with event mode.
[device_container_node-1] [INFO] [1722511934.052543866] [canopen_402_driver]: Fault reset
[device_container_node-1] [INFO] [1722511935.045446281] [ISV2]: Slave 0x1: Switched NMT state to START
## SERVICE INIT CALLED HERE ##
[device_container_node-1] [INFO] [1722512047.682393729] [canopen_402_driver]: Init: Read State
[device_container_node-1] [INFO] [1722512047.682552726] [canopen_402_driver]: Init: Enable
[device_container_node-1] [INFO] [1722512047.692108828] [canopen_402_driver]: Fault reset
[device_container_node-1] [INFO] [1722512052.682891861] [canopen_402_driver]: Transition timed out.
[device_container_node-1] Could not enable motor

CAN messages

  can0  701   [1]  00
  can0  701   [1]  7F           # Heartbeat signals
  can0  701   [1]  7F           # Heartbeat signals
  can0  701   [1]  7F           # Heartbeat signals
  can0  701   [1]  7F           # Heartbeat signals
  can0  702   [1]  00
  can0  000   [2]  82 00      # NMT msg: Reset Communication
  can0  080   [0] 
  can0  701   [1]  00
  can0  601   [8]  40 00 10 00 00 00 00 00       # Reading Manufacturer dictionaries
  can0  581   [8]  43 00 10 00 92 01 02 00       #
  can0  601   [8]  40 18 10 01 00 00 00 00       #
  can0  581   [8]  43 18 10 01 31 03 00 00       #
  can0  601   [8]  40 18 10 02 00 00 00 00       #
  can0  080   [0] 
  can0  581   [8]  43 18 10 02 4A 00 00 00       #
  can0  601   [8]  40 18 10 03 00 00 00 00       #
  can0  581   [8]  43 18 10 03 00 01 00 00       #
  can0  601   [8]  40 18 10 04 00 00 00 00       #
  can0  581   [8]  43 18 10 04 01 00 00 00       # Reading Manufacturer dictionaries
  can0  601   [8]  2B 17 10 00 E8 03 00 00      # Setting new heartbeat value
  can0  581   [8]  60 17 10 00 00 00 00 00
  can0  601   [8]  23 81 60 00 E8 03 00 00       # Config SDO's
  can0  581   [8]  60 81 60 00 00 00 00 00       #
  can0  601   [8]  23 83 60 00 E8 03 00 00       #
  can0  581   [8]  60 83 60 00 00 00 00 00       #
  can0  601   [8]  23 84 60 00 E8 03 00 00       #
  can0  080   [0] 
  can0  581   [8]  60 84 60 00 00 00 00 00       #
  can0  601   [8]  23 85 60 00 10 27 00 00       #
  can0  581   [8]  60 85 60 00 00 00 00 00       #
  can0  601   [8]  2F 98 60 00 03 00 00 00       #
  can0  581   [8]  60 98 60 00 00 00 00 00       #
  can0  601   [8]  23 99 60 01 E8 03 00 00       #
  can0  581   [8]  60 99 60 01 00 00 00 00       #
  can0  601   [8]  23 99 60 02 64 00 00 00       #
  can0  581   [8]  60 99 60 02 00 00 00 00       #
  can0  601   [8]  23 9A 60 00 E8 03 00 00       #
  can0  581   [8]  60 9A 60 00 00 00 00 00       # Config SDO's
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  .
  .
  .
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  701   [1]  7F
  can0  000   [2]  01 01              # NMT msg Switch slave 1 to the "Operational" state
  can0  181   [2]  00 04
  can0  281   [7]  00 04 51 1A 00 00 00
  can0  381   [8]  51 1A 00 00 00 00 00 00
  can0  481   [8]  51 1A 00 00 00 00 00 01
  can0  181   [2]  50 06
  can0  080   [0] 
  can0  281   [7]  50 06 51 1A 00 00 01
  can0  201   [7]  6E 4D 00 00 00 00 00
  can0  401   [7]  6E 4D 00 00 00 00 00
  can0  181   [2]  31 06
  can0  281   [7]  31 06 51 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  6E 4D 00 00 00 00 00
  can0  401   [7]  6E 4D 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  6E 4D 00 00 00 00 00
  can0  401   [7]  6E 4D 00 00 00 00 00
  can0  080   [0] 
  .
  .
  .
  can0  201   [7]  6E 4D 00 00 00 00 00
  can0  401   [7]  6E 4D 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  6E 4D 00 00 00 00 00
  can0  401   [7]  6E 4D 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  6E 4D 00 00 00 00 00
  can0  401   [7]  6E 4D 00 00 00 00 00            # HERE I CALL THE INIT SERVICE
  can0  601   [8]  40 02 65 00 00 00 00 00        # Reading OD 6502h
  can0  581   [8]  43 02 65 00 2D 00 03 00        # Success reading 
  can0  601   [8]  40 02 65 00 00 00 00 00        #
  can0  581   [8]  43 02 65 00 2D 00 03 00        #
  can0  601   [8]  40 02 65 00 00 00 00 00        #
  can0  581   [8]  43 02 65 00 2D 00 03 00        #
  can0  601   [8]  40 02 65 00 00 00 00 00        #
  can0  581   [8]  43 02 65 00 2D 00 03 00        #
  can0  601   [8]  40 02 65 00 00 00 00 00        #
  can0  581   [8]  43 02 65 00 2D 00 03 00        #
  can0  601   [8]  40 02 65 00 00 00 00 00        #
  can0  080   [0] 
  can0  201   [7]  6E 4D 00 00 00 00 00            #
  can0  581   [8]  43 02 65 00 2D 00 03 00        #
  can0  401   [7]  6E 4D 00 00 00 00 00            #
  can0  601   [8]  40 02 65 00 00 00 00 00        #
  can0  581   [8]  43 02 65 00 2D 00 03 00        #
  can0  601   [8]  40 02 65 00 00 00 00 00        #
  can0  581   [8]  43 02 65 00 2D 00 03 00        #
  can0  601   [8]  40 02 65 00 00 00 00 00        # Reading OD 6502h
  can0  581   [8]  43 02 65 00 2D 00 03 00        # Success reading 
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00             # Controlword setting bits to enable motor
  can0  401   [7]  07 01 00 00 00 00 00
  can0  181   [2]  33 06
  can0  281   [7]  33 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00             # Controlword setting bits to enable motor
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  181   [2]  37 06
  can0  281   [7]  37 06 52 1A 00 00 00
  can0  081   [8]  01 52 80 00 00 00 70 08        # ERROR 5201
  can0  481   [8]  52 1A 00 00 00 00 00 03
  can0  181   [2]  38 06
  can0  281   [7]  38 06 52 1A 00 00 00
  can0  481   [8]  52 1A 00 00 00 00 00 01
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  181   [2]  70 06
  can0  281   [7]  70 06 52 1A 00 00 00
  can0  081   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0E 01 00 00 00 00 00
  can0  401   [7]  0E 01 00 00 00 00 00
  can0  181   [2]  31 06
  can0  281   [7]  31 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  0E 01 00 00 00 00 00
  can0  401   [7]  0E 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  181   [2]  33 06
  can0  281   [7]  33 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  181   [2]  37 06
  can0  281   [7]  37 06 52 1A 00 00 00
  can0  481   [8]  52 1A 00 00 00 00 00 03
  can0  081   [8]  01 52 80 00 00 00 70 08
  can0  181   [2]  38 06
  can0  281   [7]  38 06 52 1A 00 00 00
  can0  481   [8]  52 1A 00 00 00 00 00 01
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  181   [2]  70 06
  can0  281   [7]  70 06 52 1A 00 00 00
  can0  081   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0E 01 00 00 00 00 00
  can0  401   [7]  0E 01 00 00 00 00 00
  can0  181   [2]  31 06
  can0  281   [7]  31 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  0E 01 00 00 00 00 00
  can0  401   [7]  0E 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  181   [2]  33 06
  can0  281   [7]  33 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  181   [2]  37 06
  can0  281   [7]  37 06 52 1A 00 00 00
  can0  481   [8]  52 1A 00 00 00 00 00 03
  can0  081   [8]  01 52 80 00 00 00 70 08
  can0  181   [2]  38 06
  can0  701   [1]  05
  can0  281   [7]  38 06 52 1A 00 00 00
  can0  481   [8]  52 1A 00 00 00 00 00 01
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  181   [2]  70 06
  can0  281   [7]  70 06 52 1A 00 00 00
  can0  081   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0E 01 00 00 00 00 00
  can0  401   [7]  0E 01 00 00 00 00 00
  can0  181   [2]  31 06
  can0  281   [7]  31 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  0E 01 00 00 00 00 00
  can0  401   [7]  0E 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  181   [2]  33 06
  can0  281   [7]  33 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  181   [2]  37 06
  can0  281   [7]  37 06 52 1A 00 00 00
  can0  081   [8]  01 52 80 00 00 00 70 08
  can0  481   [8]  52 1A 00 00 00 00 00 03
  can0  181   [2]  38 06
  can0  281   [7]  38 06 52 1A 00 00 00
  can0  481   [8]  52 1A 00 00 00 00 00 01
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  181   [2]  70 06
  can0  281   [7]  70 06 52 1A 00 00 00
  can0  081   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0E 01 00 00 00 00 00
  can0  401   [7]  0E 01 00 00 00 00 00
  can0  181   [2]  31 06
  can0  281   [7]  31 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  0E 01 00 00 00 00 00
  can0  401   [7]  0E 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  181   [2]  33 06
  can0  281   [7]  33 06 52 1A 00 00 00
  can0  080   [0] 
  can0  201   [7]  07 01 00 00 00 00 00
  can0  401   [7]  07 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  181   [2]  37 06
  can0  281   [7]  37 06 52 1A 00 00 00
  can0  481   [8]  52 1A 00 00 00 00 00 03
  can0  081   [8]  01 52 80 00 00 00 70 08
  can0  181   [2]  38 06
  can0  281   [7]  38 06 52 1A 00 00 00
  can0  481   [8]  52 1A 00 00 00 00 00 01
  can0  080   [0] 
  can0  201   [7]  0F 01 00 00 00 00 00
  can0  401   [7]  0F 01 00 00 00 00 00
  can0  080   [0] 
  can0  201   [7]  8F 01 00 00 00 00 00
  can0  401   [7]  8F 01 00 00 00 00 00
  can0  181   [2]  70 06
  can0  281   [7]  70 06 52 1A 00 00 00
  can0  081   [8]  00 00 00 00 00 00 00 00
  can0  080   [0]

Setup:

cschindlbeck commented 2 months ago

We are experiencing the same issue, this is our bus.yml

  package: "canopen_master_driver"
  revision_number: 0
  sync_period: 100000

defaults:
  dcf: "CANedsGoldV005_0_without_buffer_overflow.dcf"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  revision_number: 0
  period: 100000
  polling: true
  switching_state: 5
  scale_pos_to_dev: 31831
  scale_pos_from_dev: 0.00003141
  scale_vel_to_dev: 31831
  scale_vel_from_dev: 0.00003141

nodes:
  front_left_steer_joint:
    node_id: 2
    serial_number: 22320XXX

  front_right_steer_joint:
    node_id: 3
    serial_number: 22320XXX  

and the error is:

[device_container_node-1] [INFO] [1722512047.682393729] [canopen_402_driver]: Init: Read State
[device_container_node-1] [INFO] [1722512047.682552726] [canopen_402_driver]: Init: Enable
[device_container_node-1] [INFO] [1722512047.692108828] [canopen_402_driver]: Fault reset
[device_container_node-1] [INFO] [1722512052.682891861] [canopen_402_driver]: Transition timed out.
[device_container_node-1] Could not enable motor

Did you figure out, what was wrong @david-paltech ?

hellantos commented 2 months ago

Hi, Just for checking could you guys try to set Homing Method to 35 using sdos in bus.yml. we have not extensively tested other Homing methods due to lack of available hardware. Maybe that's the issue.

The error displayed by the device could also hint at a switching state issue. E.g. operating mode is switched in the wrong state.

cschindlbeck commented 2 months ago

Setting homing to 35 did not make any change....

We added the heartbeats and we get 05 so that we are in operational state, and then we do

ros2 service call /front_left_steer_joint/init std_srvs/srv/Trigger 

requester: making request: std_srvs.srv.Trigger_Request()
response:
std_srvs.srv.Trigger_Response(success=False, message='')

This is the candump message:

  can1  703   [1]  05
  can1  702   [1]  05
  can1  703   [1]  05
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  602   [8]  40 02 65 00 00 00 00 00
  can1  582   [8]  43 02 65 00 ED 03 00 00
  can1  702   [1]  05
  can1  703   [1]  05
  can1  702   [1]  05
  can1  703   [1]  05

Why is this service returning success=False

danzimmerman commented 1 month ago

@cschindlbeck @david-paltech I'm seeing the same at the moment with my drive. Also have both my master node and drive node returning 05 heartbeats and I'm reading data from the drive.

Have you made any progress on your end?

I'm seeing my desired TPDOs configured in bus.yml on the bus with candump but I have no data coming in to my device node's /tpdo topic.

I do have RPDOs on the /rpdo topic and the drive's position seems to be correctly reported and updates as I turn the motor by hand, but I can't enable the motor with the device node's /init service call.

I'm using CiA402 lifecycle nodes for both master and device node (I use /lifecycle_manager to step through the configure and activate steps which are both successful and result in the device sending data).

I tried homing method 35 and also homing method 37 which seems to be the "current position" homing mode actually supported by my drive.

danzimmerman commented 1 month ago

I got my drive to spin. In my case, I dug into the candump output and found a repeated emergency message about motor overtemperature (actually a disconnected temperature sensor). This was putting the drive in a fault state.

The node tried several times to clear that fault after I called /init, but with the missing temperature sensor, it would just fault again until timeout.

I do ALSO to get the issues related to the [6502] supported drive modes with the same symptom: repeated sdo transactions like above. My EDS file does have a supported drive modes entry supplied by the manufacturer, but it seems like something is still going wrong there.

Despite that, once I cleared my "over temperature" fault by disabling the temperature sensor it didn't have, I could init the motor and use the driver.

rishavbpm commented 3 weeks ago

I had this issue as well, I resolved it by adding fault reset in the beginning. I can spin the motor in the velocity mode but not in position mode.


options:
  dcf_path: "@BUS_CONFIG_PATH@"

master:
  node_id: 5
  driver: "ros2_canopen::MasterDriver"
  package: "canopen_master_driver"
  baudrate: 1000

nodes:
  pd4_x:
    node_id: 1
    dcf: "PD4_2.eds"
    driver: "ros2_canopen::Cia402Driver"
    package: "canopen_402_driver"
    sdo:
      - {index: 0x6040, sub_index: 0, value: 0x80}  # Fault reset
      - {index: 0x6040, sub_index: 0, value: 0x06}  # Shutdown
      - {index: 0x6040, sub_index: 0, value: 0x07}  # Switch on
      - {index: 0x6060, sub_index: 0, value: 1}  # Set operation mode to Profile Position
      - {index: 0x6040, sub_index: 0, value: 0x0F}  # Enable operation