ros-industrial / ros2_canopen

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

Stuck on "Wait for device to boot." #204

Open jitaxis opened 1 year ago

jitaxis commented 1 year ago

I am running a basic lunch file that launches the /canopen.launch.py file. I am using a KINCO motor driver with the .eds coming from the supplier. When I run the file, the terminal gets stuck on: [kinco_124S]: Wait for device to boot.

If I try to use the nmt_start service I get the following: [kinco_124S]: Could not start device via NMT because driver not activated.

I am using ROS2 Humble on Ubuntu 22.04

I feel like I must be making a basic mistake but I am just unsure of what I am doing wrong. Any help is greatly appreciated, and let me know if there is anything required. Thank you.

My bus.yaml and .eds file: can_driver_config.zip

My launch file: def generate_launch_description(): ld = LaunchDescription() master_bin_path = os.path.join( get_package_share_directory("bhm_can_interface"), "config", "single-kinco-fd124s", "master.bin", )

if not os.path.exists(master_bin_path):
    master_bin_path = ""

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("bhm_can_interface"),
            "config",
            "single-kinco-fd124s",
            "master.dcf",
        ),
        "master_bin": master_bin_path,
        "bus_config": os.path.join(
            get_package_share_directory("bhm_can_interface"),
            "config",
            "single-kinco-fd124s",
            "bus.yml",
        ),
        "can_interface_name": "can0",
    }.items(),
)

ld.add_action(device_container)

return ld

When running the above I get the following candump (master ID 2 and Device is ID 1): can0 702 [1] 00 can0 000 [2] 82 00 can0 701 [1] 00 can0 601 [8] 40 00 10 00 00 00 00 00 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 00 03 00 00 can0 601 [8] 40 18 10 02 00 00 00 00 can0 581 [8] 43 18 10 02 44 46 00 00

hellantos commented 1 year ago

This could be related to a failed start-up due to missing sdo timeouts. We are currently working on a patch. Some CANopen devices do not respond within 100ms.

jitaxis commented 1 year ago

Do you know how long until that patch is complete? Also if I understand correctly the candump shows the following: Master node Heartbeat NMT reset communication Slave Node Heartbeat Slave Node RX Slave Node TX ... So it looks like there is communication between the driver and my PC. Here is a the candump with time zeroed: (000.000000) can0 702 [1] 00 (000.000183) can0 000 [2] 82 00 (000.001968) can0 701 [1] 00 (000.002108) can0 601 [8] 40 00 10 00 00 00 00 00 (000.003869) can0 581 [8] 43 00 10 00 92 01 02 00 (000.004002) can0 601 [8] 40 18 10 01 00 00 00 00 (000.005613) can0 581 [8] 43 18 10 01 00 03 00 00 (000.005709) can0 601 [8] 40 18 10 02 00 00 00 00 (000.007415) can0 581 [8] 43 18 10 02 44 46 00 00

Is there anything I could do to make it activate?

hellantos commented 1 year ago

@jitaxis is that everything or is there more communication Happening?

jitaxis commented 1 year ago

Yeah thats all that happens.

jitaxis commented 1 year ago

@ipa-cmh are there any updates?

yuriyfedyuk commented 1 year ago

This could be related to a failed start-up due to missing sdo timeouts. We are currently working on a patch. Some CANopen devices do not respond within 100ms.

We faced a similar issue. Could you please provide an estimation of when we can expect this patch? Or you can point us to a place where it should be implemented and we will be more than happy to fix that.

hellantos commented 1 year ago

220 does add this feature. As you can see there are still a couple of changes to do.

lvjinxin-l commented 8 months ago

Hello,where is the configuration of sdo and pdo in your bus.yml file? How did you get these packets without configuration? (000.002108) can0 601 [8] 40 00 10 00 00 00 00 00 (000.003869) can0 581 [8] 43 00 10 00 92 01 02 00 (000.004002) can0 601 [8] 40 18 10 01 00 00 00 00 (000.005613) can0 581 [8] 43 18 10 01 00 03 00 00 (000.005709) can0 601 [8] 40 18 10 02 00 00 00 00 (000.007415) can0 581 [8] 43 18 10 02 44 46 00 00 @jitaxis

remco-r commented 5 months ago

I have a similar issue (humble, ubuntu22, 1dd817c67c6b1b1dee53e4851f1bc3c391d6ff43)

bus setup:

master:
  node_id: 1
  driver: "ros2_canopen::MasterDriver"
  package: "canopen_master_driver"
  # baudrate: The baudrate in kbit/s (default 1000)
  # vendor_id:The vendor-ID (default 0x00000000)
  # product_code:The product code (default 0x00000000)
  # revision_number: The revision number (default 0x00000000).
  # serial_number:  The serial number (default 0x00000000).
  # heartbeat_multiplier: The multiplication factor used to obtain the slave heartbeat consumer time from the master heartbeat producer time (default see options section).
  # heartbeat_consumer: Specifies whether the master should monitor the heartbeats of the slaves (default true).
  # heartbeat_producer: The heartbeat producer time in ms (default 0).
  # emcy_inhibit_time: The EMCY inhibit time in multiples of 100 μs (default 0, see object 1015).
  sync_period: 10000 # The SYNC interval in μs (default 0).
  sync_window: 10000 # The SYNC window length in μs (default 0, see object 1007).
  # sync_overflow: The SYNC counter overflow value (default 0, see object 1019).
  # error_behavior: A dictionary of error behaviors for different classes or errors (default {1: 0x00}, see object 1029).
  nmt_inhibit_time: 10000 # The NMT inhibit time in multiples of 100 μs (default 0, see object 102A).
  # start: Specifies whether the master shall switch into the NMT operational state by itself (default true, see bit 2 in object 1F80).
  # start_nodes: Specifies whether the master shall start the slaves (default true, see bit 3 in object 1F80).
  start_all_nodes: true # Specifies whether the master shall start all nodes simultaneously (default false, see bit 1 in object 1F80).
  # reset_all_nodes: Specifies whether all slaves shall be reset in case of an error event on a mandatory slave (default false, see bit 4 in object 1F80).
  # stop_all_nodes: Specifies whether all slaves shall be stopped in case of an error event on a mandatory slave (default false, see bit 6 in object 1F80).
  boot_time: 1000 # The timeout for booting mandatory slaves in ms (default 0, see object 1F89).
  boot_timeout: 2000 # The timeout for booting all slaves in ms (default 2000ms).

radar_left:
  node_id: 10
  dcf: "radar_sensor.eds"
  driver: "ros2_canopen::ProxyDriver"
  package: "canopen_proxy_driver"

Launch file output:

[device_container_node-1] [INFO] [1720181221.407411051] [radar_left]: eds file ***.eds
[device_container_node-1] [INFO] [1720181221.407448612] [radar_left]: bin file ***.bin
[device_container_node-1] Found tpdo mapped object: index=2000 subindex=1
[device_container_node-1] Found tpdo mapped object: index=2000 subindex=2
[device_container_node-1] Found tpdo mapped object: index=2000 subindex=3
[device_container_node-1] Found tpdo mapped object: index=2000 subindex=5
[device_container_node-1] [WARN] [1720181221.409308197] [radar_left]: Wait for device to boot.

On the canbus i see the master resetting the bus, the radar sensor replying with boot message, but there its stuck.

 (071.342994)  can0  TX - -  701   [1]  00
 (000.000048)  can0  TX - -  000   [2]  82 00
 (000.002481)  can0  RX - -  710   [1]  00

Notes:

chinaheyu commented 4 months ago

I'm facing a similar problem with @remco-r.

I am running the latest branch on ubuntu 22.04, humble (https://github.com/ros-industrial/ros2_canopen/commit/1dd817c67c6b1b1dee53e4851f1bc3c391d6ff43), with the following bus.yml.

options:
  dcf_path: "@BUS_CONFIG_PATH@"

master:
  node_id: 1
  driver: "ros2_canopen::MasterDriver"
  package: "canopen_master_driver"

defaults:
  dcf: "ZeroErr Driver_V1.5.eds"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  enable_lazy_load: false
  sdo:
    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms
    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s
    - {index: 0x6081, sub_index: 0, value: 1000}
    - {index: 0x6083, sub_index: 0, value: 2000}
  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation
    1:
      enabled: true
      cob_id: "auto"
      transmission: 0x01
      mapping:
        - {index: 0x6041, sub_index: 0} # status word
        - {index: 0x6061, sub_index: 0} # mode of operation display
    2:
      enabled: true
      cob_id: "auto"
      transmission: 0x01
      mapping:
        - {index: 0x6064, sub_index: 0} # position actual value
        - {index: 0x606c, sub_index: 0} # velocity actual position
    3:
      enabled: false
    4:
      enabled: false
  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation
    1:
      enabled: true
      cob_id: "auto"
      mapping:
      - {index: 0x6040, sub_index: 0} # controlword
      - {index: 0x6060, sub_index: 0} # mode of operation
    2:
      enabled: true
      cob_id: "auto"
      mapping:
      - {index: 0x607A, sub_index: 0} # target position
      - {index: 0x60FF, sub_index: 0} # target velocity

nodes:
  cia402_device_1:
    node_id: 3

I made the following attempt to run the Cia402Driver.

  1. Runs directly on the physical interface;
  2. Runs on a virtual interface and emulates the device via cansend.

1. Running on candleLight USB-CAN Adapter (can0)

$ ros2 launch humanoid_canopen humanoid_canopen.launch.py 
[INFO] [launch]: All log files can be found below /home/heyu/.ros/log/2024-07-13-16-47-35-329718-heyu-server-411443
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [launch.user]: /home/heyu/ros2_ws/install/humanoid_canopen/share/humanoid_canopen/config/zeroerr1/bus.yml
[INFO] [launch.user]: /home/heyu/ros2_ws/install/humanoid_canopen/share/humanoid_canopen/config/zeroerr1/master.dcf
[INFO] [launch.user]: /home/heyu/ros2_ws/install/humanoid_canopen/share/humanoid_canopen/config/zeroerr1/master.bin
[INFO] [launch.user]: can0
[INFO] [device_container_node-1]: process started with pid [411454]
[device_container_node-1] [INFO] [1720860455.392262307] [device_container_node]: Starting Device Container with:
[device_container_node-1] [INFO] [1720860455.392312849] [device_container_node]:       master_config /home/heyu/ros2_ws/install/humanoid_canopen/share/humanoid_canopen/config/zeroerr1/master.dcf
[device_container_node-1] [INFO] [1720860455.392316584] [device_container_node]:       bus_config /home/heyu/ros2_ws/install/humanoid_canopen/share/humanoid_canopen/config/zeroerr1/bus.yml
[device_container_node-1] [INFO] [1720860455.392319535] [device_container_node]:       can_interface_name can0
[device_container_node-1] [INFO] [1720860455.392548548] [device_container_node]: Loading Master Configuration.
[device_container_node-1] [INFO] [1720860455.392670216] [device_container_node]: Load Library: /home/heyu/ros2_ws/install/canopen_master_driver/lib/libmaster_driver.so
[device_container_node-1] [INFO] [1720860455.393845254] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1720860455.393852996] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1720860455.394796410] [master]: NodeCanopenBasicMaster
[device_container_node-1] [INFO] [1720860455.394805605] [device_container_node]: Load master component.
[device_container_node-1] [INFO] [1720860455.394812963] [device_container_node]: Added /master to executor
[device_container_node-1] [WARN] [1720860455.395179849] [master]: No timeout parameter found in config file. Using default value of 100ms.
[device_container_node-1] [INFO] [1720860455.395192559] [master]: Master boot timeout set to 2000ms.
[device_container_node-1] [INFO] [1720860455.401037598] [device_container_node]: Loading Driver Configuration.
[device_container_node-1] [INFO] [1720860455.401056899] [device_container_node]: Found device cia402_device_1 with driver ros2_canopen::Cia402Driver
[device_container_node-1] [INFO] [1720860455.401202322] [device_container_node]: Load Library: /home/heyu/ros2_ws/install/canopen_402_driver/lib/libcia402_driver.so
[device_container_node-1] [INFO] [1720860455.403593037] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1720860455.403602178] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1720860455.404679048] [device_container_node]: Load driver component.
[device_container_node-1] [INFO] [1720860455.404692775] [device_container_node]: Added /cia402_device_1 to executor
[device_container_node-1] [INFO] [1720860455.407008729] [cia402_device_1]: Non transmit timeout100ms
[device_container_node-1] [WARN] [1720860455.407025090] [cia402_device_1]: Could not polling from config, setting to true.
[device_container_node-1] [WARN] [1720860455.407033608] [cia402_device_1]: Could not read period from config, setting to 10ms
[device_container_node-1] [WARN] [1720860455.407042227] [cia402_device_1]: Could not read enable diagnostics from config, setting to false.
[device_container_node-1] [INFO] [1720860455.407076969] [cia402_device_1]: 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] [1720860455.407456189] [cia402_device_1]: eds file /home/heyu/ros2_ws/install/humanoid_canopen/share/humanoid_canopen/config/zeroerr1/ZeroErr Driver_V1.5.eds
[device_container_node-1] [INFO] [1720860455.407462646] [cia402_device_1]: bin file /home/heyu/ros2_ws/install/humanoid_canopen/share/humanoid_canopen/config/zeroerr1/cia402_device_1.bin
[device_container_node-1] Found rpdo mapped object: index=6040 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6060 subindex=0
[device_container_node-1] Found rpdo mapped object: index=607a subindex=0
[device_container_node-1] Found rpdo mapped object: index=60ff 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 tpdo mapped object: index=6041 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=6041 subindex=0
[device_container_node-1] Found tpdo mapped object: index=606c subindex=0
[device_container_node-1] [WARN] [1720860455.408504562] [cia402_device_1]: Wait for device to boot.
↑ Stuck on here!

The output of candump is as follows.

$ candump can0
  can0  701   [1]  00
  can0  000   [2]  82 00
  can0  703   [1]  00
  can0  603   [8]  40 00 10 00 00 00 00 00
  can0  583   [8]  43 00 10 00 92 01 02 04

2. Runs on a virtual interface (vcan0)

[device_container_node-1] [WARN] [1720861353.729536979] [cia402_device_1]: Wait for device to boot.

Stuck in "Wait for device to boot." as before. But I sent some frames via cansend that mimic the device and it continued to run.

$ cansend vcan0 703#00                  # boot up
$ cansend vcan0 583#4300100092010204    # reply to 0x1000 object

The additional output is as follows.

[device_container_node-1] [ERROR] [1720861371.838648466] [cia402_device_1]: Boot Issue: Value of object 1000 from CANopen device is different to value in object 1F84 (Device type).
[device_container_node-1] [INFO] [1720861371.838694895] [cia402_device_1]: Driver booted and ready.
[device_container_node-1] [INFO] [1720861371.838734229] [cia402_device_1]: Starting with polling mode.
[device_container_node-1] [INFO] [1720861371.848897783] [canopen_402_driver]: Fault reset

The output of candump is as follows.

$ candump vcan0
  vcan0  701   [1]  00
  vcan0  000   [2]  82 00
  vcan0  703   [1]  00
  ↑ send 703#00 manually via cansend.
  vcan0  603   [8]  40 00 10 00 00 00 00 00
  vcan0  603   [8]  80 00 10 00 00 00 04 05
  vcan0  603   [8]  40 00 10 00 00 00 00 00
  vcan0  603   [8]  80 00 10 00 00 00 04 05
  vcan0  603   [8]  40 00 10 00 00 00 00 00
  vcan0  583   [8]  43 00 10 00 92 01 02 04
  ↑ repeat until recived 583#4300100092010204 from cansend.
  vcan0  203   [3]  56 65 00
  vcan0  203   [3]  D6 65 00
  vcan0  203   [3]  D6 65 00
  ↑ fast and repetitive output

The weird thing is that on the physical interface, even though the device sends 583#4300100092010204, the program is still stuck on "Wait for device to boot.", even though I send it again via cansend. But if I manually send the 703#00, the program continues to run, just like the virtual interface.