ros-industrial / ros2_canopen

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

ros2_control launch error #219

Closed alexanderjyuen closed 8 months ago

alexanderjyuen commented 8 months ago

At present we are getting the following error when we start our launch file:

[INFO] [launch]: All log files can be found below /root/.ros/log/2023-11-03-00-33-13-233571-polymath-MINIPC-PN50-E1-5019
[INFO] [launch]: Default logging verbosity is set to INFO
<launch.substitutions.path_join_substitution.PathJoinSubstitution object at 0x7f43c1b32e30>
[INFO] [ros2_control_node-1]: process started with pid [5031]
[INFO] [robot_state_publisher-2]: process started with pid [5033]
[INFO] [spawner-3]: process started with pid [5035]
[INFO] [cia402_slave_node-4]: process started with pid [5037]
[INFO] [cia402_slave_node-5]: process started with pid [5039]
[INFO] [spawner-6]: process started with pid [5041]
[INFO] [spawner-7]: process started with pid [5043]
[INFO] [spawner-8]: process started with pid [5045]
[ros2_control_node-1] [INFO] [1698971593.578500513] [resource_manager]: Loading hardware 'canopen_test_system' 
[robot_state_publisher-2] [INFO] [1698971593.584175046] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1698971593.584347007] [robot_state_publisher]: got segment node_1_link
[robot_state_publisher-2] [INFO] [1698971593.584357747] [robot_state_publisher]: got segment node_2_link
[ros2_control_node-1] [INFO] [1698971593.599997164] [resource_manager]: Initialize hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1698971593.602416550] [CanopenSystem]: bus_config: '/colcon_ws/install/hal/share/hal/config/can/bus.yml'
[ros2_control_node-1] [INFO] [1698971593.603843404] [CanopenSystem]: master_config: '/colcon_ws/install/hal/share/hal/config/can/master.dcf'
[ros2_control_node-1] [INFO] [1698971593.605540072] [CanopenSystem]: can_interface_name: 'can0'
[ros2_control_node-1] [INFO] [1698971593.607105314] [CanopenSystem]: master_bin: '""'
[ros2_control_node-1] [INFO] [1698971593.608235974] [resource_manager]: Successful initialization of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1698971593.610293145] [resource_manager]: 'configure' hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1698971593.669473035] [device_container]: Starting Device Container with:
[ros2_control_node-1] [INFO] [1698971593.669641649] [device_container]:      can_interface_name can0
[ros2_control_node-1] [INFO] [1698971593.669658641] [device_container]:      master_config /colcon_ws/install/hal/share/hal/config/can/master.dcf
[ros2_control_node-1] [INFO] [1698971593.669672367] [device_container]:      bus_config /colcon_ws/install/hal/share/hal/config/can/bus.yml
[ros2_control_node-1] [INFO] [1698971593.672908218] [device_container]: Loading Master Configuration.
[ros2_control_node-1] [INFO] [1698971593.674138174] [device_container]: Load Library: /opt/polymathrobotics/canopen_master_driver/lib/libmaster_driver.so
[ros2_control_node-1] [INFO] [1698971593.677489640] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1698971593.677575290] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1698971593.690287261] [master]: NodeCanopenBasicMaster
[ros2_control_node-1] [INFO] [1698971593.690548188] [device_container]: Load master component.
[ros2_control_node-1] [INFO] [1698971593.690794989] [device_container]: Added /master to executor
[ros2_control_node-1] [INFO] [1698971593.717157294] [device_container]: Loading Driver Configuration.
[ros2_control_node-1] [INFO] [1698971593.717342279] [device_container]: Found device left_motor with driver ros2_canopen::Cia402Driver
[ros2_control_node-1] [INFO] [1698971593.717643441] [device_container]: Load Library: /opt/polymathrobotics/canopen_402_driver/lib/libcia402_driver.so
[ros2_control_node-1] [INFO] [1698971593.718779011] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1698971593.718849753] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1698971593.733628863] [device_container]: Load driver component.
[ros2_control_node-1] [INFO] [1698971593.734148504] [device_container]: Added /left_motor to executor
[ros2_control_node-1] [ERROR] [1698971593.765973706] [left_motor]: Could not read enable diagnostics from config, setting to false.
[ros2_control_node-1] [INFO] [1698971593.766326916] [left_motor]: scale_pos_to_dev_ 1000.000000
[ros2_control_node-1] scale_pos_from_dev_ 0.001000
[ros2_control_node-1] scale_vel_to_dev_ 67.000000
[ros2_control_node-1] scale_vel_from_dev_ 0.015000
[ros2_control_node-1] 
[ros2_control_node-1] [INFO] [1698971593.769431922] [left_motor]: eds file /colcon_ws/install/hal/share/hal/config/can/roboteq_motor_controllers_v80.eds
[ros2_control_node-1] [INFO] [1698971593.769498717] [left_motor]: bin file /colcon_ws/install/hal/share/hal/config/can/left_motor.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] [INFO] [1698971593.788046984] [left_motor]: Driver booted and ready.
[ros2_control_node-1] [INFO] [1698971593.788746319] [left_motor]: Starting with polling mode.
[ros2_control_node-1] [INFO] [1698971593.790816604] [device_container]: Found device right_motor with driver ros2_canopen::Cia402Driver
[ros2_control_node-1] [INFO] [1698971593.791574629] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1698971593.791640262] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[INFO] [launch.user]: node 'basic_slave_node' reached the 'inactive' state, 'activating'.
[cia402_slave_node-4] [INFO] [1698971593.806747865] [left_motor_node]: Reaching inactive state.
[INFO] [launch.user]: node 'basic_slave_node' reached the 'inactive' state, 'activating'.
[ros2_control_node-1] [INFO] [1698971593.809130283] [device_container]: Load driver component.
[ros2_control_node-1] [INFO] [1698971593.809376052] [device_container]: Added /right_motor to executor
[ros2_control_node-1] [INFO] [1698971593.816714912] [canopen_402_driver]: Fault reset
[cia402_slave_node-5] [INFO] [1698971593.810413408] [right_motor_node]: Reaching inactive state.
[ros2_control_node-1] [ERROR] [1698971593.840834720] [right_motor]: Could not read enable diagnostics from config, setting to false.
[ros2_control_node-1] [INFO] [1698971593.841036106] [right_motor]: scale_pos_to_dev_ 1000.000000
[ros2_control_node-1] scale_pos_from_dev_ 0.001000
[ros2_control_node-1] scale_vel_to_dev_ 1.000000
[ros2_control_node-1] scale_vel_from_dev_ 1.000000
[ros2_control_node-1] 
[ros2_control_node-1] [INFO] [1698971593.843591106] [right_motor]: eds file /colcon_ws/install/hal/share/hal/config/can/roboteq_motor_controllers_v80.eds
[ros2_control_node-1] [INFO] [1698971593.843651178] [right_motor]: bin file /colcon_ws/install/hal/share/hal/config/can/right_motor.bin
[cia402_slave_node-4] [INFO] [1698971593.844934273] [left_motor_node]: Reaching active state.
[cia402_slave_node-5] [INFO] [1698971593.846344125] [right_motor_node]: Reaching active state.
[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] [INFO] [1698971593.859761464] [right_motor]: Driver booted and ready.
[ros2_control_node-1] [INFO] [1698971593.860025086] [right_motor]: Starting with polling mode.
[ros2_control_node-1] [INFO] [1698971593.860440571] [Cia402System]: Number of registered drivers: '2'
[ros2_control_node-1] [INFO] [1698971593.860644131] [Cia402System]: 
[ros2_control_node-1] Registered driver:
[ros2_control_node-1]     name: 'right_motor'
[ros2_control_node-1]     node_id: '0x1'
[ros2_control_node-1] [INFO] [1698971593.860674779] [Cia402System]: 
[ros2_control_node-1] Registered driver:
[ros2_control_node-1]     name: 'left_motor'
[ros2_control_node-1]     node_id: '0x2'
[ros2_control_node-1] [INFO] [1698971593.860688003] [device_container]: Initialisation successful.
[ros2_control_node-1] [INFO] [1698971593.860911501] [resource_manager]: Successful 'configure' of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1698971593.860999034] [resource_manager]: 'activate' hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1698971593.861031314] [resource_manager]: Successful 'activate' of hardware 'canopen_test_system'
[cia402_slave_node-5] [INFO] [1698971593.864819817] [right_motor_node]: Created cia402 slave for node_id 1.
[cia402_slave_node-4] [INFO] [1698971593.866084818] [left_motor_node]: Created cia402 slave for node_id 2.
[ros2_control_node-1] [INFO] [1698971593.866852121] [right_motor]: Slave 0x1: Switched NMT state to START
[cia402_slave_node-4] [INFO] [1698971593.867833202] [cia402_slave]: Switch_On_Disabled
[ros2_control_node-1] [ERROR] [1698971593.868382638] [left_motor]: AsyncDownload:02:6040:00: Resource not available: SDO connection (060A0023): Resource not available: SDO connection
[ros2_control_node-1] terminate called after throwing an instance of 'lely::canopen::SdoError'
[ros2_control_node-1]   what():  SubmitRead:02:6064:00: Resource not available: SDO connection (060A0023): Resource not available: SDO connection
[ros2_control_node-1] Stack trace (most recent call last) in thread 5085:
[ros2_control_node-1] #26   Object "", at 0xffffffffffffffff, in 
[ros2_control_node-1] #25   Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7fc43ad279ff, in 
[ros2_control_node-1] #24   Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7fc43ac95b42, in 
[ros2_control_node-1] #23   Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7fc43af25252, in 
[ros2_control_node-1] #22   Object "/opt/ros/humble/lib/librclcpp.so", at 0x7fc43b163099, in rclcpp::executors::MultiThreadedExecutor::run(unsigned long)
[ros2_control_node-1] #21   Object "/opt/ros/humble/lib/librclcpp.so", at 0x7fc43b15bde0, in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&)
[ros2_control_node-1] #20   Object "/opt/polymathrobotics/canopen_base_driver/lib/libnode_canopen_base_driver.so", at 0x7fc43503629c, in rclcpp::GenericTimer<std::_Bind<void (ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>::*(ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>*))()>, (void*)0>::execute_callback()
[ros2_control_node-1] #19   Object "/opt/polymathrobotics/canopen_base_driver/lib/libnode_canopen_base_driver.so", at 0x7fc43503e773, in void rclcpp::GenericTimer<std::_Bind<void (ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>::*(ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>*))()>, (void*)0>::execute_callback_delegate<std::_Bind<void (ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>::*(ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>*))()>, (void*)0>()
[ros2_control_node-1] #18   Object "/opt/polymathrobotics/canopen_base_driver/lib/libnode_canopen_base_driver.so", at 0x7fc435019c52, in void std::_Bind<void (ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>::*(ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>*))()>::operator()<, void>()

The launch file is as follows

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
import os
from ament_index_python import get_package_share_directory

def launch_setup(context, *args, **kwargs):

    name = LaunchConfiguration("name")
    prefix = LaunchConfiguration("prefix")

    # bus configuration
    bus_config_package = LaunchConfiguration("bus_config_package")
    bus_config_directory = LaunchConfiguration("bus_config_directory")
    bus_config_file = LaunchConfiguration("bus_config_file")
    # bus configuration file full path
    bus_config = PathJoinSubstitution(
        [FindPackageShare(bus_config_package), bus_config_directory, bus_config_file]
    )

    print(bus_config)

    # master configuration
    master_config_package = LaunchConfiguration("master_config_package")
    master_config_directory = LaunchConfiguration("master_config_directory")
    master_config_file = LaunchConfiguration("master_config_file")
    # master configuration file full path
    master_config = PathJoinSubstitution(
        [FindPackageShare(master_config_package), master_config_directory, master_config_file]
    )

    # can interface name
    can_interface_name = LaunchConfiguration("can_interface_name")

    # robot description stuff
    description_package = LaunchConfiguration("description_package")
    description_file = LaunchConfiguration("description_file")
    robot_description_content = Command(
        [
            PathJoinSubstitution([FindExecutable(name="xacro")]),
            " ",
            PathJoinSubstitution(
                [FindPackageShare(description_package), "urdf", "cia402_system", description_file]
            ),
            " ",
            "name:=",
            name,
            " ",
            "prefix:=",
            prefix,
            " ",
            "bus_config:=",
            bus_config,
            " ",
            "master_config:=",
            master_config,
            " ",
            "can_interface_name:=",
            can_interface_name,
            " ",
        ]
    )
    robot_description = {"robot_description": robot_description_content}

    # ros2 control configuration
    ros2_control_config_package = LaunchConfiguration("ros2_control_config_package")
    ros2_control_config_directory = LaunchConfiguration("ros2_control_config_directory")
    ros2_control_config_file = LaunchConfiguration("ros2_control_config_file")
    # ros2 control configuration file full path
    ros2_control_config = PathJoinSubstitution(
        [
            FindPackageShare(ros2_control_config_package),
            ros2_control_config_directory,
            ros2_control_config_file,
        ]
    )

    # nodes to start are listed below
    control_node = Node(
        package="controller_manager",
        executable="ros2_control_node",
        parameters=[robot_description, ros2_control_config],
        output="screen",
    )

    # load one controller just to make sure it can connect to controller_manager
    joint_state_broadcaster_spawner = Node(
        package="controller_manager",
        executable="spawner",
        arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
    )

    left_motor_controller_spawner = Node(
        package="controller_manager",
        executable="spawner",
        arguments=["left_motor_controller", "--controller-manager", "/controller_manager"],
    )

    right_motor_controller_spawner = Node(
        package="controller_manager",
        executable="spawner",
        arguments=["right_motor_controller", "--controller-manager", "/controller_manager"],
    )

    forward_position_controller = Node(
        package="controller_manager",
        executable="spawner",
        arguments=["forward_position_controller", "--controller-manager", "/controller_manager"],
    )

    robot_state_publisher_node = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        output="both",
        parameters=[robot_description],
    )

    # hardcoded slave configuration form test package
    slave_config = PathJoinSubstitution(
        [FindPackageShare("hal"), "config/can", "roboteq_motor_controllers_v80.eds"]
    )

    slave_launch = PathJoinSubstitution(
        [FindPackageShare("canopen_fake_slaves"), "launch", "cia402_slave.launch.py"]
    )

    left_motor_node = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(slave_launch),
        launch_arguments={
            "node_id": "2",
            "node_name": "left_motor_node",
            "slave_config": slave_config,
        }.items(),
    )

    right_motor_node = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(slave_launch),
        launch_arguments={
            "node_id": "1",
            "node_name": "right_motor_node",
            "slave_config": slave_config,
        }.items(),
    )

    nodes_to_start = [
        control_node,
        robot_state_publisher_node,
        joint_state_broadcaster_spawner,
        left_motor_node,
        right_motor_node,
        left_motor_controller_spawner,
        right_motor_controller_spawner,
        forward_position_controller,
    ]

    return nodes_to_start

def generate_launch_description():

    declared_arguments = []
    declared_arguments.append(
        DeclareLaunchArgument(
            "name", description="robot name", default_value="canopen_test_system"
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument("prefix", description="Prefix.", default_value="")
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "description_package",
            description="Package where urdf file is stored.",
            default_value="hal",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "description_file",
            description="Name of the urdf file.",
            default_value="cia402_system.urdf.xacro",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "ros2_control_config_package",
            default_value="hal",
            description="Path to ros2_control configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "ros2_control_config_directory",
            default_value="config/ros2_control",
            description="Path to ros2_control configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "ros2_control_config_file",
            default_value="ros2_controllers.yaml",
            description="Path to ros2_control configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "bus_config_package",
            default_value="hal",
            description="Path to bus configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "bus_config_directory",
            default_value="config/can",
            description="Path to bus configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "bus_config_file",
            default_value="bus.yml",
            description="Path to bus configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "master_config_package",
            default_value="hal",
            description="Path to master configuration file (*.dcf)",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "master_config_directory",
            default_value="config/can",
            description="Path to master configuration file (*.dcf)",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "master_config_file",
            default_value="master.dcf",
            description="Path to master configuration file (*.dcf)",
        )
    )

    declared_arguments.append(
        DeclareLaunchArgument(
            "can_interface_name",
            default_value="can0",
            description="Interface name for can",
        )

the bus.yml file is as follows:

options:
  dcf_path: "/colcon_ws/install/hal/share/hal/config/can"

master: 
  node_id: 3
  driver: "ros2_canopen::MasterDriver"
  package: "canopen_master_driver"
  sync_period: 20000

right_motor: 
  node_id: 1
  dcf: "roboteq_motor_controllers_v80.eds"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  polling: true
  period: 20
  enable_lazy_load: false
  heartbeat_producer: 1000    # ms
  heartbeat_consumer: 100     # ms
  scale_vel_to_dev: 1
  scale_vel_from_dev: 1
  velocity_mode: 1

left_motor: 
  node_id: 2
  dcf: "roboteq_motor_controllers_v80.eds"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  polling: true
  period: 20
  enable_lazy_load: false
  heartbeat_producer: 1000  # ms
  heartbeat_consumer: 100  # ms
  scale_vel_to_dev: 67
  scale_vel_from_dev: 0.015
  velocity_mode: 1  

and the ros2_control yaml file is as follows:

controller_manager:
  ros__parameters:
    update_rate: 10  # Hz

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    left_motor_controller:
      type: canopen_ros2_controllers/Cia402DeviceController

    right_motor_controller:
      type: canopen_ros2_controllers/Cia402DeviceController

    forward_position_controller:
      type: forward_command_controller/ForwardCommandController

left_motor_controller:
  ros__parameters:
    joint: left_motor

right_motor_controller:
  ros__parameters:
    joint: right_motor

forward_position_controller:
  ros__parameters:
    joints:
      - left_motor
      - right_motor
    interface_name: velocity

I am able to run the launch file with a virtual can but it breaks when I try to communicate with a real can interface, anybody have any insight into this?

hellantos commented 8 months ago

Seems you are starting the fake slaves while on real hardware. That does not work.

alexanderjyuen commented 8 months ago

Seems you are starting the fake slaves while on real hardware. That does not work.

Is there a ready made launch file that would work for a real CAN device using 402?