ros-industrial / ros2_canopen

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

6502h Object does not exist #299

Open david-paltech opened 1 month ago

david-paltech commented 1 month ago

Describe the bug

I am trying to control the motor iHSV60 but I'm getting the following error when calling the /init service. The configuration I'm using is almost the same as in the Trinamic Stepper Motor control example (launch and yml file display below).

[device_container_node-1] async_sdo_read: id=1 index=0x6502 subindex=0 object does not exist
[device_container_node-1] [ERROR] [1722519461.021056659] [IHSV60]: 01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary

I tried to fix it by adding one more entry in the EDS file like this:

[OptionalObjects]
SupportedObjects=59 -> 60
1=0x1002
2=0x1003
...
59=0x609A
60=0x6502 -> Adding this

[6502]
ParameterName=Supported Drive Modes 1
ObjectType=0x07
DataType=0x0007
AccessType=ro
DefaultValue=0x000003FF
PDOMapping=1

But this only moved the error further, now the /init call doesn't fail immediately after, now it actually tries to read the dictionary through the CAN channel:

  can0  301   [2]  00 01
  can0  501   [8]  00 00 00 00 00 00 00 01
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 00
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  00 00 00 00 00 00 00 01
  can0  601   [8]  40 02 65 00 00 00 00 00     # Reading OD 6502h
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 00
  can0  581   [8]  80 02 65 00 00 00 02 06     # Fails reading, error code (06020000): Object does not exist in the object dictionary
  can0  601   [8]  40 02 65 00 00 00 00 00     # Keeps trying
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  00 00 00 00 00 00 00 01
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 00
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  581   [8]  80 02 65 00 00 00 02 06     #
  can0  601   [8]  40 02 65 00 00 00 00 00     #
  can0  581   [8]  80 02 65 00 00 00 02 06     # It gives up
  can0  501   [8]  06 00 00 00 00 00 00 01
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  06 00 00 00 00 00 00 01
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 06

I've checked the motor's datasheet and confirmed with the manufacturer that the motor does not support the OD 6502h. So my question is: Is it still possible to use this library if the motor does not support such dictionary? If so, what is the workaround?

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 = "IHSS57_60-RC_V2.3.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: 1024   # kbit/s (default: 1000)
    product_code: 0x00000000
    driver: "ros2_canopen::MasterDriver"
    package: "canopen_master_driver"
    sync_period: 20000

defaults:
    dcf: "IHSS57_60-RC_V2.3.eds"
    driver: "ros2_canopen::Cia402Driver"
    package: "canopen_402_driver"
    polling: false
    heartbeat_producer: 1000 # Heartbeat every 1000 ms
    sdo_timeout_ms: 5000
    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: 0}       # 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: true
            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
            # cob_id: "auto"
            # mapping:
            #     - {index: 0x6502, sub_index: 0} # supported drive modes
        4:
            enabled: false

    rpdo: # RPDO needed controlword, target position, target velocity, mode of operation
        1:
            enabled: true
            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:
    IHSV60:
        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-15-56-57-036917-paltech-thinkpad-46068
[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 [46079]
[device_container_node-1] [INFO] [1722520617.164204044] [device_container_node]: Starting Device Container with:
[device_container_node-1] [INFO] [1722520617.164336244] [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] [1722520617.164343878] [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] [1722520617.164351482] [device_container_node]:     can_interface_name can0
[device_container_node-1] [INFO] [1722520617.165469895] [device_container_node]: Loading Master Configuration.
[device_container_node-1] [INFO] [1722520617.166156722] [device_container_node]: Load Library: /home/paltech/ros2_ws/install/canopen_master_driver/lib/libmaster_driver.so
[device_container_node-1] [INFO] [1722520617.169161847] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1722520617.169201192] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1722520617.172757358] [master]: NodeCanopenBasicMaster
[device_container_node-1] [INFO] [1722520617.172890029] [device_container_node]: Load master component.
[device_container_node-1] [INFO] [1722520617.172963828] [device_container_node]: Added /master to executor
[device_container_node-1] [WARN] [1722520617.174726166] [master]: No timeout parameter found in config file. Using default value of 100ms.
[device_container_node-1] [INFO] [1722520617.174778165] [master]: Master boot timeout set to 2000ms.
[device_container_node-1] [INFO] [1722520617.187685642] [device_container_node]: Loading Driver Configuration.
[device_container_node-1] [INFO] [1722520617.187797504] [device_container_node]: Found device IHSV60 with driver ros2_canopen::Cia402Driver
[device_container_node-1] [INFO] [1722520617.188177561] [device_container_node]: Load Library: /home/paltech/ros2_ws/install/canopen_402_driver/lib/libcia402_driver.so
[device_container_node-1] [INFO] [1722520617.193788208] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1722520617.193844965] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1722520617.198714772] [device_container_node]: Load driver component.
[device_container_node-1] [INFO] [1722520617.198939166] [device_container_node]: Added /IHSV60 to executor
[device_container_node-1] [INFO] [1722520617.212621347] [IHSV60]: Non transmit timeout100ms
[device_container_node-1] [WARN] [1722520617.212766852] [IHSV60]: Could not read enable diagnostics from config, setting to false.
[device_container_node-1] [INFO] [1722520617.213018768] [IHSV60]: scale_pos_to_dev_ 1000.000000
[device_container_node-1] scale_pos_from_dev_ 0.001000
[device_container_node-1] scale_vel_to_dev_ 1.000000
[device_container_node-1] scale_vel_from_dev_ 1.000000
[device_container_node-1] 
[device_container_node-1] [INFO] [1722520617.215243890] [IHSV60]: eds file /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/IHSS57_60-RC_V2.3.eds
[device_container_node-1] [INFO] [1722520617.215297241] [IHSV60]: bin file /home/paltech/ros2_ws/install/motors-config-pkg/share/motors-config-pkg/config/bus_config_motor_1/IHSV60.bin
[device_container_node-1] Found rpdo mapped object: index=607a subindex=0
[device_container_node-1] Found rpdo mapped object: index=6081 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6084 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6040 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6099 subindex=2
[device_container_node-1] Found rpdo mapped object: index=6099 subindex=1
[device_container_node-1] Found rpdo mapped object: index=609a subindex=0
[device_container_node-1] Found rpdo mapped object: index=6085 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6060 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6098 subindex=0
[device_container_node-1] Found rpdo mapped object: index=607a subindex=0
[device_container_node-1] Found rpdo mapped object: index=6040 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=6061 subindex=0
[device_container_node-1] [WARN] [1722520617.218262181] [IHSV60]: Wait for device to boot.
[device_container_node-1] [INFO] [1722520618.027707776] [IHSV60]: Driver booted and ready.
[device_container_node-1] [INFO] [1722520618.028548404] [IHSV60]: Starting with event mode.
[device_container_node-1] [INFO] [1722520619.028042748] [IHSV60]: Slave 0x1: Switched NMT state to START
[device_container_node-1] [ERROR] [1722520645.403552898] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.406511145] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.409170487] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.411753104] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.414021258] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.416728139] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.421436551] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.424831332] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [ERROR] [1722520645.427197851] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [INFO] [1722520645.427294734] [canopen_402_driver]: Init: Read State
[device_container_node-1] [INFO] [1722520645.427344318] [canopen_402_driver]: Init: Enable
[device_container_node-1] [ERROR] [1722520645.429970458] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [INFO] [1722520645.430070607] [canopen_402_driver]: Init: Switch to homing
[device_container_node-1] [ERROR] [1722520645.432443578] [IHSV60]: AsyncUpload:01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary
[device_container_node-1] [INFO] [1722520645.437869184] [canopen_402_driver]: Fault reset
[device_container_node-1] [INFO] [1722520645.458901153] [canopen_402_driver]: Init: Execute homing
[device_container_node-1] [INFO] [1722520645.464218174] [canopen_402_driver]: Init: Switch no mode

CAN channel

  can0  701   [1]  00
  can0  701   [1]  7F
  can0  701   [1]  7F
  can0  701   [1]  7F
  can0  701   [1]  7F
  can0  701   [1]  7F
  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 D9 02 00 00
  can0  601   [8]  40 18 10 02 00 00 00 00
  can0  581   [8]  43 18 10 02 01 76 18 20
  can0  601   [8]  40 18 10 03 00 00 00 00
  can0  080   [0] 
  can0  581   [8]  43 18 10 03 01 12 17 20
  can0  601   [8]  23 00 14 01 01 02 00 80     # Start SDO config
  can0  581   [8]  60 00 14 01 00 00 00 00
  can0  601   [8]  2F 00 16 00 00 00 00 00
  can0  581   [8]  60 00 16 00 00 00 00 00
  can0  601   [8]  23 00 16 01 20 00 7A 60
  can0  581   [8]  60 00 16 01 00 00 00 00
  can0  601   [8]  23 00 16 02 20 00 81 60
  can0  581   [8]  60 00 16 02 00 00 00 00
  can0  601   [8]  2F 00 16 00 02 00 00 00
  can0  581   [8]  60 00 16 00 00 00 00 00
  can0  601   [8]  23 00 14 01 01 02 00 00
  can0  581   [8]  60 00 14 01 00 00 00 00
  can0  601   [8]  23 01 14 01 01 03 00 80
  can0  581   [8]  60 01 14 01 00 00 00 00
  can0  601   [8]  2F 01 16 00 00 00 00 00
  can0  581   [8]  60 01 16 00 00 00 00 00
  can0  080   [0] 
  can0  601   [8]  23 01 16 01 10 00 40 60
  can0  581   [8]  60 01 16 01 00 00 00 00
  can0  601   [8]  2F 01 16 00 01 00 00 00
  can0  581   [8]  60 01 16 00 00 00 00 00
  can0  601   [8]  23 01 14 01 01 03 00 00
  can0  581   [8]  60 01 14 01 00 00 00 00
  can0  601   [8]  23 00 18 01 81 01 00 80
  can0  581   [8]  60 00 18 01 00 00 00 00
  can0  601   [8]  2F 00 1A 00 00 00 00 00
  can0  581   [8]  60 00 1A 00 00 00 00 00
  can0  601   [8]  23 00 1A 01 20 00 64 60
  can0  581   [8]  60 00 1A 01 00 00 00 00
  can0  601   [8]  23 00 1A 02 20 00 6C 60
  can0  581   [8]  60 00 1A 02 00 00 00 00
  can0  601   [8]  2F 00 1A 00 02 00 00 00
  can0  581   [8]  60 00 1A 00 00 00 00 00
  can0  601   [8]  23 00 18 01 81 01 00 00
  can0  080   [0] 
  can0  581   [8]  60 00 18 01 00 00 00 00
  can0  601   [8]  23 01 18 01 81 02 00 80
  can0  581   [8]  60 01 18 01 00 00 00 00
  can0  601   [8]  2F 01 1A 00 00 00 00 00
  can0  581   [8]  60 01 1A 00 00 00 00 00
  can0  601   [8]  23 01 1A 01 10 00 41 60
  can0  581   [8]  60 01 1A 01 00 00 00 00
  can0  601   [8]  23 01 1A 02 08 00 61 60
  can0  581   [8]  60 01 1A 02 00 00 00 00
  can0  601   [8]  2F 01 1A 00 02 00 00 00
  can0  581   [8]  60 01 1A 00 00 00 00 00
  can0  601   [8]  23 01 18 01 81 02 00 00
  can0  581   [8]  60 01 18 01 00 00 00 00
  can0  601   [8]  23 02 18 01 81 03 00 80
  can0  581   [8]  60 02 18 01 00 00 00 00
  can0  601   [8]  23 03 18 01 81 04 00 80
  can0  581   [8]  60 03 18 01 00 00 00 00
  can0  601   [8]  23 81 60 00 E8 03 00 00
  can0  080   [0] 
  can0  581   [8]  60 81 60 00 00 00 00 00
  can0  601   [8]  2B 83 60 00 E8 03 00 00
  can0  581   [8]  60 83 60 00 00 00 00 00
  can0  601   [8]  2B 84 60 00 E8 03 00 00
  can0  581   [8]  60 84 60 00 00 00 00 00
  can0  601   [8]  2B 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 00 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]  2B 9A 60 00 E8 03 00 00
  can0  581   [8]  60 9A 60 00 00 00 00 00     # End SDO config
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  ...
  can0  080   [0] 
  can0  080   [0] 
  can0  701   [1]  7F
  can0  000   [2]  01 01
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  00 00 00 00 00 00 00 01
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 00
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  00 00 00 00 00 00 00 01
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 00
  ...
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  00 00 00 00 00 00 00 01
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 00
  can0  080   [0] 
  can0  301   [2]  00 01                    # HERE I CALL INIT SERVICE
  can0  501   [8]  00 00 00 00 00 00 00 01
  can0  601   [8]  40 02 65 00 00 00 00 00     # Trying to read OD 6502
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 00
  can0  581   [8]  80 02 65 00 00 00 02 06     # Failing to read OD 6502
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  00 00 00 00 00 00 00 01
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 00
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  581   [8]  80 02 65 00 00 00 02 06
  can0  601   [8]  40 02 65 00 00 00 00 00
  can0  581   [8]  80 02 65 00 00 00 02 06      # It gives up reading
  can0  501   [8]  06 00 00 00 00 00 00 01
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  06 00 00 00 00 00 00 01
  can0  181   [8]  00 00 00 00 00 00 00 00
  can0  281   [3]  37 10 06
  can0  080   [0] 
  can0  301   [2]  00 01
  can0  501   [8]  06 00 00 00 00 00 00 01
  can0  601   [8]  40 98 60 00 00 00 00 00

Setup:

hellantos commented 1 month ago

Hi, currently we need 6502 to know which modes the drive supports.