Closed borongyuan closed 2 years ago
This seems to be related to dcfgen and the eds file. In my eds file the DefaultValue of [1400sub1] is DefaultValue=$NodeID+0x00000200 and [1401sub1] is $NodeID+0x80000300. This means that RPDO1 is enabled and RPDO2 is disabled by default. dcfgen seems to only modify the mappings for RPDOs that are already enabled. I see that in lely_core_libraries-extras.cmake the -r option is enabled. But I am not clear about the logic of Lely CANopen handling eds. If I set the DefaultValue of [1401sub1] to $NodeID+0x00000300 in eds, RPDO2 will be set on initialization.
Thanks for the heads up. I will see if I can reproduce.
The only time I encountered something similar was when the concise dcf generated by dcfgen for your device was not loaded correctly. Can you check the terminal output for something like "canopen_402_driver.bin not found"?
see that in lely_core_libraries-extras.cmake the -r option is enabled. But I am not clear about the logic of Lely CANopen handling eds Lely CANopen uses the eds files to configure the CANopen Master correctly. For convenience it provides the options you can specify in bus.yaml. The options specified per device will be transmitted to the device once the boot message was received by master via sdo. The -r option simplifies the access to the master's object dictionary by doing some nifty mapping - we definitively need that.
There is a "test" for this in this branch: https://github.com/ipa-cmh/ros2_canopen/tree/lifecycle Enable vcan0 and run the following commands:
ros2 launch canopen_tests cia402_lifecycle_setup.launch.py
In another terminal run:
ros2 lifecycle set lifecycle_device_manager_node configure
ros2 lifecycle set lifecycle_device_manager_node activate
ros2 service call cia402_device_1/init std_srvs/srv/Trigger
The eds file used has all pdos disabled. They are only enabled in the yaml.
conf/cia402/cia402_slave.eds
....
[1400sub1]
ParameterName=COB-ID
ObjectType=0x07
DataType=0x0007
AccessType=rw
DefaultValue=$NODEID+0x40000200
PDOMapping=0
....
conf/cia402/cia402.yml
...
tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation
1:
enabled: true
transmission: 0x01
mapping:
- {index: 0x6041, sub_index: 0} # status word
- {index: 0x6061, sub_index: 0} # mode of operaiton display
2:
enabled: true
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
mapping:
- {index: 0x6040, sub_index: 0} # controlword
- {index: 0x6060, sub_index: 0} # mode of operation
2:
enabled: true
mapping:
- {index: 0x607A, sub_index: 0} # target position
- {index: 0x60FF, sub_index: 0} # target velocity
...
The output after init.
[lifecycle_device_container_node-2] [INFO] [1660751526.548156710] [canopen_402_driver]: Init: Switch to homing
[lifecycle_device_container_node-2] [INFO] [1660751526.588145240] [canopen_402_driver]: Init: Execute homing
[lifecycle_device_container_node-2] [INFO] [1660751526.588800182] [canopen_402_driver]: Init: Switch no mode
[lifecycle_device_container_node-2] Initialised object : 6041 39 RPDO: yes TPDO: no
[lifecycle_device_container_node-2] Initialised object : 6040 271 RPDO: no TPDO: yes
[lifecycle_device_container_node-2] Initialised object : 6061 6 RPDO: yes TPDO: no
[lifecycle_device_container_node-2] Initialised object : 6060 0 RPDO: no TPDO: yes
[lifecycle_device_container_node-2] Initialised object : 6502 165 RPDO: no TPDO: no
[lifecycle_device_container_node-2] Initialised object : 607a 0 RPDO: no TPDO: yes
[lifecycle_device_container_node-2] Initialised object : 6098 0 RPDO: no TPDO: no
[lifecycle_device_container_node-2] Initialised object : 60ff 0 RPDO: no TPDO: yes
[lifecycle_device_container_node-2] Initialised object : 607a 0 RPDO: no TPDO: yes
Thanks for your reply. I set the correct path, so the bin file can be used correctly, no error is reported. The problem is the configuration of COB-ID used by PDO in eds. I noticed that you disabled PDO by setting COB-ID to $NODEID+0x40000200. However I used $NODEID+0x80000200. I tested $NODEID+0x40000200 and it works fine. So the difference is whether to use bit 31 or bit 30. I checked related documentation: bit 31: If set, PDO does not exist / is not valid bit 30: If set, NO RTR is allowed on this PDO Why the PDO configuration is skipped when bit 31 is set? I'm not sure if this is in spec?
You are right, I could reproduce this now. Sorry, it was a little late...
The solution to this is to add cob_id: "auto" to the pdo spec in bus.yml (see https://gitlab.com/lely_industries/lely-core/-/issues/111).
enabled: true/false keyword has an impact only on PDOs enabled in EDS. cob_id: "auto" does the trick for PDOs disabled in the EDS.
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 operaiton display
Thanks, I will test it again.
Thanks, it is finally normal. But it should also be noted that if $NODEID+0x40000400 is set for RPDO3 in eds, 'enabled: false' has no effect on it. Master will still use this PDO.
Hi, I'm testing canopen_402_driver on our motor. I use the same PDO config as in https://github.com/ipa-cmh/trinamic_pd42_can/blob/master/config/bus.yml I listened to CAN communication using candump. For the device initialization phase, the logs look as expected.
But I only see TPDO1 and RPDO1 configured in CAN communication. I don't understand why TPDO2 and RPDO2 are skipped. When I call the init service, it works fine, but it shows that these objects do not have PDO mapping configured.
Any suggestions? Thanks