Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

How to create a cia301 system that works with real hardware? #215

Open
jclinton830 opened this issue Oct 25, 2023 · 7 comments
Open

How to create a cia301 system that works with real hardware? #215

jclinton830 opened this issue Oct 25, 2023 · 7 comments
Labels
question Further information is requested

Comments

@jclinton830
Copy link

Describe the bug
I have been following this tutorial https://ros-industrial.github.io/ros2_canopen/manual/rolling/software-tests/ros2_control_system-test.html after setting up a canopen cia301 system by following this tutorial https://ros-industrial.github.io/ros2_canopen/manual/rolling/user-guide/how-to-create-a-cia301-system.html

I am working with real hardware instead of using the virtual slave. My motor controller of choice is an MBL1660 from roboteq.

I have the drivers booting up fine. See the below output.

jerome@jjustin:~/gh_ws$ ros2 launch canopen_tests canopen_system.launch.py 
[INFO] [launch]: All log files can be found below /home/jerome/.ros/log/2023-10-25-15-55-14-103207-jjustin-43872
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [43875]
[INFO] [robot_state_publisher-2]: process started with pid [43877]
[INFO] [spawner-3]: process started with pid [43879]
[INFO] [spawner-4]: process started with pid [43881]
[robot_state_publisher-2] [INFO] [1698209714.346875843] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1698209714.346977568] [robot_state_publisher]: got segment node_1_link
[robot_state_publisher-2] [INFO] [1698209714.346988652] [robot_state_publisher]: got segment node_2_link
[ros2_control_node-1] [INFO] [1698209714.347555741] [resource_manager]: Loading hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1698209714.355711862] [resource_manager]: Initialize hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1698209714.355931841] [CanopenSystem]: bus_config: '/home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/bus.yml'
[ros2_control_node-1] [INFO] [1698209714.355938998] [CanopenSystem]: master_config: '/home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/master.dcf'
[ros2_control_node-1] [INFO] [1698209714.355942311] [CanopenSystem]: can_interface_name: 'can0'
[ros2_control_node-1] [INFO] [1698209714.355945110] [CanopenSystem]: master_bin: '""'
[ros2_control_node-1] [INFO] [1698209714.355951352] [resource_manager]: Successful initialization of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1698209714.356157896] [resource_manager]: 'configure' hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1698209714.363262530] [device_container]: Starting Device Container with:
[ros2_control_node-1] [INFO] [1698209714.363397676] [device_container]:          can_interface_name can0
[ros2_control_node-1] [INFO] [1698209714.363413160] [device_container]:          master_config /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/master.dcf
[ros2_control_node-1] [INFO] [1698209714.363425275] [device_container]:          bus_config /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/bus.yml
[ros2_control_node-1] [INFO] [1698209714.364735438] [device_container]: Loading Master Configuration.
[ros2_control_node-1] [INFO] [1698209714.365772741] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_master_driver/lib/libmaster_driver.so
[ros2_control_node-1] [INFO] [1698209714.368552317] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1698209714.368620366] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1698209714.373982083] [master]: NodeCanopenBasicMaster
[ros2_control_node-1] [INFO] [1698209714.374199165] [device_container]: Load master component.
[ros2_control_node-1] [INFO] [1698209714.374434472] [device_container]: Added /master to executor
[ros2_control_node-1] [INFO] [1698209714.391554212] [device_container]: Loading Driver Configuration.
[ros2_control_node-1] [INFO] [1698209714.391665483] [device_container]: Found device proxy_device_1 with driver ros2_canopen::ProxyDriver
[ros2_control_node-1] [INFO] [1698209714.391866853] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_proxy_driver/lib/libproxy_driver.so
[ros2_control_node-1] [INFO] [1698209714.392575411] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::ProxyDriver>
[ros2_control_node-1] [INFO] [1698209714.392589070] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::ProxyDriver>
[ros2_control_node-1] [INFO] [1698209714.396614839] [device_container]: Load driver component.
[ros2_control_node-1] [INFO] [1698209714.396822619] [device_container]: Added /proxy_device_1 to executor
[ros2_control_node-1] [ERROR] [1698209714.405117995] [proxy_device_1]: Could not polling from config, setting to true.
[ros2_control_node-1] [ERROR] [1698209714.405265791] [proxy_device_1]: Could not read period from config, setting to 10ms
[ros2_control_node-1] [ERROR] [1698209714.405309590] [proxy_device_1]: Could not read enable diagnostics from config, setting to false.
[ros2_control_node-1] [INFO] [1698209714.407074469] [proxy_device_1]: eds file /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/roboteq_motor_controllers_v80.eds
[ros2_control_node-1] [INFO] [1698209714.407100394] [proxy_device_1]: bin file /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/proxy_device_1.bin
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=9
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=a
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=b
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=c
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=d
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=e
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=f
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=10
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=1
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=2
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=3
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=4
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=5
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=6
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=7
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=8
[ros2_control_node-1] [WARN] [1698209714.415358676] [proxy_device_1]: Wait for device to boot.
[ros2_control_node-1] [ERROR] [1698209714.527408651] [proxy_device_1]: Boot Issue: Node guarding event. No confirmation for guarding request received from CANopen device.
[ros2_control_node-1] [INFO] [1698209714.527482876] [proxy_device_1]: Driver booted and ready.
[ros2_control_node-1] [INFO] [1698209714.527759910] [proxy_device_1]: Starting with polling mode.
[ros2_control_node-1] [INFO] [1698209714.528155355] [CanopenSystem]: Number of registered drivers: '1'
[ros2_control_node-1] [INFO] [1698209714.528225537] [CanopenSystem]: 
[ros2_control_node-1] Registered driver:
[ros2_control_node-1]     name: 'proxy_device_1'
[ros2_control_node-1]     node_id: '0xC'
[ros2_control_node-1] [INFO] [1698209714.528238828] [device_container]: Initialisation successful.
[ros2_control_node-1] [INFO] [1698209714.528365362] [resource_manager]: Successful 'configure' of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1698209714.528411511] [resource_manager]: 'activate' hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1698209714.528419020] [resource_manager]: Successful 'activate' of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1698209714.531695396] [controller_manager]: update rate is 10 Hz
[ros2_control_node-1] [INFO] [1698209714.531802178] [controller_manager]: RT kernel is recommended for better performance
[ros2_control_node-1] [INFO] [1698209714.633797053] [controller_manager]: Loading controller 'joint_state_broadcaster'
[spawner-3] [INFO] [1698209714.748004453] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1698209714.748731974] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1698209714.748820209] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-3] [INFO] [1698209714.933559733] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[ros2_control_node-1] [INFO] [1698209714.955665036] [controller_manager]: Loading controller 'node_1_controller'
[spawner-4] [INFO] [1698209715.045758772] [spawner_node_1_controller]: Loaded node_1_controller
[ros2_control_node-1] [INFO] [1698209715.046551059] [controller_manager]: Configuring controller 'node_1_controller'
[ros2_control_node-1] [INFO] [1698209715.049835529] [node_1_controller]: configure successful
[INFO] [spawner-3]: process has finished cleanly [pid 43879]
[spawner-4] [INFO] [1698209715.234146487] [spawner_node_1_controller]: Configured and activated node_1_controller
[INFO] [spawner-4]: process has finished cleanly [pid 43881]

After booting up I send a command to the controller as stated in the above tutorial like this

`
ros2 topic pub /node_1_controller/tpdo canopen_interfaces/msg/COData "
index: 0x2005
subindex: 9
data: 0x3E8"

`
and this does not move the motor, I also echo the node_1_controller/rpdo topic and see no changes in the data values. See below.

---
index: 8454
subindex: 4
data: 0
---
index: 8454
subindex: 4
data: 0
---
index: 8454
subindex: 4
data: 0
---
index: 8454
subindex: 4
data: 0
---
index: 8454
subindex: 4
data: 0
---
index: 8454
subindex: 4
data: 0
---
index: 8454
subindex: 4
data: 0

My question is, have you tested this on real hardware? Am I missing something? I also see in my launch output the following warning

[joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published

Is there any additional setup one must do for this to work with real hardware?

Setup:

  • Device: Laptop
  • OS: Ubuntu 22.04
  • ROS-Distro: Humble
  • Branch/Commit: humble
@jclinton830 jclinton830 added the question Further information is requested label Oct 25, 2023
@hellantos
Copy link
Member

hellantos commented Oct 27, 2023

Can you check the candump? Is the tpdo sent out?
Did you map 0x2005 as rpdo and tpdo on your device? Does 0x2005 exist on your device? Seems your device currently only has 0x2106 mapped as tpdo.

@jclinton830
Copy link
Author

jclinton830 commented Nov 6, 2023

@ipa-cmh you are right. By default the device was mapping all the sub indexes of 0x2106 to all of its TPDOs and all the sub indexes fo object 0x2005 was being mapped to all of its RPDOs.

image

I used the remapping keyword to apply the remappings for all the tpdos and rpdos. See below for the bus.yml

options:
  dcf_path: "@BUS_CONFIG_PATH@"

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

proxy_device_1:
  node_id: 12
  dcf: "roboteq_motor_controllers_v80.eds"
  driver: "ros2_canopen::ProxyDriver"
  package: "canopen_proxy_driver"
  polling: true
  diagnostics:
    enable: true
    period: 1000 # in milliseconds
  reset_communication: false
  tpdo:
    1:
      enabled: true
      transmission: 0xFF
      cob_id: "auto"
      mapping:
        - { index: 0x2100, sub_index: 1 } # read motor amps
        - { index: 0x2101, sub_index: 1 } # read actual motor command
    2:
      enabled: true
      transmission: 0xFF
      cob_id: "auto"
      mapping:
        - { index: 0x2102, sub_index: 1 } # Read Applied Power Level
        - { index: 0x2103, sub_index: 1 } # read encoder motor speed
    3:
      enabled: true
      transmission: 0xFF
      cob_id: "auto"
      mapping:
        - { index: 0x2104, sub_index: 1 } 
        - { index: 0x2105, sub_index: 1 } 
    4:
      enabled: true
      transmission: 0xFF
      cob_id: "auto"
      mapping:
        - { index: 0x2106, sub_index: 1 } 
        - { index: 0x2107, sub_index: 1 } 
  rpdo: 
    1:
      enabled: true
      cob_id: "auto"
      mapping:
        - { index: 0x2000, sub_index: 1 } # set motor command
        - { index: 0x2001, sub_index: 1 } # set position
    2:
      enabled: true
      cob_id: "auto"
      mapping:
        - { index: 0x2002, sub_index: 1 } # set velocity
        - { index: 0x2003, sub_index: 1 } # set encoder count
    3:
      enabled: true
      cob_id: "auto"
      mapping:
        - { index: 0x2006, sub_index: 1 } # set acceleration
        - { index: 0x2007, sub_index: 1 } # set deceleration
    4: 
      enabled: false

The launch log now shows this. Note the section where it shows which RPDOs and TPDOs were found. This suggests that the remapping worked.


~/gh_ws$ ros2 launch canopen_tests canopen_system.launch.py 
[INFO] [launch]: All log files can be found below /home/jerome/.ros/log/2023-11-07-09-42-33-957353-jjustin-78109
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [78112]
[INFO] [robot_state_publisher-2]: process started with pid [78114]
[INFO] [spawner-3]: process started with pid [78116]
[INFO] [spawner-4]: process started with pid [78118]
[robot_state_publisher-2] [INFO] [1699310554.217321157] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1699310554.217432222] [robot_state_publisher]: got segment node_1_link
[ros2_control_node-1] [INFO] [1699310554.222409309] [resource_manager]: Loading hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1699310554.233651616] [resource_manager]: Initialize hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1699310554.233920362] [CanopenSystem]: bus_config: '/home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/bus.yml'
[ros2_control_node-1] [INFO] [1699310554.233929069] [CanopenSystem]: master_config: '/home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/master.dcf'
[ros2_control_node-1] [INFO] [1699310554.233934012] [CanopenSystem]: can_interface_name: 'can0'
[ros2_control_node-1] [INFO] [1699310554.233938446] [CanopenSystem]: master_bin: '""'
[ros2_control_node-1] [INFO] [1699310554.233946297] [resource_manager]: Successful initialization of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1699310554.234179117] [resource_manager]: 'configure' hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1699310554.247045163] [device_container]: Starting Device Container with:
[ros2_control_node-1] [INFO] [1699310554.247171938] [device_container]:          can_interface_name can0
[ros2_control_node-1] [INFO] [1699310554.247186669] [device_container]:          master_config /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/master.dcf
[ros2_control_node-1] [INFO] [1699310554.247198603] [device_container]:          bus_config /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/bus.yml
[ros2_control_node-1] [INFO] [1699310554.248763970] [device_container]: Loading Master Configuration.
[ros2_control_node-1] [INFO] [1699310554.249585970] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_master_driver/lib/libmaster_driver.so
[ros2_control_node-1] [INFO] [1699310554.251710337] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1699310554.251736712] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1699310554.257574053] [master]: NodeCanopenBasicMaster
[ros2_control_node-1] [INFO] [1699310554.257710486] [device_container]: Load master component.
[ros2_control_node-1] [INFO] [1699310554.257880218] [device_container]: Added /master to executor
[ros2_control_node-1] [INFO] [1699310554.271666964] [device_container]: Loading Driver Configuration.
[ros2_control_node-1] [INFO] [1699310554.271828147] [device_container]: Found device proxy_device_1 with driver ros2_canopen::ProxyDriver
[ros2_control_node-1] [INFO] [1699310554.272450935] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_proxy_driver/lib/libproxy_driver.so
[ros2_control_node-1] [INFO] [1699310554.273373905] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::ProxyDriver>
[ros2_control_node-1] [INFO] [1699310554.273391634] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::ProxyDriver>
[ros2_control_node-1] [INFO] [1699310554.277841012] [device_container]: Load driver component.
[ros2_control_node-1] [INFO] [1699310554.278012531] [device_container]: Added /proxy_device_1 to executor
[ros2_control_node-1] [ERROR] [1699310554.286969891] [proxy_device_1]: Could not read period from config, setting to 10ms
[ros2_control_node-1] [INFO] [1699310554.291363122] [proxy_device_1]: eds file /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/roboteq_motor_controllers_v80.eds
[ros2_control_node-1] [INFO] [1699310554.291404479] [proxy_device_1]: bin file /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/canopen_system/proxy_device_1.bin
[ros2_control_node-1] Found rpdo mapped object: index=2000 subindex=1
[ros2_control_node-1] Found rpdo mapped object: index=2001 subindex=1
[ros2_control_node-1] Found rpdo mapped object: index=2002 subindex=1
[ros2_control_node-1] Found rpdo mapped object: index=2003 subindex=1
[ros2_control_node-1] Found rpdo mapped object: index=2006 subindex=1
[ros2_control_node-1] Found rpdo mapped object: index=2007 subindex=1
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=f
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=10
[ros2_control_node-1] Found tpdo mapped object: index=2100 subindex=1
[ros2_control_node-1] Found tpdo mapped object: index=2101 subindex=1
[ros2_control_node-1] Found tpdo mapped object: index=2102 subindex=1
[ros2_control_node-1] Found tpdo mapped object: index=2103 subindex=1
[ros2_control_node-1] Found tpdo mapped object: index=2104 subindex=1
[ros2_control_node-1] Found tpdo mapped object: index=2105 subindex=1
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=1
[ros2_control_node-1] Found tpdo mapped object: index=2107 subindex=1
[ros2_control_node-1] [WARN] [1699310554.302977188] [proxy_device_1]: Wait for device to boot.
[ros2_control_node-1] [ERROR] [1699310554.478224802] [proxy_device_1]: Boot Issue: Node guarding event. No confirmation for guarding request received from CANopen device.
[ros2_control_node-1] [INFO] [1699310554.478275971] [proxy_device_1]: Driver booted and ready.
[ros2_control_node-1] [INFO] [1699310554.478560470] [proxy_device_1]: Starting with polling mode.
[ros2_control_node-1] [INFO] [1699310554.478872644] [proxy_device_1]: Starting with diagnostics enabled.
[ros2_control_node-1] [INFO] [1699310554.479497077] [CanopenSystem]: Number of registered drivers: '1'
[ros2_control_node-1] [INFO] [1699310554.479564480] [CanopenSystem]: 
[ros2_control_node-1] Registered driver:
[ros2_control_node-1]     name: 'proxy_device_1'
[ros2_control_node-1]     node_id: '0xC'
[ros2_control_node-1] [INFO] [1699310554.479577858] [device_container]: Initialisation successful.
[ros2_control_node-1] [INFO] [1699310554.479671398] [resource_manager]: Successful 'configure' of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1699310554.479693902] [resource_manager]: 'activate' hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1699310554.479730888] [resource_manager]: Successful 'activate' of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1699310554.505924840] [controller_manager]: update rate is 10 Hz
[ros2_control_node-1] [INFO] [1699310554.506089908] [controller_manager]: RT kernel is recommended for better performance
[ros2_control_node-1] [INFO] [1699310554.518859222] [controller_manager]: Loading controller 'joint_state_broadcaster'
[spawner-3] [INFO] [1699310554.619632114] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1699310554.620898236] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1699310554.621052498] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-3] [INFO] [1699310554.808152749] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[ros2_control_node-1] [INFO] [1699310554.811205624] [controller_manager]: Loading controller 'node_1_controller'
[spawner-4] [INFO] [1699310554.908958204] [spawner_node_1_controller]: Loaded node_1_controller
[ros2_control_node-1] [INFO] [1699310554.911122727] [controller_manager]: Configuring controller 'node_1_controller'
[ros2_control_node-1] [INFO] [1699310554.920837364] [node_1_controller]: configure successful
[INFO] [spawner-3]: process has finished cleanly [pid 78116]
[spawner-4] [INFO] [1699310555.107907728] [spawner_node_1_controller]: Configured and activated node_1_controller
[INFO] [spawner-4]: process has finished cleanly [pid 78118]

But when I do ros2 topic echo /node_1_controller/rpdo I only ever see one RPDO being reported by the publisher. See below. If this is normal behaviour then my question is what make the canopen_proxy_controller decide which one of the 4 rpdos to publish?

~/gh_ws$ ros2 topic echo /node_1_controller/rpdo 
index: 8451
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---

When I send the set motor command via 0x2000 using the command below, I see no changes in the proxy_device_1/rpdo index 0x2101. See below.

~/gh_ws$ ros2 topic pub /node_1_controller/tpdo canopen_interfaces/msg/COData "
index: 0x2000
subindex: 1
data: 0x3E8"
~/gh_ws$ ros2 topic echo /proxy_device_1/rpdo 
index: 8451
subindex: 1
data: 0
---
index: 8448
subindex: 1
data: 0
---
index: 8449
subindex: 1
data: 0
---
index: 8450
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---
index: 8448
subindex: 1
data: 0
---
index: 8449
subindex: 1
data: 0
---
index: 8450
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---
index: 8448
subindex: 1
data: 0
---
index: 8449
subindex: 1
data: 0
---
index: 8450
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---

@hellantos
Copy link
Member

@jclinton830 can you try with a sync? We have not really tested async mode for pdos (we just do not have the use case) usually with drives you want fixed periodic commands and feedback to be able to control them reliably.
Generally if you have async mode enabled for PDOs they are only published on change. That can be pretty misleading when testing. Try to set transmission: 0x01 for each pdo and for master set sync_period: 20000 in bus.yml. All pdos and rpdos should then be send every 20 ms.

Then use candump can0 to monitor the bus.
Can you then send me a the candump log?

@jclinton830
Copy link
Author

@ipa-cmh Okay, I tried that and nothing really changed. Here is the candump log

candump can0
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  00 00 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  081   [8]  20 82 11 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 
  can0  20C   [8]  E8 03 00 00 00 00 00 00
  can0  30C   [8]  00 00 00 00 00 00 00 00
  can0  40C   [8]  00 00 00 00 00 00 00 00
  can0  50C   [8]  00 00 00 00 00 00 00 00
  can0  080   [0] 

The only thing I can see here is the EMCY message 8220 being fired by the master from 081. This would suggest the length of the received PDO does not match the configured length. But I have checked the EDS and the manual and it all seems to be okay. I have attached the manual here and the eds. Can you please have a look to see if I am missing anything?

New EDS - https://github.com/jclinton830/canopen_test/blob/main/config/canopen_system/roboteq_motor_controllers_v80.eds

New bus.yaml - https://github.com/jclinton830/canopen_test/blob/main/config/canopen_system/bus.yml

and the manual for the controller (see pages 33-44) - https://github.com/jclinton830/canopen_test/blob/main/CAN%20Networking%20Manual_v2.1a.pdf

@hellantos
Copy link
Member

@jclinton830 I will see if I can setup a simulation with fake slaves today. With regards to the candump, the startup sequence is most interesting as well as a section during which you sent pdo.

@jclinton830
Copy link
Author

@ipa-cmh any update on this?

@jclinton830
Copy link
Author

@ipa-cmh any chance you can shed some light on what is going on with this setup?

I still have a few questions:

when I do ros2 topic echo /node_1_controller/rpdo I only ever see one RPDO being reported by the publisher. See below. If this is normal behaviour then my question is what makes the canopen_proxy_controller decide which one of the 4 rpdos to publish?

~/gh_ws$ ros2 topic echo /node_1_controller/rpdo 
index: 8451
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---
index: 8451
subindex: 1
data: 0
---

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
question Further information is requested
Projects
None yet
Development

No branches or pull requests

2 participants