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

Bus.yml doesn't compile if the "nodes" section is missing? #330

Open
BatisteAll opened this issue Oct 31, 2024 · 1 comment
Open

Bus.yml doesn't compile if the "nodes" section is missing? #330

BatisteAll opened this issue Oct 31, 2024 · 1 comment
Labels
question Further information is requested

Comments

@BatisteAll
Copy link

Describe the bug
It seems, in my current set up, that the bus.yml won't compile if I simply list the slave robot joints (so without a nodes section) as follow:

options:
  dcf_path: "@BUS_CONFIG_PATH@"

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

joint_1:
  node_id: 2
  dcf: "cia402_slave.eds"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  period: 10
  position_mode: 1
  revision_number: 0
  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}
    - {index: 0x6060, sub_index: 0, value: 7}
  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
  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

joint_2:
  node_id: 3
  dcf: "cia402_slave.eds"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  period: 10
  position_mode: 1
  revision_number: 0
  switching_state: 2
  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}
    - {index: 0x6060, sub_index: 0, value: 7}
  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
  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

But if I add an indentation level on the joints and add the 'nodes' section, in that case it compiles:

options:
  dcf_path: "@BUS_CONFIG_PATH@"

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

nodes:
  joint_1:
     ...
  joint_2:
     ...

Logs
The only log is when I colcon build my config package, the bus.yml doesn't get parsed and the 'preprocessed_bus.yml' is not created.
So I get an error of type:

sed: can't read /home/ros2_ws_canopen/build/lab_canopen_config/config/bus/preprocessed_bus.yml: No such file or directory
gmake[2]: *** [CMakeFiles/bus.dir/build.make:74: bus] Error 2
gmake[1]: *** [CMakeFiles/Makefile2:165: CMakeFiles/bus.dir/all] Error 2
gmake: *** [Makefile:146: all] Error 2

Setup:

  • OS: Ubuntu 22.04
  • ROS-Distro: Humble
  • Branch/Commit: Humble

Additional context
I am using ros2_canopen with ros2_control.
The bus.yml I used is as presented above, a copy of the bus.yml in ros2_canopen>canopen_tests>config>robot_control.

@BatisteAll BatisteAll added the question Further information is requested label Oct 31, 2024
@danzimmerman
Copy link

danzimmerman commented Nov 23, 2024

If you really want to do this you could modify cogen.py here to handle the case where you don't specify the nodes section, but I just think that's what's expected of the interface at this time.

You can use defaults to specify all the common stuff between the two and just have a short nodes section that names them and captures their differences:

defaults:
  dcf: "cia402_slave.eds"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  period: 10
  position_mode: 1
  revision_number: 0
  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}
    - {index: 0x6060, sub_index: 0, value: 7}
  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
  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:
  joint_1:
    node_id: 2
  joint_2:
    node_id: 3
    switching_state: 2

The bus.yml I used is as presented above, a copy of the bus.yml in ros2_canopen>canopen_tests>config>robot_control.

I think that's the equivalent of a preprocessed_bus.yml file. You should be able to run dcfgen on it directly, like the CMake macro cogen_dcf() does here: https://github.com/ros-industrial/ros2_canopen/blob/master/lely_core_libraries/cmake/lely_core_libraries-extras.cmake#L53

But if you want to use bus.yml it does expect the nodes entry, like here:

https://ros-industrial.github.io/ros2_canopen/manual/rolling/user-guide/configuration.html#bus-configuration-file

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